From 4c950bcdd6c30453b4dc30d23dc1113ca2700215 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 29 Nov 2023 19:59:50 +0100 Subject: [PATCH 001/195] [RemovingPybulletFromObjectClass] removed all usages of pybullet from the object class; needs tests to verify functionality. --- src/pycram/world.py | 1866 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 1866 insertions(+) create mode 100644 src/pycram/world.py diff --git a/src/pycram/world.py b/src/pycram/world.py new file mode 100644 index 000000000..095604298 --- /dev/null +++ b/src/pycram/world.py @@ -0,0 +1,1866 @@ +# used for delayed evaluation of typing until python 3.11 becomes mainstream +from __future__ import annotations + +import logging +import os +import pathlib +import re +import threading +import time +import xml.etree.ElementTree +from queue import Queue +import tf +from typing import List, Optional, Dict, Tuple, Callable, Iterable +from typing import Union + +import numpy as np +import pybullet as p +import rospkg +import rospy +import rosgraph + +import urdf_parser_py.urdf +from geometry_msgs.msg import Quaternion, Point +from urdf_parser_py.urdf import URDF + +from .event import Event +from .robot_descriptions import robot_description +from .enums import JointType, ObjectType +from .local_transformer import LocalTransformer +from sensor_msgs.msg import JointState + +from .pose import Pose, Transform + + +class BulletWorld: + """ + The BulletWorld Class represents the physics Simulation and belief state. + """ + + current_bullet_world: BulletWorld = None + """ + Global reference to the currently used BulletWorld, usually this is the + graphical one. However, if you are inside a Use_shadow_world() environment the current_bullet_world points to the + shadow world. In this way you can comfortably use the current_bullet_world, which should point towards the BulletWorld + used at the moment. + """ + robot: Object = None + """ + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the + URDF with the name of the URDF on the parameter server. + """ + + # Check is for sphinx autoAPI to be able to work in a CI workflow + if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): + rospy.init_node('pycram') + + def __init__(self, type: str = "GUI", is_shadow_world: bool = False): + """ + Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the + background. There can only be one rendered simulation. + The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. + + :param type: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param is_shadow_world: For internal usage, decides if this BulletWorld should be used as a shadow world. + """ + self.objects: List[Object] = [] + self.client_id: int = -1 + self.detachment_event: Event = Event() + self.attachment_event: Event = Event() + self.manipulation_event: Event = Event() + self.type: str = type + self._gui_thread: Gui = Gui(self, type) + self._gui_thread.start() + # This disables file caching from PyBullet, since this would also cache + # files that can not be loaded + p.setPhysicsEngineParameter(enableFileCaching=0) + # Needed to let the other thread start the simulation, before Objects are spawned. + time.sleep(0.1) + if BulletWorld.current_bullet_world == None: + BulletWorld.current_bullet_world = self + self.vis_axis: Object = [] + self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} + self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] + self.shadow_world: BulletWorld = BulletWorld("DIRECT", True) if not is_shadow_world else None + self.world_sync: WorldSync = WorldSync(self, self.shadow_world) if not is_shadow_world else None + self.is_shadow_world: bool = is_shadow_world + self.local_transformer = LocalTransformer() + if not is_shadow_world: + self.world_sync.start() + self.local_transformer.bullet_world = self + self.local_transformer.shadow_world = self.shadow_world + + # Some default settings + self.set_gravity([0, 0, -9.8]) + if not is_shadow_world: + plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) + # atexit.register(self.exit) + + def get_objects_by_name(self, name: str) -> List[Object]: + """ + Returns a list of all Objects in this BulletWorld with the same name as the given one. + + :param name: The name of the returned Objects. + :return: A list of all Objects with the name 'name'. + """ + return list(filter(lambda obj: obj.name == name, self.objects)) + + def get_objects_by_type(self, obj_type: str) -> List[Object]: + """ + Returns a list of all Objects which have the type 'obj_type'. + + :param obj_type: The type of the returned Objects. + :return: A list of all Objects that have the type 'obj_type'. + """ + return list(filter(lambda obj: obj.type == obj_type, self.objects)) + + def get_object_by_id(self, id: int) -> Object: + """ + Returns the single Object that has the unique id. + + :param id: The unique id for which the Object should be returned. + :return: The Object with the id 'id'. + """ + return list(filter(lambda obj: obj.id == id, self.objects))[0] + + def remove_object(self, obj_id: int) -> None: + """ + Remove an object by its ID. + + :param obj_id: The unique id of the object to be removed. + """ + + p.removeBody(obj_id, self.client_id) + + def attach(self, + parent_obj: Object, + child_obj: Object, + parent_link: Optional[str] = None, + loose: Optional[bool] = False) -> None: + """ + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a constraint of pybullet will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. + For example, if the parent object moves, the child object will also move, but not the other way around. + + :param parent_obj: The parent object (jf loose, then this would not move when child moves) + :param child_obj: The child object + :param parent_link: The link of the parent object to which the child object should be attached + :param loose: If the attachment should be a loose attachment. + """ + link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 + link_to_object = parent_obj._calculate_transform(child_obj, parent_link) + parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] + child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] + + cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, + [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], + link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + parent_obj.cids[child_obj] = cid + child_obj.cids[parent_obj] = cid + self.attachment_event(parent_obj, [parent_obj, child_obj]) + + def detach(self, obj1: Object, obj2: Object) -> None: + """ + Detaches obj2 from obj1. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of pybullet. + Afterward the detachment event of the corresponding BulletWorld will be fired. + + :param obj1: The object from which an object should be detached. + :param obj2: The object which should be detached. + """ + del obj1.attachments[obj2] + del obj2.attachments[obj1] + + p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) + + del obj1.cids[obj2] + del obj2.cids[obj1] + obj1.world.detachment_event(obj1, [obj1, obj2]) + + def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param prev_object: A list of Objects that were already moved, + these will be excluded to prevent loops in the update. + """ + for att_obj in obj.attachments: + if att_obj in prev_object: + continue + if obj.attachments[att_obj][2]: + # Updates the attachment transformation and constraint if the + # attachment is loose, instead of updating the position of all attached objects + link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) + link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 + obj.attachments[att_obj][0] = link_to_object + att_obj.attachments[obj][0] = link_to_object.invert() + p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) + cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], + link_to_object.translation_as_list(), + [0, 0, 0], link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + obj.cids[att_obj] = cid + att_obj.cids[obj] = cid + else: + link_to_object = obj.attachments[att_obj][0] + + world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") + p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), + world_to_object.orientation_as_list(), + physicsClientId=self.client_id) + att_obj._current_pose = world_to_object + self._set_attached_objects(att_obj, prev_object + [obj]) + + def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: + """ + Get the joint limits of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + :return: A tuple containing the upper and the lower limits of the joint. + """ + up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] + return up_lim, low_lim + + def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param obj: The object + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + + def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param obj: The object + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] + return JointType(joint_type) + + def get_object_joint_position(self, obj: Object, joint_name: str) -> float: + """ + Get the state of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + + def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + """ + Get the pose of a link of an articulated object with respect to the world frame. + The pose is given as a tuple of position and orientation. + + :param obj: The object + :param link_name: The name of the link + """ + return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + + def get_object_contact_points(self, obj: Object) -> List: + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :param obj: The object. + :return: A list of all contact points with other objects + """ + return p.getContactPoints(obj.id) + + def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + """ + Get the ID of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + + def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + """ + Get the name of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + + def get_object_link_name(self, obj: Object, link_idx: int) -> str: + """ + Get the name of a link in an articulated object. + + :param obj: The object + :param link_idx: The index of the link (would indicate order). + """ + return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + + def get_object_number_of_joints(self, obj: Object) -> int: + """ + Get the number of joints of an articulated object + + :param obj: The object + """ + return p.getNumJoints(obj.id, self.client_id) + + def reset_joint_state(self, obj: Object, joint_name: str, joint_pose: float) -> None: + """ + Reset the joint state instantly without physics simulation + + :param obj: The object + :param joint_name: The name of the joint + :param joint_pose: The new joint pose + """ + p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + + def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): + """ + Reset the world position and orientation of the base of the object instantaneously, + not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. + + :param obj: The object + :param position: The new position of the object as a vector of x,y,z + :param orientation: The new orientation of the object as a quaternion of x,y,z,w + """ + p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + + def step(self): + """ + Step the world simulation using forward dynamics + """ + p.stepSimulation(self.client_id) + + def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. Optionally a link name can can be provided, if no link + name is provided all links of this object will be colored. + + :param obj: The object which should be colored + :param color: The color as RGBA values between 0 and 1 + :param link: The link name of the link which should be colored + """ + if link == "": + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if obj.links != {}: + for link_id in obj.links.values(): + p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) + + def get_object_color(self, + obj: Object, + link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + """ + This method returns the color of this object or a link of this object. If no link is given then the + return is either: + + 1. A list with the color as RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + object is spawned. + + If a link is specified then the return is a list with RGBA values representing the color of this link. + It may be that this link has no color, in this case the return is None as well as an error message. + + :param obj: The object for which the color should be returned. + :param link: the link name for which the color should be returned. + :return: The color of the object or link, or a dictionary containing every colored link with its color + """ + visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) + swap = {v: k for k, v in obj.links.items()} + links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) + colors = list(map(lambda x: x[7], visual_data)) + link_to_color = dict(zip(links, colors)) + + if link: + if link in link_to_color.keys(): + return link_to_color[link] + elif link not in obj.links.keys(): + rospy.logerr(f"The link '{link}' is not part of this obejct") + return None + else: + rospy.logerr(f"The link '{link}' has no color") + return None + + if len(visual_data) == 1: + return list(visual_data[0][7]) + else: + return link_to_color + + def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case + the axis aligned bounding box of the link will be returned. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :param link_name: The Optional name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + if link_name: + return p.getAABB(obj.id, obj.links[link_name], self.client_id) + else: + return p.getAABB(obj.id, physicsClientId=self.client_id) + + def get_attachment_event(self) -> Event: + """ + Returns the event reference that is fired if an attachment occurs. + + :return: The reference to the attachment event + """ + return self.attachment_event + + def get_detachment_event(self) -> Event: + """ + Returns the event reference that is fired if a detachment occurs. + + :return: The event reference for the detachment event. + """ + return self.detachment_event + + def get_manipulation_event(self) -> Event: + """ + Returns the event reference that is fired if any manipulation occurs. + + :return: The event reference for the manipulation event. + """ + return self.manipulation_event + + def set_realtime(self, real_time: bool) -> None: + """ + Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only + simulated to reason about it. + + :param real_time: Whether the BulletWorld should simulate Physic in real time. + """ + p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + + def set_gravity(self, velocity: List[float]) -> None: + """ + Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity + is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + + :param velocity: The gravity vector that should be used in the BulletWorld. + """ + p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) + + def set_robot(self, robot: Object) -> None: + """ + Sets the global variable for the robot Object. This should be set on spawning the robot. + + :param robot: The Object reference to the Object representing the robot. + """ + BulletWorld.robot = robot + + def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + """ + Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real + time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By + setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real + time. + + :param seconds: The amount of seconds that should be simulated. + :param real_time: If the simulation should happen in real time or faster. + """ + for i in range(0, int(seconds * 240)): + p.stepSimulation(self.client_id) + for objects, callback in self.coll_callbacks.items(): + contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) + # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) + # print(contact_points[0][5]) + if contact_points != (): + callback[0]() + elif callback[1] != None: # Call no collision callback + callback[1]() + if real_time: + # Simulation runs at 240 Hz + time.sleep(0.004167) + + def exit(self) -> None: + """ + Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the + preferred method to close the BulletWorld. + """ + # True if this is NOT the shadow world since it has a reference to the + # Shadow world + time.sleep(0.1) + if self.shadow_world: + self.world_sync.terminate = True + self.world_sync.join() + self.shadow_world.exit() + p.disconnect(self.client_id) + if self._gui_thread: + self._gui_thread.join() + if BulletWorld.current_bullet_world == self: + BulletWorld.current_bullet_world = None + BulletWorld.robot = None + + def save_state(self) -> Tuple[int, Dict]: + """ + Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint + position of every Object in the BulletWorld. + + :return: A unique id of the state + """ + objects2attached = {} + # ToDo find out what this is for and where it is used + for o in self.objects: + objects2attached[o] = (o.attachments.copy(), o.cids.copy()) + return p.saveState(self.client_id), objects2attached + + def restore_state(self, state, objects2attached: Dict = {}) -> None: + """ + Restores the state of the BulletWorld according to the given state id. This includes position, orientation and + joint states. However, restore can not respawn objects if there are objects that were deleted between creation of + the state and restoring they will be skiped. + + :param state: The unique id representing the state, as returned by :func:`~save_state` + :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~bullet_world.Object.attachments` + """ + p.restoreState(state, physicsClientId=self.client_id) + for obj in self.objects: + try: + obj.attachments, obj.cids = objects2attached[obj] + except KeyError: + continue + + def copy(self) -> BulletWorld: + """ + Copies this Bullet World into another and returns it. The other BulletWorld + will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. + This method should only be used if necessary since there can be unforeseen problems. + + :return: The reference to the new BulletWorld + """ + world = BulletWorld("DIRECT") + for obj in self.objects: + o = Object(obj.name, obj.type, obj.path, obj.get_position(), obj.get_orientation(), + world, obj.color) + for joint in obj.joints: + o.set_joint_state(joint, obj.get_joint_state(joint)) + return world + + def add_vis_axis(self, pose: Pose, + length: Optional[float] = 0.2) -> None: + """ + Creates a Visual object which represents the coordinate frame at the given + position and orientation. There can be an unlimited amount of vis axis objects. + + :param pose: The pose at which the axis should be spawned + :param length: Optional parameter to configure the length of the axes + """ + + position, orientation = pose.to_list() + + vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], + rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) + vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], + rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) + vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], + rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) + + obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], + basePosition=position, baseOrientation=orientation, + linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkParentIndices=[0, 0, 0], + linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], + linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], + linkCollisionShapeIndices=[-1, -1, -1]) + + self.vis_axis.append(obj) + + def remove_vis_axis(self) -> None: + """ + Removes all spawned vis axis objects that are currently in this BulletWorld. + """ + for id in self.vis_axis: + p.removeBody(id) + self.vis_axis = [] + + def register_collision_callback(self, objectA: Object, objectB: Object, + callback_collision: Callable, + callback_no_collision: Optional[Callable] = None) -> None: + """ + Registers callback methods for contact between two Objects. There can be a callback for when the two Objects + get in contact and, optionally, for when they are not in contact anymore. + + :param objectA: An object in the BulletWorld + :param objectB: Another object in the BulletWorld + :param callback_collision: A function that should be called if the objects are in contact + :param callback_no_collision: A function that should be called if the objects are not in contact + """ + self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) + + def add_additional_resource_path(self, path: str) -> None: + """ + Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an + Object is spawned only with a filename. + + :param path: A path in the filesystem in which to search for files. + """ + self.data_directory.append(path) + + def get_shadow_object(self, object: Object) -> Object: + """ + Returns the corresponding object from the shadow world for the given object. If the given Object is already in + the shadow world it is returned. + + :param object: The object for which the shadow worlds object should be returned. + :return: The corresponding object in the shadow world. + """ + try: + return self.world_sync.object_mapping[object] + except KeyError: + shadow_world = self if self.is_shadow_world else self.shadow_world + if object in shadow_world.objects: + return object + else: + raise ValueError( + f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") + + def get_bullet_object_for_shadow(self, object: Object) -> Object: + """ + Returns the corresponding object from the main Bullet World for a given + object in the shadow world. If the given object is not in the shadow + world an error will be raised. + + :param object: The object for which the corresponding object in the main Bullet World should be found + :return: The object in the main Bullet World + """ + map = self.world_sync.object_mapping + try: + return list(map.keys())[list(map.values()).index(object)] + except ValueError: + raise ValueError("The given object is not in the shadow world.") + + def reset_bullet_world(self) -> None: + """ + Resets the BulletWorld to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and all objects will be set to the position and + orientation in which they were spawned. + """ + for obj in self.objects: + if obj.attachments: + attached_objects = list(obj.attachments.keys()) + for att_obj in attached_objects: + obj.detach(att_obj) + joint_names = list(obj.joints.keys()) + joint_poses = [0 for j in joint_names] + obj.set_joint_states(dict(zip(joint_names, joint_poses))) + obj.set_pose(obj.original_pose) + + +class Use_shadow_world(): + """ + An environment for using the shadow world, while in this environment the :py:attr:`~BulletWorld.current_bullet_world` + variable will point to the shadow world. + + Example: + with Use_shadow_world(): + NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() + """ + + def __init__(self): + self.prev_world: BulletWorld = None + + def __enter__(self): + if not BulletWorld.current_bullet_world.is_shadow_world: + time.sleep(20 / 240) + # blocks until the adding queue is ready + BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() + # **This is currently not used since the sleep(20/240) seems to be enough, but on weaker hardware this might + # not be a feasible solution** + # while not BulletWorld.current_bullet_world.world_sync.equal_states: + # time.sleep(0.1) + + self.prev_world = BulletWorld.current_bullet_world + BulletWorld.current_bullet_world.world_sync.pause_sync = True + BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.shadow_world + + def __exit__(self, *args): + if not self.prev_world == None: + BulletWorld.current_bullet_world = self.prev_world + BulletWorld.current_bullet_world.world_sync.pause_sync = False + + +class WorldSync(threading.Thread): + """ + Synchronizes the state between the BulletWorld and its shadow world. + Meaning the cartesian and joint position of everything in the shadow world will be + synchronized with the main BulletWorld. + Adding and removing objects is done via queues, such that loading times of objects + in the shadow world does not affect the BulletWorld. + The class provides the possibility to pause the synchronization, this can be used + if reasoning should be done in the shadow world. + """ + + def __init__(self, world: BulletWorld, shadow_world: BulletWorld): + threading.Thread.__init__(self) + self.world: BulletWorld = world + self.shadow_world: BulletWorld = shadow_world + self.shadow_world.world_sync: WorldSync = self + + self.terminate: bool = False + self.add_obj_queue: Queue = Queue() + self.remove_obj_queue: Queue = Queue() + self.pause_sync: bool = False + # Maps bullet to shadow world objects + self.object_mapping: Dict[Object, Object] = {} + self.equal_states = False + + def run(self): + """ + Main method of the synchronization, this thread runs in a loop until the + terminate flag is set. + While this loop runs it continuously checks the cartesian and joint position of + every object in the BulletWorld and updates the corresponding object in the + shadow world. When there are entries in the adding or removing queue the corresponding objects will be added + or removed in the same iteration. + """ + while not self.terminate: + self.check_for_pause() + # self.equal_states = False + for i in range(self.add_obj_queue.qsize()): + obj = self.add_obj_queue.get() + # [name, type, path, position, orientation, self.world.shadow_world, color, bulletworld object] + o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) + # Maps the BulletWorld object to the shadow world object + self.object_mapping[obj[7]] = o + self.add_obj_queue.task_done() + for i in range(self.remove_obj_queue.qsize()): + obj = self.remove_obj_queue.get() + # Get shadow world object reference from object mapping + shadow_obj = self.object_mapping[obj] + shadow_obj.remove() + del self.object_mapping[obj] + self.remove_obj_queue.task_done() + + for bulletworld_obj, shadow_obj in self.object_mapping.items(): + b_pose = bulletworld_obj.get_pose() + s_pose = shadow_obj.get_pose() + if b_pose.dist(s_pose) != 0.0: + shadow_obj.set_pose(bulletworld_obj.get_pose()) + + # Manage joint positions + if len(bulletworld_obj.joints) > 2: + for joint_name in bulletworld_obj.joints.keys(): + if shadow_obj.get_joint_state(joint_name) != bulletworld_obj.get_joint_state(joint_name): + shadow_obj.set_joint_states(bulletworld_obj.get_complete_joint_state()) + break + + self.check_for_pause() + # self.check_for_equal() + time.sleep(1 / 240) + + self.add_obj_queue.join() + self.remove_obj_queue.join() + + def check_for_pause(self) -> None: + """ + Checks if :py:attr:`~self.pause_sync` is true and sleeps this thread until it isn't anymore. + """ + while self.pause_sync: + time.sleep(0.1) + + def check_for_equal(self) -> None: + """ + Checks if both BulletWorlds have the same state, meaning all objects are in the same position. + This is currently not used, but might be used in the future if synchronization issues worsen. + """ + eql = True + for obj, shadow_obj in self.object_mapping.items(): + eql = eql and obj.get_pose() == shadow_obj.get_pose() + self.equal_states = eql + + +class Gui(threading.Thread): + """ + For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~BulletWorld.exit` + Also contains the code for controlling the camera. + """ + + def __init__(self, world, type): + threading.Thread.__init__(self) + self.world: BulletWorld = world + self.type: str = type + + def run(self): + """ + Initializes the new simulation and checks in an endless loop + if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and + thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. + """ + if self.type != "GUI": + self.world.client_id = p.connect(p.DIRECT) + else: + self.world.client_id = p.connect(p.GUI) + + # Disable the side windows of the GUI + p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) + # Change the init camera pose + p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, + cameraTargetPosition=[-2, 0, 1]) + + # Get the initial camera target location + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) + + # Create a sphere with a radius of 0.05 and a mass of 0 + sphereUid = p.createMultiBody(baseMass=0.0, + baseInertialFramePosition=[0, 0, 0], + baseVisualShapeIndex=sphereVisualId, + basePosition=cameraTargetPosition) + + # Define the maxSpeed, used in calculations + maxSpeed = 16 + + # Set initial Camera Rotation + cameraYaw = 50 + cameraPitch = -35 + + # Keep track of the mouse state + mouseState = [0, 0, 0] + oldMouseX, oldMouseY = 0, 0 + + # Determines if the sphere at cameraTargetPosition is visible + visible = 1 + + # Loop to update the camera position based on keyboard events + while p.isConnected(self.world.client_id): + # Monitor user input + keys = p.getKeyboardEvents() + mouse = p.getMouseEvents() + + # Get infos about the camera + width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ + p.getDebugVisualizerCamera()[10] + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + # Get vectors used for movement on x,y,z Vector + xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] + yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] + + # Check the mouse state + if mouse: + for m in mouse: + + mouseX = m[2] + mouseY = m[1] + + # update mouseState + # Left Mouse button + if m[0] == 2 and m[3] == 0: + mouseState[0] = m[4] + # Middle mouse butto (scroll wheel) + if m[0] == 2 and m[3] == 1: + mouseState[1] = m[4] + # right mouse button + if m[0] == 2 and m[3] == 2: + mouseState[2] = m[4] + + # change visibility by clicking the mousewheel + if m[4] == 6 and m[3] == 1 and visible == 1: + visible = 0 + elif m[4] == 6 and visible == 0: + visible = 1 + + # camera movement when the left mouse button is pressed + if mouseState[0] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed + + # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) + if mouseX < oldMouseX: + if (cameraPitch + speedX) < 89.5: + cameraPitch += (speedX / 4) + 1 + elif mouseX > oldMouseX: + if (cameraPitch - speedX) > -89.5: + cameraPitch -= (speedX / 4) + 1 + + if mouseY < oldMouseY: + cameraYaw += (speedY / 4) + 1 + elif mouseY > oldMouseY: + cameraYaw -= (speedY / 4) + 1 + + if mouseState[1] == 3: + speedX = abs(oldMouseX - mouseX) + factor = 0.05 + + if mouseX < oldMouseX: + dist = dist - speedX * factor + elif mouseX > oldMouseX: + dist = dist + speedX * factor + dist = max(dist, 0.1) + + # camera movement when the right mouse button is pressed + if mouseState[2] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 + factor = 0.05 + + if mouseX < oldMouseX: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + elif mouseX > oldMouseX: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + + if mouseY < oldMouseY: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + elif mouseY > oldMouseY: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + # update oldMouse values + oldMouseY, oldMouseX = mouseY, mouseX + + # check the keyboard state + if keys: + # if shift is pressed, double the speed + if p.B3G_SHIFT in keys: + speedMult = 5 + else: + speedMult = 2.5 + + # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key + # change + if p.B3G_CONTROL in keys: + + # the up and down arrowkeys cause the targetPos to move along the z axis of the map + if p.B3G_DOWN_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + elif p.B3G_UP_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + + # left and right arrowkeys cause the targetPos to move horizontally relative to the camera + if p.B3G_LEFT_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + elif p.B3G_RIGHT_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + + # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera + # while the camera stays at a constant distance. SHIFT + '=' is for US layout + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + elif ord("-") in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + + # standard bindings for thearrowkeys, the '+' as well as the '-' key + else: + + # left and right arrowkeys cause the camera to rotate around the yaw axis + if p.B3G_RIGHT_ARROW in keys: + cameraYaw += (360 / width) * speedMult + elif p.B3G_LEFT_ARROW in keys: + cameraYaw -= (360 / width) * speedMult + + # the up and down arrowkeys cause the camera to rotate around the pitch axis + if p.B3G_DOWN_ARROW in keys: + if (cameraPitch + (360 / height) * speedMult) < 89.5: + cameraPitch += (360 / height) * speedMult + elif p.B3G_UP_ARROW in keys: + if (cameraPitch - (360 / height) * speedMult) > -89.5: + cameraPitch -= (360 / height) * speedMult + + # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without + # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + if (dist - (dist * 0.02) * speedMult) > 0.1: + dist -= dist * 0.02 * speedMult + elif ord("-") in keys: + dist += dist * 0.02 * speedMult + + p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, + cameraTargetPosition=cameraTargetPosition) + if visible == 0: + cameraTargetPosition = (0.0, -50, 50) + p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) + time.sleep(1. / 80.) + + +class Object: + """ + Represents a spawned Object in the BulletWorld. + """ + + def __init__(self, name: str, type: Union[str, ObjectType], path: str, + pose: Pose = None, + world: BulletWorld = None, + color: Optional[List[float]] = [1, 1, 1, 1], + ignoreCachedFiles: Optional[bool] = False): + """ + The constructor loads the urdf file into the given BulletWorld, if no BulletWorld is specified the + :py:attr:`~BulletWorld.current_bullet_world` will be used. It is also possible to load .obj and .stl file into the BulletWorld. + The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. + + :param name: The name of the object + :param type: The type of the object + :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched + :param pose: The pose at which the Object should be spawned + :param world: The BulletWorld in which the object should be spawned, if no world is specified the :py:attr:`~BulletWorld.current_bullet_world` will be used + :param color: The color with which the object should be spawned. + :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. + """ + if not pose: + pose = Pose() + self.world: BulletWorld = world if world is not None else BulletWorld.current_bullet_world + self.local_transformer = LocalTransformer() + self.name: str = name + self.type: str = type + self.color: List[float] = color + pose_in_map = self.local_transformer.transform_pose(pose, "map") + position, orientation = pose_in_map.to_list() + self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) + self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") + self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") + self.attachments: Dict[Object, List] = {} + self.cids: Dict[Object, int] = {} + self.original_pose = pose_in_map + + self.tf_frame = ("shadow/" if self.world.is_shadow_world else "") + self.name + "_" + str(self.id) + + # This means "world" is not the shadow world since it has a reference to a shadow world + if self.world.shadow_world != None: + self.world.world_sync.add_obj_queue.put( + [name, type, path, position, orientation, self.world.shadow_world, color, self]) + + with open(self.path) as f: + self.urdf_object = URDF.from_xml_string(f.read()) + if self.urdf_object.name == robot_description.name and not BulletWorld.robot: + BulletWorld.robot = self + + self.links[self.urdf_object.get_root()] = -1 + + self._current_pose = pose_in_map + self._current_link_poses = {} + self._current_link_transforms = {} + self._current_joint_states = {} + self._init_current_joint_states() + self._update_link_poses() + + self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) + self.local_transformer.update_transforms_for_object(self) + self.link_to_geometry = self._get_geometry_for_link() + + self.world.objects.append(self) + + def __repr__(self): + skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", + "_current_link_transforms", "link_to_geometry"] + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" + + def remove(self) -> None: + """ + Removes this object from the BulletWorld it currently resides in. + For the object to be removed it has to be detached from all objects it + is currently attached to. After this is done a call to PyBullet is done + to remove this Object from the simulation. + """ + for obj in self.attachments.keys(): + self.world.detach(self, obj) + self.world.objects.remove(self) + # This means the current world of the object is not the shadow world, since it + # has a reference to the shadow world + if self.world.shadow_world is not None: + self.world.world_sync.remove_obj_queue.put(self) + self.world.world_sync.remove_obj_queue.join() + self.world.remove_object(self.id) + if BulletWorld.robot == self: + BulletWorld.robot = None + + def detach_all(self) -> None: + """ + Detach all objects attached to this object. + """ + attachments = self.attachments.copy() + for att in attachments.keys(): + self.world.detach(self, att) + + def get_position(self) -> Pose: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_pose().position + + def get_orientation(self) -> Quaternion: + """ + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw + """ + return self.get_pose().orientation + + def get_pose(self) -> Pose: + """ + Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. + + :return: The current pose of this object + """ + return self._current_pose + + def set_pose(self, pose: Pose, base: bool = False) -> None: + """ + Sets the Pose of the object. + + :param pose: New Pose for the object + :param base: If True places the object base instead of origin at the specified position and orientation + """ + pose_in_map = self.local_transformer.transform_pose(pose, "map") + position, orientation = pose_in_map.to_list() + if base: + position = np.array(position) + self.base_origin_shift + self.world.reset_object_base_pose(self, position, orientation) + self._current_pose = pose_in_map + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + @property + def pose(self) -> Pose: + """ + Property that returns the current position of this Object. + + :return: The position as a list of xyz + """ + return self.get_pose() + + @pose.setter + def pose(self, value: Pose) -> None: + """ + Sets the Pose of the Object to the given value. Function for attribute use. + + :param value: New Pose of the Object + """ + self.set_pose(value) + + def move_base_to_origin_pos(self) -> None: + """ + Move the object such that its base will be at the current origin position. + This is useful when placing objects on surfaces where you want the object base in contact with the surface. + """ + self.set_pose(self.get_pose(), base=True) + + def _calculate_transform(self, obj: Object, link: str = None) -> Transform: + """ + Calculates the transformation between another object and the given + link of this object. If no link is provided then the base position will be used. + + :param obj: The other object for which the transformation should be calculated + :param link: The optional link name + :return: The transformation from the link (or base position) to the other objects base position + """ + transform = self.local_transformer.transform_to_object_frame(obj.pose, self, link) + + return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + + def set_position(self, position: Union[Pose, Point], base=False) -> None: + """ + Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position + instead of the origin in the center of the Object. The given position can either be a Pose, + in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + + :param position: Target position as xyz. + :param base: If the bottom of the Object should be placed or the origin in the center. + """ + pose = Pose() + if isinstance(position, Pose): + target_position = position.position + pose.frame = position.frame + else: + target_position = position + + pose.pose.position = target_position + pose.pose.orientation = self.get_orientation() + self.set_pose(pose, base=base) + + def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: + """ + Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only + the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. + + :param orientation: Target orientation given as a list of xyzw. + """ + pose = Pose() + if isinstance(orientation, Pose): + target_orientation = orientation.orientation + pose.frame = orientation.frame + else: + target_orientation = orientation + + pose.pose.position = self.get_position() + pose.pose.orientation = target_orientation + self.set_pose(pose) + + def _joint_or_link_name_to_id(self, name_type: str) -> Dict[str, int]: + """ + Creates a dictionary which maps the link or joint name to the unique ids used by pybullet. + + :param name_type: Determines if the dictionary should be for joints or links + :return: A dictionary that maps joint or link names to unique ids + """ + n_joints = self.world.get_object_number_of_joints(self) + joint_name_to_id = {} + for i in range(0, n_joints): + _id = self.world.get_object_joint_id(self, i) + if name_type == "joint": + _name = self.world.get_object_joint_name(self, i) + else: + _name = self.world.get_object_link_name(self, i) + joint_name_to_id[_name] = _id + return joint_name_to_id + + def get_joint_id(self, name: str) -> int: + """ + Returns the unique id for a joint name. As used by PyBullet. + + :param name: The joint name + :return: The unique id + """ + return self.joints[name] + + def get_link_id(self, name: str) -> int: + """ + Returns a unique id for a link name. As used by PyBullet. + + :param name: The link name + :return: The unique id + """ + return self.links[name] + + def get_link_by_id(self, id: int) -> str: + """ + Returns the name of a link for a given unique PyBullet id + + :param id: PyBullet id for link + :return: The link name + """ + return dict(zip(self.links.values(), self.links.keys()))[id] + + def get_joint_by_id(self, joint_id: int) -> str: + """ + Returns the joint name for a unique PyBullet id + + :param joint_id: The Pybullet id of for joint + :return: The joint name + """ + return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] + + def get_link_relative_to_other_link(self, source_frame: str, target_frame: str) -> Pose: + """ + Calculates the position of a link in the coordinate frame of another link. + + :param source_frame: The name of the source frame + :param target_frame: The name of the target frame + :return: The pose of the source frame in the target frame + """ + source_pose = self.get_link_pose(source_frame) + return self.local_transformer.transform_to_object_frame(source_pose, self, target_frame) + + def get_link_position(self, name: str) -> Point: + """ + Returns the position of a link of this Object. Position is returned as a list of xyz. + + :param name: The link name + :return: The link position as xyz + """ + return self.get_link_pose(name).position + + def get_link_orientation(self, name: str) -> Quaternion: + """ + Returns the orientation of a link of this Object. Orientation is returned as a quaternion. + + :param name: The name of the link + :return: The orientation of the link as a quaternion + """ + return self.get_link_pose(name).orientation + + def get_link_pose(self, name: str) -> Pose: + """ + Returns a Pose of the link corresponding to the given name. The returned Pose will be in world coordinate frame. + + :param name: Link name for which a Pose should be returned + :return: The pose of the link + """ + if name in self.links.keys() and self.links[name] == -1: + return self.get_pose() + return self._current_link_poses[name] + # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) + + def set_joint_state(self, joint_name: str, joint_pose: float) -> None: + """ + Sets the state of the given joint to the given joint pose. If the pose is outside the joint limits, as stated + in the URDF, an error will be printed. However, the joint will be set either way. + + :param joint_name: The name of the joint + :param joint_pose: The target pose for this joint + """ + # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly + up_lim, low_lim = self.world.get_object_joint_limits(self, joint_name) + if low_lim > up_lim: + low_lim, up_lim = up_lim, low_lim + if not low_lim <= joint_pose <= up_lim: + logging.error( + f"The joint position has to be within the limits of the joint. The joint limits for {joint_name} are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_pose}") + # Temporarily disabled because kdl outputs values exciting joint limits + # return + self.world.reset_joint_state(self, joint_name, joint_pose) + self._current_joint_states[joint_name] = joint_pose + # self.local_transformer.update_transforms_for_object(self) + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + def set_joint_states(self, joint_poses: dict) -> None: + """ + Sets the current state of multiple joints at once, this method should be preferred when setting multiple joints + at once instead of running :func:`~Object.set_joint_state` in a loop. + + :param joint_poses: + :return: + """ + for joint_name, joint_pose in joint_poses.items(): + self.world.reset_joint_state(self, joint_name, joint_pose) + self._current_joint_states[joint_name] = joint_pose + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + def get_joint_state(self, joint_name: str) -> float: + """ + Returns the joint state for the given joint name. + + :param joint_name: The name of the joint + :return: The current pose of the joint + """ + return self._current_joint_states[joint_name] + + def contact_points(self) -> List: + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :return: A list of all contact points with other objects + """ + return self.world.get_object_contact_points(self) + + def contact_points_simulated(self) -> List: + """ + Returns a list of all contact points between this Object and other Objects after stepping the simulation once. + For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :return: A list of contact points between this Object and other Objects + """ + s = self.world.save_state() + self.world.step() + contact_points = self.contact_points() + self.world.restore_state(*s) + return contact_points + + def update_joints_from_topic(self, topic_name: str) -> None: + """ + Updates the joints of this object with positions obtained from a topic with the message type JointState. + Joint names on the topic have to correspond to the joints of this object otherwise an error message will be logged. + + :param topic_name: Name of the topic with the joint states + """ + msg = rospy.wait_for_message(topic_name, JointState) + joint_names = msg.name + joint_positions = msg.position + if set(joint_names).issubset(self.joints.keys()): + for i in range(len(joint_names)): + self.set_joint_state(joint_names[i], joint_positions[i]) + else: + add_joints = set(joint_names) - set(self.joints.keys()) + rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ + The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") + + def update_pose_from_tf(self, frame: str) -> None: + """ + Updates the pose of this object from a TF message. + + :param frame: Name of the TF frame from which the position should be taken + """ + tf_listener = tf.TransformListener() + time.sleep(0.5) + position, orientation = tf_listener.lookupTransform(frame, "map", rospy.Time(0)) + position = [position[0][0] * -1, + position[0][1] * -1, + position[0][2]] + self.set_position(Pose(position, orientation)) + + def set_color(self, color: List[float], link: Optional[str] = "") -> None: + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. Optionally a link name can can be provided, if no link + name is provided all links of this object will be colored. + + :param color: The color as RGBA values between 0 and 1 + :param link: The link name of the link which should be colored + """ + self.world.set_object_color(self, color, link) + + def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + """ + This method returns the color of this object or a link of this object. If no link is given then the + return is either: + + 1. A list with the color as RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + object is spawned. + + If a link is specified then the return is a list with RGBA values representing the color of this link. + It may be that this link has no color, in this case the return is None as well as an error message. + + :param link: the link name for which the color should be returned. + :return: The color of the object or link, or a dictionary containing every colored link with its color + """ + return self.world.get_object_color(self, link) + + def get_AABB(self, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case + the axis aligned bounding box of the link will be returned. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param link_name: The Optional name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + return self.world.get_object_AABB(self, link_name) + + def get_base_origin(self, link_name: Optional[str] = None) -> Pose: + """ + Returns the origin of the base/bottom of an object/link + + :param link_name: The link name for which the bottom position should be returned + :return: The position of the bottom of this Object or link + """ + aabb = self.get_AABB(link_name=link_name) + base_width = np.absolute(aabb[0][0] - aabb[1][0]) + base_length = np.absolute(aabb[0][1] - aabb[1][1]) + return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], + self.get_pose().orientation_as_list()) + + def get_joint_limits(self, joint: str) -> Tuple[float, float]: + """ + Returns the lower and upper limit of a joint, if the lower limit is higher + than the upper they are swapped to ensure the lower limit is always the smaller one. + + :param joint: The name of the joint for which the limits should be found. + :return: The lower and upper limit of the joint. + """ + if joint not in self.joints.keys(): + raise KeyError(f"The given Joint: {joint} is not part of this object") + lower, upper = self.world.get_object_joint_limits(self, joint) + if lower > upper: + lower, upper = upper, lower + return lower, upper + + def get_joint_axis(self, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return self.world.get_object_joint_axis(self, joint_name) + + def get_joint_type(self, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + return self.world.get_object_joint_type(self, joint_name) + + def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + """ + Traverses the chain from 'link_name' to the URDF origin and returns the first joint that is of type 'joint_type'. + + :param link_name: Link name above which the joint should be found + :param joint_type: Joint type that should be searched for + :return: Name of the first joint which has the given type + """ + chain = self.urdf_object.get_chain(self.urdf_object.get_root(), link_name) + reversed_chain = reversed(chain) + container_joint = None + for element in reversed_chain: + if element in self.joints and self.get_joint_type(element) == joint_type: + container_joint = element + break + if not container_joint: + rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") + return container_joint + + def get_complete_joint_state(self) -> Dict[str: float]: + """ + Returns the complete joint state of the object as a dictionary of joint names and joint values. + + :return: A dictionary with the complete joint state + """ + return self._current_joint_states + + def get_link_tf_frame(self, link_name: str) -> str: + """ + Returns the name of the tf frame for the given link name. This method does not check if the given name is + actually a link of this object. + + :param link_name: Name of a link for which the tf frame should be returned + :return: A TF frame name for a specific link + """ + return self.tf_frame + "/" + link_name + + def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: + """ + Extracts the geometry information for each collision of each link and links them to the respective link. + + :return: A dictionary with link name as key and geometry information as value + """ + link_to_geometry = {} + for link in self.links.keys(): + link_obj = self.urdf_object.link_map[link] + if not link_obj.collision: + link_to_geometry[link] = None + else: + link_to_geometry[link] = link_obj.collision.geometry + return link_to_geometry + + def _update_link_poses(self) -> None: + """ + Updates the cached poses and transforms for each link of this Object + """ + for link_name in self.links.keys(): + if link_name == self.urdf_object.get_root(): + self._current_link_poses[link_name] = self._current_pose + self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) + else: + self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) + self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( + self.get_link_tf_frame(link_name)) + + def _init_current_joint_states(self) -> None: + """ + Initialize the cached joint position for each joint. + """ + for joint_name in self.joints.keys(): + self._current_joint_states[joint_name] = self.world.get_object_joint_position(self, joint_name) + + +def filter_contact_points(contact_points, exclude_ids) -> List: + """ + Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. + + :param contact_points: A list of contact points + :param exclude_ids: A list of unique ids of Objects that should be removed from the list + :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' + """ + return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) + + +def get_path_from_data_dir(file_name: str, data_directory: str) -> str: + """ + Returns the full path for a given file name in the given directory. If there is no file with the given filename + this method returns None. + + :param file_name: The filename of the searched file. + :param data_directory: The directory in which to search for the file. + :return: The full path in the filesystem or None if there is no file with the filename in the directory + """ + dir = pathlib.Path(data_directory) + for file in os.listdir(data_directory): + if file == file_name: + return data_directory + f"/{file_name}" + + +def _get_robot_name_from_urdf(urdf_string: str) -> str: + """ + Extracts the robot name from the 'robot_name' tag of a URDF. + + :param urdf_string: The URDF as string. + :return: The name of the robot described by the URDF. + """ + res = re.findall(r"robot\ *name\ *=\ *\"\ *[a-zA-Z_0-9]*\ *\"", urdf_string) + if len(res) == 1: + begin = res[0].find("\"") + end = res[0][begin + 1:].find("\"") + robot = res[0][begin + 1:begin + 1 + end].lower() + return robot + + +def _load_object(name: str, + path: str, + position: List[float], + orientation: List[float], + world: BulletWorld, + color: List[float], + ignoreCachedFiles: bool) -> Tuple[int, str]: + """ + Loads an object to the given BulletWorld with the given position and orientation. The color will only be + used when an .obj or .stl file is given. + If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created + and this URDf file will be loaded instead. + When spawning a URDf file a new file will be created in the cache directory, if there exists none. + This new file will have resolved mesh file paths, meaning there will be no references + to ROS packges instead there will be absolute file paths. + + :param name: The name of the object which should be spawned + :param path: The path to the source file or the name on the ROS parameter server + :param position: The position in which the object should be spawned + :param orientation: The orientation in which the object should be spawned + :param world: The BulletWorld to which the Object should be spawned + :param color: The color of the object, only used when .obj or .stl file is given + :param ignoreCachedFiles: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path to the file used for spawning + """ + pa = pathlib.Path(path) + extension = pa.suffix + world, world_id = _world_and_id(world) + if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): + for dir in world.data_directory: + path = get_path_from_data_dir(path, dir) + if path: break + + if not path: + raise FileNotFoundError( + f"File {pa.name} could not be found in the resource directory {world.data_directory}") + # rospack = rospkg.RosPack() + # cach_dir = rospack.get_path('pycram') + '/resources/cached/' + cach_dir = world.data_directory[0] + '/cached/' + if not pathlib.Path(cach_dir).exists(): + os.mkdir(cach_dir) + + # if file is not yet cached corrcet the urdf and save if in the cache directory + if not _is_cached(path, name, cach_dir) or ignoreCachedFiles: + if extension == ".obj" or extension == ".stl": + path = _generate_urdf_file(name, path, color, cach_dir) + elif extension == ".urdf": + with open(path, mode="r") as f: + urdf_string = fix_missing_inertial(f.read()) + urdf_string = remove_error_tags(urdf_string) + urdf_string = fix_link_attributes(urdf_string) + try: + urdf_string = _correct_urdf_string(urdf_string) + except rospkg.ResourceNotFound as e: + rospy.logerr(f"Could not find resource package linked in this URDF") + raise e + path = cach_dir + pa.name + with open(path, mode="w") as f: + f.write(urdf_string) + else: # Using the urdf from the parameter server + urdf_string = rospy.get_param(path) + path = cach_dir + name + ".urdf" + with open(path, mode="w") as f: + f.write(_correct_urdf_string(urdf_string)) + # save correct path in case the file is already in the cache directory + elif extension == ".obj" or extension == ".stl": + path = cach_dir + pa.stem + ".urdf" + elif extension == ".urdf": + path = cach_dir + pa.name + else: + path = cach_dir + name + ".urdf" + + try: + obj = p.loadURDF(path, basePosition=position, baseOrientation=orientation, physicsClientId=world_id) + return obj, path + except p.error as e: + logging.error( + "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") + os.remove(path) + raise (e) + # print(f"{bcolors.BOLD}{bcolors.WARNING}The path has to be either a path to a URDf file, stl file, obj file or the name of a URDF on the parameter server.{bcolors.ENDC}") + + +def _is_cached(path: str, name: str, cach_dir: str) -> bool: + """ + Checks if the file in the given path is already cached or if + there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from + the parameter server is used. + + :param path: The path given by the user to the source file. + :param name: The name for this object. + :param cach_dir: The absolute path the cach directory in the pycram package. + :return: True if there already exists a chached file, False in any other case. + """ + file_name = pathlib.Path(path).name + p = pathlib.Path(cach_dir + file_name) + if p.exists(): + return True + # Returns filename without the filetype, e.g. returns "test" for "test.txt" + file_stem = pathlib.Path(path).stem + p = pathlib.Path(cach_dir + file_stem + ".urdf") + if p.exists(): + return True + return False + + +def _correct_urdf_string(urdf_string: str) -> str: + """ + Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS + package paths. + + :param urdf_name: The name of the URDf on the parameter server + :return: The URDF string with paths in the filesystem instead of ROS packages + """ + r = rospkg.RosPack() + new_urdf_string = "" + for line in urdf_string.split('\n'): + if "package://" in line: + s = line.split('//') + s1 = s[1].split('/') + path = r.get_path(s1[0]) + line = line.replace("package://" + s1[0], path) + new_urdf_string += line + '\n' + + return fix_missing_inertial(new_urdf_string) + + +def fix_missing_inertial(urdf_string: str) -> str: + """ + Insert inertial tags for every URDF link that has no inertia. + This is used to prevent PyBullet from dumping warnings in the terminal + + :param urdf_string: The URDF description as string + :returns: The new, corrected URDF description as string. + """ + + inertia_tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.Element("inertial")) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("mass", {"value": "0.1"})) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("inertia", {"ixx": "0.01", + "ixy": "0", + "ixz": "0", + "iyy": "0.01", + "iyz": "0", + "izz": "0.01"})) + + # create tree from string + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + + for link_element in tree.iter("link"): + inertial = [*link_element.iter("inertial")] + if len(inertial) == 0: + link_element.append(inertia_tree.getroot()) + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def remove_error_tags(urdf_string: str) -> str: + """ + Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the + URDF_parser + + :param urdf_string: String of the URDF from which the tags should be removed + :return: The URDF string with the tags removed + """ + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + removing_tags = ["gazebo", "transmission"] + for tag_name in removing_tags: + all_tags = tree.findall(tag_name) + for tag in all_tags: + tree.getroot().remove(tag) + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def fix_link_attributes(urdf_string: str) -> str: + """ + Removes the attribute 'type' from links since this is not parsable by the URDF parser. + + :param urdf_string: The string of the URDF from which the attributes should be removed + :return: The URDF string with the attributes removed + """ + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + + for link in tree.iter("link"): + if "type" in link.attrib.keys(): + del link.attrib["type"] + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) -> str: + """ + Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be + used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name + as filename. + + :param name: The name of the object + :param path: The path to the .obj or .stl file + :param color: The color which should be used for the material tag + :param cach_dir The absolute file path to the cach directory in the pycram package + :return: The absolute path of the created file + """ + urdf_template = ' \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + ' + urdf_template = fix_missing_inertial(urdf_template) + rgb = " ".join(list(map(str, color))) + pathlib_obj = pathlib.Path(path) + path = str(pathlib_obj.resolve()) + content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) + with open(cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: + file.write(content) + return cach_dir + pathlib_obj.stem + ".urdf" + + +def _world_and_id(world: BulletWorld) -> Tuple[BulletWorld, int]: + """ + Selects the world to be used. If the given world is None the 'current_bullet_world' is used. + + :param world: The world which should be used or None if 'current_bullet_world' should be used + :return: The BulletWorld object and the id of this BulletWorld + """ + world = world if world is not None else BulletWorld.current_bullet_world + id = world.client_id if world is not None else BulletWorld.current_bullet_world.client_id + return world, id From 1953249a15551dd0288caa37959fe72ac9eae2b5 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 30 Nov 2023 12:21:34 +0100 Subject: [PATCH 002/195] [RefactoringObjectClass] Now object class is independent of pybullet, and the tests are passing --- demos/pycram_bullet_world_demo/demo.py | 2 +- demos/pycram_ur5_demo/demo.py | 2 +- doc/source/notebooks/bullet_world.ipynb | 559 ++++- doc/source/notebooks/giskard.ipynb | 267 ++- src/pycram/bullet_world.py | 38 +- src/pycram/costmaps.py | 4 +- src/pycram/designator.py | 4 +- src/pycram/designators/action_designator.py | 2 +- src/pycram/designators/location_designator.py | 4 +- src/pycram/designators/motion_designator.py | 2 +- src/pycram/designators/object_designator.py | 2 +- src/pycram/external_interfaces/giskard.py | 2 +- src/pycram/external_interfaces/ik.py | 2 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/helper.py | 4 +- src/pycram/local_transformer.py | 2 +- src/pycram/pose_generator_and_validator.py | 4 +- .../process_modules/boxy_process_modules.py | 22 +- .../process_modules/donbot_process_modules.py | 16 +- .../process_modules/hsr_process_modules.py | 14 +- .../process_modules/pr2_process_modules.py | 36 +- .../resolver/location/giskard_location.py | 2 +- src/pycram/resolver/location/jpt_location.py | 2 +- src/pycram/ros/force_torque_sensor.py | 2 +- src/pycram/ros/joint_state_publisher.py | 4 +- src/pycram/ros/robot_state_updater.py | 4 +- src/pycram/ros/tf_broadcaster.py | 2 +- src/pycram/ros/viz_marker_publisher.py | 2 +- src/pycram/task.py | 2 +- src/pycram/world.py | 1866 ----------------- ..._world_reasoning.py => world_reasoning.py} | 4 +- test/local_transformer_tests.py | 2 +- test/test_action_designator.py | 8 +- test/test_bullet_world.py | 2 +- test/test_bullet_world_reasoning.py | 2 +- test/test_database_resolver.py | 2 +- test/test_jpt_resolver.py | 2 +- test/test_location_designator.py | 4 +- 38 files changed, 929 insertions(+), 1973 deletions(-) mode change 120000 => 100644 doc/source/notebooks/bullet_world.ipynb mode change 120000 => 100644 doc/source/notebooks/giskard.ipynb delete mode 100644 src/pycram/world.py rename src/pycram/{bullet_world_reasoning.py => world_reasoning.py} (99%) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index c19ad349c..0216c5474 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -2,7 +2,7 @@ from pycram.designators.location_designator import * from pycram.designators.object_designator import * from pycram.pose import Pose -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object from pycram.process_module import simulated_robot, with_simulated_robot from pycram.enums import ObjectType diff --git a/demos/pycram_ur5_demo/demo.py b/demos/pycram_ur5_demo/demo.py index 2c6d12a08..2fc87dc42 100644 --- a/demos/pycram_ur5_demo/demo.py +++ b/demos/pycram_ur5_demo/demo.py @@ -5,7 +5,7 @@ import pybullet as pb from pycram import robot_description -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object from pycram.pose import Pose from pycram.ros.force_torque_sensor import ForceTorqueSensor from pycram.ros.joint_state_publisher import JointStatePublisher diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb deleted file mode 120000 index bdb627d54..000000000 --- a/doc/source/notebooks/bullet_world.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/bullet_world.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb new file mode 100644 index 000000000..cf736fd77 --- /dev/null +++ b/doc/source/notebooks/bullet_world.ipynb @@ -0,0 +1,558 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "8d2d6a94", + "metadata": {}, + "source": [ + "# Bullet World\n", + "This Notebook will show you the basics of working with the PyCRAM BulletWorld.\n", + "\n", + "First we need to import and create a BulletWorld." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "23bbba35", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:48.492859720Z", + "start_time": "2023-11-30T09:27:47.729848173Z" + } + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "pybullet build time: Nov 28 2023 23:51:11\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/action_designator.py:10: SAWarning: Implicitly combining column Designator.dtype with column Action.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", + " class Action(MapperArgsMixin, Designator):\n", + "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/motion_designator.py:16: SAWarning: Implicitly combining column Designator.dtype with column Motion.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", + " class Motion(MapperArgsMixin, Designator):\n", + "[WARN] [1701336468.169695]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1701336468.173591]: Failed to import Giskard messages\n" + ] + } + ], + "source": [ + "from pycram.world import BulletWorld\n", + "from pycram.pose import Pose\n", + "from pycram.enums import ObjectType\n", + "\n", + "world = BulletWorld()" + ] + }, + { + "cell_type": "markdown", + "id": "dccaf6ff", + "metadata": {}, + "source": [ + "This new window is the BulletWorld, PyCRAMs internal physics simulation. You can use the mouse to move the camera around:\n", + "\n", + " * Press the left mouse button to rotate the camera\n", + " * Press the right mouse button to move the camera \n", + " * Press the middle mouse button (scroll wheel) and move the mouse up or down to zoom\n", + " \n", + "At the moment the BulletWorld only contains a floor, this is spawned by default when creating the BulletWorld. Furthermore, the gravity is set to 9.8 m^2, which is the same gravitation as the one on earth. \n", + " " + ] + }, + { + "cell_type": "markdown", + "id": "4403bf9c", + "metadata": {}, + "source": [ + "To close the BulletWorld again please use the ```exit``` method since it will also terminate threads running in the background" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "b1e6ed82", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T08:32:14.940359764Z", + "start_time": "2023-11-30T08:32:14.691411659Z" + } + }, + "outputs": [], + "source": [ + "world.exit()" + ] + }, + { + "cell_type": "markdown", + "id": "e0fc7086", + "metadata": {}, + "source": [ + "To spawn new things in the BulletWorld we need to import the Object class and create and instance of it. " + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "48a3aed2", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:52.209614939Z", + "start_time": "2023-11-30T09:27:52.159974972Z" + } + }, + "outputs": [], + "source": [ + "from pycram.world import Object\n", + "\n", + "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([0, 0, 1]))" + ] + }, + { + "cell_type": "markdown", + "id": "8a754f12", + "metadata": {}, + "source": [ + "As you can see this spawns a milk floating in the air. What we did here was create a new Object which has the name \"milk\" as well as the type ```ObjectType.MILK ``` , is spawned from the file \"milk.stl\" and is at the position [0, 0, 1]. \n", + "\n", + "The type of an Object can either be from the enum ObjectType or a string. However, it is recommended to use the enum since this would make for a more consistent naming of types which makes it easiert to work with types. But since the types of the enum might not fit your case you can also use strings. \n", + "\n", + "The first three of these parameters are required while the position is optional. As you can see it was sufficent to only specify the filename for PyCRAM to spawn the milk mesh. When only providing a filename PyCRAM will search in its resource directory for a matching file and use it. \n", + "\n", + "For a complete list of all parameters that can be used to crate an Object please check the documentation. \n", + "\n", + "\n", + "\n", + "Since the Object is spawned we can now interact with it. First we want to move it around and change it's orientation" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "4ae2bc42", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:57.498773893Z", + "start_time": "2023-11-30T09:27:57.497252820Z" + } + }, + "outputs": [], + "source": [ + "milk.set_position(Pose([1, 1, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "4adc7b11", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:57.867485393Z", + "start_time": "2023-11-30T09:27:57.865626321Z" + } + }, + "outputs": [], + "source": [ + "milk.set_orientation(Pose(orientation=[1,0, 0, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "id": "f91d1809", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:58.203719277Z", + "start_time": "2023-11-30T09:27:58.201735028Z" + } + }, + "outputs": [], + "source": [ + "milk.set_pose(Pose([0, 0, 1], [0, 0, 0, 1]))" + ] + }, + { + "cell_type": "markdown", + "id": "5805be38", + "metadata": {}, + "source": [ + "In the same sense as setting the position or orientation you can also get the position and orientation." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "id": "1db2aa78", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:27:59.859274393Z", + "start_time": "2023-11-30T09:27:59.856354972Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Position: \n", + "x: 0.0\n", + "y: 0.0\n", + "z: 1.0\n", + "Orientation: \n", + "x: 0.0\n", + "y: 0.0\n", + "z: 0.0\n", + "w: 1.0\n", + "Pose: \n", + "header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1701336478\n", + " nsecs: 200602293\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 1.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0\n" + ] + } + ], + "source": [ + "print(f\"Position: \\n{milk.get_position()}\")\n", + "\n", + "print(f\"Orientation: \\n{milk.get_orientation()}\")\n", + "\n", + "print(f\"Pose: \\n{milk.get_pose()}\")" + ] + }, + { + "cell_type": "markdown", + "id": "68c02db9", + "metadata": {}, + "source": [ + "## Attachments\n", + "You can attach Objects to each other simply by calling the attach method on one of them and providing the other as parameter. Since attachments are bi-directional it doesn't matter on which Object you call the method. \n", + "\n", + "First we neeed another Object" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "id": "10a493b1", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:02.809496385Z", + "start_time": "2023-11-30T09:28:02.808590814Z" + } + }, + "outputs": [], + "source": [ + "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", pose=Pose([1, 0, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "id": "275372e3", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:03.828259221Z", + "start_time": "2023-11-30T09:28:03.825819607Z" + } + }, + "outputs": [], + "source": [ + "milk.attach(cereal)" + ] + }, + { + "cell_type": "markdown", + "id": "5577c567", + "metadata": {}, + "source": [ + "Now since they are attached to each other, if we move one of them the other will move in conjunction." + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "id": "dff85834", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:05.435992616Z", + "start_time": "2023-11-30T09:28:05.433266300Z" + } + }, + "outputs": [], + "source": [ + "milk.set_position(Pose([1,1,1]))" + ] + }, + { + "cell_type": "markdown", + "id": "196bd705", + "metadata": {}, + "source": [ + "In the same way the Object can also be detached, just call the detach method on one of the two attached Objects." + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "id": "b0bba145", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:06.817969292Z", + "start_time": "2023-11-30T09:28:06.815384873Z" + } + }, + "outputs": [], + "source": [ + "cereal.detach(milk)" + ] + }, + { + "cell_type": "markdown", + "id": "e5e44a67", + "metadata": {}, + "source": [ + "## Links and Joints\n", + "Objects spawned from mesh files do not have links or joints, but if you spawn things from a URDF like a robot they will have a lot of links and joints. Every Object has two dictionaries as attributes namley ```links``` and ```joints``` which contain every link or joint as key and a unique id, used by PyBullet, as value. \n", + "\n", + "We will see this at the example of the PR2" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "id": "edf5cb72", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:13.754327852Z", + "start_time": "2023-11-30T09:28:10.551209150Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "{'base_link': 0, 'base_bellow_link': 1, 'base_laser_link': 2, 'fl_caster_rotation_link': 3, 'fl_caster_l_wheel_link': 4, 'fl_caster_r_wheel_link': 5, 'fr_caster_rotation_link': 6, 'fr_caster_l_wheel_link': 7, 'fr_caster_r_wheel_link': 8, 'bl_caster_rotation_link': 9, 'bl_caster_l_wheel_link': 10, 'bl_caster_r_wheel_link': 11, 'br_caster_rotation_link': 12, 'br_caster_l_wheel_link': 13, 'br_caster_r_wheel_link': 14, 'torso_lift_link': 15, 'l_torso_lift_side_plate_link': 16, 'r_torso_lift_side_plate_link': 17, 'imu_link': 18, 'head_pan_link': 19, 'head_tilt_link': 20, 'head_plate_frame': 21, 'sensor_mount_link': 22, 'high_def_frame': 23, 'high_def_optical_frame': 24, 'double_stereo_link': 25, 'wide_stereo_link': 26, 'wide_stereo_optical_frame': 27, 'wide_stereo_l_stereo_camera_frame': 28, 'wide_stereo_l_stereo_camera_optical_frame': 29, 'wide_stereo_r_stereo_camera_frame': 30, 'wide_stereo_r_stereo_camera_optical_frame': 31, 'narrow_stereo_link': 32, 'narrow_stereo_optical_frame': 33, 'narrow_stereo_l_stereo_camera_frame': 34, 'narrow_stereo_l_stereo_camera_optical_frame': 35, 'narrow_stereo_r_stereo_camera_frame': 36, 'narrow_stereo_r_stereo_camera_optical_frame': 37, 'projector_wg6802418_frame': 38, 'projector_wg6802418_child_frame': 39, 'laser_tilt_mount_link': 40, 'laser_tilt_link': 41, 'r_shoulder_pan_link': 42, 'r_shoulder_lift_link': 43, 'r_upper_arm_roll_link': 44, 'r_upper_arm_link': 45, 'r_elbow_flex_link': 46, 'r_forearm_roll_link': 47, 'r_forearm_link': 48, 'r_wrist_flex_link': 49, 'r_wrist_roll_link': 50, 'r_gripper_palm_link': 51, 'r_gripper_led_frame': 52, 'r_gripper_motor_accelerometer_link': 53, 'r_gripper_tool_frame': 54, 'r_gripper_motor_slider_link': 55, 'r_gripper_motor_screw_link': 56, 'r_gripper_l_finger_link': 57, 'r_gripper_l_finger_tip_link': 58, 'r_gripper_r_finger_link': 59, 'r_gripper_r_finger_tip_link': 60, 'r_gripper_l_finger_tip_frame': 61, 'r_forearm_cam_frame': 62, 'r_forearm_cam_optical_frame': 63, 'l_shoulder_pan_link': 64, 'l_shoulder_lift_link': 65, 'l_upper_arm_roll_link': 66, 'l_upper_arm_link': 67, 'l_elbow_flex_link': 68, 'l_forearm_roll_link': 69, 'l_forearm_link': 70, 'l_wrist_flex_link': 71, 'l_wrist_roll_link': 72, 'l_gripper_palm_link': 73, 'l_gripper_led_frame': 74, 'l_gripper_motor_accelerometer_link': 75, 'l_gripper_tool_frame': 76, 'l_gripper_motor_slider_link': 77, 'l_gripper_motor_screw_link': 78, 'l_gripper_l_finger_link': 79, 'l_gripper_l_finger_tip_link': 80, 'l_gripper_r_finger_link': 81, 'l_gripper_r_finger_tip_link': 82, 'l_gripper_l_finger_tip_frame': 83, 'l_forearm_cam_frame': 84, 'l_forearm_cam_optical_frame': 85, 'torso_lift_motor_screw_link': 86, 'base_footprint': -1}\n" + ] + } + ], + "source": [ + "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\")\n", + "print(pr2.links)" + ] + }, + { + "cell_type": "markdown", + "id": "e157eb6f", + "metadata": {}, + "source": [ + "For links there are similar methods available as for the pose. However, you can only **get** the position and orientation of a link. " + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "id": "51b59ffd", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:17.138722982Z", + "start_time": "2023-11-30T09:28:17.136550048Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Position: \n", + "x: -0.05000000447034836\n", + "y: 0.0\n", + "z: 0.7906750440597534\n", + "Orientation: \n", + "x: 0.0\n", + "y: 0.0\n", + "z: 0.0\n", + "w: 1.0\n", + "Pose: \n", + "header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1701336493\n", + " nsecs: 695036649\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.05000000447034836\n", + " y: 0.0\n", + " z: 0.7906750440597534\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0\n" + ] + } + ], + "source": [ + "print(f\"Position: \\n{pr2.get_link_position('torso_lift_link')}\")\n", + "\n", + "print(f\"Orientation: \\n{pr2.get_link_orientation('torso_lift_link')}\")\n", + "\n", + "print(f\"Pose: \\n{pr2.get_link_pose('torso_lift_link')}\")" + ] + }, + { + "cell_type": "markdown", + "id": "ecd9c4a3", + "metadata": {}, + "source": [ + "Methods available for joints are:\n", + "\n", + " * ```get_joint_state```\n", + " * ```set_joint_state```\n", + " * ```get_joint_limits```\n", + " \n", + "We will see how these methods work at the example of the torso_lift_joint" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "id": "38a8aef4", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:19.963901990Z", + "start_time": "2023-11-30T09:28:19.914673646Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Joint limits: (0.0, 0.33)\n", + "Current Joint state: 0.0\n", + "New Joint state: 0.2\n" + ] + } + ], + "source": [ + "print(f\"Joint limits: {pr2.get_joint_limits('torso_lift_joint')}\")\n", + "\n", + "print(f\"Current Joint state: {pr2.get_joint_state('torso_lift_joint')}\")\n", + "\n", + "pr2.set_joint_state(\"torso_lift_joint\", 0.2)\n", + "\n", + "print(f\"New Joint state: {pr2.get_joint_state('torso_lift_joint')}\")" + ] + }, + { + "cell_type": "markdown", + "id": "6d4ee70a", + "metadata": {}, + "source": [ + "## Misc Methods\n", + "There are a few methods that don't fit any category but could be helpful anyways. The first two are ```get_color``` and ```set_color```, as the name implies they can be used to get or set the color for specific links or the whole Object. " + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "id": "5eee9b8a", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-30T09:28:22.289708761Z", + "start_time": "2023-11-30T09:28:22.287988559Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Pr2 forearm color: (0.699999988079071, 0.699999988079071, 0.699999988079071, 1.0)\n" + ] + } + ], + "source": [ + "print(f\"Pr2 forearm color: {pr2.get_color('r_forearm_link')}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "id": "07aa1c3f", + "metadata": {}, + "outputs": [], + "source": [ + "pr2.set_color([1, 0, 0], \"r_forearm_link\")" + ] + }, + { + "cell_type": "markdown", + "id": "ce5d910b", + "metadata": {}, + "source": [ + "Lastly, there is ```get_AABB``` AABB stands for axis aligned bounding box. This method returns two points in world coordinates which span a rectangle representing the AABB." + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "id": "2a78715b", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "((-0.0015000000000000005, -0.0015000000000000005, 0.06949999999999999),\n", + " (0.0015000000000000005, 0.0015000000000000005, 0.0725))" + ] + }, + "execution_count": 19, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "pr2.get_AABB()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/doc/source/notebooks/giskard.ipynb b/doc/source/notebooks/giskard.ipynb deleted file mode 120000 index 6d8f4dcef..000000000 --- a/doc/source/notebooks/giskard.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/interface_examples/giskard.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/giskard.ipynb b/doc/source/notebooks/giskard.ipynb new file mode 100644 index 000000000..747e789cc --- /dev/null +++ b/doc/source/notebooks/giskard.ipynb @@ -0,0 +1,266 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "6577676e", + "metadata": {}, + "source": [ + "# Giskard interface in PyCRAM\n", + "This notebook should provide you with an example on how to use the Giskard interface. This includes how to use the interface, how it actually works and how to extend it. \n", + "\n", + "We start installing and starting Giskard. For the installation please follow the instructions [here](https://github.com/SemRoCo/giskardpy).\n", + "After you finish the installation you should be able to start giskard by calling \n", + "```\n", + "roslaunch giskardpy giskardpy_pr2_standalone.launch\n", + "```\n", + "\n", + "In this way you can start Giskard for any robot that is supported.\n", + "```\n", + "roslaunch giskardpy giskardpy_hsr_standalone.launch\n", + "```\n", + "\"Standalone\" means that Giskard only uses a simulated robot and does not look for a real robot. If you want to use Giskard with a real robot you have to switch \"standalone\" with \"iai\". \n", + "```\n", + "roslaunch giskardpy giskardpy_hsr_iai.launch\n", + "```\n", + "\n", + "To see what Giskard is doing you can start RViz, there should already be a MarkerArray when starting otherwise you have to add this manually." + ] + }, + { + "cell_type": "markdown", + "id": "a86d4f3b", + "metadata": {}, + "source": [ + "## How to use the Giskard interface \n", + "Everything related to the Giskard interface is located in ```pycram.external_interfaces.giskard```. \n", + "The content of the file can be roughtly divided into three parts:\n", + " 1. Methods to manage the beliefe states between PyCRAM and Giskard\n", + " 2. Motion goals that should be send to Giskard for execution \n", + " 3. Helper methods to construct ROS messages\n", + " \n", + "The most useful methods are the ones for sending and executing Motion goals. These are the ones we will mostly look at.\n", + "\n", + "We will now start by setting up PyCRAM and then try to send some simple motion goals." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "50cd3e8d", + "metadata": { + "ExecuteTime": { + "end_time": "2023-11-29T10:35:04.790103741Z", + "start_time": "2023-11-29T10:35:03.914188198Z" + } + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "pybullet build time: Nov 28 2023 23:51:11\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/action_designator.py:10: SAWarning: Implicitly combining column Designator.dtype with column Action.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", + " class Action(MapperArgsMixin, Designator):\n", + "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/motion_designator.py:16: SAWarning: Implicitly combining column Designator.dtype with column Motion.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", + " class Motion(MapperArgsMixin, Designator):\n", + "[WARN] [1701254104.411256]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1701254104.415521]: Failed to import Giskard messages\n" + ] + } + ], + "source": [ + "from pycram.bullet_world import BulletWorld, Object\n", + "from pycram.enums import ObjectType\n", + "\n", + "world = BulletWorld(\"DIRECT\")\n", + "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\")" + ] + }, + { + "cell_type": "markdown", + "id": "e4166109", + "metadata": {}, + "source": [ + "When you are working on the real robot you also need to initialize the RobotStateUpdater, this module updates the robot in the BulletWorld with the pose and joint state of the real robot. \n", + "\n", + "You might need to change to topic names to fit the topic names as published by your robot. " + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "outputs": [], + "source": [ + "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", + "vis = VizMarkerPublisher()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2023-11-29T10:36:14.233784427Z", + "start_time": "2023-11-29T10:36:14.188401451Z" + } + }, + "id": "5a3cb3f6c8d2d5b" + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a3eff6ba", + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.ros.robot_state_updater import RobotStateUpdater\n", + "\n", + "r = RobotStateUpdater(\"/tf\", \"/joint_states\")" + ] + }, + { + "cell_type": "markdown", + "id": "f4c4f85d", + "metadata": {}, + "source": [ + "Now we have a PyCRAM belief state set up, belief state in this case just refeers to the BulletWorld since the BulletWorld represents what we belief the world to look like. \n", + "\n", + "The next step will be to send a simple motion goal. The motion goal we will be sending is moving the torso up. For this we just need to move one joint so we use the ```achive_joint_goal```. This method takes a dictionary with the joints that should be moved and the target value for the joint. \n", + "\n", + "Look at Rviz to see the robot move, since we call Giskard for movement the robot in the BulletWorld will not move." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "79fb8a5a", + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "from pycram.external_interfaces import giskard\n", + "\n", + "giskard.achieve_joint_goal({\"torso_lift_joint\": 0.28})" + ] + }, + { + "cell_type": "markdown", + "id": "77dbded9", + "metadata": {}, + "source": [ + "For Giskard everything is connected by joints (this is called [World Tree](https://github.com/SemRoCo/giskardpy/wiki/World-Tree) by Giskard) therefore we can move the robot by using a motion goal between the map origin and the robot base. \n", + "\n", + "In the example below we use a cartesian goal, meaning we give Giskard a goal pose, a root link and a tip link and Giskard tries to move all joints between root link and tip link such that the tip link is at the goal pose.\n", + "\n", + "This sort of movement is fine for short distance but keep in mind that Giskard has no collision avoidance for longer journeys. So using MoveBase for longer distances is a better idea." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ec79b6b5", + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.external_interfaces import giskard\n", + "from pycram.pose import Pose\n", + "\n", + "giskard.achieve_cartesian_goal(Pose([1, 0, 0]), \"base_link\", \"map\")" + ] + }, + { + "cell_type": "markdown", + "id": "98af5723", + "metadata": {}, + "source": [ + "Now for the last example: we will move the gripper using full body motion controll. \n", + "\n", + "We will again use the cartesian goal, but now between \"map\" and \"r_gripper_tool_frame\". This will not only move the robot (because the chain between \"map\" and \"base_link\" as used in the previous example is also part of this chain) but also move the arm of the robot such that it reaches the goal pose." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a255212e", + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.external_interfaces import giskard\n", + "from pycram.pose import Pose\n", + "\n", + "giskard.achieve_cartesian_goal(Pose([1, 0.5, 0.7]), \"r_gripper_tool_frame\", \"map\")" + ] + }, + { + "cell_type": "markdown", + "id": "7dfe78ba", + "metadata": {}, + "source": [ + "That conludes this example you can now close the BulletWorld by using the \"exit\" method." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "id": "197aa1f0", + "metadata": {}, + "outputs": [], + "source": [ + "world.exit()" + ] + }, + { + "cell_type": "markdown", + "id": "2ae027ac", + "metadata": {}, + "source": [ + "## How the Giskard interface works \n", + "The PyCRAM interface to Giskard mostly relies on the Python interface that Giskard already proviedes ([tutorial](https://github.com/SemRoCo/giskardpy/wiki/Python-Interface) and the [source code](https://github.com/SemRoCo/giskardpy/blob/master/src/giskardpy/python_interface.py)). This inteface provides methods to achive motion goals and load things into the Giskard believe state. \n", + "\n", + "What PyCRAM with this does is: Synchronize the believe state of Giskard with the one of PyCRAM by loading the environment URDF in Giskard, this is done before any motion goal is send. Furthermore, the motion goals are wrapped in methods that use PyCRAM data types. \n", + "\n", + "You can also set collisions between different groups of links. By default Giskard avoids all collisions but for things like grasping an object you want to allow collisions of the gripper. The interface also the following colliion modes:\n", + " * avoid_all_collisions\n", + " * allow_self_collision\n", + " * allow_gripper_collision\n", + "The collision mode can be set by calling the respective method, after calling the method the collision mode is valid for the next motion goal afterwards it default back to avoid_all_collisions.\n", + "\n", + "There is a ```init_giskard_interface``` method which can be used as a decorator. This decorator should be used on all methods that access the giskard_wrapper, since it assures that the interface is working and checks if Giskard died or the imports for the giskard_msgs failed. " + ] + }, + { + "cell_type": "markdown", + "id": "6908a9ab", + "metadata": {}, + "source": [ + "## Extend the Giskard interface\n", + "At the moment the PyCRAM Giskard interface is mostly a wrapper around the Python interface provided by Giskard. If you want to extend the interface there are two ways:\n", + " * Wrap more motion goals which are provided by the Python interface \n", + " * Design new Higher-Level motion goals by combining the motion goals already provided" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 23c40d591..19671d8c3 100644 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -261,7 +261,7 @@ def copy(self) -> BulletWorld: o = Object(obj.name, obj.type, obj.path, obj.get_position(), obj.get_orientation(), world, obj.color) for joint in obj.joints: - o.set_joint_state(joint, obj.get_joint_state(joint)) + o.set_joint_position(joint, obj.get_joint_position(joint)) return world def add_vis_axis(self, pose: Pose, @@ -374,7 +374,7 @@ def reset_bullet_world(self) -> None: obj.detach(att_obj) joint_names = list(obj.joints.keys()) joint_poses = [0 for j in joint_names] - obj.set_joint_states(dict(zip(joint_names, joint_poses))) + obj.set_joint_positions(dict(zip(joint_names, joint_poses))) obj.set_pose(obj.original_pose) @@ -472,8 +472,8 @@ def run(self): # Manage joint positions if len(bulletworld_obj.joints) > 2: for joint_name in bulletworld_obj.joints.keys(): - if shadow_obj.get_joint_state(joint_name) != bulletworld_obj.get_joint_state(joint_name): - shadow_obj.set_joint_states(bulletworld_obj.get_complete_joint_state()) + if shadow_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): + shadow_obj.set_joint_positions(bulletworld_obj.get_positions_of_all_joints()) break self.check_for_pause() @@ -770,8 +770,8 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self._current_pose = pose_in_map self._current_link_poses = {} self._current_link_transforms = {} - self._current_joint_states = {} - self._init_current_joint_states() + self._current_joints_positions = {} + self._init_current_positions_of_joints() self._update_link_poses() self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) @@ -1104,7 +1104,7 @@ def get_link_pose(self, name: str) -> Pose: return self._current_link_poses[name] # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) - def set_joint_state(self, joint_name: str, joint_pose: float) -> None: + def set_joint_position(self, joint_name: str, joint_pose: float) -> None: """ Sets the state of the given joint to the given joint pose. If the pose is outside the joint limits, as stated in the URDF, an error will be printed. However, the joint will be set either way. @@ -1124,12 +1124,12 @@ def set_joint_state(self, joint_name: str, joint_pose: float) -> None: # Temporarily disabled because kdl outputs values exciting joint limits # return p.resetJointState(self.id, self.joints[joint_name], joint_pose, physicsClientId=self.world.client_id) - self._current_joint_states[joint_name] = joint_pose + self._current_joints_positions[joint_name] = joint_pose # self.local_transformer.update_transforms_for_object(self) self._update_link_poses() self._set_attached_objects([self]) - def set_joint_states(self, joint_poses: dict) -> None: + def set_joint_positions(self, joint_poses: dict) -> None: """ Sets the current state of multiple joints at once, this method should be preferred when setting multiple joints at once instead of running :func:`~Object.set_joint_state` in a loop. @@ -1139,18 +1139,18 @@ def set_joint_states(self, joint_poses: dict) -> None: """ for joint_name, joint_pose in joint_poses.items(): p.resetJointState(self.id, self.joints[joint_name], joint_pose, physicsClientId=self.world.client_id) - self._current_joint_states[joint_name] = joint_pose + self._current_joints_positions[joint_name] = joint_pose self._update_link_poses() self._set_attached_objects([self]) - def get_joint_state(self, joint_name: str) -> float: + def get_joint_position(self, joint_name: str) -> float: """ Returns the joint state for the given joint name. :param joint_name: The name of the joint :return: The current pose of the joint """ - return self._current_joint_states[joint_name] + return self._current_joints_positions[joint_name] def contact_points(self) -> List: """ @@ -1187,7 +1187,7 @@ def update_joints_from_topic(self, topic_name: str) -> None: joint_positions = msg.position if set(joint_names).issubset(self.joints.keys()): for i in range(len(joint_names)): - self.set_joint_state(joint_names[i], joint_positions[i]) + self.set_joint_position(joint_names[i], joint_positions[i]) else: add_joints = set(joint_names) - set(self.joints.keys()) rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ @@ -1345,13 +1345,13 @@ def find_joint_above(self, link_name: str, joint_type: JointType) -> str: rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") return container_joint - def get_complete_joint_state(self) -> Dict[str: float]: + def get_positions_of_all_joints(self) -> Dict[str: float]: """ - Returns the complete joint state of the object as a dictionary of joint names and joint values. + Returns the positions of all joints of the object as a dictionary of joint names and joint positions. - :return: A dictionary with the complete joint state + :return: A dictionary with all joints positions'. """ - return self._current_joint_states + return self._current_joints_positions def get_link_tf_frame(self, link_name: str) -> str: """ @@ -1392,12 +1392,12 @@ def _update_link_poses(self) -> None: self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( self.get_link_tf_frame(link_name)) - def _init_current_joint_states(self) -> None: + def _init_current_positions_of_joints(self) -> None: """ Initialize the cached joint position for each joint. """ for joint_name in self.joints.keys(): - self._current_joint_states[joint_name] = \ + self._current_joints_positions[joint_name] = \ p.getJointState(self.id, self.joints[joint_name], physicsClientId=self.world.client_id)[0] diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 5aee3d24a..67d4c6fc9 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -8,8 +8,8 @@ from matplotlib import colors import psutil import time -from .bullet_world import BulletWorld, Use_shadow_world, Object -from .bullet_world_reasoning import _get_images_for_target +from .world import BulletWorld, Use_shadow_world, Object +from .world_reasoning import _get_images_for_target from nav_msgs.msg import OccupancyGrid, MapMetaData from typing import Tuple, List, Union, Optional diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 20f1beb48..38ce79ab7 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -9,7 +9,7 @@ from sqlalchemy.orm.session import Session import rospy -from .bullet_world import (Object as BulletWorldObject, BulletWorld) +from .world import (Object as BulletWorldObject, BulletWorld) from .helper import GeneratorList, bcolors from threading import Lock from time import time @@ -486,7 +486,7 @@ class Action: def __post_init__(self): self.robot_position = BulletWorld.robot.get_pose() - self.robot_torso_height = BulletWorld.robot.get_joint_state(robot_description.torso_joint) + self.robot_torso_height = BulletWorld.robot.get_joint_position(robot_description.torso_joint) self.robot_type = BulletWorld.robot.type @with_tree diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index ddc9b24ab..354aed83e 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -23,7 +23,7 @@ from ..task import with_tree from ..enums import Arms from ..designator import ActionDesignatorDescription -from ..bullet_world import BulletWorld +from ..world import BulletWorld from ..pose import Pose from ..helper import multiply_quaternions diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 1edb9d17d..7b62fb27c 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -3,8 +3,8 @@ from typing import List, Tuple, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..bullet_world import Object, BulletWorld, Use_shadow_world -from ..bullet_world_reasoning import link_pose_for_joint_config +from ..world import Object, BulletWorld, Use_shadow_world +from ..world_reasoning import link_pose_for_joint_config from ..designator import Designator, DesignatorError, LocationDesignatorDescription from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap from ..robot_descriptions import robot_description diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index c6535a3a6..8d618ed20 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -2,7 +2,7 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..bullet_world import Object, BulletWorld +from ..world import Object, BulletWorld from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 02a58ef41..0b063ac9f 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,7 +1,7 @@ import dataclasses from typing import List, Union, Optional, Callable, Tuple, Iterable import sqlalchemy.orm -from ..bullet_world import BulletWorld, Object as BulletWorldObject +from ..world import BulletWorld, Object as BulletWorldObject from ..designator import DesignatorDescription, ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 3742d1d16..98f15d55a 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -6,7 +6,7 @@ from ..pose import Pose from ..robot_descriptions import robot_description -from ..bullet_world import BulletWorld, Object +from ..world import BulletWorld, Object from ..robot_description import ManipulatorDescription from typing import List, Tuple, Dict, Callable diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index d84e9a027..a42acd13a 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -7,7 +7,7 @@ from moveit_msgs.srv import GetPositionIK from sensor_msgs.msg import JointState -from ..bullet_world import Object +from ..world import Object from ..helper import calculate_wrist_tool_offset from ..local_transformer import LocalTransformer from ..pose import Pose, Transform diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index e332c3e07..3a41c2074 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -9,7 +9,7 @@ from ..designator import ObjectDesignatorDescription from ..pose import Pose from ..local_transformer import LocalTransformer -from ..bullet_world import BulletWorld +from ..world import BulletWorld from ..enums import ObjectType try: diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 64acc9cad..aad79a9d1 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -16,7 +16,7 @@ from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform from macropy.core.quotes import ast_literal, q -from .bullet_world import Object as BulletWorldObject +from .world import Object as BulletWorldObject from .local_transformer import LocalTransformer from .pose import Transform, Pose from .robot_descriptions import robot_description @@ -54,7 +54,7 @@ def _apply_ik(robot: BulletWorldObject, joint_poses: List[float], joints: List[s # arm ="left" if gripper == robot_description.get_tool_frame("left") else "right" # ik_joints = [robot_description.torso_joint] + robot_description._safely_access_chains(arm).joints # ik_joints = robot_description._safely_access_chains(arm).joints - robot.set_joint_states(dict(zip(joints, joint_poses))) + robot.set_positions_of_all_joints(dict(zip(joints, joint_poses))) # for i in range(0, len(joints)): # robot.set_joint_state(joints[i], joint_poses[i]) diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 5ef4d5c85..c68945182 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -53,7 +53,7 @@ def __init__(self): self.tf_stampeds: List[TransformStamped] = [] self.static_tf_stampeds: List[TransformStamped] = [] - # Since this file can't import bullet_world.py this holds the reference to the current_bullet_world + # Since this file can't import world.py this holds the reference to the current_bullet_world self.bullet_world = None self.shadow_world = None diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index cc45ad372..a836034d1 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -3,8 +3,8 @@ import rospy import pybullet as p -from .bullet_world import Object, BulletWorld, Use_shadow_world -from .bullet_world_reasoning import contact +from .world import Object, BulletWorld, Use_shadow_world +from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform from .robot_descriptions import robot_description diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 7879654ca..f8c3e5d17 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -3,9 +3,9 @@ import pybullet as p -import pycram.bullet_world_reasoning as btr +import pycram.world_reasoning as btr import pycram.helper as helper -from ..bullet_world import BulletWorld +from ..world import BulletWorld from ..external_interfaces.ik import request_ik from ..local_transformer import LocalTransformer as local_tf from ..process_module import ProcessModule, ProcessModuleManager @@ -22,10 +22,10 @@ def _park_arms(arm): robot = BulletWorld.robot if arm == "right": for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) class BoxyNavigation(ProcessModule): @@ -39,7 +39,7 @@ def _execute(self, desig): robot = BulletWorld.robot # Reset odom joints to zero for joint_name in robot_description.odom_joints: - robot.set_joint_state(joint_name, 0.0) + robot.set_joint_position(joint_name, 0.0) # Set actual goal pose robot.set_position_and_orientation(solution['target'], solution['orientation']) time.sleep(0.5) @@ -110,7 +110,7 @@ def _execute(self, desig): drawer_handle = solution['drawer_handle'] drawer_joint = solution['drawer_joint'] dis = solution['distance'] - robot.set_joint_state(robot_description.torso_joint, -0.1) + robot.set_joint_position(robot_description.torso_joint, -0.1) arm = "left" if solution['gripper'] == robot_description.get_tool_frame("left") else "right" joints = robot_description._safely_access_chains(arm).joints #inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), kitchen.get_link_position(drawer_handle)) @@ -126,7 +126,7 @@ def _execute(self, desig): new_p = helper._transform_to_torso(new_p, robot) inv = request_ik(robot_description.base_frame, gripper, new_p, robot, joints) helper._apply_ik(robot, inv, gripper) - kitchen.set_joint_state(drawer_joint, 0.3) + kitchen.set_joint_position(drawer_joint, 0.3) time.sleep(0.5) @@ -190,7 +190,7 @@ def _execute(self, desig): else: conf = "behind_up" for joint, state in robot_description.get_static_joint_chain("neck", conf).items(): - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) class BoxyMoveGripper(ProcessModule): @@ -207,7 +207,7 @@ def _execute(self, desig): motion = solution['motion'] for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): # TODO: Test this, add gripper-opening/-closing to the demo.py - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) time.sleep(0.5) @@ -261,13 +261,13 @@ def _execute(self, desig): left_arm_poses = solution['left_arm_poses'] if type(right_arm_poses) == dict: for joint, pose in right_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) elif type(right_arm_poses) == str and right_arm_poses == "park": _park_arms("right") if type(left_arm_poses) == dict: for joint, pose in left_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) elif type(right_arm_poses) == str and left_arm_poses == "park": _park_arms("left") diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 98d45f430..44db2771f 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -3,9 +3,9 @@ import pybullet as p -import pycram.bullet_world_reasoning as btr +import pycram.world_reasoning as btr import pycram.helper as helper -from ..bullet_world import BulletWorld +from ..world import BulletWorld from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description @@ -21,7 +21,7 @@ def _park_arms(arm): robot = BulletWorld.robot if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) class DonbotNavigation(ProcessModule): @@ -35,7 +35,7 @@ def _execute(self, desig): robot = BulletWorld.robot # Reset odom joints to zero for joint_name in robot_description.odom_joints: - robot.set_joint_state(joint_name, 0.0) + robot.set_joint_position(joint_name, 0.0) # Set actual goal pose robot.set_position_and_orientation(solution['target'], solution['orientation']) time.sleep(0.5) @@ -102,7 +102,7 @@ def _execute(self, desig): new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) helper._apply_ik(robot, inv) - kitchen.set_joint_state(drawer_joint, 0.3) + kitchen.set_joint_position(drawer_joint, 0.3) time.sleep(0.5) @@ -153,7 +153,7 @@ def _execute(self, desig): else: conf = "right" for joint, state in robot_description.get_static_joint_chain("neck", conf).items(): - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) class DonbotMoveGripper(ProcessModule): @@ -170,7 +170,7 @@ def _execute(self, desig): motion = solution['motion'] for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): # TODO: Test this, add gripper-opening/-closing to the demo.py - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) time.sleep(0.5) @@ -224,7 +224,7 @@ def _execute(self, desig): if type(left_arm_poses) == dict: for joint, pose in left_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) elif type(left_arm_poses) == str and left_arm_poses == "park": _park_arms("left") diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index e3df9dba1..594f355f1 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -2,9 +2,9 @@ from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld +from ..world import BulletWorld from ..helper import _apply_ik -import pycram.bullet_world_reasoning as btr +import pycram.world_reasoning as btr import pybullet as p import logging import time @@ -20,7 +20,7 @@ def _park_arms(arm): robot = BulletWorld.robot if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) class HSRNavigation(ProcessModule): @@ -96,7 +96,7 @@ def _execute(self, desig): new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) _apply_ik(robot, inv) - kitchen.set_joint_state(drawer_joint, 0.3) + kitchen.set_joint_position(drawer_joint, 0.3) time.sleep(0.5) @@ -125,7 +125,7 @@ def _execute(self, desig): if target == 'forward' or target == 'down': robot = BulletWorld.robot for joint, state in robot_description.get_static_joint_chain("neck", target).items(): - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) else: logging.error("There is no target position defined with the target %s.", target) @@ -143,7 +143,7 @@ def _execute(self, desig): gripper = solution['gripper'] motion = solution['motion'] for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) time.sleep(0.5) @@ -197,7 +197,7 @@ def _execute(self, desig): if type(left_arm_poses) == dict: for joint, pose in left_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) elif type(left_arm_poses) == str and left_arm_poses == "park": _park_arms("left") diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index f93544d70..07800af68 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -4,7 +4,7 @@ import actionlib -import pycram.bullet_world_reasoning as btr +import pycram.world_reasoning as btr import numpy as np import time import rospy @@ -13,7 +13,7 @@ from ..plan_failures import EnvironmentManipulationImpossible from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld, Object +from ..world import BulletWorld, Object from ..helper import transform from ..external_interfaces.ik import request_ik, IKError from ..helper import _transform_to_torso, _apply_ik, calculate_wrist_tool_offset, inverseTimes @@ -39,10 +39,10 @@ def _park_arms(arm): robot = BulletWorld.robot if arm == "right": for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) class Pr2Navigation(ProcessModule): @@ -121,11 +121,11 @@ def _execute(self, desig: LookingMotion.Motion): new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = robot.get_joint_state("head_pan_joint") - current_tilt = robot.get_joint_state("head_tilt_joint") + current_pan = robot.get_joint_position("head_pan_joint") + current_tilt = robot.get_joint_position("head_tilt_joint") - robot.set_joint_state("head_pan_joint", new_pan + current_pan) - robot.set_joint_state("head_tilt_joint", new_tilt + current_tilt) + robot.set_joint_position("head_pan_joint", new_pan + current_pan) + robot.set_joint_position("head_tilt_joint", new_tilt + current_tilt) class Pr2MoveGripper(ProcessModule): @@ -139,7 +139,7 @@ def _execute(self, desig: MoveGripperMotion.Motion): gripper = desig.gripper motion = desig.motion for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): - robot.set_joint_state(joint, state) + robot.set_joint_position(joint, state) class Pr2Detecting(ProcessModule): @@ -184,9 +184,9 @@ def _execute(self, desig: MoveArmJointsMotion.Motion): robot = BulletWorld.robot if desig.right_arm_poses: - robot.set_joint_states(desig.right_arm_poses) + robot.set_positions_of_all_joints(desig.right_arm_poses) if desig.left_arm_poses: - robot.set_joint_states(desig.left_arm_poses) + robot.set_positions_of_all_joints(desig.left_arm_poses) class PR2MoveJoints(ProcessModule): @@ -195,7 +195,7 @@ class PR2MoveJoints(ProcessModule): """ def _execute(self, desig: MoveJointsMotion.Motion): robot = BulletWorld.robot - robot.set_joint_states(dict(zip(desig.names, desig.positions))) + robot.set_positions_of_all_joints(dict(zip(desig.names, desig.positions))) class Pr2WorldStateDetecting(ProcessModule): @@ -223,8 +223,8 @@ def _execute(self, desig: OpeningMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.bullet_world_object.set_joint_position(container_joint, + part_of_object.get_joint_limits( container_joint)[1]) @@ -243,8 +243,8 @@ def _execute(self, desig: ClosingMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.bullet_world_object.set_joint_position(container_joint, + part_of_object.get_joint_limits( container_joint)[0]) @@ -301,8 +301,8 @@ def _execute(self, desig: LookingMotion.Motion): new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = robot.get_joint_state("head_pan_joint") - current_tilt = robot.get_joint_state("head_tilt_joint") + current_pan = robot.get_joint_position("head_pan_joint") + current_tilt = robot.get_joint_position("head_tilt_joint") giskard.avoid_all_collisions() giskard.achieve_joint_goal({"head_pan_joint": new_pan + current_pan, diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index c031ed840..cd2c76430 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,6 +1,6 @@ from pycram.external_interfaces.giskard import achieve_cartesian_goal from pycram.designators.location_designator import CostmapLocation -from pycram.bullet_world import Use_shadow_world, BulletWorld +from pycram.world import Use_shadow_world, BulletWorld from pycram.helper import _apply_ik from pycram.pose import Pose from pycram.robot_descriptions import robot_description diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 2f728d14c..5c7bf1bae 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -12,7 +12,7 @@ from ...costmaps import OccupancyCostmap, plot_grid from ...plan_failures import PlanFailure from ...pose import Pose -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index d61f292a3..6da358d55 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -7,7 +7,7 @@ from geometry_msgs.msg import WrenchStamped from std_msgs.msg import Header -from..bullet_world import BulletWorld +from..world import BulletWorld class ForceTorqueSensor: diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index 8cefe2547..1126c535d 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -6,7 +6,7 @@ from sensor_msgs.msg import JointState from std_msgs.msg import Header -from ..bullet_world import BulletWorld +from ..world import BulletWorld class JointStatePublisher: @@ -41,7 +41,7 @@ def _publish(self) -> None: seq = 0 while not self.kill_event.is_set(): - current_joint_states = [robot.get_joint_state(joint_name) for joint_name in joint_names] + current_joint_states = [robot.get_joint_position(joint_name) for joint_name in joint_names] h = Header() h.stamp = rospy.Time.now() h.seq = seq diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index 6f8382544..845d20351 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -6,7 +6,7 @@ from geometry_msgs.msg import TransformStamped from sensor_msgs.msg import JointState -from pycram.bullet_world import BulletWorld +from pycram.world import BulletWorld from pycram.robot_descriptions import robot_description from pycram.pose import Transform, Pose @@ -58,7 +58,7 @@ def _subscribe_joint_state(self, msg: JointState) -> None: try: msg = rospy.wait_for_message(self.joint_state_topic, JointState) for name, position in zip(msg.name, msg.position): - BulletWorld.robot.set_joint_state(name, position) + BulletWorld.robot.set_joint_position(name, position) except AttributeError: pass diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index 25c6878ed..ec0ab9cc3 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -4,7 +4,7 @@ import atexit from ..pose import Pose -from ..bullet_world import BulletWorld +from ..world import BulletWorld from tf2_msgs.msg import TFMessage diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 52bfe879c..90278afd4 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -5,7 +5,7 @@ from geometry_msgs.msg import Vector3 from std_msgs.msg import ColorRGBA -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object from visualization_msgs.msg import MarkerArray, Marker import rospy import urdf_parser_py diff --git a/src/pycram/task.py b/src/pycram/task.py index f17e2b7e1..74df58952 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -14,7 +14,7 @@ import sqlalchemy.orm.session import tqdm -from .bullet_world import BulletWorld +from .world import BulletWorld from .orm.task import (Code as ORMCode, TaskTreeNode as ORMTaskTreeNode) from .orm.base import ProcessMetaData from .plan_failures import PlanFailure diff --git a/src/pycram/world.py b/src/pycram/world.py deleted file mode 100644 index 095604298..000000000 --- a/src/pycram/world.py +++ /dev/null @@ -1,1866 +0,0 @@ -# used for delayed evaluation of typing until python 3.11 becomes mainstream -from __future__ import annotations - -import logging -import os -import pathlib -import re -import threading -import time -import xml.etree.ElementTree -from queue import Queue -import tf -from typing import List, Optional, Dict, Tuple, Callable, Iterable -from typing import Union - -import numpy as np -import pybullet as p -import rospkg -import rospy -import rosgraph - -import urdf_parser_py.urdf -from geometry_msgs.msg import Quaternion, Point -from urdf_parser_py.urdf import URDF - -from .event import Event -from .robot_descriptions import robot_description -from .enums import JointType, ObjectType -from .local_transformer import LocalTransformer -from sensor_msgs.msg import JointState - -from .pose import Pose, Transform - - -class BulletWorld: - """ - The BulletWorld Class represents the physics Simulation and belief state. - """ - - current_bullet_world: BulletWorld = None - """ - Global reference to the currently used BulletWorld, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_bullet_world points to the - shadow world. In this way you can comfortably use the current_bullet_world, which should point towards the BulletWorld - used at the moment. - """ - robot: Object = None - """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the - URDF with the name of the URDF on the parameter server. - """ - - # Check is for sphinx autoAPI to be able to work in a CI workflow - if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): - rospy.init_node('pycram') - - def __init__(self, type: str = "GUI", is_shadow_world: bool = False): - """ - Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the - background. There can only be one rendered simulation. - The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. - - :param type: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" - :param is_shadow_world: For internal usage, decides if this BulletWorld should be used as a shadow world. - """ - self.objects: List[Object] = [] - self.client_id: int = -1 - self.detachment_event: Event = Event() - self.attachment_event: Event = Event() - self.manipulation_event: Event = Event() - self.type: str = type - self._gui_thread: Gui = Gui(self, type) - self._gui_thread.start() - # This disables file caching from PyBullet, since this would also cache - # files that can not be loaded - p.setPhysicsEngineParameter(enableFileCaching=0) - # Needed to let the other thread start the simulation, before Objects are spawned. - time.sleep(0.1) - if BulletWorld.current_bullet_world == None: - BulletWorld.current_bullet_world = self - self.vis_axis: Object = [] - self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} - self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] - self.shadow_world: BulletWorld = BulletWorld("DIRECT", True) if not is_shadow_world else None - self.world_sync: WorldSync = WorldSync(self, self.shadow_world) if not is_shadow_world else None - self.is_shadow_world: bool = is_shadow_world - self.local_transformer = LocalTransformer() - if not is_shadow_world: - self.world_sync.start() - self.local_transformer.bullet_world = self - self.local_transformer.shadow_world = self.shadow_world - - # Some default settings - self.set_gravity([0, 0, -9.8]) - if not is_shadow_world: - plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - # atexit.register(self.exit) - - def get_objects_by_name(self, name: str) -> List[Object]: - """ - Returns a list of all Objects in this BulletWorld with the same name as the given one. - - :param name: The name of the returned Objects. - :return: A list of all Objects with the name 'name'. - """ - return list(filter(lambda obj: obj.name == name, self.objects)) - - def get_objects_by_type(self, obj_type: str) -> List[Object]: - """ - Returns a list of all Objects which have the type 'obj_type'. - - :param obj_type: The type of the returned Objects. - :return: A list of all Objects that have the type 'obj_type'. - """ - return list(filter(lambda obj: obj.type == obj_type, self.objects)) - - def get_object_by_id(self, id: int) -> Object: - """ - Returns the single Object that has the unique id. - - :param id: The unique id for which the Object should be returned. - :return: The Object with the id 'id'. - """ - return list(filter(lambda obj: obj.id == id, self.objects))[0] - - def remove_object(self, obj_id: int) -> None: - """ - Remove an object by its ID. - - :param obj_id: The unique id of the object to be removed. - """ - - p.removeBody(obj_id, self.client_id) - - def attach(self, - parent_obj: Object, - child_obj: Object, - parent_link: Optional[str] = None, - loose: Optional[bool] = False) -> None: - """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a constraint of pybullet will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. - For example, if the parent object moves, the child object will also move, but not the other way around. - - :param parent_obj: The parent object (jf loose, then this would not move when child moves) - :param child_obj: The child object - :param parent_link: The link of the parent object to which the child object should be attached - :param loose: If the attachment should be a loose attachment. - """ - link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 - link_to_object = parent_obj._calculate_transform(child_obj, parent_link) - parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] - child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] - - cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, - [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], - link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - parent_obj.cids[child_obj] = cid - child_obj.cids[parent_obj] = cid - self.attachment_event(parent_obj, [parent_obj, child_obj]) - - def detach(self, obj1: Object, obj2: Object) -> None: - """ - Detaches obj2 from obj1. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of pybullet. - Afterward the detachment event of the corresponding BulletWorld will be fired. - - :param obj1: The object from which an object should be detached. - :param obj2: The object which should be detached. - """ - del obj1.attachments[obj2] - del obj2.attachments[obj1] - - p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) - - del obj1.cids[obj2] - del obj2.cids[obj1] - obj1.world.detachment_event(obj1, [obj1, obj2]) - - def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param prev_object: A list of Objects that were already moved, - these will be excluded to prevent loops in the update. - """ - for att_obj in obj.attachments: - if att_obj in prev_object: - continue - if obj.attachments[att_obj][2]: - # Updates the attachment transformation and constraint if the - # attachment is loose, instead of updating the position of all attached objects - link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) - link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 - obj.attachments[att_obj][0] = link_to_object - att_obj.attachments[obj][0] = link_to_object.invert() - p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) - cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], - link_to_object.translation_as_list(), - [0, 0, 0], link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - obj.cids[att_obj] = cid - att_obj.cids[obj] = cid - else: - link_to_object = obj.attachments[att_obj][0] - - world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), - world_to_object.orientation_as_list(), - physicsClientId=self.client_id) - att_obj._current_pose = world_to_object - self._set_attached_objects(att_obj, prev_object + [obj]) - - def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: - """ - Get the joint limits of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - :return: A tuple containing the upper and the lower limits of the joint. - """ - up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] - return up_lim, low_lim - - def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param obj: The object - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ - return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] - - def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param obj: The object - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ - joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] - return JointType(joint_type) - - def get_object_joint_position(self, obj: Object, joint_name: str) -> float: - """ - Get the state of a joint of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - """ - return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] - - def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: - """ - Get the pose of a link of an articulated object with respect to the world frame. - The pose is given as a tuple of position and orientation. - - :param obj: The object - :param link_name: The name of the link - """ - return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] - - def get_object_contact_points(self, obj: Object) -> List: - """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :param obj: The object. - :return: A list of all contact points with other objects - """ - return p.getContactPoints(obj.id) - - def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: - """ - Get the ID of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). - """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] - - def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: - """ - Get the name of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). - """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') - - def get_object_link_name(self, obj: Object, link_idx: int) -> str: - """ - Get the name of a link in an articulated object. - - :param obj: The object - :param link_idx: The index of the link (would indicate order). - """ - return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') - - def get_object_number_of_joints(self, obj: Object) -> int: - """ - Get the number of joints of an articulated object - - :param obj: The object - """ - return p.getNumJoints(obj.id, self.client_id) - - def reset_joint_state(self, obj: Object, joint_name: str, joint_pose: float) -> None: - """ - Reset the joint state instantly without physics simulation - - :param obj: The object - :param joint_name: The name of the joint - :param joint_pose: The new joint pose - """ - p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) - - def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): - """ - Reset the world position and orientation of the base of the object instantaneously, - not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. - - :param obj: The object - :param position: The new position of the object as a vector of x,y,z - :param orientation: The new orientation of the object as a quaternion of x,y,z,w - """ - p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) - - def step(self): - """ - Step the world simulation using forward dynamics - """ - p.stepSimulation(self.client_id) - - def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): - """ - Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. - - :param obj: The object which should be colored - :param color: The color as RGBA values between 0 and 1 - :param link: The link name of the link which should be colored - """ - if link == "": - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if obj.links != {}: - for link_id in obj.links.values(): - p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) - else: - p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) - else: - p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) - - def get_object_color(self, - obj: Object, - link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: - """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: - - 1. A list with the color as RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the - object is spawned. - - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. - - :param obj: The object for which the color should be returned. - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color - """ - visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) - swap = {v: k for k, v in obj.links.items()} - links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = list(map(lambda x: x[7], visual_data)) - link_to_color = dict(zip(links, colors)) - - if link: - if link in link_to_color.keys(): - return link_to_color[link] - elif link not in obj.links.keys(): - rospy.logerr(f"The link '{link}' is not part of this obejct") - return None - else: - rospy.logerr(f"The link '{link}' has no color") - return None - - if len(visual_data) == 1: - return list(visual_data[0][7]) - else: - return link_to_color - - def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :param link_name: The Optional name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. - """ - if link_name: - return p.getAABB(obj.id, obj.links[link_name], self.client_id) - else: - return p.getAABB(obj.id, physicsClientId=self.client_id) - - def get_attachment_event(self) -> Event: - """ - Returns the event reference that is fired if an attachment occurs. - - :return: The reference to the attachment event - """ - return self.attachment_event - - def get_detachment_event(self) -> Event: - """ - Returns the event reference that is fired if a detachment occurs. - - :return: The event reference for the detachment event. - """ - return self.detachment_event - - def get_manipulation_event(self) -> Event: - """ - Returns the event reference that is fired if any manipulation occurs. - - :return: The event reference for the manipulation event. - """ - return self.manipulation_event - - def set_realtime(self, real_time: bool) -> None: - """ - Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only - simulated to reason about it. - - :param real_time: Whether the BulletWorld should simulate Physic in real time. - """ - p.setRealTimeSimulation(1 if real_time else 0, self.client_id) - - def set_gravity(self, velocity: List[float]) -> None: - """ - Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity - is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - - :param velocity: The gravity vector that should be used in the BulletWorld. - """ - p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) - - def set_robot(self, robot: Object) -> None: - """ - Sets the global variable for the robot Object. This should be set on spawning the robot. - - :param robot: The Object reference to the Object representing the robot. - """ - BulletWorld.robot = robot - - def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: - """ - Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real - time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By - setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real - time. - - :param seconds: The amount of seconds that should be simulated. - :param real_time: If the simulation should happen in real time or faster. - """ - for i in range(0, int(seconds * 240)): - p.stepSimulation(self.client_id) - for objects, callback in self.coll_callbacks.items(): - contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) - # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) - # print(contact_points[0][5]) - if contact_points != (): - callback[0]() - elif callback[1] != None: # Call no collision callback - callback[1]() - if real_time: - # Simulation runs at 240 Hz - time.sleep(0.004167) - - def exit(self) -> None: - """ - Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the - preferred method to close the BulletWorld. - """ - # True if this is NOT the shadow world since it has a reference to the - # Shadow world - time.sleep(0.1) - if self.shadow_world: - self.world_sync.terminate = True - self.world_sync.join() - self.shadow_world.exit() - p.disconnect(self.client_id) - if self._gui_thread: - self._gui_thread.join() - if BulletWorld.current_bullet_world == self: - BulletWorld.current_bullet_world = None - BulletWorld.robot = None - - def save_state(self) -> Tuple[int, Dict]: - """ - Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint - position of every Object in the BulletWorld. - - :return: A unique id of the state - """ - objects2attached = {} - # ToDo find out what this is for and where it is used - for o in self.objects: - objects2attached[o] = (o.attachments.copy(), o.cids.copy()) - return p.saveState(self.client_id), objects2attached - - def restore_state(self, state, objects2attached: Dict = {}) -> None: - """ - Restores the state of the BulletWorld according to the given state id. This includes position, orientation and - joint states. However, restore can not respawn objects if there are objects that were deleted between creation of - the state and restoring they will be skiped. - - :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~bullet_world.Object.attachments` - """ - p.restoreState(state, physicsClientId=self.client_id) - for obj in self.objects: - try: - obj.attachments, obj.cids = objects2attached[obj] - except KeyError: - continue - - def copy(self) -> BulletWorld: - """ - Copies this Bullet World into another and returns it. The other BulletWorld - will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. - This method should only be used if necessary since there can be unforeseen problems. - - :return: The reference to the new BulletWorld - """ - world = BulletWorld("DIRECT") - for obj in self.objects: - o = Object(obj.name, obj.type, obj.path, obj.get_position(), obj.get_orientation(), - world, obj.color) - for joint in obj.joints: - o.set_joint_state(joint, obj.get_joint_state(joint)) - return world - - def add_vis_axis(self, pose: Pose, - length: Optional[float] = 0.2) -> None: - """ - Creates a Visual object which represents the coordinate frame at the given - position and orientation. There can be an unlimited amount of vis axis objects. - - :param pose: The pose at which the axis should be spawned - :param length: Optional parameter to configure the length of the axes - """ - - position, orientation = pose.to_list() - - vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) - vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) - vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) - - obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], - basePosition=position, baseOrientation=orientation, - linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkParentIndices=[0, 0, 0], - linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], - linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1]) - - self.vis_axis.append(obj) - - def remove_vis_axis(self) -> None: - """ - Removes all spawned vis axis objects that are currently in this BulletWorld. - """ - for id in self.vis_axis: - p.removeBody(id) - self.vis_axis = [] - - def register_collision_callback(self, objectA: Object, objectB: Object, - callback_collision: Callable, - callback_no_collision: Optional[Callable] = None) -> None: - """ - Registers callback methods for contact between two Objects. There can be a callback for when the two Objects - get in contact and, optionally, for when they are not in contact anymore. - - :param objectA: An object in the BulletWorld - :param objectB: Another object in the BulletWorld - :param callback_collision: A function that should be called if the objects are in contact - :param callback_no_collision: A function that should be called if the objects are not in contact - """ - self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) - - def add_additional_resource_path(self, path: str) -> None: - """ - Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an - Object is spawned only with a filename. - - :param path: A path in the filesystem in which to search for files. - """ - self.data_directory.append(path) - - def get_shadow_object(self, object: Object) -> Object: - """ - Returns the corresponding object from the shadow world for the given object. If the given Object is already in - the shadow world it is returned. - - :param object: The object for which the shadow worlds object should be returned. - :return: The corresponding object in the shadow world. - """ - try: - return self.world_sync.object_mapping[object] - except KeyError: - shadow_world = self if self.is_shadow_world else self.shadow_world - if object in shadow_world.objects: - return object - else: - raise ValueError( - f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") - - def get_bullet_object_for_shadow(self, object: Object) -> Object: - """ - Returns the corresponding object from the main Bullet World for a given - object in the shadow world. If the given object is not in the shadow - world an error will be raised. - - :param object: The object for which the corresponding object in the main Bullet World should be found - :return: The object in the main Bullet World - """ - map = self.world_sync.object_mapping - try: - return list(map.keys())[list(map.values()).index(object)] - except ValueError: - raise ValueError("The given object is not in the shadow world.") - - def reset_bullet_world(self) -> None: - """ - Resets the BulletWorld to the state it was first spawned in. - All attached objects will be detached, all joints will be set to the - default position of 0 and all objects will be set to the position and - orientation in which they were spawned. - """ - for obj in self.objects: - if obj.attachments: - attached_objects = list(obj.attachments.keys()) - for att_obj in attached_objects: - obj.detach(att_obj) - joint_names = list(obj.joints.keys()) - joint_poses = [0 for j in joint_names] - obj.set_joint_states(dict(zip(joint_names, joint_poses))) - obj.set_pose(obj.original_pose) - - -class Use_shadow_world(): - """ - An environment for using the shadow world, while in this environment the :py:attr:`~BulletWorld.current_bullet_world` - variable will point to the shadow world. - - Example: - with Use_shadow_world(): - NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() - """ - - def __init__(self): - self.prev_world: BulletWorld = None - - def __enter__(self): - if not BulletWorld.current_bullet_world.is_shadow_world: - time.sleep(20 / 240) - # blocks until the adding queue is ready - BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() - # **This is currently not used since the sleep(20/240) seems to be enough, but on weaker hardware this might - # not be a feasible solution** - # while not BulletWorld.current_bullet_world.world_sync.equal_states: - # time.sleep(0.1) - - self.prev_world = BulletWorld.current_bullet_world - BulletWorld.current_bullet_world.world_sync.pause_sync = True - BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.shadow_world - - def __exit__(self, *args): - if not self.prev_world == None: - BulletWorld.current_bullet_world = self.prev_world - BulletWorld.current_bullet_world.world_sync.pause_sync = False - - -class WorldSync(threading.Thread): - """ - Synchronizes the state between the BulletWorld and its shadow world. - Meaning the cartesian and joint position of everything in the shadow world will be - synchronized with the main BulletWorld. - Adding and removing objects is done via queues, such that loading times of objects - in the shadow world does not affect the BulletWorld. - The class provides the possibility to pause the synchronization, this can be used - if reasoning should be done in the shadow world. - """ - - def __init__(self, world: BulletWorld, shadow_world: BulletWorld): - threading.Thread.__init__(self) - self.world: BulletWorld = world - self.shadow_world: BulletWorld = shadow_world - self.shadow_world.world_sync: WorldSync = self - - self.terminate: bool = False - self.add_obj_queue: Queue = Queue() - self.remove_obj_queue: Queue = Queue() - self.pause_sync: bool = False - # Maps bullet to shadow world objects - self.object_mapping: Dict[Object, Object] = {} - self.equal_states = False - - def run(self): - """ - Main method of the synchronization, this thread runs in a loop until the - terminate flag is set. - While this loop runs it continuously checks the cartesian and joint position of - every object in the BulletWorld and updates the corresponding object in the - shadow world. When there are entries in the adding or removing queue the corresponding objects will be added - or removed in the same iteration. - """ - while not self.terminate: - self.check_for_pause() - # self.equal_states = False - for i in range(self.add_obj_queue.qsize()): - obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.shadow_world, color, bulletworld object] - o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) - # Maps the BulletWorld object to the shadow world object - self.object_mapping[obj[7]] = o - self.add_obj_queue.task_done() - for i in range(self.remove_obj_queue.qsize()): - obj = self.remove_obj_queue.get() - # Get shadow world object reference from object mapping - shadow_obj = self.object_mapping[obj] - shadow_obj.remove() - del self.object_mapping[obj] - self.remove_obj_queue.task_done() - - for bulletworld_obj, shadow_obj in self.object_mapping.items(): - b_pose = bulletworld_obj.get_pose() - s_pose = shadow_obj.get_pose() - if b_pose.dist(s_pose) != 0.0: - shadow_obj.set_pose(bulletworld_obj.get_pose()) - - # Manage joint positions - if len(bulletworld_obj.joints) > 2: - for joint_name in bulletworld_obj.joints.keys(): - if shadow_obj.get_joint_state(joint_name) != bulletworld_obj.get_joint_state(joint_name): - shadow_obj.set_joint_states(bulletworld_obj.get_complete_joint_state()) - break - - self.check_for_pause() - # self.check_for_equal() - time.sleep(1 / 240) - - self.add_obj_queue.join() - self.remove_obj_queue.join() - - def check_for_pause(self) -> None: - """ - Checks if :py:attr:`~self.pause_sync` is true and sleeps this thread until it isn't anymore. - """ - while self.pause_sync: - time.sleep(0.1) - - def check_for_equal(self) -> None: - """ - Checks if both BulletWorlds have the same state, meaning all objects are in the same position. - This is currently not used, but might be used in the future if synchronization issues worsen. - """ - eql = True - for obj, shadow_obj in self.object_mapping.items(): - eql = eql and obj.get_pose() == shadow_obj.get_pose() - self.equal_states = eql - - -class Gui(threading.Thread): - """ - For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~BulletWorld.exit` - Also contains the code for controlling the camera. - """ - - def __init__(self, world, type): - threading.Thread.__init__(self) - self.world: BulletWorld = world - self.type: str = type - - def run(self): - """ - Initializes the new simulation and checks in an endless loop - if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and - thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. - """ - if self.type != "GUI": - self.world.client_id = p.connect(p.DIRECT) - else: - self.world.client_id = p.connect(p.GUI) - - # Disable the side windows of the GUI - p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) - # Change the init camera pose - p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1]) - - # Get the initial camera target location - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) - - # Create a sphere with a radius of 0.05 and a mass of 0 - sphereUid = p.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=sphereVisualId, - basePosition=cameraTargetPosition) - - # Define the maxSpeed, used in calculations - maxSpeed = 16 - - # Set initial Camera Rotation - cameraYaw = 50 - cameraPitch = -35 - - # Keep track of the mouse state - mouseState = [0, 0, 0] - oldMouseX, oldMouseY = 0, 0 - - # Determines if the sphere at cameraTargetPosition is visible - visible = 1 - - # Loop to update the camera position based on keyboard events - while p.isConnected(self.world.client_id): - # Monitor user input - keys = p.getKeyboardEvents() - mouse = p.getMouseEvents() - - # Get infos about the camera - width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ - p.getDebugVisualizerCamera()[10] - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] - zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] - - # Check the mouse state - if mouse: - for m in mouse: - - mouseX = m[2] - mouseY = m[1] - - # update mouseState - # Left Mouse button - if m[0] == 2 and m[3] == 0: - mouseState[0] = m[4] - # Middle mouse butto (scroll wheel) - if m[0] == 2 and m[3] == 1: - mouseState[1] = m[4] - # right mouse button - if m[0] == 2 and m[3] == 2: - mouseState[2] = m[4] - - # change visibility by clicking the mousewheel - if m[4] == 6 and m[3] == 1 and visible == 1: - visible = 0 - elif m[4] == 6 and visible == 0: - visible = 1 - - # camera movement when the left mouse button is pressed - if mouseState[0] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed - - # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) - if mouseX < oldMouseX: - if (cameraPitch + speedX) < 89.5: - cameraPitch += (speedX / 4) + 1 - elif mouseX > oldMouseX: - if (cameraPitch - speedX) > -89.5: - cameraPitch -= (speedX / 4) + 1 - - if mouseY < oldMouseY: - cameraYaw += (speedY / 4) + 1 - elif mouseY > oldMouseY: - cameraYaw -= (speedY / 4) + 1 - - if mouseState[1] == 3: - speedX = abs(oldMouseX - mouseX) - factor = 0.05 - - if mouseX < oldMouseX: - dist = dist - speedX * factor - elif mouseX > oldMouseX: - dist = dist + speedX * factor - dist = max(dist, 0.1) - - # camera movement when the right mouse button is pressed - if mouseState[2] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 - factor = 0.05 - - if mouseX < oldMouseX: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - elif mouseX > oldMouseX: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - - if mouseY < oldMouseY: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - elif mouseY > oldMouseY: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - # update oldMouse values - oldMouseY, oldMouseX = mouseY, mouseX - - # check the keyboard state - if keys: - # if shift is pressed, double the speed - if p.B3G_SHIFT in keys: - speedMult = 5 - else: - speedMult = 2.5 - - # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key - # change - if p.B3G_CONTROL in keys: - - # the up and down arrowkeys cause the targetPos to move along the z axis of the map - if p.B3G_DOWN_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - elif p.B3G_UP_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - - # left and right arrowkeys cause the targetPos to move horizontally relative to the camera - if p.B3G_LEFT_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - elif p.B3G_RIGHT_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - - # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera - # while the camera stays at a constant distance. SHIFT + '=' is for US layout - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - elif ord("-") in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - - # standard bindings for thearrowkeys, the '+' as well as the '-' key - else: - - # left and right arrowkeys cause the camera to rotate around the yaw axis - if p.B3G_RIGHT_ARROW in keys: - cameraYaw += (360 / width) * speedMult - elif p.B3G_LEFT_ARROW in keys: - cameraYaw -= (360 / width) * speedMult - - # the up and down arrowkeys cause the camera to rotate around the pitch axis - if p.B3G_DOWN_ARROW in keys: - if (cameraPitch + (360 / height) * speedMult) < 89.5: - cameraPitch += (360 / height) * speedMult - elif p.B3G_UP_ARROW in keys: - if (cameraPitch - (360 / height) * speedMult) > -89.5: - cameraPitch -= (360 / height) * speedMult - - # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without - # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - if (dist - (dist * 0.02) * speedMult) > 0.1: - dist -= dist * 0.02 * speedMult - elif ord("-") in keys: - dist += dist * 0.02 * speedMult - - p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition) - if visible == 0: - cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) - time.sleep(1. / 80.) - - -class Object: - """ - Represents a spawned Object in the BulletWorld. - """ - - def __init__(self, name: str, type: Union[str, ObjectType], path: str, - pose: Pose = None, - world: BulletWorld = None, - color: Optional[List[float]] = [1, 1, 1, 1], - ignoreCachedFiles: Optional[bool] = False): - """ - The constructor loads the urdf file into the given BulletWorld, if no BulletWorld is specified the - :py:attr:`~BulletWorld.current_bullet_world` will be used. It is also possible to load .obj and .stl file into the BulletWorld. - The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. - - :param name: The name of the object - :param type: The type of the object - :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched - :param pose: The pose at which the Object should be spawned - :param world: The BulletWorld in which the object should be spawned, if no world is specified the :py:attr:`~BulletWorld.current_bullet_world` will be used - :param color: The color with which the object should be spawned. - :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. - """ - if not pose: - pose = Pose() - self.world: BulletWorld = world if world is not None else BulletWorld.current_bullet_world - self.local_transformer = LocalTransformer() - self.name: str = name - self.type: str = type - self.color: List[float] = color - pose_in_map = self.local_transformer.transform_pose(pose, "map") - position, orientation = pose_in_map.to_list() - self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) - self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") - self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") - self.attachments: Dict[Object, List] = {} - self.cids: Dict[Object, int] = {} - self.original_pose = pose_in_map - - self.tf_frame = ("shadow/" if self.world.is_shadow_world else "") + self.name + "_" + str(self.id) - - # This means "world" is not the shadow world since it has a reference to a shadow world - if self.world.shadow_world != None: - self.world.world_sync.add_obj_queue.put( - [name, type, path, position, orientation, self.world.shadow_world, color, self]) - - with open(self.path) as f: - self.urdf_object = URDF.from_xml_string(f.read()) - if self.urdf_object.name == robot_description.name and not BulletWorld.robot: - BulletWorld.robot = self - - self.links[self.urdf_object.get_root()] = -1 - - self._current_pose = pose_in_map - self._current_link_poses = {} - self._current_link_transforms = {} - self._current_joint_states = {} - self._init_current_joint_states() - self._update_link_poses() - - self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) - self.local_transformer.update_transforms_for_object(self) - self.link_to_geometry = self._get_geometry_for_link() - - self.world.objects.append(self) - - def __repr__(self): - skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", - "_current_link_transforms", "link_to_geometry"] - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" - - def remove(self) -> None: - """ - Removes this object from the BulletWorld it currently resides in. - For the object to be removed it has to be detached from all objects it - is currently attached to. After this is done a call to PyBullet is done - to remove this Object from the simulation. - """ - for obj in self.attachments.keys(): - self.world.detach(self, obj) - self.world.objects.remove(self) - # This means the current world of the object is not the shadow world, since it - # has a reference to the shadow world - if self.world.shadow_world is not None: - self.world.world_sync.remove_obj_queue.put(self) - self.world.world_sync.remove_obj_queue.join() - self.world.remove_object(self.id) - if BulletWorld.robot == self: - BulletWorld.robot = None - - def detach_all(self) -> None: - """ - Detach all objects attached to this object. - """ - attachments = self.attachments.copy() - for att in attachments.keys(): - self.world.detach(self, att) - - def get_position(self) -> Pose: - """ - Returns the position of this Object as a list of xyz. - - :return: The current position of this object - """ - return self.get_pose().position - - def get_orientation(self) -> Quaternion: - """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. - - :return: A list of xyzw - """ - return self.get_pose().orientation - - def get_pose(self) -> Pose: - """ - Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. - - :return: The current pose of this object - """ - return self._current_pose - - def set_pose(self, pose: Pose, base: bool = False) -> None: - """ - Sets the Pose of the object. - - :param pose: New Pose for the object - :param base: If True places the object base instead of origin at the specified position and orientation - """ - pose_in_map = self.local_transformer.transform_pose(pose, "map") - position, orientation = pose_in_map.to_list() - if base: - position = np.array(position) + self.base_origin_shift - self.world.reset_object_base_pose(self, position, orientation) - self._current_pose = pose_in_map - self._update_link_poses() - self.world._set_attached_objects(self, [self]) - - @property - def pose(self) -> Pose: - """ - Property that returns the current position of this Object. - - :return: The position as a list of xyz - """ - return self.get_pose() - - @pose.setter - def pose(self, value: Pose) -> None: - """ - Sets the Pose of the Object to the given value. Function for attribute use. - - :param value: New Pose of the Object - """ - self.set_pose(value) - - def move_base_to_origin_pos(self) -> None: - """ - Move the object such that its base will be at the current origin position. - This is useful when placing objects on surfaces where you want the object base in contact with the surface. - """ - self.set_pose(self.get_pose(), base=True) - - def _calculate_transform(self, obj: Object, link: str = None) -> Transform: - """ - Calculates the transformation between another object and the given - link of this object. If no link is provided then the base position will be used. - - :param obj: The other object for which the transformation should be calculated - :param link: The optional link name - :return: The transformation from the link (or base position) to the other objects base position - """ - transform = self.local_transformer.transform_to_object_frame(obj.pose, self, link) - - return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) - - def set_position(self, position: Union[Pose, Point], base=False) -> None: - """ - Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position - instead of the origin in the center of the Object. The given position can either be a Pose, - in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. - - :param position: Target position as xyz. - :param base: If the bottom of the Object should be placed or the origin in the center. - """ - pose = Pose() - if isinstance(position, Pose): - target_position = position.position - pose.frame = position.frame - else: - target_position = position - - pose.pose.position = target_position - pose.pose.orientation = self.get_orientation() - self.set_pose(pose, base=base) - - def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: - """ - Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only - the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. - - :param orientation: Target orientation given as a list of xyzw. - """ - pose = Pose() - if isinstance(orientation, Pose): - target_orientation = orientation.orientation - pose.frame = orientation.frame - else: - target_orientation = orientation - - pose.pose.position = self.get_position() - pose.pose.orientation = target_orientation - self.set_pose(pose) - - def _joint_or_link_name_to_id(self, name_type: str) -> Dict[str, int]: - """ - Creates a dictionary which maps the link or joint name to the unique ids used by pybullet. - - :param name_type: Determines if the dictionary should be for joints or links - :return: A dictionary that maps joint or link names to unique ids - """ - n_joints = self.world.get_object_number_of_joints(self) - joint_name_to_id = {} - for i in range(0, n_joints): - _id = self.world.get_object_joint_id(self, i) - if name_type == "joint": - _name = self.world.get_object_joint_name(self, i) - else: - _name = self.world.get_object_link_name(self, i) - joint_name_to_id[_name] = _id - return joint_name_to_id - - def get_joint_id(self, name: str) -> int: - """ - Returns the unique id for a joint name. As used by PyBullet. - - :param name: The joint name - :return: The unique id - """ - return self.joints[name] - - def get_link_id(self, name: str) -> int: - """ - Returns a unique id for a link name. As used by PyBullet. - - :param name: The link name - :return: The unique id - """ - return self.links[name] - - def get_link_by_id(self, id: int) -> str: - """ - Returns the name of a link for a given unique PyBullet id - - :param id: PyBullet id for link - :return: The link name - """ - return dict(zip(self.links.values(), self.links.keys()))[id] - - def get_joint_by_id(self, joint_id: int) -> str: - """ - Returns the joint name for a unique PyBullet id - - :param joint_id: The Pybullet id of for joint - :return: The joint name - """ - return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] - - def get_link_relative_to_other_link(self, source_frame: str, target_frame: str) -> Pose: - """ - Calculates the position of a link in the coordinate frame of another link. - - :param source_frame: The name of the source frame - :param target_frame: The name of the target frame - :return: The pose of the source frame in the target frame - """ - source_pose = self.get_link_pose(source_frame) - return self.local_transformer.transform_to_object_frame(source_pose, self, target_frame) - - def get_link_position(self, name: str) -> Point: - """ - Returns the position of a link of this Object. Position is returned as a list of xyz. - - :param name: The link name - :return: The link position as xyz - """ - return self.get_link_pose(name).position - - def get_link_orientation(self, name: str) -> Quaternion: - """ - Returns the orientation of a link of this Object. Orientation is returned as a quaternion. - - :param name: The name of the link - :return: The orientation of the link as a quaternion - """ - return self.get_link_pose(name).orientation - - def get_link_pose(self, name: str) -> Pose: - """ - Returns a Pose of the link corresponding to the given name. The returned Pose will be in world coordinate frame. - - :param name: Link name for which a Pose should be returned - :return: The pose of the link - """ - if name in self.links.keys() and self.links[name] == -1: - return self.get_pose() - return self._current_link_poses[name] - # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) - - def set_joint_state(self, joint_name: str, joint_pose: float) -> None: - """ - Sets the state of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. - - :param joint_name: The name of the joint - :param joint_pose: The target pose for this joint - """ - # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - up_lim, low_lim = self.world.get_object_joint_limits(self, joint_name) - if low_lim > up_lim: - low_lim, up_lim = up_lim, low_lim - if not low_lim <= joint_pose <= up_lim: - logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {joint_name} are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_pose}") - # Temporarily disabled because kdl outputs values exciting joint limits - # return - self.world.reset_joint_state(self, joint_name, joint_pose) - self._current_joint_states[joint_name] = joint_pose - # self.local_transformer.update_transforms_for_object(self) - self._update_link_poses() - self.world._set_attached_objects(self, [self]) - - def set_joint_states(self, joint_poses: dict) -> None: - """ - Sets the current state of multiple joints at once, this method should be preferred when setting multiple joints - at once instead of running :func:`~Object.set_joint_state` in a loop. - - :param joint_poses: - :return: - """ - for joint_name, joint_pose in joint_poses.items(): - self.world.reset_joint_state(self, joint_name, joint_pose) - self._current_joint_states[joint_name] = joint_pose - self._update_link_poses() - self.world._set_attached_objects(self, [self]) - - def get_joint_state(self, joint_name: str) -> float: - """ - Returns the joint state for the given joint name. - - :param joint_name: The name of the joint - :return: The current pose of the joint - """ - return self._current_joint_states[joint_name] - - def contact_points(self) -> List: - """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :return: A list of all contact points with other objects - """ - return self.world.get_object_contact_points(self) - - def contact_points_simulated(self) -> List: - """ - Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :return: A list of contact points between this Object and other Objects - """ - s = self.world.save_state() - self.world.step() - contact_points = self.contact_points() - self.world.restore_state(*s) - return contact_points - - def update_joints_from_topic(self, topic_name: str) -> None: - """ - Updates the joints of this object with positions obtained from a topic with the message type JointState. - Joint names on the topic have to correspond to the joints of this object otherwise an error message will be logged. - - :param topic_name: Name of the topic with the joint states - """ - msg = rospy.wait_for_message(topic_name, JointState) - joint_names = msg.name - joint_positions = msg.position - if set(joint_names).issubset(self.joints.keys()): - for i in range(len(joint_names)): - self.set_joint_state(joint_names[i], joint_positions[i]) - else: - add_joints = set(joint_names) - set(self.joints.keys()) - rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ - The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") - - def update_pose_from_tf(self, frame: str) -> None: - """ - Updates the pose of this object from a TF message. - - :param frame: Name of the TF frame from which the position should be taken - """ - tf_listener = tf.TransformListener() - time.sleep(0.5) - position, orientation = tf_listener.lookupTransform(frame, "map", rospy.Time(0)) - position = [position[0][0] * -1, - position[0][1] * -1, - position[0][2]] - self.set_position(Pose(position, orientation)) - - def set_color(self, color: List[float], link: Optional[str] = "") -> None: - """ - Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. - - :param color: The color as RGBA values between 0 and 1 - :param link: The link name of the link which should be colored - """ - self.world.set_object_color(self, color, link) - - def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: - """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: - - 1. A list with the color as RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the - object is spawned. - - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. - - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color - """ - return self.world.get_object_color(self, link) - - def get_AABB(self, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param link_name: The Optional name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. - """ - return self.world.get_object_AABB(self, link_name) - - def get_base_origin(self, link_name: Optional[str] = None) -> Pose: - """ - Returns the origin of the base/bottom of an object/link - - :param link_name: The link name for which the bottom position should be returned - :return: The position of the bottom of this Object or link - """ - aabb = self.get_AABB(link_name=link_name) - base_width = np.absolute(aabb[0][0] - aabb[1][0]) - base_length = np.absolute(aabb[0][1] - aabb[1][1]) - return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], - self.get_pose().orientation_as_list()) - - def get_joint_limits(self, joint: str) -> Tuple[float, float]: - """ - Returns the lower and upper limit of a joint, if the lower limit is higher - than the upper they are swapped to ensure the lower limit is always the smaller one. - - :param joint: The name of the joint for which the limits should be found. - :return: The lower and upper limit of the joint. - """ - if joint not in self.joints.keys(): - raise KeyError(f"The given Joint: {joint} is not part of this object") - lower, upper = self.world.get_object_joint_limits(self, joint) - if lower > upper: - lower, upper = upper, lower - return lower, upper - - def get_joint_axis(self, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ - return self.world.get_object_joint_axis(self, joint_name) - - def get_joint_type(self, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ - return self.world.get_object_joint_type(self, joint_name) - - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: - """ - Traverses the chain from 'link_name' to the URDF origin and returns the first joint that is of type 'joint_type'. - - :param link_name: Link name above which the joint should be found - :param joint_type: Joint type that should be searched for - :return: Name of the first joint which has the given type - """ - chain = self.urdf_object.get_chain(self.urdf_object.get_root(), link_name) - reversed_chain = reversed(chain) - container_joint = None - for element in reversed_chain: - if element in self.joints and self.get_joint_type(element) == joint_type: - container_joint = element - break - if not container_joint: - rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") - return container_joint - - def get_complete_joint_state(self) -> Dict[str: float]: - """ - Returns the complete joint state of the object as a dictionary of joint names and joint values. - - :return: A dictionary with the complete joint state - """ - return self._current_joint_states - - def get_link_tf_frame(self, link_name: str) -> str: - """ - Returns the name of the tf frame for the given link name. This method does not check if the given name is - actually a link of this object. - - :param link_name: Name of a link for which the tf frame should be returned - :return: A TF frame name for a specific link - """ - return self.tf_frame + "/" + link_name - - def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: - """ - Extracts the geometry information for each collision of each link and links them to the respective link. - - :return: A dictionary with link name as key and geometry information as value - """ - link_to_geometry = {} - for link in self.links.keys(): - link_obj = self.urdf_object.link_map[link] - if not link_obj.collision: - link_to_geometry[link] = None - else: - link_to_geometry[link] = link_obj.collision.geometry - return link_to_geometry - - def _update_link_poses(self) -> None: - """ - Updates the cached poses and transforms for each link of this Object - """ - for link_name in self.links.keys(): - if link_name == self.urdf_object.get_root(): - self._current_link_poses[link_name] = self._current_pose - self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) - else: - self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) - self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( - self.get_link_tf_frame(link_name)) - - def _init_current_joint_states(self) -> None: - """ - Initialize the cached joint position for each joint. - """ - for joint_name in self.joints.keys(): - self._current_joint_states[joint_name] = self.world.get_object_joint_position(self, joint_name) - - -def filter_contact_points(contact_points, exclude_ids) -> List: - """ - Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. - - :param contact_points: A list of contact points - :param exclude_ids: A list of unique ids of Objects that should be removed from the list - :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' - """ - return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) - - -def get_path_from_data_dir(file_name: str, data_directory: str) -> str: - """ - Returns the full path for a given file name in the given directory. If there is no file with the given filename - this method returns None. - - :param file_name: The filename of the searched file. - :param data_directory: The directory in which to search for the file. - :return: The full path in the filesystem or None if there is no file with the filename in the directory - """ - dir = pathlib.Path(data_directory) - for file in os.listdir(data_directory): - if file == file_name: - return data_directory + f"/{file_name}" - - -def _get_robot_name_from_urdf(urdf_string: str) -> str: - """ - Extracts the robot name from the 'robot_name' tag of a URDF. - - :param urdf_string: The URDF as string. - :return: The name of the robot described by the URDF. - """ - res = re.findall(r"robot\ *name\ *=\ *\"\ *[a-zA-Z_0-9]*\ *\"", urdf_string) - if len(res) == 1: - begin = res[0].find("\"") - end = res[0][begin + 1:].find("\"") - robot = res[0][begin + 1:begin + 1 + end].lower() - return robot - - -def _load_object(name: str, - path: str, - position: List[float], - orientation: List[float], - world: BulletWorld, - color: List[float], - ignoreCachedFiles: bool) -> Tuple[int, str]: - """ - Loads an object to the given BulletWorld with the given position and orientation. The color will only be - used when an .obj or .stl file is given. - If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created - and this URDf file will be loaded instead. - When spawning a URDf file a new file will be created in the cache directory, if there exists none. - This new file will have resolved mesh file paths, meaning there will be no references - to ROS packges instead there will be absolute file paths. - - :param name: The name of the object which should be spawned - :param path: The path to the source file or the name on the ROS parameter server - :param position: The position in which the object should be spawned - :param orientation: The orientation in which the object should be spawned - :param world: The BulletWorld to which the Object should be spawned - :param color: The color of the object, only used when .obj or .stl file is given - :param ignoreCachedFiles: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path to the file used for spawning - """ - pa = pathlib.Path(path) - extension = pa.suffix - world, world_id = _world_and_id(world) - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for dir in world.data_directory: - path = get_path_from_data_dir(path, dir) - if path: break - - if not path: - raise FileNotFoundError( - f"File {pa.name} could not be found in the resource directory {world.data_directory}") - # rospack = rospkg.RosPack() - # cach_dir = rospack.get_path('pycram') + '/resources/cached/' - cach_dir = world.data_directory[0] + '/cached/' - if not pathlib.Path(cach_dir).exists(): - os.mkdir(cach_dir) - - # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path, name, cach_dir) or ignoreCachedFiles: - if extension == ".obj" or extension == ".stl": - path = _generate_urdf_file(name, path, color, cach_dir) - elif extension == ".urdf": - with open(path, mode="r") as f: - urdf_string = fix_missing_inertial(f.read()) - urdf_string = remove_error_tags(urdf_string) - urdf_string = fix_link_attributes(urdf_string) - try: - urdf_string = _correct_urdf_string(urdf_string) - except rospkg.ResourceNotFound as e: - rospy.logerr(f"Could not find resource package linked in this URDF") - raise e - path = cach_dir + pa.name - with open(path, mode="w") as f: - f.write(urdf_string) - else: # Using the urdf from the parameter server - urdf_string = rospy.get_param(path) - path = cach_dir + name + ".urdf" - with open(path, mode="w") as f: - f.write(_correct_urdf_string(urdf_string)) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = cach_dir + pa.stem + ".urdf" - elif extension == ".urdf": - path = cach_dir + pa.name - else: - path = cach_dir + name + ".urdf" - - try: - obj = p.loadURDF(path, basePosition=position, baseOrientation=orientation, physicsClientId=world_id) - return obj, path - except p.error as e: - logging.error( - "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") - os.remove(path) - raise (e) - # print(f"{bcolors.BOLD}{bcolors.WARNING}The path has to be either a path to a URDf file, stl file, obj file or the name of a URDF on the parameter server.{bcolors.ENDC}") - - -def _is_cached(path: str, name: str, cach_dir: str) -> bool: - """ - Checks if the file in the given path is already cached or if - there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from - the parameter server is used. - - :param path: The path given by the user to the source file. - :param name: The name for this object. - :param cach_dir: The absolute path the cach directory in the pycram package. - :return: True if there already exists a chached file, False in any other case. - """ - file_name = pathlib.Path(path).name - p = pathlib.Path(cach_dir + file_name) - if p.exists(): - return True - # Returns filename without the filetype, e.g. returns "test" for "test.txt" - file_stem = pathlib.Path(path).stem - p = pathlib.Path(cach_dir + file_stem + ".urdf") - if p.exists(): - return True - return False - - -def _correct_urdf_string(urdf_string: str) -> str: - """ - Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS - package paths. - - :param urdf_name: The name of the URDf on the parameter server - :return: The URDF string with paths in the filesystem instead of ROS packages - """ - r = rospkg.RosPack() - new_urdf_string = "" - for line in urdf_string.split('\n'): - if "package://" in line: - s = line.split('//') - s1 = s[1].split('/') - path = r.get_path(s1[0]) - line = line.replace("package://" + s1[0], path) - new_urdf_string += line + '\n' - - return fix_missing_inertial(new_urdf_string) - - -def fix_missing_inertial(urdf_string: str) -> str: - """ - Insert inertial tags for every URDF link that has no inertia. - This is used to prevent PyBullet from dumping warnings in the terminal - - :param urdf_string: The URDF description as string - :returns: The new, corrected URDF description as string. - """ - - inertia_tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.Element("inertial")) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("mass", {"value": "0.1"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("inertia", {"ixx": "0.01", - "ixy": "0", - "ixz": "0", - "iyy": "0.01", - "iyz": "0", - "izz": "0.01"})) - - # create tree from string - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - - for link_element in tree.iter("link"): - inertial = [*link_element.iter("inertial")] - if len(inertial) == 0: - link_element.append(inertia_tree.getroot()) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def remove_error_tags(urdf_string: str) -> str: - """ - Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the - URDF_parser - - :param urdf_string: String of the URDF from which the tags should be removed - :return: The URDF string with the tags removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - removing_tags = ["gazebo", "transmission"] - for tag_name in removing_tags: - all_tags = tree.findall(tag_name) - for tag in all_tags: - tree.getroot().remove(tag) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def fix_link_attributes(urdf_string: str) -> str: - """ - Removes the attribute 'type' from links since this is not parsable by the URDF parser. - - :param urdf_string: The string of the URDF from which the attributes should be removed - :return: The URDF string with the attributes removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - - for link in tree.iter("link"): - if "type" in link.attrib.keys(): - del link.attrib["type"] - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) -> str: - """ - Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be - used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name - as filename. - - :param name: The name of the object - :param path: The path to the .obj or .stl file - :param color: The color which should be used for the material tag - :param cach_dir The absolute file path to the cach directory in the pycram package - :return: The absolute path of the created file - """ - urdf_template = ' \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - ' - urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, color))) - pathlib_obj = pathlib.Path(path) - path = str(pathlib_obj.resolve()) - content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) - with open(cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: - file.write(content) - return cach_dir + pathlib_obj.stem + ".urdf" - - -def _world_and_id(world: BulletWorld) -> Tuple[BulletWorld, int]: - """ - Selects the world to be used. If the given world is None the 'current_bullet_world' is used. - - :param world: The world which should be used or None if 'current_bullet_world' should be used - :return: The BulletWorld object and the id of this BulletWorld - """ - world = world if world is not None else BulletWorld.current_bullet_world - id = world.client_id if world is not None else BulletWorld.current_bullet_world.client_id - return world, id diff --git a/src/pycram/bullet_world_reasoning.py b/src/pycram/world_reasoning.py similarity index 99% rename from src/pycram/bullet_world_reasoning.py rename to src/pycram/world_reasoning.py index 9a6c0ee94..23e0c8924 100644 --- a/src/pycram/bullet_world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -3,7 +3,7 @@ import numpy as np import rospy -from .bullet_world import _world_and_id, Object, Use_shadow_world, BulletWorld +from .world import _world_and_id, Object, Use_shadow_world, BulletWorld from .external_interfaces.ik import request_ik from .local_transformer import LocalTransformer from .plan_failures import IKError @@ -360,5 +360,5 @@ def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], l shadow_object = BulletWorld.current_bullet_world.get_shadow_object(object) with Use_shadow_world(): for joint, pose in joint_config.items(): - shadow_object.set_joint_state(joint, pose) + shadow_object.set_joint_position(joint, pose) return shadow_object.get_link_pose(link_name) diff --git a/test/local_transformer_tests.py b/test/local_transformer_tests.py index ee7375fcb..fc8c48f3e 100644 --- a/test/local_transformer_tests.py +++ b/test/local_transformer_tests.py @@ -3,7 +3,7 @@ from time import sleep -from src.pycram.bullet_world import BulletWorld, Object +from src.pycram.world import BulletWorld, Object from src.pycram.local_transformer import LocalTransformer from pycram.robot_descriptions import robot_description from pycram.pose import Pose, Transform diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 49c58c436..5c5b41b3b 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -18,7 +18,7 @@ def test_move_torso(self): self.assertEqual(description.ground().position, 0.3) with simulated_robot: description.resolve().perform() - self.assertEqual(self.world.robot.get_joint_state(robot_description.torso_joint), 0.3) + self.assertEqual(self.world.robot.get_joint_position(robot_description.torso_joint), 0.3) def test_set_gripper(self): description = action_designator.SetGripperAction(["left"], ["open", "close"]) @@ -28,7 +28,7 @@ def test_set_gripper(self): with simulated_robot: description.resolve().perform() for joint, state in robot_description.get_static_gripper_chain("left", "open").items(): - self.assertEqual(self.world.robot.get_joint_state(joint), state) + self.assertEqual(self.world.robot.get_joint_position(joint), state) def test_release(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) @@ -48,9 +48,9 @@ def test_park_arms(self): with simulated_robot: description.resolve().perform() for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - self.assertEqual(self.world.robot.get_joint_state(joint), pose) + self.assertEqual(self.world.robot.get_joint_position(joint), pose) for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - self.assertEqual(self.world.robot.get_joint_state(joint), pose) + self.assertEqual(self.world.robot.get_joint_position(joint), pose) def test_navigate(self): description = action_designator.NavigateAction([Pose([0, 0, 0], [0, 0, 0, 1])]) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 6417e739c..fbe4d3605 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -1,7 +1,7 @@ import unittest import numpy as np -from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial +from pycram.world import BulletWorld, Object, fix_missing_inertial from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index da537fff3..085b15d47 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -1,7 +1,7 @@ import time from test_bullet_world import BulletWorldTest -import pycram.bullet_world_reasoning as btr +import pycram.world_reasoning as btr from pycram.pose import Pose from pycram.robot_descriptions import robot_description diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 585a77774..124057c4d 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -5,7 +5,7 @@ import sqlalchemy.orm import pycram.plan_failures -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 98884a0d7..5a9101ebe 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -5,7 +5,7 @@ import requests import pycram.plan_failures -from pycram.bullet_world import BulletWorld, Object +from pycram.world import BulletWorld, Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot diff --git a/test/test_location_designator.py b/test/test_location_designator.py index ab94ec6bb..f4a9fdb74 100644 --- a/test/test_location_designator.py +++ b/test/test_location_designator.py @@ -11,7 +11,7 @@ class TestActionDesignatorGrounding(test_bullet_world.BulletWorldTest): def test_reachability(self): - self.robot.set_joint_state(robot_description.torso_joint, 0.3) + self.robot.set_joint_position(robot_description.torso_joint, 0.3) object_desig = ObjectDesignatorDescription(names=["milk"]) robot_desig = ObjectDesignatorDescription(names=[robot_description.name]) location_desig = CostmapLocation(object_desig.resolve(), reachable_for=robot_desig.resolve()) @@ -37,7 +37,7 @@ def test_visibility(self): self.assertTrue(len(location.pose.orientation_as_list()) == 4) def test_reachability_and_visibility(self): - self.robot.set_joint_state(robot_description.torso_joint, 0.3) + self.robot.set_joint_position(robot_description.torso_joint, 0.3) object_desig = ObjectDesignatorDescription(names=["milk"]) robot_desig = ObjectDesignatorDescription(names=[robot_description.name]) location_desig = CostmapLocation(object_desig.resolve(), reachable_for=robot_desig.resolve(), visible_for=robot_desig.resolve()) From 40d2d47c6ff418f1e3bc0eb4ea113e5196e48d25 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 30 Nov 2023 12:23:56 +0100 Subject: [PATCH 003/195] [RefactoringObjectClass] Now object class is independent of pybullet, and the tests are passing --- src/pycram/world.py | 1907 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 1907 insertions(+) create mode 100644 src/pycram/world.py diff --git a/src/pycram/world.py b/src/pycram/world.py new file mode 100644 index 000000000..695900c90 --- /dev/null +++ b/src/pycram/world.py @@ -0,0 +1,1907 @@ +# used for delayed evaluation of typing until python 3.11 becomes mainstream +from __future__ import annotations + +import logging +import os +import pathlib +import re +import threading +import time +import xml.etree.ElementTree +from queue import Queue +import tf +from typing import List, Optional, Dict, Tuple, Callable +from typing import Union + +import numpy as np +import pybullet as p +import rospkg +import rospy +import rosgraph + +import urdf_parser_py.urdf +from geometry_msgs.msg import Quaternion, Point +from urdf_parser_py.urdf import URDF + +from .event import Event +from .robot_descriptions import robot_description +from .enums import JointType, ObjectType +from .local_transformer import LocalTransformer +from sensor_msgs.msg import JointState + +from .pose import Pose, Transform + + +class BulletWorld: + """ + The BulletWorld Class represents the physics Simulation and belief state. + """ + + current_bullet_world: BulletWorld = None + """ + Global reference to the currently used BulletWorld, usually this is the + graphical one. However, if you are inside a Use_shadow_world() environment the current_bullet_world points to the + shadow world. In this way you can comfortably use the current_bullet_world, which should point towards the BulletWorld + used at the moment. + """ + robot: Object = None + """ + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the + URDF with the name of the URDF on the parameter server. + """ + + # Check is for sphinx autoAPI to be able to work in a CI workflow + if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): + rospy.init_node('pycram') + + def __init__(self, type: str = "GUI", is_shadow_world: bool = False): + """ + Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the + background. There can only be one rendered simulation. + The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. + + :param type: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param is_shadow_world: For internal usage, decides if this BulletWorld should be used as a shadow world. + """ + self.objects: List[Object] = [] + self.client_id: int = -1 + self.detachment_event: Event = Event() + self.attachment_event: Event = Event() + self.manipulation_event: Event = Event() + self.type: str = type + self._gui_thread: Gui = Gui(self, type) + self._gui_thread.start() + # This disables file caching from PyBullet, since this would also cache + # files that can not be loaded + p.setPhysicsEngineParameter(enableFileCaching=0) + # Needed to let the other thread start the simulation, before Objects are spawned. + time.sleep(0.1) + if BulletWorld.current_bullet_world == None: + BulletWorld.current_bullet_world = self + self.vis_axis: List[Object] = [] + self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} + self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] + self.shadow_world: BulletWorld = BulletWorld("DIRECT", True) if not is_shadow_world else None + self.world_sync: WorldSync = WorldSync(self, self.shadow_world) if not is_shadow_world else None + self.is_shadow_world: bool = is_shadow_world + self.local_transformer = LocalTransformer() + if not is_shadow_world: + self.world_sync.start() + self.local_transformer.bullet_world = self + self.local_transformer.shadow_world = self.shadow_world + + # Some default settings + self.set_gravity([0, 0, -9.8]) + if not is_shadow_world: + plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) + # atexit.register(self.exit) + + def get_objects_by_name(self, name: str) -> List[Object]: + """ + Returns a list of all Objects in this BulletWorld with the same name as the given one. + + :param name: The name of the returned Objects. + :return: A list of all Objects with the name 'name'. + """ + return list(filter(lambda obj: obj.name == name, self.objects)) + + def get_objects_by_type(self, obj_type: str) -> List[Object]: + """ + Returns a list of all Objects which have the type 'obj_type'. + + :param obj_type: The type of the returned Objects. + :return: A list of all Objects that have the type 'obj_type'. + """ + return list(filter(lambda obj: obj.type == obj_type, self.objects)) + + def get_object_by_id(self, id: int) -> Object: + """ + Returns the single Object that has the unique id. + + :param id: The unique id for which the Object should be returned. + :return: The Object with the id 'id'. + """ + return list(filter(lambda obj: obj.id == id, self.objects))[0] + + def remove_object(self, obj_id: int) -> None: + """ + Remove an object by its ID. + + :param obj_id: The unique id of the object to be removed. + """ + + p.removeBody(obj_id, self.client_id) + + def attach_objects(self, + parent_obj: Object, + child_obj: Object, + parent_link: Optional[str] = None, + loose: Optional[bool] = False) -> None: + """ + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a constraint of pybullet will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. + For example, if the parent object moves, the child object will also move, but not the other way around. + + :param parent_obj: The parent object (jf loose, then this would not move when child moves) + :param child_obj: The child object + :param parent_link: The link of the parent object to which the child object should be attached + :param loose: If the attachment should be a loose attachment. + """ + link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 + link_to_object = parent_obj._calculate_transform(child_obj, parent_link) + parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] + child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] + + cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, + [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], + link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + parent_obj.cids[child_obj] = cid + child_obj.cids[parent_obj] = cid + self.attachment_event(parent_obj, [parent_obj, child_obj]) + + def detach_objects(self, obj1: Object, obj2: Object) -> None: + """ + Detaches obj2 from obj1. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of pybullet. + Afterward the detachment event of the corresponding BulletWorld will be fired. + + :param obj1: The object from which an object should be detached. + :param obj2: The object which should be detached. + """ + del obj1.attachments[obj2] + del obj2.attachments[obj1] + + p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) + + del obj1.cids[obj2] + del obj2.cids[obj1] + obj1.world.detachment_event(obj1, [obj1, obj2]) + + def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param prev_object: A list of Objects that were already moved, + these will be excluded to prevent loops in the update. + """ + for att_obj in obj.attachments: + if att_obj in prev_object: + continue + if obj.attachments[att_obj][2]: + # Updates the attachment transformation and constraint if the + # attachment is loose, instead of updating the position of all attached objects + link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) + link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 + obj.attachments[att_obj][0] = link_to_object + att_obj.attachments[obj][0] = link_to_object.invert() + p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) + cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], + link_to_object.translation_as_list(), + [0, 0, 0], link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + obj.cids[att_obj] = cid + att_obj.cids[obj] = cid + else: + link_to_object = obj.attachments[att_obj][0] + + world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") + p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), + world_to_object.orientation_as_list(), + physicsClientId=self.client_id) + att_obj._current_pose = world_to_object + self._set_attached_objects(att_obj, prev_object + [obj]) + + def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: + """ + Get the joint limits of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + :return: A tuple containing the upper and the lower limits of the joint. + """ + up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] + return up_lim, low_lim + + def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param obj: The object + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + + def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param obj: The object + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] + return JointType(joint_type) + + def get_object_joint_position(self, obj: Object, joint_name: str) -> float: + """ + Get the state of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + + def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + """ + Get the pose of a link of an articulated object with respect to the world frame. + The pose is given as a tuple of position and orientation. + + :param obj: The object + :param link_name: The name of the link + """ + return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + + def get_object_contact_points(self, obj: Object) -> List: + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :param obj: The object. + :return: A list of all contact points with other objects + """ + return p.getContactPoints(obj.id) + + def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + """ + Get the ID of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + + def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + """ + Get the name of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + + def get_object_link_name(self, obj: Object, link_idx: int) -> str: + """ + Get the name of a link in an articulated object. + + :param obj: The object + :param link_idx: The index of the link (would indicate order). + """ + return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + + def get_object_number_of_joints(self, obj: Object) -> int: + """ + Get the number of joints of an articulated object + + :param obj: The object + """ + return p.getNumJoints(obj.id, self.client_id) + + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + """ + Reset the joint position instantly without physics simulation + + :param obj: The object + :param joint_name: The name of the joint + :param joint_pose: The new joint pose + """ + p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + + def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): + """ + Reset the world position and orientation of the base of the object instantaneously, + not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. + + :param obj: The object + :param position: The new position of the object as a vector of x,y,z + :param orientation: The new orientation of the object as a quaternion of x,y,z,w + """ + p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + + def step(self): + """ + Step the world simulation using forward dynamics + """ + p.stepSimulation(self.client_id) + + def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. Optionally a link name can can be provided, if no link + name is provided all links of this object will be colored. + + :param obj: The object which should be colored + :param color: The color as RGBA values between 0 and 1 + :param link: The link name of the link which should be colored + """ + if link == "": + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if obj.links != {}: + for link_id in obj.links.values(): + p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) + + def get_object_color(self, + obj: Object, + link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + """ + This method returns the color of this object or a link of this object. If no link is given then the + return is either: + + 1. A list with the color as RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + object is spawned. + + If a link is specified then the return is a list with RGBA values representing the color of this link. + It may be that this link has no color, in this case the return is None as well as an error message. + + :param obj: The object for which the color should be returned. + :param link: the link name for which the color should be returned. + :return: The color of the object or link, or a dictionary containing every colored link with its color + """ + visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) + swap = {v: k for k, v in obj.links.items()} + links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) + colors = list(map(lambda x: x[7], visual_data)) + link_to_color = dict(zip(links, colors)) + + if link: + if link in link_to_color.keys(): + return link_to_color[link] + elif link not in obj.links.keys(): + rospy.logerr(f"The link '{link}' is not part of this obejct") + return None + else: + rospy.logerr(f"The link '{link}' has no color") + return None + + if len(visual_data) == 1: + return list(visual_data[0][7]) + else: + return link_to_color + + def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case + the axis aligned bounding box of the link will be returned. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :param link_name: The Optional name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + if link_name: + return p.getAABB(obj.id, obj.links[link_name], self.client_id) + else: + return p.getAABB(obj.id, physicsClientId=self.client_id) + + def get_attachment_event(self) -> Event: + """ + Returns the event reference that is fired if an attachment occurs. + + :return: The reference to the attachment event + """ + return self.attachment_event + + def get_detachment_event(self) -> Event: + """ + Returns the event reference that is fired if a detachment occurs. + + :return: The event reference for the detachment event. + """ + return self.detachment_event + + def get_manipulation_event(self) -> Event: + """ + Returns the event reference that is fired if any manipulation occurs. + + :return: The event reference for the manipulation event. + """ + return self.manipulation_event + + def set_realtime(self, real_time: bool) -> None: + """ + Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only + simulated to reason about it. + + :param real_time: Whether the BulletWorld should simulate Physic in real time. + """ + p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + + def set_gravity(self, velocity: List[float]) -> None: + """ + Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity + is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + + :param velocity: The gravity vector that should be used in the BulletWorld. + """ + p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) + + def set_robot(self, robot: Object) -> None: + """ + Sets the global variable for the robot Object. This should be set on spawning the robot. + + :param robot: The Object reference to the Object representing the robot. + """ + BulletWorld.robot = robot + + def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + """ + Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real + time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By + setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real + time. + + :param seconds: The amount of seconds that should be simulated. + :param real_time: If the simulation should happen in real time or faster. + """ + for i in range(0, int(seconds * 240)): + p.stepSimulation(self.client_id) + for objects, callback in self.coll_callbacks.items(): + contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) + # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) + # print(contact_points[0][5]) + if contact_points != (): + callback[0]() + elif callback[1] != None: # Call no collision callback + callback[1]() + if real_time: + # Simulation runs at 240 Hz + time.sleep(0.004167) + + def exit(self) -> None: + """ + Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the + preferred method to close the BulletWorld. + """ + # True if this is NOT the shadow world since it has a reference to the + # Shadow world + time.sleep(0.1) + if self.shadow_world: + self.world_sync.terminate = True + self.world_sync.join() + self.shadow_world.exit() + p.disconnect(self.client_id) + if self._gui_thread: + self._gui_thread.join() + if BulletWorld.current_bullet_world == self: + BulletWorld.current_bullet_world = None + BulletWorld.robot = None + + def save_state(self) -> Tuple[int, Dict]: + """ + Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint + position of every Object in the BulletWorld. + + :return: A unique id of the state + """ + objects2attached = {} + # ToDo find out what this is for and where it is used + for o in self.objects: + objects2attached[o] = (o.attachments.copy(), o.cids.copy()) + return p.saveState(self.client_id), objects2attached + + def restore_state(self, state, objects2attached: Optional[Dict] = None) -> None: + """ + Restores the state of the BulletWorld according to the given state id. This includes position, orientation and + joint states. However, restore can not respawn objects if there are objects that were deleted between creation of + the state and restoring they will be skiped. + + :param state: The unique id representing the state, as returned by :func:`~save_state` + :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~bullet_world.Object.attachments` + """ + p.restoreState(state, physicsClientId=self.client_id) + objects2attached = {} if objects2attached is None else objects2attached + for obj in self.objects: + try: + obj.attachments, obj.cids = objects2attached[obj] + except KeyError: + continue + + def copy(self) -> BulletWorld: + """ + Copies this Bullet World into another and returns it. The other BulletWorld + will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. + This method should only be used if necessary since there can be unforeseen problems. + + :return: The reference to the new BulletWorld + """ + world = BulletWorld("DIRECT") + for obj in self.objects: + o = Object(obj.name, obj.type, obj.path, Pose(obj.get_position(), obj.get_orientation()), + world, obj.color) + for joint in obj.joints: + o.set_joint_position(joint, obj.get_joint_position(joint)) + return world + + def add_vis_axis(self, pose: Pose, + length: Optional[float] = 0.2) -> None: + """ + Creates a Visual object which represents the coordinate frame at the given + position and orientation. There can be an unlimited amount of vis axis objects. + + :param pose: The pose at which the axis should be spawned + :param length: Optional parameter to configure the length of the axes + """ + + position, orientation = pose.to_list() + + vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], + rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) + vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], + rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) + vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], + rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) + + obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], + basePosition=position, baseOrientation=orientation, + linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkParentIndices=[0, 0, 0], + linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], + linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], + linkCollisionShapeIndices=[-1, -1, -1]) + + self.vis_axis.append(obj) + + def remove_vis_axis(self) -> None: + """ + Removes all spawned vis axis objects that are currently in this BulletWorld. + """ + for id in self.vis_axis: + p.removeBody(id) + self.vis_axis = [] + + def register_collision_callback(self, objectA: Object, objectB: Object, + callback_collision: Callable, + callback_no_collision: Optional[Callable] = None) -> None: + """ + Registers callback methods for contact between two Objects. There can be a callback for when the two Objects + get in contact and, optionally, for when they are not in contact anymore. + + :param objectA: An object in the BulletWorld + :param objectB: Another object in the BulletWorld + :param callback_collision: A function that should be called if the objects are in contact + :param callback_no_collision: A function that should be called if the objects are not in contact + """ + self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) + + def add_additional_resource_path(self, path: str) -> None: + """ + Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an + Object is spawned only with a filename. + + :param path: A path in the filesystem in which to search for files. + """ + self.data_directory.append(path) + + def get_shadow_object(self, object: Object) -> Object: + """ + Returns the corresponding object from the shadow world for the given object. If the given Object is already in + the shadow world it is returned. + + :param object: The object for which the shadow worlds object should be returned. + :return: The corresponding object in the shadow world. + """ + try: + return self.world_sync.object_mapping[object] + except KeyError: + shadow_world = self if self.is_shadow_world else self.shadow_world + if object in shadow_world.objects: + return object + else: + raise ValueError( + f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") + + def get_bullet_object_for_shadow(self, object: Object) -> Object: + """ + Returns the corresponding object from the main Bullet World for a given + object in the shadow world. If the given object is not in the shadow + world an error will be raised. + + :param object: The object for which the corresponding object in the main Bullet World should be found + :return: The object in the main Bullet World + """ + map = self.world_sync.object_mapping + try: + return list(map.keys())[list(map.values()).index(object)] + except ValueError: + raise ValueError("The given object is not in the shadow world.") + + def reset_bullet_world(self) -> None: + """ + Resets the BulletWorld to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and all objects will be set to the position and + orientation in which they were spawned. + """ + for obj in self.objects: + if obj.attachments: + attached_objects = list(obj.attachments.keys()) + for att_obj in attached_objects: + obj.detach(att_obj) + joint_names = list(obj.joints.keys()) + joint_poses = [0 for j in joint_names] + obj.set_positions_of_all_joints(dict(zip(joint_names, joint_poses))) + obj.set_pose(obj.original_pose) + + +class Use_shadow_world(): + """ + An environment for using the shadow world, while in this environment the :py:attr:`~BulletWorld.current_bullet_world` + variable will point to the shadow world. + + Example: + with Use_shadow_world(): + NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() + """ + + def __init__(self): + self.prev_world: BulletWorld = None + + def __enter__(self): + if not BulletWorld.current_bullet_world.is_shadow_world: + time.sleep(20 / 240) + # blocks until the adding queue is ready + BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() + # **This is currently not used since the sleep(20/240) seems to be enough, but on weaker hardware this might + # not be a feasible solution** + # while not BulletWorld.current_bullet_world.world_sync.equal_states: + # time.sleep(0.1) + + self.prev_world = BulletWorld.current_bullet_world + BulletWorld.current_bullet_world.world_sync.pause_sync = True + BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.shadow_world + + def __exit__(self, *args): + if not self.prev_world == None: + BulletWorld.current_bullet_world = self.prev_world + BulletWorld.current_bullet_world.world_sync.pause_sync = False + + +class WorldSync(threading.Thread): + """ + Synchronizes the state between the BulletWorld and its shadow world. + Meaning the cartesian and joint position of everything in the shadow world will be + synchronized with the main BulletWorld. + Adding and removing objects is done via queues, such that loading times of objects + in the shadow world does not affect the BulletWorld. + The class provides the possibility to pause the synchronization, this can be used + if reasoning should be done in the shadow world. + """ + + def __init__(self, world: BulletWorld, shadow_world: BulletWorld): + threading.Thread.__init__(self) + self.world: BulletWorld = world + self.shadow_world: BulletWorld = shadow_world + self.shadow_world.world_sync: WorldSync = self + + self.terminate: bool = False + self.add_obj_queue: Queue = Queue() + self.remove_obj_queue: Queue = Queue() + self.pause_sync: bool = False + # Maps bullet to shadow world objects + self.object_mapping: Dict[Object, Object] = {} + self.equal_states = False + + def run(self): + """ + Main method of the synchronization, this thread runs in a loop until the + terminate flag is set. + While this loop runs it continuously checks the cartesian and joint position of + every object in the BulletWorld and updates the corresponding object in the + shadow world. When there are entries in the adding or removing queue the corresponding objects will be added + or removed in the same iteration. + """ + while not self.terminate: + self.check_for_pause() + # self.equal_states = False + for i in range(self.add_obj_queue.qsize()): + obj = self.add_obj_queue.get() + # [name, type, path, position, orientation, self.world.shadow_world, color, bulletworld object] + o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) + # Maps the BulletWorld object to the shadow world object + self.object_mapping[obj[7]] = o + self.add_obj_queue.task_done() + for i in range(self.remove_obj_queue.qsize()): + obj = self.remove_obj_queue.get() + # Get shadow world object reference from object mapping + shadow_obj = self.object_mapping[obj] + shadow_obj.remove() + del self.object_mapping[obj] + self.remove_obj_queue.task_done() + + for bulletworld_obj, shadow_obj in self.object_mapping.items(): + b_pose = bulletworld_obj.get_pose() + s_pose = shadow_obj.get_pose() + if b_pose.dist(s_pose) != 0.0: + shadow_obj.set_pose(bulletworld_obj.get_pose()) + + # Manage joint positions + if len(bulletworld_obj.joints) > 2: + for joint_name in bulletworld_obj.joints.keys(): + if shadow_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): + shadow_obj.set_positions_of_all_joints(bulletworld_obj.get_positions_of_all_joints()) + break + + self.check_for_pause() + # self.check_for_equal() + time.sleep(1 / 240) + + self.add_obj_queue.join() + self.remove_obj_queue.join() + + def check_for_pause(self) -> None: + """ + Checks if :py:attr:`~self.pause_sync` is true and sleeps this thread until it isn't anymore. + """ + while self.pause_sync: + time.sleep(0.1) + + def check_for_equal(self) -> None: + """ + Checks if both BulletWorlds have the same state, meaning all objects are in the same position. + This is currently not used, but might be used in the future if synchronization issues worsen. + """ + eql = True + for obj, shadow_obj in self.object_mapping.items(): + eql = eql and obj.get_pose() == shadow_obj.get_pose() + self.equal_states = eql + + +class Gui(threading.Thread): + """ + For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~BulletWorld.exit` + Also contains the code for controlling the camera. + """ + + def __init__(self, world, type): + threading.Thread.__init__(self) + self.world: BulletWorld = world + self.type: str = type + + def run(self): + """ + Initializes the new simulation and checks in an endless loop + if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and + thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. + """ + if self.type != "GUI": + self.world.client_id = p.connect(p.DIRECT) + else: + self.world.client_id = p.connect(p.GUI) + + # Disable the side windows of the GUI + p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) + # Change the init camera pose + p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, + cameraTargetPosition=[-2, 0, 1]) + + # Get the initial camera target location + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) + + # Create a sphere with a radius of 0.05 and a mass of 0 + sphereUid = p.createMultiBody(baseMass=0.0, + baseInertialFramePosition=[0, 0, 0], + baseVisualShapeIndex=sphereVisualId, + basePosition=cameraTargetPosition) + + # Define the maxSpeed, used in calculations + maxSpeed = 16 + + # Set initial Camera Rotation + cameraYaw = 50 + cameraPitch = -35 + + # Keep track of the mouse state + mouseState = [0, 0, 0] + oldMouseX, oldMouseY = 0, 0 + + # Determines if the sphere at cameraTargetPosition is visible + visible = 1 + + # Loop to update the camera position based on keyboard events + while p.isConnected(self.world.client_id): + # Monitor user input + keys = p.getKeyboardEvents() + mouse = p.getMouseEvents() + + # Get infos about the camera + width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ + p.getDebugVisualizerCamera()[10] + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + # Get vectors used for movement on x,y,z Vector + xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] + yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] + + # Check the mouse state + if mouse: + for m in mouse: + + mouseX = m[2] + mouseY = m[1] + + # update mouseState + # Left Mouse button + if m[0] == 2 and m[3] == 0: + mouseState[0] = m[4] + # Middle mouse butto (scroll wheel) + if m[0] == 2 and m[3] == 1: + mouseState[1] = m[4] + # right mouse button + if m[0] == 2 and m[3] == 2: + mouseState[2] = m[4] + + # change visibility by clicking the mousewheel + if m[4] == 6 and m[3] == 1 and visible == 1: + visible = 0 + elif m[4] == 6 and visible == 0: + visible = 1 + + # camera movement when the left mouse button is pressed + if mouseState[0] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed + + # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) + if mouseX < oldMouseX: + if (cameraPitch + speedX) < 89.5: + cameraPitch += (speedX / 4) + 1 + elif mouseX > oldMouseX: + if (cameraPitch - speedX) > -89.5: + cameraPitch -= (speedX / 4) + 1 + + if mouseY < oldMouseY: + cameraYaw += (speedY / 4) + 1 + elif mouseY > oldMouseY: + cameraYaw -= (speedY / 4) + 1 + + if mouseState[1] == 3: + speedX = abs(oldMouseX - mouseX) + factor = 0.05 + + if mouseX < oldMouseX: + dist = dist - speedX * factor + elif mouseX > oldMouseX: + dist = dist + speedX * factor + dist = max(dist, 0.1) + + # camera movement when the right mouse button is pressed + if mouseState[2] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 + factor = 0.05 + + if mouseX < oldMouseX: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + elif mouseX > oldMouseX: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + + if mouseY < oldMouseY: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + elif mouseY > oldMouseY: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + # update oldMouse values + oldMouseY, oldMouseX = mouseY, mouseX + + # check the keyboard state + if keys: + # if shift is pressed, double the speed + if p.B3G_SHIFT in keys: + speedMult = 5 + else: + speedMult = 2.5 + + # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key + # change + if p.B3G_CONTROL in keys: + + # the up and down arrowkeys cause the targetPos to move along the z axis of the map + if p.B3G_DOWN_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + elif p.B3G_UP_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + + # left and right arrowkeys cause the targetPos to move horizontally relative to the camera + if p.B3G_LEFT_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + elif p.B3G_RIGHT_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + + # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera + # while the camera stays at a constant distance. SHIFT + '=' is for US layout + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + elif ord("-") in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + + # standard bindings for thearrowkeys, the '+' as well as the '-' key + else: + + # left and right arrowkeys cause the camera to rotate around the yaw axis + if p.B3G_RIGHT_ARROW in keys: + cameraYaw += (360 / width) * speedMult + elif p.B3G_LEFT_ARROW in keys: + cameraYaw -= (360 / width) * speedMult + + # the up and down arrowkeys cause the camera to rotate around the pitch axis + if p.B3G_DOWN_ARROW in keys: + if (cameraPitch + (360 / height) * speedMult) < 89.5: + cameraPitch += (360 / height) * speedMult + elif p.B3G_UP_ARROW in keys: + if (cameraPitch - (360 / height) * speedMult) > -89.5: + cameraPitch -= (360 / height) * speedMult + + # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without + # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + if (dist - (dist * 0.02) * speedMult) > 0.1: + dist -= dist * 0.02 * speedMult + elif ord("-") in keys: + dist += dist * 0.02 * speedMult + + p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, + cameraTargetPosition=cameraTargetPosition) + if visible == 0: + cameraTargetPosition = (0.0, -50, 50) + p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) + time.sleep(1. / 80.) + + +class Object: + """ + Represents a spawned Object in the BulletWorld. + """ + + def __init__(self, name: str, type: Union[str, ObjectType], path: str, + pose: Pose = None, + world: BulletWorld = None, + color: Optional[List[float]] = [1, 1, 1, 1], + ignoreCachedFiles: Optional[bool] = False): + """ + The constructor loads the urdf file into the given BulletWorld, if no BulletWorld is specified the + :py:attr:`~BulletWorld.current_bullet_world` will be used. It is also possible to load .obj and .stl file into the BulletWorld. + The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. + + :param name: The name of the object + :param type: The type of the object + :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched + :param pose: The pose at which the Object should be spawned + :param world: The BulletWorld in which the object should be spawned, if no world is specified the :py:attr:`~BulletWorld.current_bullet_world` will be used + :param color: The color with which the object should be spawned. + :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. + """ + if not pose: + pose = Pose() + self.world: BulletWorld = world if world is not None else BulletWorld.current_bullet_world + self.local_transformer = LocalTransformer() + self.name: str = name + self.type: str = type + self.color: List[float] = color + pose_in_map = self.local_transformer.transform_pose(pose, "map") + position, orientation = pose_in_map.to_list() + self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) + self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") + self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") + self.attachments: Dict[Object, List] = {} + self.cids: Dict[Object, int] = {} + self.original_pose = pose_in_map + + self.tf_frame = ("shadow/" if self.world.is_shadow_world else "") + self.name + "_" + str(self.id) + + # This means "world" is not the shadow world since it has a reference to a shadow world + if self.world.shadow_world != None: + self.world.world_sync.add_obj_queue.put( + [name, type, path, position, orientation, self.world.shadow_world, color, self]) + + with open(self.path) as f: + self.urdf_object = URDF.from_xml_string(f.read()) + if self.urdf_object.name == robot_description.name and not BulletWorld.robot: + BulletWorld.robot = self + + self.links[self.urdf_object.get_root()] = -1 + + self._current_pose = pose_in_map + self._current_link_poses = {} + self._current_link_transforms = {} + self._current_joints_positions = {} + self._init_current_positions_of_joint() + self._update_link_poses() + + self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) + self.local_transformer.update_transforms_for_object(self) + self.link_to_geometry = self._get_geometry_for_link() + + self.world.objects.append(self) + + def __repr__(self): + skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", + "_current_link_transforms", "link_to_geometry"] + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" + + def remove(self) -> None: + """ + Removes this object from the BulletWorld it currently resides in. + For the object to be removed it has to be detached from all objects it + is currently attached to. After this is done a call to PyBullet is done + to remove this Object from the simulation. + """ + for obj in self.attachments.keys(): + self.world.detach(self, obj) + self.world.objects.remove(self) + # This means the current world of the object is not the shadow world, since it + # has a reference to the shadow world + if self.world.shadow_world is not None: + self.world.world_sync.remove_obj_queue.put(self) + self.world.world_sync.remove_obj_queue.join() + self.world.remove_object(self.id) + if BulletWorld.robot == self: + BulletWorld.robot = None + + def attach(self, obj: Object, link: Optional[str] = None, loose: Optional[bool] = False) -> None: + """ + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a constraint of pybullet will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. For example, if this object moves the + other, attached, object will also move but not the other way around. + + :param object: The other object that should be attached + :param link: The link of this object to which the other object should be + :param loose: If the attachment should be a loose attachment. + """ + self.world.attach_objects(self, obj, link, loose) + + def detach(self, obj: Object) -> None: + """ + Detaches another object from this object. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of pybullet. + Afterward the detachment event of the corresponding BulletWorld will be fired. + + :param object: The object which should be detached + """ + self.world.detach_objects(self, obj) + + def detach_all(self) -> None: + """ + Detach all objects attached to this object. + """ + attachments = self.attachments.copy() + for att in attachments.keys(): + self.world.detach(self, att) + + def get_position(self) -> Pose: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_pose().position + + def get_orientation(self) -> Quaternion: + """ + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw + """ + return self.get_pose().orientation + + def get_pose(self) -> Pose: + """ + Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. + + :return: The current pose of this object + """ + return self._current_pose + + def set_pose(self, pose: Pose, base: bool = False) -> None: + """ + Sets the Pose of the object. + + :param pose: New Pose for the object + :param base: If True places the object base instead of origin at the specified position and orientation + """ + pose_in_map = self.local_transformer.transform_pose(pose, "map") + position, orientation = pose_in_map.to_list() + if base: + position = np.array(position) + self.base_origin_shift + self.world.reset_object_base_pose(self, position, orientation) + self._current_pose = pose_in_map + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + @property + def pose(self) -> Pose: + """ + Property that returns the current position of this Object. + + :return: The position as a list of xyz + """ + return self.get_pose() + + @pose.setter + def pose(self, value: Pose) -> None: + """ + Sets the Pose of the Object to the given value. Function for attribute use. + + :param value: New Pose of the Object + """ + self.set_pose(value) + + def move_base_to_origin_pos(self) -> None: + """ + Move the object such that its base will be at the current origin position. + This is useful when placing objects on surfaces where you want the object base in contact with the surface. + """ + self.set_pose(self.get_pose(), base=True) + + def _set_attached_objects(self, prev_object: List[Object]) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param prev_object: A list of Objects that were already moved, these will be excluded to prevent loops in the update. + """ + self.world._set_attached_objects(self, prev_object) + + def _calculate_transform(self, obj: Object, link: str = None) -> Transform: + """ + Calculates the transformation between another object and the given + link of this object. If no link is provided then the base position will be used. + + :param obj: The other object for which the transformation should be calculated + :param link: The optional link name + :return: The transformation from the link (or base position) to the other objects base position + """ + transform = self.local_transformer.transform_to_object_frame(obj.pose, self, link) + + return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + + def set_position(self, position: Union[Pose, Point], base=False) -> None: + """ + Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position + instead of the origin in the center of the Object. The given position can either be a Pose, + in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + + :param position: Target position as xyz. + :param base: If the bottom of the Object should be placed or the origin in the center. + """ + pose = Pose() + if isinstance(position, Pose): + target_position = position.position + pose.frame = position.frame + else: + target_position = position + + pose.pose.position = target_position + pose.pose.orientation = self.get_orientation() + self.set_pose(pose, base=base) + + def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: + """ + Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only + the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. + + :param orientation: Target orientation given as a list of xyzw. + """ + pose = Pose() + if isinstance(orientation, Pose): + target_orientation = orientation.orientation + pose.frame = orientation.frame + else: + target_orientation = orientation + + pose.pose.position = self.get_position() + pose.pose.orientation = target_orientation + self.set_pose(pose) + + def _joint_or_link_name_to_id(self, name_type: str) -> Dict[str, int]: + """ + Creates a dictionary which maps the link or joint name to the unique ids used by pybullet. + + :param name_type: Determines if the dictionary should be for joints or links + :return: A dictionary that maps joint or link names to unique ids + """ + n_joints = self.world.get_object_number_of_joints(self) + joint_name_to_id = {} + for i in range(0, n_joints): + _id = self.world.get_object_joint_id(self, i) + if name_type == "joint": + _name = self.world.get_object_joint_name(self, i) + else: + _name = self.world.get_object_link_name(self, i) + joint_name_to_id[_name] = _id + return joint_name_to_id + + def get_joint_id(self, name: str) -> int: + """ + Returns the unique id for a joint name. As used by PyBullet. + + :param name: The joint name + :return: The unique id + """ + return self.joints[name] + + def get_link_id(self, name: str) -> int: + """ + Returns a unique id for a link name. As used by PyBullet. + + :param name: The link name + :return: The unique id + """ + return self.links[name] + + def get_link_by_id(self, id: int) -> str: + """ + Returns the name of a link for a given unique PyBullet id + + :param id: PyBullet id for link + :return: The link name + """ + return dict(zip(self.links.values(), self.links.keys()))[id] + + def get_joint_by_id(self, joint_id: int) -> str: + """ + Returns the joint name for a unique PyBullet id + + :param joint_id: The Pybullet id of for joint + :return: The joint name + """ + return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] + + def get_link_relative_to_other_link(self, source_frame: str, target_frame: str) -> Pose: + """ + Calculates the position of a link in the coordinate frame of another link. + + :param source_frame: The name of the source frame + :param target_frame: The name of the target frame + :return: The pose of the source frame in the target frame + """ + source_pose = self.get_link_pose(source_frame) + return self.local_transformer.transform_to_object_frame(source_pose, self, target_frame) + + def get_link_position(self, name: str) -> Point: + """ + Returns the position of a link of this Object. Position is returned as a list of xyz. + + :param name: The link name + :return: The link position as xyz + """ + return self.get_link_pose(name).position + + def get_link_orientation(self, name: str) -> Quaternion: + """ + Returns the orientation of a link of this Object. Orientation is returned as a quaternion. + + :param name: The name of the link + :return: The orientation of the link as a quaternion + """ + return self.get_link_pose(name).orientation + + def get_link_pose(self, name: str) -> Pose: + """ + Returns a Pose of the link corresponding to the given name. The returned Pose will be in world coordinate frame. + + :param name: Link name for which a Pose should be returned + :return: The pose of the link + """ + if name in self.links.keys() and self.links[name] == -1: + return self.get_pose() + return self._current_link_poses[name] + # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) + + def set_joint_position(self, joint_name: str, joint_pose: float) -> None: + """ + Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated + in the URDF, an error will be printed. However, the joint will be set either way. + + :param joint_name: The name of the joint + :param joint_pose: The target pose for this joint + """ + # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly + up_lim, low_lim = self.world.get_object_joint_limits(self, joint_name) + if low_lim > up_lim: + low_lim, up_lim = up_lim, low_lim + if not low_lim <= joint_pose <= up_lim: + logging.error( + f"The joint position has to be within the limits of the joint. The joint limits for {joint_name} are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_pose}") + # Temporarily disabled because kdl outputs values exciting joint limits + # return + self.world.reset_joint_position(self, joint_name, joint_pose) + self._current_joints_positions[joint_name] = joint_pose + # self.local_transformer.update_transforms_for_object(self) + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + def set_positions_of_all_joints(self, joint_poses: dict) -> None: + """ + Sets the current position of multiple joints at once, this method should be preferred when setting multiple joints + at once instead of running :func:`~Object.set_joint_position` in a loop. + + :param joint_poses: + :return: + """ + for joint_name, joint_pose in joint_poses.items(): + self.world.reset_joint_position(self, joint_name, joint_pose) + self._current_joints_positions[joint_name] = joint_pose + self._update_link_poses() + self.world._set_attached_objects(self, [self]) + + def get_joint_position(self, joint_name: str) -> float: + """ + Returns the joint position for the given joint name. + + :param joint_name: The name of the joint + :return: The current pose of the joint + """ + return self._current_joints_positions[joint_name] + + def contact_points(self) -> List: + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :return: A list of all contact points with other objects + """ + return self.world.get_object_contact_points(self) + + def contact_points_simulated(self) -> List: + """ + Returns a list of all contact points between this Object and other Objects after stepping the simulation once. + For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :return: A list of contact points between this Object and other Objects + """ + s = self.world.save_state() + self.world.step() + contact_points = self.contact_points() + self.world.restore_state(*s) + return contact_points + + def update_joints_from_topic(self, topic_name: str) -> None: + """ + Updates the joints of this object with positions obtained from a topic with the message type JointState. + Joint names on the topic have to correspond to the joints of this object otherwise an error message will be logged. + + :param topic_name: Name of the topic with the joint states + """ + msg = rospy.wait_for_message(topic_name, JointState) + joint_names = msg.name + joint_positions = msg.position + if set(joint_names).issubset(self.joints.keys()): + for i in range(len(joint_names)): + self.set_joint_position(joint_names[i], joint_positions[i]) + else: + add_joints = set(joint_names) - set(self.joints.keys()) + rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ + The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") + + def update_pose_from_tf(self, frame: str) -> None: + """ + Updates the pose of this object from a TF message. + + :param frame: Name of the TF frame from which the position should be taken + """ + tf_listener = tf.TransformListener() + time.sleep(0.5) + position, orientation = tf_listener.lookupTransform(frame, "map", rospy.Time(0)) + position = [position[0][0] * -1, + position[0][1] * -1, + position[0][2]] + self.set_position(Pose(position, orientation)) + + def set_color(self, color: List[float], link: Optional[str] = "") -> None: + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. Optionally a link name can can be provided, if no link + name is provided all links of this object will be colored. + + :param color: The color as RGBA values between 0 and 1 + :param link: The link name of the link which should be colored + """ + self.world.set_object_color(self, color, link) + + def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + """ + This method returns the color of this object or a link of this object. If no link is given then the + return is either: + + 1. A list with the color as RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + object is spawned. + + If a link is specified then the return is a list with RGBA values representing the color of this link. + It may be that this link has no color, in this case the return is None as well as an error message. + + :param link: the link name for which the color should be returned. + :return: The color of the object or link, or a dictionary containing every colored link with its color + """ + return self.world.get_object_color(self, link) + + def get_AABB(self, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case + the axis aligned bounding box of the link will be returned. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param link_name: The Optional name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + return self.world.get_object_AABB(self, link_name) + + def get_base_origin(self, link_name: Optional[str] = None) -> Pose: + """ + Returns the origin of the base/bottom of an object/link + + :param link_name: The link name for which the bottom position should be returned + :return: The position of the bottom of this Object or link + """ + aabb = self.get_AABB(link_name=link_name) + base_width = np.absolute(aabb[0][0] - aabb[1][0]) + base_length = np.absolute(aabb[0][1] - aabb[1][1]) + return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], + self.get_pose().orientation_as_list()) + + def get_joint_limits(self, joint: str) -> Tuple[float, float]: + """ + Returns the lower and upper limit of a joint, if the lower limit is higher + than the upper they are swapped to ensure the lower limit is always the smaller one. + + :param joint: The name of the joint for which the limits should be found. + :return: The lower and upper limit of the joint. + """ + if joint not in self.joints.keys(): + raise KeyError(f"The given Joint: {joint} is not part of this object") + lower, upper = self.world.get_object_joint_limits(self, joint) + if lower > upper: + lower, upper = upper, lower + return lower, upper + + def get_joint_axis(self, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return self.world.get_object_joint_axis(self, joint_name) + + def get_joint_type(self, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + return self.world.get_object_joint_type(self, joint_name) + + def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + """ + Traverses the chain from 'link_name' to the URDF origin and returns the first joint that is of type 'joint_type'. + + :param link_name: Link name above which the joint should be found + :param joint_type: Joint type that should be searched for + :return: Name of the first joint which has the given type + """ + chain = self.urdf_object.get_chain(self.urdf_object.get_root(), link_name) + reversed_chain = reversed(chain) + container_joint = None + for element in reversed_chain: + if element in self.joints and self.get_joint_type(element) == joint_type: + container_joint = element + break + if not container_joint: + rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") + return container_joint + + def get_positions_of_all_joints(self) -> Dict[str: float]: + """ + Returns the positions of all joints of the object as a dictionary of joint names and joint positions. + + :return: A dictionary with all joints positions'. + """ + return self._current_joints_positions + + def get_link_tf_frame(self, link_name: str) -> str: + """ + Returns the name of the tf frame for the given link name. This method does not check if the given name is + actually a link of this object. + + :param link_name: Name of a link for which the tf frame should be returned + :return: A TF frame name for a specific link + """ + return self.tf_frame + "/" + link_name + + def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: + """ + Extracts the geometry information for each collision of each link and links them to the respective link. + + :return: A dictionary with link name as key and geometry information as value + """ + link_to_geometry = {} + for link in self.links.keys(): + link_obj = self.urdf_object.link_map[link] + if not link_obj.collision: + link_to_geometry[link] = None + else: + link_to_geometry[link] = link_obj.collision.geometry + return link_to_geometry + + def _update_link_poses(self) -> None: + """ + Updates the cached poses and transforms for each link of this Object + """ + for link_name in self.links.keys(): + if link_name == self.urdf_object.get_root(): + self._current_link_poses[link_name] = self._current_pose + self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) + else: + self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) + self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( + self.get_link_tf_frame(link_name)) + + def _init_current_positions_of_joint(self) -> None: + """ + Initialize the cached joint position for each joint. + """ + for joint_name in self.joints.keys(): + self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) + + +def filter_contact_points(contact_points, exclude_ids) -> List: + """ + Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. + + :param contact_points: A list of contact points + :param exclude_ids: A list of unique ids of Objects that should be removed from the list + :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' + """ + return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) + + +def get_path_from_data_dir(file_name: str, data_directory: str) -> str: + """ + Returns the full path for a given file name in the given directory. If there is no file with the given filename + this method returns None. + + :param file_name: The filename of the searched file. + :param data_directory: The directory in which to search for the file. + :return: The full path in the filesystem or None if there is no file with the filename in the directory + """ + dir = pathlib.Path(data_directory) + for file in os.listdir(data_directory): + if file == file_name: + return data_directory + f"/{file_name}" + + +def _get_robot_name_from_urdf(urdf_string: str) -> str: + """ + Extracts the robot name from the 'robot_name' tag of a URDF. + + :param urdf_string: The URDF as string. + :return: The name of the robot described by the URDF. + """ + res = re.findall(r"robot\ *name\ *=\ *\"\ *[a-zA-Z_0-9]*\ *\"", urdf_string) + if len(res) == 1: + begin = res[0].find("\"") + end = res[0][begin + 1:].find("\"") + robot = res[0][begin + 1:begin + 1 + end].lower() + return robot + + +def _load_object(name: str, + path: str, + position: List[float], + orientation: List[float], + world: BulletWorld, + color: List[float], + ignoreCachedFiles: bool) -> Tuple[int, str]: + """ + Loads an object to the given BulletWorld with the given position and orientation. The color will only be + used when an .obj or .stl file is given. + If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created + and this URDf file will be loaded instead. + When spawning a URDf file a new file will be created in the cache directory, if there exists none. + This new file will have resolved mesh file paths, meaning there will be no references + to ROS packges instead there will be absolute file paths. + + :param name: The name of the object which should be spawned + :param path: The path to the source file or the name on the ROS parameter server + :param position: The position in which the object should be spawned + :param orientation: The orientation in which the object should be spawned + :param world: The BulletWorld to which the Object should be spawned + :param color: The color of the object, only used when .obj or .stl file is given + :param ignoreCachedFiles: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path to the file used for spawning + """ + pa = pathlib.Path(path) + extension = pa.suffix + world, world_id = _world_and_id(world) + if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): + for dir in world.data_directory: + path = get_path_from_data_dir(path, dir) + if path: break + + if not path: + raise FileNotFoundError( + f"File {pa.name} could not be found in the resource directory {world.data_directory}") + # rospack = rospkg.RosPack() + # cach_dir = rospack.get_path('pycram') + '/resources/cached/' + cach_dir = world.data_directory[0] + '/cached/' + if not pathlib.Path(cach_dir).exists(): + os.mkdir(cach_dir) + + # if file is not yet cached corrcet the urdf and save if in the cache directory + if not _is_cached(path, name, cach_dir) or ignoreCachedFiles: + if extension == ".obj" or extension == ".stl": + path = _generate_urdf_file(name, path, color, cach_dir) + elif extension == ".urdf": + with open(path, mode="r") as f: + urdf_string = fix_missing_inertial(f.read()) + urdf_string = remove_error_tags(urdf_string) + urdf_string = fix_link_attributes(urdf_string) + try: + urdf_string = _correct_urdf_string(urdf_string) + except rospkg.ResourceNotFound as e: + rospy.logerr(f"Could not find resource package linked in this URDF") + raise e + path = cach_dir + pa.name + with open(path, mode="w") as f: + f.write(urdf_string) + else: # Using the urdf from the parameter server + urdf_string = rospy.get_param(path) + path = cach_dir + name + ".urdf" + with open(path, mode="w") as f: + f.write(_correct_urdf_string(urdf_string)) + # save correct path in case the file is already in the cache directory + elif extension == ".obj" or extension == ".stl": + path = cach_dir + pa.stem + ".urdf" + elif extension == ".urdf": + path = cach_dir + pa.name + else: + path = cach_dir + name + ".urdf" + + try: + obj = p.loadURDF(path, basePosition=position, baseOrientation=orientation, physicsClientId=world_id) + return obj, path + except p.error as e: + logging.error( + "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") + os.remove(path) + raise (e) + # print(f"{bcolors.BOLD}{bcolors.WARNING}The path has to be either a path to a URDf file, stl file, obj file or the name of a URDF on the parameter server.{bcolors.ENDC}") + + +def _is_cached(path: str, name: str, cach_dir: str) -> bool: + """ + Checks if the file in the given path is already cached or if + there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from + the parameter server is used. + + :param path: The path given by the user to the source file. + :param name: The name for this object. + :param cach_dir: The absolute path the cach directory in the pycram package. + :return: True if there already exists a chached file, False in any other case. + """ + file_name = pathlib.Path(path).name + p = pathlib.Path(cach_dir + file_name) + if p.exists(): + return True + # Returns filename without the filetype, e.g. returns "test" for "test.txt" + file_stem = pathlib.Path(path).stem + p = pathlib.Path(cach_dir + file_stem + ".urdf") + if p.exists(): + return True + return False + + +def _correct_urdf_string(urdf_string: str) -> str: + """ + Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS + package paths. + + :param urdf_name: The name of the URDf on the parameter server + :return: The URDF string with paths in the filesystem instead of ROS packages + """ + r = rospkg.RosPack() + new_urdf_string = "" + for line in urdf_string.split('\n'): + if "package://" in line: + s = line.split('//') + s1 = s[1].split('/') + path = r.get_path(s1[0]) + line = line.replace("package://" + s1[0], path) + new_urdf_string += line + '\n' + + return fix_missing_inertial(new_urdf_string) + + +def fix_missing_inertial(urdf_string: str) -> str: + """ + Insert inertial tags for every URDF link that has no inertia. + This is used to prevent PyBullet from dumping warnings in the terminal + + :param urdf_string: The URDF description as string + :returns: The new, corrected URDF description as string. + """ + + inertia_tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.Element("inertial")) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("mass", {"value": "0.1"})) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) + inertia_tree.getroot().append(xml.etree.ElementTree.Element("inertia", {"ixx": "0.01", + "ixy": "0", + "ixz": "0", + "iyy": "0.01", + "iyz": "0", + "izz": "0.01"})) + + # create tree from string + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + + for link_element in tree.iter("link"): + inertial = [*link_element.iter("inertial")] + if len(inertial) == 0: + link_element.append(inertia_tree.getroot()) + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def remove_error_tags(urdf_string: str) -> str: + """ + Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the + URDF_parser + + :param urdf_string: String of the URDF from which the tags should be removed + :return: The URDF string with the tags removed + """ + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + removing_tags = ["gazebo", "transmission"] + for tag_name in removing_tags: + all_tags = tree.findall(tag_name) + for tag in all_tags: + tree.getroot().remove(tag) + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def fix_link_attributes(urdf_string: str) -> str: + """ + Removes the attribute 'type' from links since this is not parsable by the URDF parser. + + :param urdf_string: The string of the URDF from which the attributes should be removed + :return: The URDF string with the attributes removed + """ + tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + + for link in tree.iter("link"): + if "type" in link.attrib.keys(): + del link.attrib["type"] + + return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) -> str: + """ + Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be + used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name + as filename. + + :param name: The name of the object + :param path: The path to the .obj or .stl file + :param color: The color which should be used for the material tag + :param cach_dir The absolute file path to the cach directory in the pycram package + :return: The absolute path of the created file + """ + urdf_template = ' \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + ' + urdf_template = fix_missing_inertial(urdf_template) + rgb = " ".join(list(map(str, color))) + pathlib_obj = pathlib.Path(path) + path = str(pathlib_obj.resolve()) + content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) + with open(cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: + file.write(content) + return cach_dir + pathlib_obj.stem + ".urdf" + + +def _world_and_id(world: BulletWorld) -> Tuple[BulletWorld, int]: + """ + Selects the world to be used. If the given world is None the 'current_bullet_world' is used. + + :param world: The world which should be used or None if 'current_bullet_world' should be used + :return: The BulletWorld object and the id of this BulletWorld + """ + world = world if world is not None else BulletWorld.current_bullet_world + id = world.client_id if world is not None else BulletWorld.current_bullet_world.client_id + return world, id From 3af92d4fe401551d34c770688f25c034dd946122 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 30 Nov 2023 17:44:16 +0100 Subject: [PATCH 004/195] [WorldAbstractClass] InProgress , currently in add_constraint method --- doc/source/conf.py | 2 +- src/pycram/bullet_world.py | 8 +- src/pycram/local_transformer.py | 28 +- src/pycram/robot_description.py | 6 +- src/pycram/ros/force_torque_sensor.py | 4 +- src/pycram/ros/joint_state_publisher.py | 4 +- src/pycram/world.py | 702 ++++++++++++++++++++++-- test/test_action_designator.py | 2 +- 8 files changed, 690 insertions(+), 66 deletions(-) diff --git a/doc/source/conf.py b/doc/source/conf.py index cb9889b21..a21923062 100644 --- a/doc/source/conf.py +++ b/doc/source/conf.py @@ -196,7 +196,7 @@ # Example Thumbnail config nbsphinx_thumbnails = { - 'notebooks/bullet_world': os.path.abspath("notebooks/thumbnails/bullet_world.png"), + 'notebooks/world': os.path.abspath("notebooks/thumbnails/bullet_world.png"), 'notebooks/minimal_task_tree': os.path.abspath("notebooks/thumbnails/tree.png"), 'notebooks/action_designator': os.path.abspath("notebooks/thumbnails/action_designator.png"), 'notebooks/motion_designator': os.path.abspath("notebooks/thumbnails/motion_designator.png"), diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 19671d8c3..75de52e45 100644 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -90,8 +90,8 @@ def __init__(self, type: str = "GUI", is_shadow_world: bool = False): self.local_transformer = LocalTransformer() if not is_shadow_world: self.world_sync.start() - self.local_transformer.bullet_world = self - self.local_transformer.shadow_world = self.shadow_world + self.local_transformer.world = self + self.local_transformer.prospection_world = self.shadow_world # Some default settings self.set_gravity([0, 0, -9.8]) @@ -239,7 +239,7 @@ def restore_state(self, state, objects2attached: Dict = {}) -> None: the state and restoring they will be skiped. :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~bullet_world.Object.attachments` + :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` """ p.restoreState(state, physicsClientId=self.client_id) for obj in self.objects: @@ -450,7 +450,7 @@ def run(self): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.shadow_world, color, bulletworld object] + # [name, type, path, position, orientation, self.world.prospection_world, color, bulletworld object] o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) # Maps the BulletWorld object to the shadow world object self.object_mapping[obj[7]] = o diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index c68945182..9c0ede811 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -3,8 +3,8 @@ import tf -if 'bullet_world' in sys.modules: - logging.warning("(publisher) Make sure that you are not loading this module from pycram.bullet_world.") +if 'world' in sys.modules: + logging.warning("(publisher) Make sure that you are not loading this module from pycram.world.") import rospkg import rospy import atexit @@ -54,18 +54,18 @@ def __init__(self): self.static_tf_stampeds: List[TransformStamped] = [] # Since this file can't import world.py this holds the reference to the current_bullet_world - self.bullet_world = None - self.shadow_world = None + self.world = None + self.prospection_world = None # If the singelton was already initialized self._initialized = True def update_objects_for_current_world(self) -> None: """ - Updates transformations for all objects that are currently in :py:attr:`~pycram.bullet_world.BulletWorld.current_bullet_world` + Updates transformations for all objects that are currently in :py:attr:`~pycram.world.World.current_world` """ curr_time = rospy.Time.now() - for obj in list(self.bullet_world.current_bullet_world.objects): + for obj in list(self.world.current_bullet_world.objects): self.update_transforms_for_object(obj, curr_time) def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: @@ -92,20 +92,20 @@ def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: return Pose(*copy_pose.to_list(), frame=new_pose.header.frame_id) def transform_to_object_frame(self, pose: Pose, - bullet_object: 'bullet_world.Object', link_name: str = None) -> Union[Pose, None]: + world_object: 'world.Object', link_name: str = None) -> Union[Pose, None]: """ Transforms the given pose to the coordinate frame of the given BulletWorld object. If no link name is given the base frame of the Object is used, otherwise the link frame is used as target for the transformation. :param pose: Pose that should be transformed - :param bullet_object: BulletWorld Object in which frame the pose should be transformed - :param link_name: A link of the BulletWorld Object which will be used as target coordinate frame instead + :param world_object: World Object in which frame the pose should be transformed + :param link_name: A link of the World Object which will be used as target coordinate frame instead :return: The new pose the in coordinate frame of the object """ if link_name: - target_frame = bullet_object.get_link_tf_frame(link_name) + target_frame = world_object.get_link_tf_frame(link_name) else: - target_frame = bullet_object.tf_frame + target_frame = world_object.tf_frame return self.transform_pose(pose, target_frame) def tf_transform(self, source_frame: str, target_frame: str, @@ -124,15 +124,15 @@ def tf_transform(self, source_frame: str, target_frame: str, translation, rotation = self.lookupTransform(source_frame, target_frame, tf_time) return Transform(translation, rotation, source_frame, target_frame) - def update_transforms_for_object(self, bullet_object: 'bullet_world.Object', time: rospy.Time = None) -> None: + def update_transforms_for_object(self, world_object: 'world.Object', time: rospy.Time = None) -> None: """ Updates local transforms for a Bullet Object, this includes the base as well as all links - :param bullet_object: Object for which the Transforms should be updated + :param world_object: Object for which the Transforms should be updated :param time: a specific time that should be used """ time = time if time else rospy.Time.now() - for transform in bullet_object._current_link_transforms.values(): + for transform in world_object._current_link_transforms.values(): transform.header.stamp = time self.setTransform(transform) diff --git a/src/pycram/robot_description.py b/src/pycram/robot_description.py index d8df6f5b8..ab896d1e1 100644 --- a/src/pycram/robot_description.py +++ b/src/pycram/robot_description.py @@ -186,7 +186,7 @@ class GraspingDescription: """ def __init__(self, grasp_dir: Optional[Dict] = None): self.grasps: Dict[str, List[float]] = grasp_dir if grasp_dir else {} - self.grasps_for_object: Dict['bullet_world.Object', List[str]] = {} + self.grasps_for_object: Dict['world.Object', List[str]] = {} def add_grasp(self, grasp: str, orientation: List[float]) -> None: """ @@ -198,7 +198,7 @@ def add_grasp(self, grasp: str, orientation: List[float]) -> None: """ self.grasps[grasp] = orientation - def add_graspings_for_object(self, grasps: List[str], object: 'bullet_world.Object') -> None: + def add_graspings_for_object(self, grasps: List[str], object: 'world.Object') -> None: """ Adds all possible Grasps for the specified object. The used grasps have to be registered beforehand via the add_grasp method. @@ -214,7 +214,7 @@ def get_all_grasps(self) -> List[str]: def get_orientation_for_grasp(self, grasp: str) -> List[float]: return self.grasps[grasp] - def get_grasps_for_object(self, object: 'bullet_world.Object') -> List[str]: + def get_grasps_for_object(self, object: 'world.Object') -> List[str]: return self.grasps_for_object[object] diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index 6da358d55..314a9239a 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -13,12 +13,12 @@ class ForceTorqueSensor: """ Simulated force-torque sensor for a joint with a given name. - Reads simulated forces and torques at that joint from bullet_world and publishes geometry_msgs/Wrench messages + Reads simulated forces and torques at that joint from world and publishes geometry_msgs/Wrench messages to the given topic. """ def __init__(self, joint_name, fts_topic="/pycram/fts", interval=0.1): """ - The given joint_name has to be part of :py:attr:`~pycram.bullet_world.BulletWorld.robot` otherwise a + The given joint_name has to be part of :py:attr:`~pycram.world.BulletWorld.robot` otherwise a RuntimeError will be raised. :param joint_name: Name of the joint for which force-torque should be simulated diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index 1126c535d..f771b5565 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -15,7 +15,7 @@ class JointStatePublisher: """ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): """ - Robot object is from :py:attr:`~pycram.bullet_world.BulletWorld.robot` and current joint states are published to + Robot object is from :py:attr:`~pycram.world.BulletWorld.robot` and current joint states are published to the given joint_state_topic as a JointState message. :param joint_state_topic: Topic name to which the joint states should be published @@ -33,7 +33,7 @@ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): def _publish(self) -> None: """ - Publishes the current joint states of the :py:attr:`~pycram.bullet_world.BulletWorld.robot` in an infinite loop. + Publishes the current joint states of the :py:attr:`~pycram.world.BulletWorld.robot` in an infinite loop. The joint states are published as long as the kill_event is not set by :py:meth:`~JointStatePublisher._stop_publishing` """ robot = BulletWorld.robot diff --git a/src/pycram/world.py b/src/pycram/world.py index 695900c90..2e3c0f159 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -31,8 +31,648 @@ from .pose import Pose, Transform +from abc import ABC, abstractproperty, abstractmethod -class BulletWorld: + +class World(ABC): + """ + The World Class represents the physics Simulation and belief state. + """ + current_world: World = None + """ + Global reference to the currently used World, usually this is the + graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the + shadow world. In this way you can comfortably use the current_world, which should point towards the World + used at the moment. + """ + robot: Object = None + """ + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the + URDF with the name of the URDF on the parameter server. + """ + def __init__(self, mode: str, is_prospection_world: bool): + """ + Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the + background. There can only be one rendered simulation. + The World object also initializes the Events for attachment, detachment and for manipulating the world. + + :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param is_prospection_world: For internal usage, decides if this World should be used as a prospection world. + """ + self.objects: List[Object] = [] + self.client_id: int = -1 + self.detachment_event: Event = Event() + self.attachment_event: Event = Event() + self.manipulation_event: Event = Event() + self.mode: str = mode + if World.current_world is None: + World.current_world = self + self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} + self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] + self.prospection_world: World = World("DIRECT", True) if not is_prospection_world else None + self.world_sync: WorldSync = WorldSync(self, self.prospection_world) if not is_prospection_world else None + self.is_prospection_world: bool = is_prospection_world + self.local_transformer = LocalTransformer() + if not is_prospection_world: + self.world_sync.start() + self.local_transformer.world = self + self.local_transformer.prospection_world = self.prospection_world + + def get_objects_by_name(self, name: str) -> List[Object]: + """ + Returns a list of all Objects in this World with the same name as the given one. + + :param name: The name of the returned Objects. + :return: A list of all Objects with the name 'name'. + """ + return list(filter(lambda obj: obj.name == name, self.objects)) + + def get_objects_by_type(self, obj_type: str) -> List[Object]: + """ + Returns a list of all Objects which have the type 'obj_type'. + + :param obj_type: The type of the returned Objects. + :return: A list of all Objects that have the type 'obj_type'. + """ + return list(filter(lambda obj: obj.type == obj_type, self.objects)) + + def get_object_by_id(self, id: int) -> Object: + """ + Returns the single Object that has the unique id. + + :param id: The unique id for which the Object should be returned. + :return: The Object with the id 'id'. + """ + return list(filter(lambda obj: obj.id == id, self.objects))[0] + + @abstractmethod + def remove_object(self, obj_id: int) -> None: + """ + Remove an object by its ID. + + :param obj_id: The unique id of the object to be removed. + """ + pass + + def add_constraint(self, + parent_obj_id: int, + child_obj_id: int, + parent_link_id: int, + joint_type: int, + parent_to_child_transform: Transform, + joint_axis: List, + child_link_id: int) -> int: + """ + Add a constraint between two objects so that attachment they become attached + """ + cid = p.createConstraint(parent_obj_id, parent_link_id, child_obj_id, child_link_id, joint_type, + joint_axis, parent_to_child_transform.translation_as_list(), [0, 0, 0], + parent_to_child_transform.rotation_as_list(), + physicsClientId=self.client_id) + return cid + def attach_objects(self, + parent_obj: Object, + child_obj: Object, + parent_link: Optional[str] = None, + loose: Optional[bool] = False) -> None: + """ + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a constraint will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. + For example, if the parent object moves, the child object will also move, but not the other way around. + + :param parent_obj: The parent object (jf loose, then this would not move when child moves) + :param child_obj: The child object + :param parent_link: The link of the parent object to which the child object should be attached + :param loose: If the attachment should be a loose attachment. + """ + link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 + link_to_object = parent_obj._calculate_transform(child_obj, parent_link) + parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] + child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] + + cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, + [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], + link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + parent_obj.cids[child_obj] = cid + child_obj.cids[parent_obj] = cid + self.attachment_event(parent_obj, [parent_obj, child_obj]) + + def detach_objects(self, obj1: Object, obj2: Object) -> None: + """ + Detaches obj2 from obj1. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of pybullet. + Afterward the detachment event of the corresponding BulletWorld will be fired. + + :param obj1: The object from which an object should be detached. + :param obj2: The object which should be detached. + """ + del obj1.attachments[obj2] + del obj2.attachments[obj1] + + p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) + + del obj1.cids[obj2] + del obj2.cids[obj1] + obj1.world.detachment_event(obj1, [obj1, obj2]) + + def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param prev_object: A list of Objects that were already moved, + these will be excluded to prevent loops in the update. + """ + for att_obj in obj.attachments: + if att_obj in prev_object: + continue + if obj.attachments[att_obj][2]: + # Updates the attachment transformation and constraint if the + # attachment is loose, instead of updating the position of all attached objects + link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) + link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 + obj.attachments[att_obj][0] = link_to_object + att_obj.attachments[obj][0] = link_to_object.invert() + p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) + cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], + link_to_object.translation_as_list(), + [0, 0, 0], link_to_object.rotation_as_list(), + physicsClientId=self.client_id) + obj.cids[att_obj] = cid + att_obj.cids[obj] = cid + else: + link_to_object = obj.attachments[att_obj][0] + + world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") + p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), + world_to_object.orientation_as_list(), + physicsClientId=self.client_id) + att_obj._current_pose = world_to_object + self._set_attached_objects(att_obj, prev_object + [obj]) + + def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: + """ + Get the joint limits of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + :return: A tuple containing the upper and the lower limits of the joint. + """ + up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] + return up_lim, low_lim + + def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param obj: The object + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + + def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param obj: The object + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] + return JointType(joint_type) + + def get_object_joint_position(self, obj: Object, joint_name: str) -> float: + """ + Get the state of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + + def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + """ + Get the pose of a link of an articulated object with respect to the world frame. + The pose is given as a tuple of position and orientation. + + :param obj: The object + :param link_name: The name of the link + """ + return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + + def get_object_contact_points(self, obj: Object) -> List: + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :param obj: The object. + :return: A list of all contact points with other objects + """ + return p.getContactPoints(obj.id) + + def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + """ + Get the ID of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + + def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + """ + Get the name of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + + def get_object_link_name(self, obj: Object, link_idx: int) -> str: + """ + Get the name of a link in an articulated object. + + :param obj: The object + :param link_idx: The index of the link (would indicate order). + """ + return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + + def get_object_number_of_joints(self, obj: Object) -> int: + """ + Get the number of joints of an articulated object + + :param obj: The object + """ + return p.getNumJoints(obj.id, self.client_id) + + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + """ + Reset the joint position instantly without physics simulation + + :param obj: The object + :param joint_name: The name of the joint + :param joint_pose: The new joint pose + """ + p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + + def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): + """ + Reset the world position and orientation of the base of the object instantaneously, + not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. + + :param obj: The object + :param position: The new position of the object as a vector of x,y,z + :param orientation: The new orientation of the object as a quaternion of x,y,z,w + """ + p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + + def step(self): + """ + Step the world simulation using forward dynamics + """ + p.stepSimulation(self.client_id) + + def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. Optionally a link name can can be provided, if no link + name is provided all links of this object will be colored. + + :param obj: The object which should be colored + :param color: The color as RGBA values between 0 and 1 + :param link: The link name of the link which should be colored + """ + if link == "": + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if obj.links != {}: + for link_id in obj.links.values(): + p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) + else: + p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) + + def get_object_color(self, + obj: Object, + link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + """ + This method returns the color of this object or a link of this object. If no link is given then the + return is either: + + 1. A list with the color as RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + object is spawned. + + If a link is specified then the return is a list with RGBA values representing the color of this link. + It may be that this link has no color, in this case the return is None as well as an error message. + + :param obj: The object for which the color should be returned. + :param link: the link name for which the color should be returned. + :return: The color of the object or link, or a dictionary containing every colored link with its color + """ + visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) + swap = {v: k for k, v in obj.links.items()} + links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) + colors = list(map(lambda x: x[7], visual_data)) + link_to_color = dict(zip(links, colors)) + + if link: + if link in link_to_color.keys(): + return link_to_color[link] + elif link not in obj.links.keys(): + rospy.logerr(f"The link '{link}' is not part of this obejct") + return None + else: + rospy.logerr(f"The link '{link}' has no color") + return None + + if len(visual_data) == 1: + return list(visual_data[0][7]) + else: + return link_to_color + + def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case + the axis aligned bounding box of the link will be returned. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :param link_name: The Optional name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + if link_name: + return p.getAABB(obj.id, obj.links[link_name], self.client_id) + else: + return p.getAABB(obj.id, physicsClientId=self.client_id) + + def get_attachment_event(self) -> Event: + """ + Returns the event reference that is fired if an attachment occurs. + + :return: The reference to the attachment event + """ + return self.attachment_event + + def get_detachment_event(self) -> Event: + """ + Returns the event reference that is fired if a detachment occurs. + + :return: The event reference for the detachment event. + """ + return self.detachment_event + + def get_manipulation_event(self) -> Event: + """ + Returns the event reference that is fired if any manipulation occurs. + + :return: The event reference for the manipulation event. + """ + return self.manipulation_event + + def set_realtime(self, real_time: bool) -> None: + """ + Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only + simulated to reason about it. + + :param real_time: Whether the BulletWorld should simulate Physic in real time. + """ + p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + + def set_gravity(self, velocity: List[float]) -> None: + """ + Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity + is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + + :param velocity: The gravity vector that should be used in the BulletWorld. + """ + p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) + + def set_robot(self, robot: Object) -> None: + """ + Sets the global variable for the robot Object. This should be set on spawning the robot. + + :param robot: The Object reference to the Object representing the robot. + """ + BulletWorld.robot = robot + + def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + """ + Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real + time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By + setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real + time. + + :param seconds: The amount of seconds that should be simulated. + :param real_time: If the simulation should happen in real time or faster. + """ + for i in range(0, int(seconds * 240)): + p.stepSimulation(self.client_id) + for objects, callback in self.coll_callbacks.items(): + contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) + # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) + # print(contact_points[0][5]) + if contact_points != (): + callback[0]() + elif callback[1] != None: # Call no collision callback + callback[1]() + if real_time: + # Simulation runs at 240 Hz + time.sleep(0.004167) + + def exit(self) -> None: + """ + Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the + preferred method to close the BulletWorld. + """ + # True if this is NOT the shadow world since it has a reference to the + # Shadow world + time.sleep(0.1) + if self.prospection_world: + self.world_sync.terminate = True + self.world_sync.join() + self.prospection_world.exit() + p.disconnect(self.client_id) + if self._gui_thread: + self._gui_thread.join() + if BulletWorld.current_bullet_world == self: + BulletWorld.current_bullet_world = None + BulletWorld.robot = None + + def save_state(self) -> Tuple[int, Dict]: + """ + Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint + position of every Object in the BulletWorld. + + :return: A unique id of the state + """ + objects2attached = {} + # ToDo find out what this is for and where it is used + for o in self.objects: + objects2attached[o] = (o.attachments.copy(), o.cids.copy()) + return p.saveState(self.client_id), objects2attached + + def restore_state(self, state, objects2attached: Optional[Dict] = None) -> None: + """ + Restores the state of the BulletWorld according to the given state id. This includes position, orientation and + joint states. However, restore can not respawn objects if there are objects that were deleted between creation of + the state and restoring they will be skiped. + + :param state: The unique id representing the state, as returned by :func:`~save_state` + :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` + """ + p.restoreState(state, physicsClientId=self.client_id) + objects2attached = {} if objects2attached is None else objects2attached + for obj in self.objects: + try: + obj.attachments, obj.cids = objects2attached[obj] + except KeyError: + continue + + def copy(self) -> BulletWorld: + """ + Copies this Bullet World into another and returns it. The other BulletWorld + will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. + This method should only be used if necessary since there can be unforeseen problems. + + :return: The reference to the new BulletWorld + """ + world = BulletWorld("DIRECT") + for obj in self.objects: + o = Object(obj.name, obj.type, obj.path, Pose(obj.get_position(), obj.get_orientation()), + world, obj.color) + for joint in obj.joints: + o.set_joint_position(joint, obj.get_joint_position(joint)) + return world + + def add_vis_axis(self, pose: Pose, + length: Optional[float] = 0.2) -> None: + """ + Creates a Visual object which represents the coordinate frame at the given + position and orientation. There can be an unlimited amount of vis axis objects. + + :param pose: The pose at which the axis should be spawned + :param length: Optional parameter to configure the length of the axes + """ + + position, orientation = pose.to_list() + + vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], + rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) + vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], + rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) + vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], + rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) + + obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], + basePosition=position, baseOrientation=orientation, + linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkParentIndices=[0, 0, 0], + linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], + linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], + linkCollisionShapeIndices=[-1, -1, -1]) + + self.vis_axis.append(obj) + + def remove_vis_axis(self) -> None: + """ + Removes all spawned vis axis objects that are currently in this BulletWorld. + """ + for id in self.vis_axis: + p.removeBody(id) + self.vis_axis = [] + + def register_collision_callback(self, objectA: Object, objectB: Object, + callback_collision: Callable, + callback_no_collision: Optional[Callable] = None) -> None: + """ + Registers callback methods for contact between two Objects. There can be a callback for when the two Objects + get in contact and, optionally, for when they are not in contact anymore. + + :param objectA: An object in the BulletWorld + :param objectB: Another object in the BulletWorld + :param callback_collision: A function that should be called if the objects are in contact + :param callback_no_collision: A function that should be called if the objects are not in contact + """ + self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) + + def add_additional_resource_path(self, path: str) -> None: + """ + Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an + Object is spawned only with a filename. + + :param path: A path in the filesystem in which to search for files. + """ + self.data_directory.append(path) + + def get_shadow_object(self, object: Object) -> Object: + """ + Returns the corresponding object from the shadow world for the given object. If the given Object is already in + the shadow world it is returned. + + :param object: The object for which the shadow worlds object should be returned. + :return: The corresponding object in the shadow world. + """ + try: + return self.world_sync.object_mapping[object] + except KeyError: + shadow_world = self if self.is_prospection_world else self.prospection_world + if object in shadow_world.objects: + return object + else: + raise ValueError( + f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") + + def get_bullet_object_for_shadow(self, object: Object) -> Object: + """ + Returns the corresponding object from the main Bullet World for a given + object in the shadow world. If the given object is not in the shadow + world an error will be raised. + + :param object: The object for which the corresponding object in the main Bullet World should be found + :return: The object in the main Bullet World + """ + map = self.world_sync.object_mapping + try: + return list(map.keys())[list(map.values()).index(object)] + except ValueError: + raise ValueError("The given object is not in the shadow world.") + + def reset_bullet_world(self) -> None: + """ + Resets the BulletWorld to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and all objects will be set to the position and + orientation in which they were spawned. + """ + for obj in self.objects: + if obj.attachments: + attached_objects = list(obj.attachments.keys()) + for att_obj in attached_objects: + obj.detach(att_obj) + joint_names = list(obj.joints.keys()) + joint_poses = [0 for j in joint_names] + obj.set_positions_of_all_joints(dict(zip(joint_names, joint_poses))) + obj.set_pose(obj.original_pose) + +class BulletWorld(World): """ The BulletWorld Class represents the physics Simulation and belief state. """ @@ -54,45 +694,29 @@ class BulletWorld: if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): rospy.init_node('pycram') - def __init__(self, type: str = "GUI", is_shadow_world: bool = False): + def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): """ Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. - :param type: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" - :param is_shadow_world: For internal usage, decides if this BulletWorld should be used as a shadow world. + :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. """ - self.objects: List[Object] = [] - self.client_id: int = -1 - self.detachment_event: Event = Event() - self.attachment_event: Event = Event() - self.manipulation_event: Event = Event() - self.type: str = type - self._gui_thread: Gui = Gui(self, type) + super().__init__(mode=mode, is_prospection_world=is_prospection_world) + + self._gui_thread: Gui = Gui(self, mode) self._gui_thread.start() # This disables file caching from PyBullet, since this would also cache # files that can not be loaded p.setPhysicsEngineParameter(enableFileCaching=0) # Needed to let the other thread start the simulation, before Objects are spawned. time.sleep(0.1) - if BulletWorld.current_bullet_world == None: - BulletWorld.current_bullet_world = self self.vis_axis: List[Object] = [] - self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} - self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] - self.shadow_world: BulletWorld = BulletWorld("DIRECT", True) if not is_shadow_world else None - self.world_sync: WorldSync = WorldSync(self, self.shadow_world) if not is_shadow_world else None - self.is_shadow_world: bool = is_shadow_world - self.local_transformer = LocalTransformer() - if not is_shadow_world: - self.world_sync.start() - self.local_transformer.bullet_world = self - self.local_transformer.shadow_world = self.shadow_world # Some default settings self.set_gravity([0, 0, -9.8]) - if not is_shadow_world: + if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) # atexit.register(self.exit) @@ -504,10 +1128,10 @@ def exit(self) -> None: # True if this is NOT the shadow world since it has a reference to the # Shadow world time.sleep(0.1) - if self.shadow_world: + if self.prospection_world: self.world_sync.terminate = True self.world_sync.join() - self.shadow_world.exit() + self.prospection_world.exit() p.disconnect(self.client_id) if self._gui_thread: self._gui_thread.join() @@ -535,7 +1159,7 @@ def restore_state(self, state, objects2attached: Optional[Dict] = None) -> None: the state and restoring they will be skiped. :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~bullet_world.Object.attachments` + :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` """ p.restoreState(state, physicsClientId=self.client_id) objects2attached = {} if objects2attached is None else objects2attached @@ -635,7 +1259,7 @@ def get_shadow_object(self, object: Object) -> Object: try: return self.world_sync.object_mapping[object] except KeyError: - shadow_world = self if self.is_shadow_world else self.shadow_world + shadow_world = self if self.is_prospection_world else self.prospection_world if object in shadow_world.objects: return object else: @@ -689,7 +1313,7 @@ def __init__(self): self.prev_world: BulletWorld = None def __enter__(self): - if not BulletWorld.current_bullet_world.is_shadow_world: + if not BulletWorld.current_bullet_world.is_prospection_world: time.sleep(20 / 240) # blocks until the adding queue is ready BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() @@ -700,7 +1324,7 @@ def __enter__(self): self.prev_world = BulletWorld.current_bullet_world BulletWorld.current_bullet_world.world_sync.pause_sync = True - BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.shadow_world + BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.prospection_world def __exit__(self, *args): if not self.prev_world == None: @@ -719,11 +1343,11 @@ class WorldSync(threading.Thread): if reasoning should be done in the shadow world. """ - def __init__(self, world: BulletWorld, shadow_world: BulletWorld): + def __init__(self, world: World, prospection_world: World): threading.Thread.__init__(self) - self.world: BulletWorld = world - self.shadow_world: BulletWorld = shadow_world - self.shadow_world.world_sync: WorldSync = self + self.world: World = world + self.prospection_world: World = prospection_world + self.prospection_world.world_sync = self self.terminate: bool = False self.add_obj_queue: Queue = Queue() @@ -747,7 +1371,7 @@ def run(self): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.shadow_world, color, bulletworld object] + # [name, type, path, position, orientation, self.world.prospection_world, color, bulletworld object] o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) # Maps the BulletWorld object to the shadow world object self.object_mapping[obj[7]] = o @@ -1050,12 +1674,12 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self.cids: Dict[Object, int] = {} self.original_pose = pose_in_map - self.tf_frame = ("shadow/" if self.world.is_shadow_world else "") + self.name + "_" + str(self.id) + self.tf_frame = ("shadow/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) # This means "world" is not the shadow world since it has a reference to a shadow world - if self.world.shadow_world != None: + if self.world.prospection_world != None: self.world.world_sync.add_obj_queue.put( - [name, type, path, position, orientation, self.world.shadow_world, color, self]) + [name, type, path, position, orientation, self.world.prospection_world, color, self]) with open(self.path) as f: self.urdf_object = URDF.from_xml_string(f.read()) @@ -1095,7 +1719,7 @@ def remove(self) -> None: self.world.objects.remove(self) # This means the current world of the object is not the shadow world, since it # has a reference to the shadow world - if self.world.shadow_world is not None: + if self.world.prospection_world is not None: self.world.world_sync.remove_obj_queue.put(self) self.world.world_sync.remove_obj_queue.join() self.world.remove_object(self.id) diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 5c5b41b3b..e196bb51e 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -94,7 +94,7 @@ def test_detect(self): with simulated_robot: detected_object = description.resolve().perform() self.assertEqual(detected_object.name, "milk") - self.assertEqual(detected_object.type, ObjectType.MILK) + self.assertEqual(detected_object.mode, ObjectType.MILK) self.assertEqual(detected_object.bullet_world_object, self.milk) # Skipped since open and close work only in the apartment at the moment From bbb180043654c139961e7663e29a2abdb24bc80c Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 5 Dec 2023 17:43:09 +0100 Subject: [PATCH 005/195] [WorldAbstractClass] InProgress , refactoring transform_pose, _calculate_transform, and attach. --- src/pycram/bullet_world.py | 1685 ----------------- src/pycram/costmaps.py | 2 +- src/pycram/designator.py | 2 +- src/pycram/designators/action_designator.py | 20 +- src/pycram/external_interfaces/ik.py | 4 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/helper.py | 2 +- src/pycram/local_transformer.py | 28 +- .../process_modules/pr2_process_modules.py | 14 +- src/pycram/world.py | 144 +- src/pycram/world_reasoning.py | 2 +- test/local_transformer_tests.py | 4 +- 12 files changed, 151 insertions(+), 1758 deletions(-) delete mode 100644 src/pycram/bullet_world.py diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py deleted file mode 100644 index 75de52e45..000000000 --- a/src/pycram/bullet_world.py +++ /dev/null @@ -1,1685 +0,0 @@ -# used for delayed evaluation of typing until python 3.11 becomes mainstream -from __future__ import annotations - -import logging -import os -import pathlib -import re -import threading -import time -import xml.etree.ElementTree -from queue import Queue -import tf -from typing import List, Optional, Dict, Tuple, Callable -from typing import Union - -import numpy as np -import pybullet as p -import rospkg -import rospy -import rosgraph -import rosnode -import atexit - -import urdf_parser_py.urdf -from geometry_msgs.msg import Quaternion, Point, TransformStamped -from urdf_parser_py.urdf import URDF - -from . import utils -from .event import Event -from .robot_descriptions import robot_description -from .enums import JointType, ObjectType -from .local_transformer import LocalTransformer -from sensor_msgs.msg import JointState - -from .pose import Pose, Transform - - -class BulletWorld: - """ - The BulletWorld Class represents the physics Simulation and belief state. - """ - - current_bullet_world: BulletWorld = None - """ - Global reference to the currently used BulletWorld, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_bullet_world points to the - shadow world. In this way you can comfortably use the current_bullet_world, which should point towards the BulletWorld - used at the moment. - """ - robot: Object = None - """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the - URDF with the name of the URDF on the parameter server. - """ - - # Check is for sphinx autoAPI to be able to work in a CI workflow - if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): - rospy.init_node('pycram') - - def __init__(self, type: str = "GUI", is_shadow_world: bool = False): - """ - Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the - background. There can only be one rendered simulation. - The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. - - :param type: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" - :param is_shadow_world: For internal usage, decides if this BulletWorld should be used as a shadow world. - """ - self.objects: List[Object] = [] - self.client_id: int = -1 - self.detachment_event: Event = Event() - self.attachment_event: Event = Event() - self.manipulation_event: Event = Event() - self.type: str = type - self._gui_thread: Gui = Gui(self, type) - self._gui_thread.start() - # This disables file caching from PyBullet, since this would also cache - # files that can not be loaded - p.setPhysicsEngineParameter(enableFileCaching=0) - # Needed to let the other thread start the simulation, before Objects are spawned. - time.sleep(0.1) - if BulletWorld.current_bullet_world == None: - BulletWorld.current_bullet_world = self - self.vis_axis: Object = [] - self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} - self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] - self.shadow_world: BulletWorld = BulletWorld("DIRECT", True) if not is_shadow_world else None - self.world_sync: WorldSync = WorldSync(self, self.shadow_world) if not is_shadow_world else None - self.is_shadow_world: bool = is_shadow_world - self.local_transformer = LocalTransformer() - if not is_shadow_world: - self.world_sync.start() - self.local_transformer.world = self - self.local_transformer.prospection_world = self.shadow_world - - # Some default settings - self.set_gravity([0, 0, -9.8]) - if not is_shadow_world: - plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - # atexit.register(self.exit) - - def get_objects_by_name(self, name: str) -> List[Object]: - """ - Returns a list of all Objects in this BulletWorld with the same name as the given one. - - :param name: The name of the returned Objects. - :return: A list of all Objects with the name 'name'. - """ - return list(filter(lambda obj: obj.name == name, self.objects)) - - def get_objects_by_type(self, obj_type: str) -> List[Object]: - """ - Returns a list of all Objects which have the type 'obj_type'. - - :param obj_type: The type of the returned Objects. - :return: A list of all Objects that have the type 'obj_type'. - """ - return list(filter(lambda obj: obj.type == obj_type, self.objects)) - - def get_object_by_id(self, id: int) -> Object: - """ - Returns the single Object that has the unique id. - - :param id: The unique id for which the Object should be returned. - :return: The Object with the id 'id'. - """ - return list(filter(lambda obj: obj.id == id, self.objects))[0] - - def get_attachment_event(self) -> Event: - """ - Returns the event reference that is fired if an attachment occurs. - - :return: The reference to the attachment event - """ - return self.attachment_event - - def get_detachment_event(self) -> Event: - """ - Returns the event reference that is fired if a detachment occurs. - - :return: The event reference for the detachment event. - """ - return self.detachment_event - - def get_manipulation_event(self) -> Event: - """ - Returns the event reference that is fired if any manipulation occurs. - - :return: The event reference for the manipulation event. - """ - return self.manipulation_event - - def set_realtime(self, real_time: bool) -> None: - """ - Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only - simulated to reason about it. - - :param real_time: Whether the BulletWorld should simulate Physic in real time. - """ - p.setRealTimeSimulation(1 if real_time else 0, self.client_id) - - def set_gravity(self, velocity: List[float]) -> None: - """ - Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity - is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - - :param velocity: The gravity vector that should be used in the BulletWorld. - """ - p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) - - def set_robot(self, robot: Object) -> None: - """ - Sets the global variable for the robot Object. This should be set on spawning the robot. - - :param robot: The Object reference to the Object representing the robot. - """ - BulletWorld.robot = robot - - def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: - """ - Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real - time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By - setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real - time. - - :param seconds: The amount of seconds that should be simulated. - :param real_time: If the simulation should happen in real time or faster. - """ - for i in range(0, int(seconds * 240)): - p.stepSimulation(self.client_id) - for objects, callback in self.coll_callbacks.items(): - contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) - # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) - # print(contact_points[0][5]) - if contact_points != (): - callback[0]() - elif callback[1] != None: # Call no collision callback - callback[1]() - if real_time: - # Simulation runs at 240 Hz - time.sleep(0.004167) - - def exit(self) -> None: - """ - Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the - preferred method to close the BulletWorld. - """ - # True if this is NOT the shadow world since it has a reference to the - # Shadow world - time.sleep(0.1) - if self.shadow_world: - self.world_sync.terminate = True - self.world_sync.join() - self.shadow_world.exit() - p.disconnect(self.client_id) - if self._gui_thread: - self._gui_thread.join() - if BulletWorld.current_bullet_world == self: - BulletWorld.current_bullet_world = None - BulletWorld.robot = None - - def save_state(self) -> int: - """ - Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint - position of every Object in the BulletWorld. - - :return: A unique id of the state - """ - objects2attached = {} - # ToDo find out what this is for and where it is used - for o in self.objects: - objects2attached[o] = (o.attachments.copy(), o.cids.copy()) - return p.saveState(self.client_id), objects2attached - - def restore_state(self, state, objects2attached: Dict = {}) -> None: - """ - Restores the state of the BulletWorld according to the given state id. This includes position, orientation and - joint states. However, restore can not respawn objects if there are objects that were deleted between creation of - the state and restoring they will be skiped. - - :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` - """ - p.restoreState(state, physicsClientId=self.client_id) - for obj in self.objects: - try: - obj.attachments, obj.cids = objects2attached[obj] - except KeyError: - continue - - def copy(self) -> BulletWorld: - """ - Copies this Bullet World into another and returns it. The other BulletWorld - will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. - This method should only be used if necessary since there can be unforeseen problems. - - :return: The reference to the new BulletWorld - """ - world = BulletWorld("DIRECT") - for obj in self.objects: - o = Object(obj.name, obj.type, obj.path, obj.get_position(), obj.get_orientation(), - world, obj.color) - for joint in obj.joints: - o.set_joint_position(joint, obj.get_joint_position(joint)) - return world - - def add_vis_axis(self, pose: Pose, - length: Optional[float] = 0.2) -> None: - """ - Creates a Visual object which represents the coordinate frame at the given - position and orientation. There can be an unlimited amount of vis axis objects. - - :param pose: The pose at which the axis should be spawned - :param length: Optional parameter to configure the length of the axes - """ - - position, orientation = pose.to_list() - - vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) - vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) - vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) - - obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], - basePosition=position, baseOrientation=orientation, - linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkParentIndices=[0, 0, 0], - linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], - linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1]) - - self.vis_axis.append(obj) - - def remove_vis_axis(self) -> None: - """ - Removes all spawned vis axis objects that are currently in this BulletWorld. - """ - for id in self.vis_axis: - p.removeBody(id) - self.vis_axis = [] - - def register_collision_callback(self, objectA: Object, objectB: Object, - callback_collision: Callable, - callback_no_collision: Optional[Callable] = None) -> None: - """ - Registers callback methods for contact between two Objects. There can be a callback for when the two Objects - get in contact and, optionally, for when they are not in contact anymore. - - :param objectA: An object in the BulletWorld - :param objectB: Another object in the BulletWorld - :param callback_collision: A function that should be called if the objects are in contact - :param callback_no_collision: A function that should be called if the objects are not in contact - """ - self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) - - def add_additional_resource_path(self, path: str) -> None: - """ - Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an - Object is spawned only with a filename. - - :param path: A path in the filesystem in which to search for files. - """ - self.data_directory.append(path) - - def get_shadow_object(self, object: Object) -> Object: - """ - Returns the corresponding object from the shadow world for the given object. If the given Object is already in - the shadow world it is returned. - - :param object: The object for which the shadow worlds object should be returned. - :return: The corresponding object in the shadow world. - """ - try: - return self.world_sync.object_mapping[object] - except KeyError: - shadow_world = self if self.is_shadow_world else self.shadow_world - if object in shadow_world.objects: - return object - else: - raise ValueError( - f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") - - def get_bullet_object_for_shadow(self, object: Object) -> Object: - """ - Returns the corresponding object from the main Bullet World for a given - object in the shadow world. If the given object is not in the shadow - world an error will be raised. - - :param object: The object for which the corresponding object in the main Bullet World should be found - :return: The object in the main Bullet World - """ - map = self.world_sync.object_mapping - try: - return list(map.keys())[list(map.values()).index(object)] - except ValueError: - raise ValueError("The given object is not in the shadow world.") - - def reset_bullet_world(self) -> None: - """ - Resets the BulletWorld to the state it was first spawned in. - All attached objects will be detached, all joints will be set to the - default position of 0 and all objects will be set to the position and - orientation in which they were spawned. - """ - for obj in self.objects: - if obj.attachments: - attached_objects = list(obj.attachments.keys()) - for att_obj in attached_objects: - obj.detach(att_obj) - joint_names = list(obj.joints.keys()) - joint_poses = [0 for j in joint_names] - obj.set_joint_positions(dict(zip(joint_names, joint_poses))) - obj.set_pose(obj.original_pose) - - -class Use_shadow_world(): - """ - An environment for using the shadow world, while in this environment the :py:attr:`~BulletWorld.current_bullet_world` - variable will point to the shadow world. - - Example: - with Use_shadow_world(): - NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() - """ - - def __init__(self): - self.prev_world: BulletWorld = None - - def __enter__(self): - if not BulletWorld.current_bullet_world.is_shadow_world: - time.sleep(20 / 240) - # blocks until the adding queue is ready - BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() - # **This is currently not used since the sleep(20/240) seems to be enough, but on weaker hardware this might - # not be a feasible solution** - # while not BulletWorld.current_bullet_world.world_sync.equal_states: - # time.sleep(0.1) - - self.prev_world = BulletWorld.current_bullet_world - BulletWorld.current_bullet_world.world_sync.pause_sync = True - BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.shadow_world - - def __exit__(self, *args): - if not self.prev_world == None: - BulletWorld.current_bullet_world = self.prev_world - BulletWorld.current_bullet_world.world_sync.pause_sync = False - - -class WorldSync(threading.Thread): - """ - Synchronizes the state between the BulletWorld and its shadow world. - Meaning the cartesian and joint position of everything in the shadow world will be - synchronized with the main BulletWorld. - Adding and removing objects is done via queues, such that loading times of objects - in the shadow world does not affect the BulletWorld. - The class provides the possibility to pause the synchronization, this can be used - if reasoning should be done in the shadow world. - """ - - def __init__(self, world: BulletWorld, shadow_world: BulletWorld): - threading.Thread.__init__(self) - self.world: BulletWorld = world - self.shadow_world: BulletWorld = shadow_world - self.shadow_world.world_sync: WorldSync = self - - self.terminate: bool = False - self.add_obj_queue: Queue = Queue() - self.remove_obj_queue: Queue = Queue() - self.pause_sync: bool = False - # Maps bullet to shadow world objects - self.object_mapping: Dict[Object, Object] = {} - self.equal_states = False - - def run(self): - """ - Main method of the synchronization, this thread runs in a loop until the - terminate flag is set. - While this loop runs it continuously checks the cartesian and joint position of - every object in the BulletWorld and updates the corresponding object in the - shadow world. When there are entries in the adding or removing queue the corresponding objects will be added - or removed in the same iteration. - """ - while not self.terminate: - self.check_for_pause() - # self.equal_states = False - for i in range(self.add_obj_queue.qsize()): - obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.prospection_world, color, bulletworld object] - o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) - # Maps the BulletWorld object to the shadow world object - self.object_mapping[obj[7]] = o - self.add_obj_queue.task_done() - for i in range(self.remove_obj_queue.qsize()): - obj = self.remove_obj_queue.get() - # Get shadow world object reference from object mapping - shadow_obj = self.object_mapping[obj] - shadow_obj.remove() - del self.object_mapping[obj] - self.remove_obj_queue.task_done() - - for bulletworld_obj, shadow_obj in self.object_mapping.items(): - b_pose = bulletworld_obj.get_pose() - s_pose = shadow_obj.get_pose() - if b_pose.dist(s_pose) != 0.0: - shadow_obj.set_pose(bulletworld_obj.get_pose()) - - # Manage joint positions - if len(bulletworld_obj.joints) > 2: - for joint_name in bulletworld_obj.joints.keys(): - if shadow_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): - shadow_obj.set_joint_positions(bulletworld_obj.get_positions_of_all_joints()) - break - - self.check_for_pause() - # self.check_for_equal() - time.sleep(1 / 240) - - self.add_obj_queue.join() - self.remove_obj_queue.join() - - def check_for_pause(self) -> None: - """ - Checks if :py:attr:`~self.pause_sync` is true and sleeps this thread until it isn't anymore. - """ - while self.pause_sync: - time.sleep(0.1) - - def check_for_equal(self) -> None: - """ - Checks if both BulletWorlds have the same state, meaning all objects are in the same position. - This is currently not used, but might be used in the future if synchronization issues worsen. - """ - eql = True - for obj, shadow_obj in self.object_mapping.items(): - eql = eql and obj.get_pose() == shadow_obj.get_pose() - self.equal_states = eql - - -class Gui(threading.Thread): - """ - For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~BulletWorld.exit` - Also contains the code for controlling the camera. - """ - - def __init__(self, world, type): - threading.Thread.__init__(self) - self.world: BulletWorld = world - self.type: str = type - - def run(self): - """ - Initializes the new simulation and checks in an endless loop - if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and - thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. - """ - if self.type != "GUI": - self.world.client_id = p.connect(p.DIRECT) - else: - self.world.client_id = p.connect(p.GUI) - - # Disable the side windows of the GUI - p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) - # Change the init camera pose - p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1]) - - # Get the initial camera target location - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) - - # Create a sphere with a radius of 0.05 and a mass of 0 - sphereUid = p.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=sphereVisualId, - basePosition=cameraTargetPosition) - - # Define the maxSpeed, used in calculations - maxSpeed = 16 - - # Set initial Camera Rotation - cameraYaw = 50 - cameraPitch = -35 - - # Keep track of the mouse state - mouseState = [0, 0, 0] - oldMouseX, oldMouseY = 0, 0 - - # Determines if the sphere at cameraTargetPosition is visible - visible = 1 - - # Loop to update the camera position based on keyboard events - while p.isConnected(self.world.client_id): - # Monitor user input - keys = p.getKeyboardEvents() - mouse = p.getMouseEvents() - - # Get infos about the camera - width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ - p.getDebugVisualizerCamera()[10] - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] - zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] - - # Check the mouse state - if mouse: - for m in mouse: - - mouseX = m[2] - mouseY = m[1] - - # update mouseState - # Left Mouse button - if m[0] == 2 and m[3] == 0: - mouseState[0] = m[4] - # Middle mouse butto (scroll wheel) - if m[0] == 2 and m[3] == 1: - mouseState[1] = m[4] - # right mouse button - if m[0] == 2 and m[3] == 2: - mouseState[2] = m[4] - - # change visibility by clicking the mousewheel - if m[4] == 6 and m[3] == 1 and visible == 1: - visible = 0 - elif m[4] == 6 and visible == 0: - visible = 1 - - # camera movement when the left mouse button is pressed - if mouseState[0] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed - - # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) - if mouseX < oldMouseX: - if (cameraPitch + speedX) < 89.5: - cameraPitch += (speedX / 4) + 1 - elif mouseX > oldMouseX: - if (cameraPitch - speedX) > -89.5: - cameraPitch -= (speedX / 4) + 1 - - if mouseY < oldMouseY: - cameraYaw += (speedY / 4) + 1 - elif mouseY > oldMouseY: - cameraYaw -= (speedY / 4) + 1 - - if mouseState[1] == 3: - speedX = abs(oldMouseX - mouseX) - factor = 0.05 - - if mouseX < oldMouseX: - dist = dist - speedX * factor - elif mouseX > oldMouseX: - dist = dist + speedX * factor - dist = max(dist, 0.1) - - # camera movement when the right mouse button is pressed - if mouseState[2] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 - factor = 0.05 - - if mouseX < oldMouseX: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - elif mouseX > oldMouseX: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - - if mouseY < oldMouseY: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - elif mouseY > oldMouseY: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - # update oldMouse values - oldMouseY, oldMouseX = mouseY, mouseX - - # check the keyboard state - if keys: - # if shift is pressed, double the speed - if p.B3G_SHIFT in keys: - speedMult = 5 - else: - speedMult = 2.5 - - # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key - # change - if p.B3G_CONTROL in keys: - - # the up and down arrowkeys cause the targetPos to move along the z axis of the map - if p.B3G_DOWN_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - elif p.B3G_UP_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - - # left and right arrowkeys cause the targetPos to move horizontally relative to the camera - if p.B3G_LEFT_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - elif p.B3G_RIGHT_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - - # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera - # while the camera stays at a constant distance. SHIFT + '=' is for US layout - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - elif ord("-") in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - - # standard bindings for thearrowkeys, the '+' as well as the '-' key - else: - - # left and right arrowkeys cause the camera to rotate around the yaw axis - if p.B3G_RIGHT_ARROW in keys: - cameraYaw += (360 / width) * speedMult - elif p.B3G_LEFT_ARROW in keys: - cameraYaw -= (360 / width) * speedMult - - # the up and down arrowkeys cause the camera to rotate around the pitch axis - if p.B3G_DOWN_ARROW in keys: - if (cameraPitch + (360 / height) * speedMult) < 89.5: - cameraPitch += (360 / height) * speedMult - elif p.B3G_UP_ARROW in keys: - if (cameraPitch - (360 / height) * speedMult) > -89.5: - cameraPitch -= (360 / height) * speedMult - - # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without - # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - if (dist - (dist * 0.02) * speedMult) > 0.1: - dist -= dist * 0.02 * speedMult - elif ord("-") in keys: - dist += dist * 0.02 * speedMult - - p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition) - if visible == 0: - cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) - time.sleep(1. / 80.) - - -class Object: - """ - Represents a spawned Object in the BulletWorld. - """ - - def __init__(self, name: str, type: Union[str, ObjectType], path: str, - pose: Pose = None, - world: BulletWorld = None, - color: Optional[List[float]] = [1, 1, 1, 1], - ignoreCachedFiles: Optional[bool] = False): - """ - The constructor loads the urdf file into the given BulletWorld, if no BulletWorld is specified the - :py:attr:`~BulletWorld.current_bullet_world` will be used. It is also possible to load .obj and .stl file into the BulletWorld. - The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. - - :param name: The name of the object - :param type: The type of the object - :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched - :param pose: The pose at which the Object should be spawned - :param world: The BulletWorld in which the object should be spawned, if no world is specified the :py:attr:`~BulletWorld.current_bullet_world` will be used - :param color: The color with which the object should be spawned. - :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. - """ - if not pose: - pose = Pose() - self.world: BulletWorld = world if world is not None else BulletWorld.current_bullet_world - self.local_transformer = LocalTransformer() - self.name: str = name - self.type: str = type - self.color: List[float] = color - pose_in_map = self.local_transformer.transform_pose(pose, "map") - position, orientation = pose_in_map.to_list() - self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) - self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") - self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") - self.attachments: Dict[Object, List] = {} - self.cids: Dict[Object, int] = {} - self.original_pose = pose_in_map - - self.tf_frame = ("shadow/" if self.world.is_shadow_world else "") + self.name + "_" + str(self.id) - - # This means "world" is not the shadow world since it has a reference to a shadow world - if self.world.shadow_world != None: - self.world.world_sync.add_obj_queue.put( - [name, type, path, position, orientation, self.world.shadow_world, color, self]) - - with open(self.path) as f: - self.urdf_object = URDF.from_xml_string(f.read()) - if self.urdf_object.name == robot_description.name and not BulletWorld.robot: - BulletWorld.robot = self - - self.links[self.urdf_object.get_root()] = -1 - - self._current_pose = pose_in_map - self._current_link_poses = {} - self._current_link_transforms = {} - self._current_joints_positions = {} - self._init_current_positions_of_joints() - self._update_link_poses() - - self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) - self.local_transformer.update_transforms_for_object(self) - self.link_to_geometry = self._get_geometry_for_link() - - self.world.objects.append(self) - - def __repr__(self): - skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", - "_current_link_transforms", "link_to_geometry"] - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" - - def remove(self) -> None: - """ - Removes this object from the BulletWorld it currently resides in. - For the object to be removed it has to be detached from all objects it - is currently attached to. After this is done a call to PyBullet is done - to remove this Object from the simulation. - """ - for obj in self.attachments.keys(): - self.detach(obj) - self.world.objects.remove(self) - # This means the current world of the object is not the shaow world, since it - # has a reference to the shadow world - if self.world.shadow_world != None: - self.world.world_sync.remove_obj_queue.put(self) - self.world.world_sync.remove_obj_queue.join() - p.removeBody(self.id, physicsClientId=self.world.client_id) - if BulletWorld.robot == self: - BulletWorld.robot = None - - def attach(self, object: Object, link: Optional[str] = None, loose: Optional[bool] = False) -> None: - """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a constraint of pybullet will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. For example, if this object moves the - other, attached, object will also move but not the other way around. - - :param object: The other object that should be attached - :param link: The link of this object to which the other object should be - :param loose: If the attachment should be a loose attachment. - """ - link_id = self.get_link_id(link) if link else -1 - link_to_object = self._calculate_transform(object, link) - self.attachments[object] = [link_to_object, link, loose] - object.attachments[self] = [link_to_object.invert(), None, False] - - cid = p.createConstraint(self.id, link_id, object.id, -1, p.JOINT_FIXED, - [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], - link_to_object.rotation_as_list(), - physicsClientId=self.world.client_id) - self.cids[object] = cid - object.cids[self] = cid - self.world.attachment_event(self, [self, object]) - - def detach(self, object: Object) -> None: - """ - Detaches another object from this object. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of pybullet. - Afterward the detachment event of the corresponding BulletWorld will be fired. - - :param object: The object which should be detached - """ - del self.attachments[object] - del object.attachments[self] - - p.removeConstraint(self.cids[object], physicsClientId=self.world.client_id) - - del self.cids[object] - del object.cids[self] - self.world.detachment_event(self, [self, object]) - - def detach_all(self) -> None: - """ - Detach all objects attached to this object. - """ - attachments = self.attachments.copy() - for att in attachments.keys(): - self.detach(att) - - def get_position(self) -> Point: - """ - Returns the position of this Object as a list of xyz. - - :return: The current position of this object - """ - return self.get_pose().position - - def get_orientation(self) -> Quaternion: - """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. - - :return: A list of xyzw - """ - return self.get_pose().orientation - - def get_pose(self) -> Pose: - """ - Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. - - :return: The current pose of this object - """ - return self._current_pose - - def set_pose(self, pose: Pose, base: bool = False) -> None: - """ - Sets the Pose of the object. - - :param pose: New Pose for the object - :param base: If True places the object base instead of origin at the specified position and orientation - """ - pose_in_map = self.local_transformer.transform_pose(pose, "map") - position, orientation = pose_in_map.to_list() - if base: - position = np.array(position) + self.base_origin_shift - p.resetBasePositionAndOrientation(self.id, position, orientation, self.world.client_id) - self._current_pose = pose_in_map - self._update_link_poses() - self._set_attached_objects([self]) - - @property - def pose(self) -> Pose: - """ - Property that returns the current position of this Object. - - :return: The position as a list of xyz - """ - return self.get_pose() - - @pose.setter - def pose(self, value: Pose) -> None: - """ - Sets the Pose of the Object to the given value. Function for attribute use. - - :param value: New Pose of the Object - """ - self.set_pose(value) - - def move_base_to_origin_pos(self) -> None: - """ - Move the object such that its base will be at the current origin position. - This is useful when placing objects on surfaces where you want the object base in contact with the surface. - """ - self.set_pose(self.get_pose(), base=True) - - def _set_attached_objects(self, prev_object: List[Object]) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param prev_object: A list of Objects that were already moved, these will be excluded to prevent loops in the update. - """ - for obj in self.attachments: - if obj in prev_object: - continue - if self.attachments[obj][2]: - # Updates the attachment transformation and contraint if the - # attachment is loos, instead of updating the position of all attached objects - link_to_object = self._calculate_transform(obj, self.attachments[obj][1]) - link_id = self.get_link_id(self.attachments[obj][1]) if self.attachments[obj][1] else -1 - self.attachments[obj][0] = link_to_object - obj.attachments[self][0] = link_to_object.invert() - p.removeConstraint(self.cids[obj], physicsClientId=self.world.client_id) - cid = p.createConstraint(self.id, link_id, obj.id, -1, p.JOINT_FIXED, [0, 0, 0], - link_to_object.translation_as_list(), - [0, 0, 0], link_to_object.rotation_as_list(), - physicsClientId=self.world.client_id) - self.cids[obj] = cid - obj.cids[self] = cid - else: - link_to_object = self.attachments[obj][0] - - world_to_object = self.local_transformer.transform_pose(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(obj.id, world_to_object.position_as_list(), - world_to_object.orientation_as_list(), - physicsClientId=self.world.client_id) - obj._current_pose = world_to_object - obj._set_attached_objects(prev_object + [self]) - - def _calculate_transform(self, obj: Object, link: str = None) -> Transform: - """ - Calculates the transformation between another object and the given - link of this object. If no link is provided then the base position will be used. - - :param obj: The other object for which the transformation should be calculated - :param link: The optional link name - :return: The transformation from the link (or base position) to the other objects base position - """ - transform = self.local_transformer.transform_to_object_frame(obj.pose, self, link) - - return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) - - def set_position(self, position: Union[Pose, Point], base=False) -> None: - """ - Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position - instead of the origin in the center of the Object. The given position can either be a Pose, in this case only the - position is used or a geometry_msgs.msg/Point which is the position part of a Pose. - - :param position: Target position as xyz. - :param base: If the bottom of the Object should be placed or the origin in the center. - """ - pose = Pose() - if type(position) == Pose: - target_position = position.position - pose.frame = position.frame - else: - target_position = position - - pose.pose.position = target_position - pose.pose.orientation = self.get_orientation() - self.set_pose(pose, base=base) - - def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: - """ - Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only - the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. - - :param orientation: Target orientation given as a list of xyzw. - """ - pose = Pose() - if type(orientation) == Pose: - target_orientation = orientation.orientation - pose.frame = orientation.frame - else: - target_orientation = orientation - - pose.pose.position = self.get_position() - pose.pose.orientation = target_orientation - self.set_pose(pose) - - def _joint_or_link_name_to_id(self, type: str) -> Dict[str, int]: - """ - Creates a dictionary which maps the link or joint name to the unique ids used by pybullet. - - :param type: Determines if the dictionary should be for joints or links - :return: A dictionary that maps joint or link names to unique ids - """ - nJoints = p.getNumJoints(self.id, self.world.client_id) - joint_name_to_id = {} - info = 1 if type == "joint" else 12 - for i in range(0, nJoints): - joint_info = p.getJointInfo(self.id, i, self.world.client_id) - joint_name_to_id[joint_info[info].decode('utf-8')] = joint_info[0] - return joint_name_to_id - - def get_joint_id(self, name: str) -> int: - """ - Returns the unique id for a joint name. As used by PyBullet. - - :param name: The joint name - :return: The unique id - """ - return self.joints[name] - - def get_link_id(self, name: str) -> int: - """ - Returns a unique id for a link name. As used by PyBullet. - - :param name: The link name - :return: The unique id - """ - return self.links[name] - - def get_link_by_id(self, id: int) -> str: - """ - Returns the name of a link for a given unique PyBullet id - - :param id: PyBullet id for link - :return: The link name - """ - return dict(zip(self.links.values(), self.links.keys()))[id] - - def get_joint_by_id(self, id: int) -> str: - """ - Returns the joint name for a unique PyBullet id - - :param id: The Pybullet id of for joint - :return: The joint name - """ - return dict(zip(self.joints.values(), self.joints.keys()))[id] - - def get_link_relative_to_other_link(self, source_frame: str, target_frame: str) -> Pose: - """ - Calculates the position of a link in the coordinate frame of another link. - - :param source_frame: The name of the source frame - :param target_frame: The name of the target frame - :return: The pose of the source frame in the target frame - """ - source_pose = self.get_link_pose(source_frame) - return self.local_transformer.transform_to_object_frame(source_pose, self, target_frame) - - def get_link_position(self, name: str) -> Point: - """ - Returns the position of a link of this Object. Position is returned as a list of xyz. - - :param name: The link name - :return: The link position as xyz - """ - return self.get_link_pose(name).position - - def get_link_orientation(self, name: str) -> Quaternion: - """ - Returns the orientation of a link of this Object. Orientation is returned as a quaternion. - - :param name: The name of the link - :return: The orientation of the link as a quaternion - """ - return self.get_link_pose(name).orientation - - def get_link_pose(self, name: str) -> Pose: - """ - Returns a Pose of the link corresponding to the given name. The returned Pose will be in world coordinate frame. - - :param name: Link name for which a Pose should returned - :return: The pose of the link - """ - if name in self.links.keys() and self.links[name] == -1: - return self.get_pose() - return self._current_link_poses[name] - # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) - - def set_joint_position(self, joint_name: str, joint_pose: float) -> None: - """ - Sets the state of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. - - :param joint_name: The name of the joint - :param joint_pose: The target pose for this joint - """ - # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - up_lim, low_lim = p.getJointInfo(self.id, self.joints[joint_name], physicsClientId=self.world.client_id)[ - 8:10] - if low_lim > up_lim: - low_lim, up_lim = up_lim, low_lim - if not low_lim <= joint_pose <= up_lim: - logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {joint_name} are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_pose}") - # Temporarily disabled because kdl outputs values exciting joint limits - # return - p.resetJointState(self.id, self.joints[joint_name], joint_pose, physicsClientId=self.world.client_id) - self._current_joints_positions[joint_name] = joint_pose - # self.local_transformer.update_transforms_for_object(self) - self._update_link_poses() - self._set_attached_objects([self]) - - def set_joint_positions(self, joint_poses: dict) -> None: - """ - Sets the current state of multiple joints at once, this method should be preferred when setting multiple joints - at once instead of running :func:`~Object.set_joint_state` in a loop. - - :param joint_poses: - :return: - """ - for joint_name, joint_pose in joint_poses.items(): - p.resetJointState(self.id, self.joints[joint_name], joint_pose, physicsClientId=self.world.client_id) - self._current_joints_positions[joint_name] = joint_pose - self._update_link_poses() - self._set_attached_objects([self]) - - def get_joint_position(self, joint_name: str) -> float: - """ - Returns the joint state for the given joint name. - - :param joint_name: The name of the joint - :return: The current pose of the joint - """ - return self._current_joints_positions[joint_name] - - def contact_points(self) -> List: - """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :return: A list of all contact points with other objects - """ - return p.getContactPoints(self.id) - - def contact_points_simulated(self) -> List: - """ - Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :return: A list of contact points between this Object and other Objects - """ - s = self.world.save_state() - p.stepSimulation(self.world.client_id) - contact_points = self.contact_points() - self.world.restore_state(*s) - return contact_points - - def update_joints_from_topic(self, topic_name: str) -> None: - """ - Updates the joints of this object with positions obtained from a topic with the message type JointState. - Joint names on the topic have to correspond to the joints of this object otherwise an error message will be logged. - - :param topic_name: Name of the topic with the joint states - """ - msg = rospy.wait_for_message(topic_name, JointState) - joint_names = msg.name - joint_positions = msg.position - if set(joint_names).issubset(self.joints.keys()): - for i in range(len(joint_names)): - self.set_joint_position(joint_names[i], joint_positions[i]) - else: - add_joints = set(joint_names) - set(self.joints.keys()) - rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ - The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") - - def update_pose_from_tf(self, frame: str) -> None: - """ - Updates the pose of this object from a TF message. - - :param frame: Name of the TF frame from which the position should be taken - """ - tf_listener = tf.TransformListener() - time.sleep(0.5) - position, orientation = tf_listener.lookupTransform(frame, "map", rospy.Time(0)) - position = [position[0][0] * -1, - position[0][1] * -1, - position[0][2]] - self.set_position(Pose(position, orientation)) - - def set_color(self, color: List[float], link: Optional[str] = "") -> None: - """ - Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. - - :param color: The color as RGBA values between 0 and 1 - :param link: The link name of the link which should be colored - """ - if link == "": - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if self.links != {}: - for link_id in self.links.values(): - p.changeVisualShape(self.id, link_id, rgbaColor=color, physicsClientId=self.world.client_id) - else: - p.changeVisualShape(self.id, -1, rgbaColor=color, physicsClientId=self.world.client_id) - else: - p.changeVisualShape(self.id, self.links[link], rgbaColor=color, physicsClientId=self.world.client_id) - - def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: - """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: - - 1. A list with the color as RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the - object is spawned. - - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. - - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color - """ - visual_data = p.getVisualShapeData(self.id, physicsClientId=self.world.client_id) - swap = {v: k for k, v in self.links.items()} - links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = list(map(lambda x: x[7], visual_data)) - link_to_color = dict(zip(links, colors)) - - if link: - if link in link_to_color.keys(): - return link_to_color[link] - elif link not in self.links.keys(): - rospy.logerr(f"The link '{link}' is not part of this obejct") - return None - else: - rospy.logerr(f"The link '{link}' has no color") - return None - - if len(visual_data) == 1: - return list(visual_data[0][7]) - else: - return link_to_color - - def get_AABB(self, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param link_name: The Optional name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. - """ - if link_name: - return p.getAABB(self.id, self.links[link_name], self.world.client_id) - else: - return p.getAABB(self.id, physicsClientId=self.world.client_id) - - def get_base_origin(self, link_name: Optional[str] = None) -> Pose: - """ - Returns the origin of the base/bottom of an object/link - - :param link_name: The link name for which the bottom position should be returned - :return: The position of the bottom of this Object or link - """ - aabb = self.get_AABB(link_name=link_name) - base_width = np.absolute(aabb[0][0] - aabb[1][0]) - base_length = np.absolute(aabb[0][1] - aabb[1][1]) - return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], - self.get_pose().orientation_as_list()) - - def get_joint_limits(self, joint: str) -> Tuple[float, float]: - """ - Returns the lower and upper limit of a joint, if the lower limit is higher - than the upper they are swapped to ensure the lower limit is always the smaller one. - - :param joint: The name of the joint for which the limits should be found. - :return: The lower and upper limit of the joint. - """ - if joint not in self.joints.keys(): - raise KeyError(f"The given Joint: {joint} is not part of this object") - lower, upper = p.getJointInfo(self.id, self.joints[joint], self.world.client_id)[8: 10] - if lower > upper: - lower, upper = upper, lower - return lower, upper - - def get_joint_axis(self, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ - return p.getJointInfo(self.id, self.joints[joint_name], self.world.client_id)[13] - - def get_joint_type(self, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ - joint_type = p.getJointInfo(self.id, self.joints[joint_name], self.world.client_id)[2] - return JointType(joint_type) - - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: - """ - Traverses the chain from 'link_name' to the URDF origin and returns the first joint that is of type 'joint_type'. - - :param link_name: Link name above which the joint should be found - :param joint_type: Joint type that should be searched for - :return: Name of the first joint which has the given type - """ - chain = self.urdf_object.get_chain(self.urdf_object.get_root(), link_name) - reversed_chain = reversed(chain) - container_joint = None - for element in reversed_chain: - if element in self.joints and self.get_joint_type(element) == joint_type: - container_joint = element - break - if not container_joint: - rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") - return container_joint - - def get_positions_of_all_joints(self) -> Dict[str: float]: - """ - Returns the positions of all joints of the object as a dictionary of joint names and joint positions. - - :return: A dictionary with all joints positions'. - """ - return self._current_joints_positions - - def get_link_tf_frame(self, link_name: str) -> str: - """ - Returns the name of the tf frame for the given link name. This method does not check if the given name is - actually a link of this object. - - :param link_name: Name of a link for which the tf frame should be returned - :return: A TF frame name for a specific link - """ - return self.tf_frame + "/" + link_name - - def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: - """ - Extracts the geometry information for each collision of each link and links them to the respective link. - - :return: A dictionary with link name as key and geometry information as value - """ - link_to_geometry = {} - for link in self.links.keys(): - link_obj = self.urdf_object.link_map[link] - if not link_obj.collision: - link_to_geometry[link] = None - else: - link_to_geometry[link] = link_obj.collision.geometry - return link_to_geometry - - def _update_link_poses(self) -> None: - """ - Updates the cached poses and transforms for each link of this Object - """ - for link_name in self.links.keys(): - if link_name == self.urdf_object.get_root(): - self._current_link_poses[link_name] = self._current_pose - self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) - else: - self._current_link_poses[link_name] = Pose(*p.getLinkState(self.id, self.links[link_name], - physicsClientId=self.world.client_id)[4:6]) - self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( - self.get_link_tf_frame(link_name)) - - def _init_current_positions_of_joints(self) -> None: - """ - Initialize the cached joint position for each joint. - """ - for joint_name in self.joints.keys(): - self._current_joints_positions[joint_name] = \ - p.getJointState(self.id, self.joints[joint_name], physicsClientId=self.world.client_id)[0] - - -def filter_contact_points(contact_points, exclude_ids) -> List: - """ - Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. - - :param contact_points: A list of contact points - :param exclude_ids: A list of unique ids of Objects that should be removed from the list - :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' - """ - return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) - - -def get_path_from_data_dir(file_name: str, data_directory: str) -> str: - """ - Returns the full path for a given file name in the given directory. If there is no file with the given filename - this method returns None. - - :param file_name: The filename of the searched file. - :param data_directory: The directory in which to search for the file. - :return: The full path in the filesystem or None if there is no file with the filename in the directory - """ - dir = pathlib.Path(data_directory) - for file in os.listdir(data_directory): - if file == file_name: - return data_directory + f"/{file_name}" - - -def _get_robot_name_from_urdf(urdf_string: str) -> str: - """ - Extracts the robot name from the 'robot_name' tag of a URDF. - - :param urdf_string: The URDF as string. - :return: The name of the robot described by the URDF. - """ - res = re.findall(r"robot\ *name\ *=\ *\"\ *[a-zA-Z_0-9]*\ *\"", urdf_string) - if len(res) == 1: - begin = res[0].find("\"") - end = res[0][begin + 1:].find("\"") - robot = res[0][begin + 1:begin + 1 + end].lower() - return robot - - -def _load_object(name: str, - path: str, - position: List[float], - orientation: List[float], - world: BulletWorld, - color: List[float], - ignoreCachedFiles: bool) -> Tuple[int, str]: - """ - Loads an object to the given BulletWorld with the given position and orientation. The color will only be - used when an .obj or .stl file is given. - If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created - and this URDf file will be loaded instead. - When spawning a URDf file a new file will be created in the cache directory, if there exists none. - This new file will have resolved mesh file paths, meaning there will be no references - to ROS packges instead there will be absolute file paths. - - :param name: The name of the object which should be spawned - :param path: The path to the source file or the name on the ROS parameter server - :param position: The position in which the object should be spawned - :param orientation: The orientation in which the object should be spawned - :param world: The BulletWorld to which the Object should be spawned - :param color: The color of the object, only used when .obj or .stl file is given - :param ignoreCachedFiles: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path to the file used for spawning - """ - pa = pathlib.Path(path) - extension = pa.suffix - world, world_id = _world_and_id(world) - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for dir in world.data_directory: - path = get_path_from_data_dir(path, dir) - if path: break - - if not path: - raise FileNotFoundError( - f"File {pa.name} could not be found in the resource directory {world.data_directory}") - # rospack = rospkg.RosPack() - # cach_dir = rospack.get_path('pycram') + '/resources/cached/' - cach_dir = world.data_directory[0] + '/cached/' - if not pathlib.Path(cach_dir).exists(): - os.mkdir(cach_dir) - - # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path, name, cach_dir) or ignoreCachedFiles: - if extension == ".obj" or extension == ".stl": - path = _generate_urdf_file(name, path, color, cach_dir) - elif extension == ".urdf": - with open(path, mode="r") as f: - urdf_string = fix_missing_inertial(f.read()) - urdf_string = remove_error_tags(urdf_string) - urdf_string = fix_link_attributes(urdf_string) - try: - urdf_string = _correct_urdf_string(urdf_string) - except rospkg.ResourceNotFound as e: - rospy.logerr(f"Could not find resource package linked in this URDF") - raise e - path = cach_dir + pa.name - with open(path, mode="w") as f: - f.write(urdf_string) - else: # Using the urdf from the parameter server - urdf_string = rospy.get_param(path) - path = cach_dir + name + ".urdf" - with open(path, mode="w") as f: - f.write(_correct_urdf_string(urdf_string)) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = cach_dir + pa.stem + ".urdf" - elif extension == ".urdf": - path = cach_dir + pa.name - else: - path = cach_dir + name + ".urdf" - - try: - obj = p.loadURDF(path, basePosition=position, baseOrientation=orientation, physicsClientId=world_id) - return obj, path - except p.error as e: - logging.error( - "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") - os.remove(path) - raise (e) - # print(f"{bcolors.BOLD}{bcolors.WARNING}The path has to be either a path to a URDf file, stl file, obj file or the name of a URDF on the parameter server.{bcolors.ENDC}") - - -def _is_cached(path: str, name: str, cach_dir: str) -> bool: - """ - Checks if the file in the given path is already cached or if - there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from - the parameter server is used. - - :param path: The path given by the user to the source file. - :param name: The name for this object. - :param cach_dir: The absolute path the cach directory in the pycram package. - :return: True if there already exists a chached file, False in any other case. - """ - file_name = pathlib.Path(path).name - p = pathlib.Path(cach_dir + file_name) - if p.exists(): - return True - # Returns filename without the filetype, e.g. returns "test" for "test.txt" - file_stem = pathlib.Path(path).stem - p = pathlib.Path(cach_dir + file_stem + ".urdf") - if p.exists(): - return True - return False - - -def _correct_urdf_string(urdf_string: str) -> str: - """ - Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS - package paths. - - :param urdf_name: The name of the URDf on the parameter server - :return: The URDF string with paths in the filesystem instead of ROS packages - """ - r = rospkg.RosPack() - new_urdf_string = "" - for line in urdf_string.split('\n'): - if "package://" in line: - s = line.split('//') - s1 = s[1].split('/') - path = r.get_path(s1[0]) - line = line.replace("package://" + s1[0], path) - new_urdf_string += line + '\n' - - return fix_missing_inertial(new_urdf_string) - - -def fix_missing_inertial(urdf_string: str) -> str: - """ - Insert inertial tags for every URDF link that has no inertia. - This is used to prevent PyBullet from dumping warnings in the terminal - - :param urdf_string: The URDF description as string - :returns: The new, corrected URDF description as string. - """ - - inertia_tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.Element("inertial")) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("mass", {"value": "0.1"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("inertia", {"ixx": "0.01", - "ixy": "0", - "ixz": "0", - "iyy": "0.01", - "iyz": "0", - "izz": "0.01"})) - - # create tree from string - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - - for link_element in tree.iter("link"): - inertial = [*link_element.iter("inertial")] - if len(inertial) == 0: - link_element.append(inertia_tree.getroot()) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def remove_error_tags(urdf_string: str) -> str: - """ - Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the - URDF_parser - - :param urdf_string: String of the URDF from which the tags should be removed - :return: The URDF string with the tags removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - removing_tags = ["gazebo", "transmission"] - for tag_name in removing_tags: - all_tags = tree.findall(tag_name) - for tag in all_tags: - tree.getroot().remove(tag) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def fix_link_attributes(urdf_string: str) -> str: - """ - Removes the attribute 'type' from links since this is not parsable by the URDF parser. - - :param urdf_string: The string of the URDF from which the attributes should be removed - :return: The URDF string with the attributes removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - - for link in tree.iter("link"): - if "type" in link.attrib.keys(): - del link.attrib["type"] - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) -> str: - """ - Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be - used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name - as filename. - - :param name: The name of the object - :param path: The path to the .obj or .stl file - :param color: The color which should be used for the material tag - :param cach_dir The absolute file path to the cach directory in the pycram package - :return: The absolute path of the created file - """ - urdf_template = ' \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - ' - urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, color))) - pathlib_obj = pathlib.Path(path) - path = str(pathlib_obj.resolve()) - content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) - with open(cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: - file.write(content) - return cach_dir + pathlib_obj.stem + ".urdf" - - -def _world_and_id(world: BulletWorld) -> Tuple[BulletWorld, int]: - """ - Selects the world to be used. If the given world is None the 'current_bullet_world' is used. - - :param world: The world which should be used or None if 'current_bullet_world' should be used - :return: The BulletWorld object and the id of this BulletWorld - """ - world = world if world is not None else BulletWorld.current_bullet_world - id = world.client_id if world is not None else BulletWorld.current_bullet_world.client_id - return world, id diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 67d4c6fc9..586758694 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -42,7 +42,7 @@ def __init__(self, resolution: float, self.height: int = height self.width: int = width local_transformer = LocalTransformer() - self.origin: Pose = local_transformer.transform_pose(origin, 'map') + self.origin: Pose = local_transformer.transform_pose_to_target_frame(origin, 'map') self.map: np.ndarray = map self.vis_ids: List[int] = [] diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 38ce79ab7..e902df6e4 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -690,7 +690,7 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: :return: The adjusted grasp pose """ lt = LocalTransformer() - pose_in_object = lt.transform_to_object_frame(pose, self.bullet_world_object) + pose_in_object = lt.transform_pose_to_object_base_frame(pose, self.bullet_world_object) special_knowledge = [] # Initialize as an empty list if self.type in SPECIAL_KNOWLEDGE: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 354aed83e..5f1a8c5cc 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -310,11 +310,11 @@ def perform(self) -> None: # oTm = Object Pose in Frame map oTm = object.get_pose() # Transform the object pose to the object frame, basically the origin of the object frame - mTo = object.local_transformer.transform_to_object_frame(oTm, object) + mTo = object.local_transformer.transform_pose_to_object_base_frame(oTm, object) # Adjust the pose according to the special knowledge of the object designator adjusted_pose = self.object_designator.special_knowledge_adjustment_pose(self.grasp, mTo) # Transform the adjusted pose to the map frame - adjusted_oTm = object.local_transformer.transform_pose(adjusted_pose, "map") + adjusted_oTm = object.local_transformer.transform_pose_to_target_frame(adjusted_pose, "map") # multiplying the orientation therefore "rotating" it, to get the correct orientation of the gripper ori = multiply_quaternions([adjusted_oTm.orientation.x, adjusted_oTm.orientation.y, adjusted_oTm.orientation.z, adjusted_oTm.orientation.w], @@ -330,19 +330,19 @@ def perform(self) -> None: # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" gripper_frame = robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm)) # First rotate the gripper, so the further calculations makes sense - tmp_for_rotate_pose = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) + tmp_for_rotate_pose = object.local_transformer.transform_pose_to_target_frame(adjusted_oTm, gripper_frame) tmp_for_rotate_pose.pose.position.x = 0 tmp_for_rotate_pose.pose.position.y = 0 tmp_for_rotate_pose.pose.position.z = -0.1 - gripper_rotate_pose = object.local_transformer.transform_pose(tmp_for_rotate_pose, "map") + gripper_rotate_pose = object.local_transformer.transform_pose_to_target_frame(tmp_for_rotate_pose, "map") #Perform Gripper Rotate # BulletWorld.current_bullet_world.add_vis_axis(gripper_rotate_pose) # MoveTCPMotion(gripper_rotate_pose, self.arm).resolve().perform() - oTg = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) + oTg = object.local_transformer.transform_pose_to_target_frame(adjusted_oTm, gripper_frame) oTg.pose.position.x -= 0.1 # in x since this is how the gripper is oriented - prepose = object.local_transformer.transform_pose(oTg, "map") + prepose = object.local_transformer.transform_pose_to_target_frame(oTg, "map") # Perform the motion with the prepose and open gripper BulletWorld.current_bullet_world.add_vis_axis(prepose) @@ -434,8 +434,8 @@ def perform(self) -> None: local_tf = LocalTransformer() # Transformations such that the target position is the position of the object and not the tcp - tcp_to_object = local_tf.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame( + tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, + BulletWorld.robot.get_link_tf_frame( robot_description.get_tool_frame(self.arm))) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() @@ -884,8 +884,8 @@ def perform(self) -> Any: lt = LocalTransformer() gripper_name = robot_description.get_tool_frame(self.arm) - object_pose_in_gripper = lt.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame(gripper_name)) + object_pose_in_gripper = lt.transform_pose_to_target_frame(object_pose, + BulletWorld.robot.get_link_tf_frame(gripper_name)) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index a42acd13a..8a5dc60bb 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -45,7 +45,7 @@ def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_ob :return: A moveit_msgs/PositionIKRequest message containing all the information from the parameter """ local_transformer = LocalTransformer() - target_pose = local_transformer.transform_pose(target_pose, robot_object.get_link_tf_frame(root_link)) + target_pose = local_transformer.transform_pose_to_target_frame(target_pose, robot_object.get_link_tf_frame(root_link)) robot_state = RobotState() joint_state = JointState() @@ -124,7 +124,7 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str # Get link after last joint in chain end_effector = robot_description.get_child(joints[-1]) - target_torso = local_transformer.transform_pose(target_pose, robot.get_link_tf_frame(base_link)) + target_torso = local_transformer.transform_pose_to_target_frame(target_pose, robot.get_link_tf_frame(base_link)) # target_torso = _transform_to_torso(pose, shadow_robot) diff = calculate_wrist_tool_offset(end_effector, gripper, robot) diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index 3a41c2074..d092dbe2a 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -129,7 +129,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti source = query_result.res[0].poseSource[i] lt = LocalTransformer() - pose = lt.transform_pose(pose, "map") + pose = lt.transform_pose_to_target_frame(pose, "map") pose_candidates[source] = pose diff --git a/src/pycram/helper.py b/src/pycram/helper.py index aad79a9d1..719fd040c 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -73,7 +73,7 @@ def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robo def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: BulletWorldObject) -> Transform: local_transformer = LocalTransformer() tool_pose = robot.get_link_pose(tool_frame) - wrist_to_tool = local_transformer.transform_pose(tool_pose, robot.get_link_tf_frame(wrist_frame)) + wrist_to_tool = local_transformer.transform_pose_to_target_frame(tool_pose, robot.get_link_tf_frame(wrist_frame)) return wrist_to_tool.to_transform(robot.get_link_tf_frame(tool_frame)) diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 9c0ede811..256d49b3a 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -68,7 +68,7 @@ def update_objects_for_current_world(self) -> None: for obj in list(self.world.current_bullet_world.objects): self.update_transforms_for_object(obj, curr_time) - def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: + def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union[Pose, None]: """ Transforms a given pose to the target frame. @@ -91,6 +91,28 @@ def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: return Pose(*copy_pose.to_list(), frame=new_pose.header.frame_id) + def transform_pose_to_object_base_frame(self, pose: Pose, world_object: 'world.Object') -> Union[Pose, None]: + """ + Transforms the given pose to the base frame of the given BulletWorld object. + + :param pose: Pose that should be transformed + :param world_object: World Object with frame to which the pose should be transformed + :return: The new pose transformed to the base coordinate frame of the object + """ + return self.transform_to_object_frame(pose, world_object.tf_frame) + + def transform_pose_to_object_link_frame(self, pose: Pose, world_object: 'world.Object', link_name: str) -> Union[Pose, None]: + """ + Transforms the given pose to the link frame of the given BulletWorld object. + + :param pose: Pose that should be transformed + :param world_object: World Object with frame to which the pose should be transformed + :param link_name: Name of the link of the object to which the pose should be transformed + :return: The new pose transformed to the link coordinate frame of the object + """ + target_frame = world_object.get_link_tf_frame(link_name) + return self.transform_to_object_frame(pose, target_frame) + def transform_to_object_frame(self, pose: Pose, world_object: 'world.Object', link_name: str = None) -> Union[Pose, None]: """ @@ -106,7 +128,7 @@ def transform_to_object_frame(self, pose: Pose, target_frame = world_object.get_link_tf_frame(link_name) else: target_frame = world_object.tf_frame - return self.transform_pose(pose, target_frame) + return self.transform_pose_to_target_frame(pose, target_frame) def tf_transform(self, source_frame: str, target_frame: str, time: Optional[rospy.rostime.Time] = None) -> Transform: @@ -156,5 +178,5 @@ def transformPose(self, target_frame, ps) -> Pose: :param ps: Pose that should be transformed :return: Input pose in the target_frame """ - return self.transform_pose(ps, target_frame) + return self.transform_pose_to_target_frame(ps, target_frame) diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 07800af68..c446b1463 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -97,7 +97,7 @@ def _execute(self, desig: PlaceMotion.Motion): # Transformations such that the target position is the position of the object and not the tcp object_pose = object.get_pose() local_tf = LocalTransformer() - tcp_to_object = local_tf.transform_pose(object_pose, robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) + tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) @@ -115,8 +115,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) - pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) + pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_tilt_link")) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -295,8 +295,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) - pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) + pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_tilt_link")) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -321,7 +321,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose(obj_pose, BulletWorld.robot.get_link_tf_frame("torso_lift_link")) + obj_pose = lt.transform_pose_to_target_frame(obj_pose, BulletWorld.robot.get_link_tf_frame("torso_lift_link")) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 @@ -350,7 +350,7 @@ class Pr2MoveTCPReal(ProcessModule): def _execute(self, designator: MoveTCPMotion.Motion) -> Any: lt = LocalTransformer() - pose_in_map = lt.transform_pose(designator.target, "map") + pose_in_map = lt.transform_pose_to_target_frame(designator.target, "map") if designator.allow_gripper_collision: giskard.allow_gripper_collision(designator.arm) diff --git a/src/pycram/world.py b/src/pycram/world.py index 2e3c0f159..af9e34a3f 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,7 +10,7 @@ import xml.etree.ElementTree from queue import Queue import tf -from typing import List, Optional, Dict, Tuple, Callable +from typing import List, Optional, Dict, Tuple, Callable, Set from typing import Union import numpy as np @@ -32,24 +32,51 @@ from .pose import Pose, Transform from abc import ABC, abstractproperty, abstractmethod +from dataclasses import dataclass + + +@dataclass +class Constraint: + parent_obj_id: int + child_obj_id: int + parent_link_id: int + child_link_id: int + parent_to_child_transform: Transform + joint_type: int + joint_axis: List + + +@dataclass +class Attachment: + parent_obj: Object + child_obj: Object + parent_link: Optional[str] + loose: bool class World(ABC): """ The World Class represents the physics Simulation and belief state. """ - current_world: World = None """ Global reference to the currently used World, usually this is the graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the shadow world. In this way you can comfortably use the current_world, which should point towards the World used at the moment. """ - robot: Object = None + current_world: World = None + """ Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the URDF with the name of the URDF on the parameter server. """ + robot: Object = None + + """ + Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. + """ + data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} + def __init__(self, mode: str, is_prospection_world: bool): """ Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the @@ -61,22 +88,40 @@ def __init__(self, mode: str, is_prospection_world: bool): """ self.objects: List[Object] = [] self.client_id: int = -1 - self.detachment_event: Event = Event() - self.attachment_event: Event = Event() - self.manipulation_event: Event = Event() self.mode: str = mode - if World.current_world is None: - World.current_world = self + self._initialize_events() + World.current_world = self if World.current_world is None else World.current_world self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} - self.data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] - self.prospection_world: World = World("DIRECT", True) if not is_prospection_world else None - self.world_sync: WorldSync = WorldSync(self, self.prospection_world) if not is_prospection_world else None - self.is_prospection_world: bool = is_prospection_world self.local_transformer = LocalTransformer() - if not is_prospection_world: - self.world_sync.start() - self.local_transformer.world = self - self.local_transformer.prospection_world = self.prospection_world + + self.is_prospection_world: bool = is_prospection_world + + if is_prospection_world: # then no need to add another prospection world + self.prospection_world = None + self.world_sync = None + else: # a normal world should have a synced prospection world + self._init_and_sync_prospection_world() + self._update_local_transformer_worlds() + + def _init_and_sync_prospection_world(self): + self._init_prospection_world() + self._sync_prospection_world() + + def _update_local_transformer_worlds(self): + self.local_transformer.world = self + self.local_transformer.prospection_world = self.prospection_world + + def _init_prospection_world(self): + self.prospection_world: World = World("DIRECT", True) + + def _sync_prospection_world(self): + self.world_sync: WorldSync = WorldSync(self, self.prospection_world) + self.world_sync.start() + + def _initialize_events(self): + self.detachment_event: Event = Event() + self.attachment_event: Event = Event() + self.manipulation_event: Event = Event() def get_objects_by_name(self, name: str) -> List[Object]: """ @@ -114,22 +159,33 @@ def remove_object(self, obj_id: int) -> None: """ pass - def add_constraint(self, - parent_obj_id: int, - child_obj_id: int, - parent_link_id: int, - joint_type: int, - parent_to_child_transform: Transform, - joint_axis: List, - child_link_id: int) -> int: + def add_constraint(self, constraint: Constraint) -> int: """ Add a constraint between two objects so that attachment they become attached """ - cid = p.createConstraint(parent_obj_id, parent_link_id, child_obj_id, child_link_id, joint_type, - joint_axis, parent_to_child_transform.translation_as_list(), [0, 0, 0], - parent_to_child_transform.rotation_as_list(), + cid = p.createConstraint(constraint.parent_obj_id, + constraint.parent_link_id, + constraint.child_obj_id, + constraint.child_link_id, + constraint.joint_type, + constraint.joint_axis, + constraint.parent_to_child_transform.translation_as_list(), + [0, 0, 0], + constraint.parent_to_child_transform.rotation_as_list(), physicsClientId=self.client_id) return cid + + def attach_object_base_to_parent_object_base(self, parent_obj: Object, + child_obj: Object, + loose: Optional[bool] = False) -> None: + pass # TODO: implement this function + + def attach_object_base_to_parent_object_link(self, parent_obj: Object, + child_obj: Object, + parent_link: str, + loose: Optional[bool] = False) -> None: + pass # TODO: implement this function + def attach_objects(self, parent_obj: Object, child_obj: Object, @@ -151,7 +207,7 @@ def attach_objects(self, :param loose: If the attachment should be a loose attachment. """ link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 - link_to_object = parent_obj._calculate_transform(child_obj, parent_link) + link_to_object = parent_obj._calculate_transform_of_object_base_to_this_object_link(child_obj, parent_link) parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] @@ -213,7 +269,7 @@ def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: else: link_to_object = obj.attachments[att_obj][0] - world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") + world_to_object = obj.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), world_to_object.orientation_as_list(), physicsClientId=self.client_id) @@ -620,7 +676,7 @@ def add_additional_resource_path(self, path: str) -> None: :param path: A path in the filesystem in which to search for files. """ - self.data_directory.append(path) + World.data_directory.append(path) def get_shadow_object(self, object: Object) -> Object: """ @@ -707,18 +763,20 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): self._gui_thread: Gui = Gui(self, mode) self._gui_thread.start() + # This disables file caching from PyBullet, since this would also cache # files that can not be loaded p.setPhysicsEngineParameter(enableFileCaching=0) + # Needed to let the other thread start the simulation, before Objects are spawned. time.sleep(0.1) self.vis_axis: List[Object] = [] # Some default settings self.set_gravity([0, 0, -9.8]) + if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - # atexit.register(self.exit) def get_objects_by_name(self, name: str) -> List[Object]: """ @@ -839,7 +897,7 @@ def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: else: link_to_object = obj.attachments[att_obj][0] - world_to_object = obj.local_transformer.transform_pose(link_to_object.to_pose(), "map") + world_to_object = obj.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), world_to_object.orientation_as_list(), physicsClientId=self.client_id) @@ -1239,15 +1297,6 @@ def register_collision_callback(self, objectA: Object, objectB: Object, """ self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) - def add_additional_resource_path(self, path: str) -> None: - """ - Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an - Object is spawned only with a filename. - - :param path: A path in the filesystem in which to search for files. - """ - self.data_directory.append(path) - def get_shadow_object(self, object: Object) -> Object: """ Returns the corresponding object from the shadow world for the given object. If the given Object is already in @@ -1665,7 +1714,7 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self.name: str = name self.type: str = type self.color: List[float] = color - pose_in_map = self.local_transformer.transform_pose(pose, "map") + pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") @@ -1793,7 +1842,7 @@ def set_pose(self, pose: Pose, base: bool = False) -> None: :param pose: New Pose for the object :param base: If True places the object base instead of origin at the specified position and orientation """ - pose_in_map = self.local_transformer.transform_pose(pose, "map") + pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() if base: position = np.array(position) + self.base_origin_shift @@ -1839,6 +1888,14 @@ def _set_attached_objects(self, prev_object: List[Object]) -> None: """ self.world._set_attached_objects(self, prev_object) + def _calculate_transform_of_object_base_to_this_object_base(self, obj: Object): + transform = self.local_transformer.transform_pose_to_object_base_frame(obj.pose, self) + return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + + def _calculate_transform_of_object_base_to_this_object_link(self, obj: Object, link: str): + transform = self.local_transformer.transform_pose_to_object_link_frame(obj.pose, self, link) + return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + def _calculate_transform(self, obj: Object, link: str = None) -> Transform: """ Calculates the transformation between another object and the given @@ -2267,7 +2324,6 @@ def get_path_from_data_dir(file_name: str, data_directory: str) -> str: :param data_directory: The directory in which to search for the file. :return: The full path in the filesystem or None if there is no file with the filename in the directory """ - dir = pathlib.Path(data_directory) for file in os.listdir(data_directory): if file == file_name: return data_directory + f"/{file_name}" diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 23e0c8924..d655b8f8c 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -311,7 +311,7 @@ def blocking(pose_or_object: Union[Object, Pose], joints = robot_description.chains[arm].joints local_transformer = LocalTransformer() - target_map = local_transformer.transform_pose(input_pose, "map") + target_map = local_transformer.transform_pose_to_target_frame(input_pose, "map") if grasp: grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) target_map.orientation.x = grasp_orientation[0] diff --git a/test/local_transformer_tests.py b/test/local_transformer_tests.py index fc8c48f3e..b3f3b8bd1 100644 --- a/test/local_transformer_tests.py +++ b/test/local_transformer_tests.py @@ -26,7 +26,7 @@ def test_transform_pose(self): l.setTransform(Transform([1, 1, 1], [0, 0, 0, 1], "map", "test_frame")) p = Pose() - transformed_pose = l.transform_pose(p, "test_frame") + transformed_pose = l.transform_pose_to_target_frame(p, "test_frame") self.assertTrue(transformed_pose.position_as_list() == [-1, -1, -1]) self.assertTrue(transformed_pose.orientation_as_list() == [0, 0, 0, 1]) @@ -37,7 +37,7 @@ def test_transform_pose_position(self): l.setTransform(Transform([1, 1, 1], [0, 0, 0, 1], "map", "test_frame")) p = Pose() - transformed_pose = l.transform_pose(p, "test_frame") + transformed_pose = l.transform_pose_to_target_frame(p, "test_frame") self.assertTrue(transformed_pose.position == transformed_pose.pose.position) From a5ae78bdb11113ddc2882ebf76a1ba4a9c5b8328 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 6 Dec 2023 19:08:31 +0100 Subject: [PATCH 006/195] [WorldAbstractClass] InProgress , currently in _set_attached_objects method, and defining the Attachment class and making the necessary changes for that, also add_constraint is still in progress. --- examples/local_transformer.ipynb | 2 +- src/pycram/local_transformer.py | 4 +- src/pycram/pose.py | 4 + src/pycram/world.py | 243 ++++++++++++++++++++----------- 4 files changed, 163 insertions(+), 90 deletions(-) diff --git a/examples/local_transformer.ipynb b/examples/local_transformer.ipynb index 2d4d41c03..31017bebb 100644 --- a/examples/local_transformer.ipynb +++ b/examples/local_transformer.ipynb @@ -233,7 +233,7 @@ "l = LocalTransformer()\n", "test_pose = Pose([1, 1, 1], [0, 0, 0, 1], \"map\")\n", "\n", - "transformed_pose = l.transform_to_object_frame(test_pose, milk)\n", + "transformed_pose = l.transform_pose_to_object_frame(test_pose, milk)\n", "print(transformed_pose)\n", "\n", "new_pose = l.transform_pose(transformed_pose, \"map\")\n", diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 256d49b3a..23bcb3cdc 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -99,7 +99,7 @@ def transform_pose_to_object_base_frame(self, pose: Pose, world_object: 'world.O :param world_object: World Object with frame to which the pose should be transformed :return: The new pose transformed to the base coordinate frame of the object """ - return self.transform_to_object_frame(pose, world_object.tf_frame) + return self.transform_pose_to_target_frame(pose, world_object.tf_frame) def transform_pose_to_object_link_frame(self, pose: Pose, world_object: 'world.Object', link_name: str) -> Union[Pose, None]: """ @@ -111,7 +111,7 @@ def transform_pose_to_object_link_frame(self, pose: Pose, world_object: 'world.O :return: The new pose transformed to the link coordinate frame of the object """ target_frame = world_object.get_link_tf_frame(link_name) - return self.transform_to_object_frame(pose, target_frame) + return self.transform_pose_to_target_frame(pose, target_frame) def transform_to_object_frame(self, pose: Pose, world_object: 'world.Object', link_name: str = None) -> Union[Pose, None]: diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 852f20967..0b9feeaca 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -301,6 +301,10 @@ def __init__(self, translation: Optional[List[float]] = None, rotation: Optional self.frame = frame + @classmethod + def from_pose_and_child_frame(cls, pose: Pose, child_frame_name: str) -> Transform: + return cls(pose.position_as_list(), pose.orientation_as_list(), pose.frame, child_frame_name) + @staticmethod def from_transform_stamped(transform_stamped: TransformStamped) -> Transform: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index af9e34a3f..9ff813e65 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -38,20 +38,22 @@ @dataclass class Constraint: parent_obj_id: int - child_obj_id: int parent_link_id: int + child_obj_id: int child_link_id: int - parent_to_child_transform: Transform - joint_type: int - joint_axis: List + joint_type: JointType + joint_axis_in_child_link_frame: List[int] + joint_frame_position_wrt_parent_origin: List[float] + joint_frame_position_wrt_child_origin: List[float] + joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None + joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None @dataclass class Attachment: - parent_obj: Object - child_obj: Object - parent_link: Optional[str] - loose: bool + transform_from_child_base_to_parent_link: Transform + parent_link: Optional[str] = None + loose: Optional[bool] = False class World(ABC): @@ -123,6 +125,10 @@ def _initialize_events(self): self.attachment_event: Event = Event() self.manipulation_event: Event = Event() + @abstractmethod + def load_urdf_with_pose_and_get_world_object_id(self, path: str, pose: Pose) -> int: + pass + def get_objects_by_name(self, name: str) -> List[Object]: """ Returns a list of all Objects in this World with the same name as the given one. @@ -159,33 +165,73 @@ def remove_object(self, obj_id: int) -> None: """ pass + @abstractmethod def add_constraint(self, constraint: Constraint) -> int: """ - Add a constraint between two objects so that attachment they become attached + Add a constraint between two objects so that they become attached """ - cid = p.createConstraint(constraint.parent_obj_id, - constraint.parent_link_id, - constraint.child_obj_id, - constraint.child_link_id, - constraint.joint_type, - constraint.joint_axis, - constraint.parent_to_child_transform.translation_as_list(), - [0, 0, 0], - constraint.parent_to_child_transform.rotation_as_list(), - physicsClientId=self.client_id) - return cid + pass - def attach_object_base_to_parent_object_base(self, parent_obj: Object, - child_obj: Object, - loose: Optional[bool] = False) -> None: - pass # TODO: implement this function + @abstractmethod + def remove_constraint(self, constraint_id): + pass - def attach_object_base_to_parent_object_link(self, parent_obj: Object, - child_obj: Object, - parent_link: str, - loose: Optional[bool] = False) -> None: + def create_fixed_constraint_to_parent_link_at_child_origin(self, + parent_object: Object, + child_object: Object, + parent_link: str) -> Constraint: + parent_link_id = parent_object.get_link_id(parent_link) + child_base_wrt_parent_link = \ + parent_object._calculate_transform_from_other_object_base_to_this_object_link(child_object, parent_link) + constraint = Constraint(parent_object.id, + parent_link_id, + child_object.id, + child_link_id=-1, # -1 means use the base link + joint_type=JointType.FIXED, + joint_axis_in_child_link_frame=[0, 1, 0], + joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), + joint_frame_position_wrt_child_origin=[0, 0, 0], + joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), + ) + return constraint + + def add_attachment_to_parent_and_child_attachments(self, + parent_object: Object, + child_object: Object, + new_attachment: Attachment): + + parent_object.attachments[child_object] = [child_base_wrt_parent_link, parent_link, loose] + child_object.attachments[parent_object] = [child_base_wrt_parent_link.invert(), None, False] + + def attach_child_object_base_to_parent_object_base(self, parent_obj: Object, + child_obj: Object, + loose: Optional[bool] = False) -> None: pass # TODO: implement this function + def attach_child_object_base_to_parent_object_link(self, parent_obj: Object, + child_obj: Object, + parent_link: str, + loose: Optional[bool] = False) -> None: + parent_link_id = parent_obj.get_link_id(parent_link) + child_base_wrt_parent_link = \ + parent_obj._calculate_transform_from_other_object_base_to_this_object_link(child_obj, parent_link) + parent_obj.attachments[child_obj] = [child_base_wrt_parent_link, parent_link, loose] + child_obj.attachments[parent_obj] = [child_base_wrt_parent_link.invert(), None, False] + constraint = Constraint(parent_obj.id, + parent_link_id, + child_obj.id, + child_link_id=-1, # -1 means use the base link + joint_type=JointType.FIXED, + joint_axis_in_child_link_frame=[0, 1, 0], + joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), + joint_frame_position_wrt_child_origin=[0, 0, 0], + joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), + ) + constraint_id = self.add_constraint(constraint) + parent_obj.cids[child_obj] = constraint_id + child_obj.cids[parent_obj] = constraint_id + self.attachment_event(parent_obj, [parent_obj, child_obj]) + def attach_objects(self, parent_obj: Object, child_obj: Object, @@ -206,17 +252,24 @@ def attach_objects(self, :param parent_link: The link of the parent object to which the child object should be attached :param loose: If the attachment should be a loose attachment. """ - link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 - link_to_object = parent_obj._calculate_transform_of_object_base_to_this_object_link(child_obj, parent_link) - parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] - child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] - - cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, - [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], - link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - parent_obj.cids[child_obj] = cid - child_obj.cids[parent_obj] = cid + parent_link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 + child_base_wrt_parent_link =\ + parent_obj._calculate_transform_from_other_object_base_to_this_object_link(child_obj, parent_link) + parent_obj.attachments[child_obj] = [child_base_wrt_parent_link, parent_link, loose] + child_obj.attachments[parent_obj] = [child_base_wrt_parent_link.invert(), None, False] + constraint = Constraint(parent_obj.id, + parent_link_id, + child_obj.id, + child_link_id=-1, + joint_type=JointType.FIXED, + joint_axis_in_child_link_frame=[0, 1, 0], + joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), + joint_frame_position_wrt_child_origin=[0, 0, 0], + joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), + ) + constraint_id = self.add_constraint(constraint) + parent_obj.cids[child_obj] = constraint_id + child_obj.cids[parent_obj] = constraint_id self.attachment_event(parent_obj, [parent_obj, child_obj]) def detach_objects(self, obj1: Object, obj2: Object) -> None: @@ -252,14 +305,17 @@ def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: for att_obj in obj.attachments: if att_obj in prev_object: continue - if obj.attachments[att_obj][2]: + if obj.attachments[att_obj].loose: # Updates the attachment transformation and constraint if the # attachment is loose, instead of updating the position of all attached objects - link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) - link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 - obj.attachments[att_obj][0] = link_to_object - att_obj.attachments[obj][0] = link_to_object.invert() - p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) + link_to_object = ( + obj._calculate_transform_from_other_object_base_to_this_object_link(att_obj, + obj.attachments[att_obj].parent_link)) + link_id = obj.get_link_id(obj.attachments[att_obj].parent_link) if obj.attachments[att_obj].parent_link else -1 + obj.attachments[att_obj].transform_from_child_base_to_parent_link = link_to_object + att_obj.attachments[obj].transform_from_child_base_to_parent_link = link_to_object.invert() + self.remove_constraint(obj.cids[att_obj]) + # TODO: Ask Jonas what is the benefit of joint axis in a fixed joint. cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], link_to_object.translation_as_list(), [0, 0, 0], link_to_object.rotation_as_list(), @@ -729,22 +785,6 @@ def reset_bullet_world(self) -> None: obj.set_pose(obj.original_pose) class BulletWorld(World): - """ - The BulletWorld Class represents the physics Simulation and belief state. - """ - - current_bullet_world: BulletWorld = None - """ - Global reference to the currently used BulletWorld, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_bullet_world points to the - shadow world. In this way you can comfortably use the current_bullet_world, which should point towards the BulletWorld - used at the moment. - """ - robot: Object = None - """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the - URDF with the name of the URDF on the parameter server. - """ # Check is for sphinx autoAPI to be able to work in a CI workflow if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): @@ -778,6 +818,11 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) + def load_urdf_with_pose_and_get_world_object_id(self, path: str, pose: Pose) -> int: + return p.loadURDF(path, + basePosition=pose.position_as_list(), + baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) + def get_objects_by_name(self, name: str) -> List[Object]: """ Returns a list of all Objects in this BulletWorld with the same name as the given one. @@ -814,6 +859,26 @@ def remove_object(self, obj_id: int) -> None: p.removeBody(obj_id, self.client_id) + def add_constraint(self, constraint: Constraint) -> int: + """ + Add a constraint between two objects so that attachment they become attached + """ + constraint_id = p.createConstraint(constraint.parent_obj_id, + constraint.parent_link_id, + constraint.child_obj_id, + constraint.child_link_id, + constraint.joint_type, + constraint.joint_axis, + constraint.joint_frame_position_wrt_parent_origin, + constraint.joint_frame_position_wrt_child_origin, + constraint.joint_frame_orientation_wrt_parent_origin, + constraint.joint_frame_orientation_wrt_child_origin, + physicsClientId=self.client_id) + return constraint_id + + def remove_constraint(self, constraint_id): + p.removeConstraint(constraint_id, physicsClientId=self.client_id) + def attach_objects(self, parent_obj: Object, child_obj: Object, @@ -1686,30 +1751,30 @@ def run(self): class Object: """ - Represents a spawned Object in the BulletWorld. + Represents a spawned Object in the World. """ def __init__(self, name: str, type: Union[str, ObjectType], path: str, pose: Pose = None, - world: BulletWorld = None, + world: World = None, color: Optional[List[float]] = [1, 1, 1, 1], ignoreCachedFiles: Optional[bool] = False): """ - The constructor loads the urdf file into the given BulletWorld, if no BulletWorld is specified the - :py:attr:`~BulletWorld.current_bullet_world` will be used. It is also possible to load .obj and .stl file into the BulletWorld. + The constructor loads the urdf file into the given World, if no World is specified the + :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object :param type: The type of the object :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched :param pose: The pose at which the Object should be spawned - :param world: The BulletWorld in which the object should be spawned, if no world is specified the :py:attr:`~BulletWorld.current_bullet_world` will be used + :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used :param color: The color with which the object should be spawned. :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. """ if not pose: pose = Pose() - self.world: BulletWorld = world if world is not None else BulletWorld.current_bullet_world + self.world: World = world if world is not None else World.current_world self.local_transformer = LocalTransformer() self.name: str = name self.type: str = type @@ -1719,21 +1784,21 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") - self.attachments: Dict[Object, List] = {} + self.attachments: Dict[Object, Attachment] = {} self.cids: Dict[Object, int] = {} self.original_pose = pose_in_map self.tf_frame = ("shadow/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) # This means "world" is not the shadow world since it has a reference to a shadow world - if self.world.prospection_world != None: + if self.world.prospection_world is not None: self.world.world_sync.add_obj_queue.put( [name, type, path, position, orientation, self.world.prospection_world, color, self]) with open(self.path) as f: self.urdf_object = URDF.from_xml_string(f.read()) - if self.urdf_object.name == robot_description.name and not BulletWorld.robot: - BulletWorld.robot = self + if self.urdf_object.name == robot_description.name and not World.robot: + World.robot = self self.links[self.urdf_object.get_root()] = -1 @@ -1758,13 +1823,13 @@ def __repr__(self): def remove(self) -> None: """ - Removes this object from the BulletWorld it currently resides in. + Removes this object from the World it currently resides in. For the object to be removed it has to be detached from all objects it is currently attached to. After this is done a call to PyBullet is done to remove this Object from the simulation. """ for obj in self.attachments.keys(): - self.world.detach(self, obj) + self.world.detach_objects(self, obj) self.world.objects.remove(self) # This means the current world of the object is not the shadow world, since it # has a reference to the shadow world @@ -1772,8 +1837,8 @@ def remove(self) -> None: self.world.world_sync.remove_obj_queue.put(self) self.world.world_sync.remove_obj_queue.join() self.world.remove_object(self.id) - if BulletWorld.robot == self: - BulletWorld.robot = None + if World.robot == self: + World.robot = None def attach(self, obj: Object, link: Optional[str] = None, loose: Optional[bool] = False) -> None: """ @@ -1797,7 +1862,7 @@ def detach(self, obj: Object) -> None: Detaches another object from this object. This is done by deleting the attachment from the attachments dictionary of both objects and deleting the constraint of pybullet. - Afterward the detachment event of the corresponding BulletWorld will be fired. + Afterward the detachment event of the corresponding World will be fired. :param object: The object which should be detached """ @@ -1809,7 +1874,7 @@ def detach_all(self) -> None: """ attachments = self.attachments.copy() for att in attachments.keys(): - self.world.detach(self, att) + self.world.detach_objects(self, att) def get_position(self) -> Pose: """ @@ -1888,13 +1953,17 @@ def _set_attached_objects(self, prev_object: List[Object]) -> None: """ self.world._set_attached_objects(self, prev_object) - def _calculate_transform_of_object_base_to_this_object_base(self, obj: Object): - transform = self.local_transformer.transform_pose_to_object_base_frame(obj.pose, self) - return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + def _calculate_transform_from_other_object_base_to_this_object_base(self, other_object: Object): + pose_wrt_this_object_base = self.local_transformer.transform_pose_to_object_base_frame(other_object.pose, self) + return Transform.from_pose_and_child_frame(pose_wrt_this_object_base, other_object.tf_frame) - def _calculate_transform_of_object_base_to_this_object_link(self, obj: Object, link: str): - transform = self.local_transformer.transform_pose_to_object_link_frame(obj.pose, self, link) - return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + def _calculate_transform_from_other_object_base_to_this_object_link(self, + other_object: Object, + this_object_link_name: str): + pose_wrt_this_object_link = self.local_transformer.transform_pose_to_object_link_frame(other_object.pose, + self, + this_object_link_name) + return Transform.from_pose_and_child_frame(pose_wrt_this_object_link, other_object.tf_frame) def _calculate_transform(self, obj: Object, link: str = None) -> Transform: """ @@ -2348,11 +2417,11 @@ def _load_object(name: str, path: str, position: List[float], orientation: List[float], - world: BulletWorld, + world: World, color: List[float], ignoreCachedFiles: bool) -> Tuple[int, str]: """ - Loads an object to the given BulletWorld with the given position and orientation. The color will only be + Loads an object to the given World with the given position and orientation. The color will only be used when an .obj or .stl file is given. If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created and this URDf file will be loaded instead. @@ -2364,7 +2433,7 @@ def _load_object(name: str, :param path: The path to the source file or the name on the ROS parameter server :param position: The position in which the object should be spawned :param orientation: The orientation in which the object should be spawned - :param world: The BulletWorld to which the Object should be spawned + :param world: The World to which the Object should be spawned :param color: The color of the object, only used when .obj or .stl file is given :param ignoreCachedFiles: Whether to ignore files in the cache directory. :return: The unique id of the object and the path to the file used for spawning @@ -2417,7 +2486,7 @@ def _load_object(name: str, path = cach_dir + name + ".urdf" try: - obj = p.loadURDF(path, basePosition=position, baseOrientation=orientation, physicsClientId=world_id) + obj = world.load_urdf_with_pose_and_get_world_object_id(path, Pose(position, orientation)) return obj, path except p.error as e: logging.error( From 5188eed31aaa681f02bf146e4dce7dd85a01fb71 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 7 Dec 2023 19:12:07 +0100 Subject: [PATCH 007/195] [WorldAbstractClass] InProgress , currently in refactoring attachments. --- src/pycram/world.py | 231 +++++++++++++++++++++++--------------------- 1 file changed, 122 insertions(+), 109 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 9ff813e65..9dfffabc5 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -49,35 +49,66 @@ class Constraint: joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None -@dataclass class Attachment: - transform_from_child_base_to_parent_link: Transform - parent_link: Optional[str] = None - loose: Optional[bool] = False + def __init__(self, + parent_object: Object, + child_object: Object, + parent_link: Optional[str] = None, + bidirectional: Optional[bool] = False): + """ + Creates an attachment between the parent object and the child object. + """ + self.parent_object = parent_object + self.child_object = child_object + self.parent_link = parent_link + self.child_link = None + self.bidirectional = bidirectional + self.child_base_to_parent_link_transform = self._calculate_transforms() + + def _calculate_transforms(self): + # TODO: need to handle inverse case where there is a child link but no parent link + if self.parent_link is None: + return self.parent_object._calculate_transform_from_other_object_base_to_this_object_base(self.child_object) + else: + return self.parent_object._calculate_transform_from_other_object_base_to_this_object_link(self.child_object, + self.parent_link) + + def update_transforms(self): + self.child_base_to_parent_link_transform = self._calculate_transforms() + + def get_inverse(self): + attachment = Attachment(self.child_object, self.parent_object, None, self.bidirectional) + attachment.child_link = self.parent_link + return attachment + + def add_to_objects_attachments_collection(self): + self.parent_object.attachments[self.child_object] = self + self.child_object.attachments[self.parent_object] = self.get_inverse() class World(ABC): """ The World Class represents the physics Simulation and belief state. """ + + current_world: World = None """ - Global reference to the currently used World, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the - shadow world. In this way you can comfortably use the current_world, which should point towards the World - used at the moment. + Global reference to the currently used World, usually this is the + graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the + shadow world. In this way you can comfortably use the current_world, which should point towards the World + used at the moment. """ - current_world: World = None + robot: Object = None """ Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the URDF with the name of the URDF on the parameter server. """ - robot: Object = None + data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} """ Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ - data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} def __init__(self, mode: str, is_prospection_world: bool): """ @@ -176,67 +207,61 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): pass - def create_fixed_constraint_to_parent_link_at_child_origin(self, - parent_object: Object, - child_object: Object, - parent_link: str) -> Constraint: - parent_link_id = parent_object.get_link_id(parent_link) - child_base_wrt_parent_link = \ - parent_object._calculate_transform_from_other_object_base_to_this_object_link(child_object, parent_link) - constraint = Constraint(parent_object.id, - parent_link_id, - child_object.id, + def add_fixed_constraint_between_parent_link_and_child_base(self, + parent_object: Object, + child_object: Object, + child_base_wrt_parent_link: Transform, + parent_link: Optional[str] = None) -> int: + """ + Creates a fixed joint constraint between the given parent link and the base of the child object, + the joint frame will be at the origin of the parent link and the child base, and would have the same orientation + as the child base frame. + + returns the constraint id + """ + + constraint = Constraint(parent_obj_id=parent_object.id, + parent_link_id=parent_object.get_link_id(parent_link) if parent_link else -1, + child_obj_id=child_object.id, child_link_id=-1, # -1 means use the base link joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=[0, 1, 0], + joint_axis_in_child_link_frame=[0, 0, 0], joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), joint_frame_position_wrt_child_origin=[0, 0, 0], joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), ) - return constraint - - def add_attachment_to_parent_and_child_attachments(self, - parent_object: Object, - child_object: Object, - new_attachment: Attachment): - - parent_object.attachments[child_object] = [child_base_wrt_parent_link, parent_link, loose] - child_object.attachments[parent_object] = [child_base_wrt_parent_link.invert(), None, False] + constraint_id = self.add_constraint(constraint) + return constraint_id def attach_child_object_base_to_parent_object_base(self, parent_obj: Object, child_obj: Object, loose: Optional[bool] = False) -> None: pass # TODO: implement this function - def attach_child_object_base_to_parent_object_link(self, parent_obj: Object, + def _create_attachment_and_constraint(self, + parent_object: Object, + child_object: Object, + parent_link: str, + loose: Optional[bool] = False) -> None: + + # Add the attachment to the attachment dictionary of both objects + attachment = Attachment(parent_object, child_object, parent_link, loose) + + # Create the constraint + constraint_id = self.add_fixed_constraint_between_parent_link_and_child_base(parent_object, + child_object, + attachment.transform_from_child_base_to_parent_link, + parent_link) + + # Update the attachment and constraint dictionary in both objects + parent_object.cids[child_object] = constraint_id + child_object.cids[parent_object] = constraint_id + + def attach_child_object_base_to_parent_object_link(self, + parent_obj: Object, child_obj: Object, - parent_link: str, + parent_link: Optional[str] = None, loose: Optional[bool] = False) -> None: - parent_link_id = parent_obj.get_link_id(parent_link) - child_base_wrt_parent_link = \ - parent_obj._calculate_transform_from_other_object_base_to_this_object_link(child_obj, parent_link) - parent_obj.attachments[child_obj] = [child_base_wrt_parent_link, parent_link, loose] - child_obj.attachments[parent_obj] = [child_base_wrt_parent_link.invert(), None, False] - constraint = Constraint(parent_obj.id, - parent_link_id, - child_obj.id, - child_link_id=-1, # -1 means use the base link - joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=[0, 1, 0], - joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), - joint_frame_position_wrt_child_origin=[0, 0, 0], - joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), - ) - constraint_id = self.add_constraint(constraint) - parent_obj.cids[child_obj] = constraint_id - child_obj.cids[parent_obj] = constraint_id - self.attachment_event(parent_obj, [parent_obj, child_obj]) - - def attach_objects(self, - parent_obj: Object, - child_obj: Object, - parent_link: Optional[str] = None, - loose: Optional[bool] = False) -> None: """ Attaches another object to this object. This is done by saving the transformation between the given link, if there is one, and @@ -252,24 +277,8 @@ def attach_objects(self, :param parent_link: The link of the parent object to which the child object should be attached :param loose: If the attachment should be a loose attachment. """ - parent_link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 - child_base_wrt_parent_link =\ - parent_obj._calculate_transform_from_other_object_base_to_this_object_link(child_obj, parent_link) - parent_obj.attachments[child_obj] = [child_base_wrt_parent_link, parent_link, loose] - child_obj.attachments[parent_obj] = [child_base_wrt_parent_link.invert(), None, False] - constraint = Constraint(parent_obj.id, - parent_link_id, - child_obj.id, - child_link_id=-1, - joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=[0, 1, 0], - joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), - joint_frame_position_wrt_child_origin=[0, 0, 0], - joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), - ) - constraint_id = self.add_constraint(constraint) - parent_obj.cids[child_obj] = constraint_id - child_obj.cids[parent_obj] = constraint_id + + self._create_attachment_and_constraint(parent_obj, child_obj, parent_link, loose) self.attachment_event(parent_obj, [parent_obj, child_obj]) def detach_objects(self, obj1: Object, obj2: Object) -> None: @@ -291,7 +300,7 @@ def detach_objects(self, obj1: Object, obj2: Object) -> None: del obj2.cids[obj1] obj1.world.detachment_event(obj1, [obj1, obj2]) - def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: + def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: """ Updates the positions of all attached objects. This is done by calculating the new pose in world coordinate frame and setting the @@ -302,35 +311,39 @@ def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: :param prev_object: A list of Objects that were already moved, these will be excluded to prevent loops in the update. """ - for att_obj in obj.attachments: - if att_obj in prev_object: + for child in parent.attachments: + if child in prev_object: continue - if obj.attachments[att_obj].loose: + if parent.attachments[child].loose: + parent_link = parent.attachments[child].parent_link # Updates the attachment transformation and constraint if the # attachment is loose, instead of updating the position of all attached objects - link_to_object = ( - obj._calculate_transform_from_other_object_base_to_this_object_link(att_obj, - obj.attachments[att_obj].parent_link)) - link_id = obj.get_link_id(obj.attachments[att_obj].parent_link) if obj.attachments[att_obj].parent_link else -1 - obj.attachments[att_obj].transform_from_child_base_to_parent_link = link_to_object - att_obj.attachments[obj].transform_from_child_base_to_parent_link = link_to_object.invert() - self.remove_constraint(obj.cids[att_obj]) - # TODO: Ask Jonas what is the benefit of joint axis in a fixed joint. - cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], - link_to_object.translation_as_list(), - [0, 0, 0], link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - obj.cids[att_obj] = cid - att_obj.cids[obj] = cid + + # Update the attachment transformation + # link_to_object = ( + # parent._calculate_transform_from_other_object_base_to_this_object_link(child, parent_link)) + # link_id = parent.get_link_id(parent.attachments[child].parent_link) if parent.attachments[child].parent_link else -1 + # parent.attachments[child].transform_from_child_base_to_parent_link = link_to_object + # child.attachments[parent].transform_from_child_base_to_parent_link = link_to_object.invert() + + # Update the constraint + self.remove_constraint(parent.cids[child]) + constraint_id = self.add_fixed_constraint_between_parent_link_and_child_base(parent, child, parent_link) + # cid = p.createConstraint(parent.id, link_id, child.id, -1, p.JOINT_FIXED, [0, 0, 0], + # link_to_object.translation_as_list(), + # [0, 0, 0], link_to_object.rotation_as_list(), + # physicsClientId=self.client_id) + parent.cids[child] = constraint_id + child.cids[parent] = constraint_id else: - link_to_object = obj.attachments[att_obj][0] + link_to_object = parent.attachments[child].transform_from_child_base_to_parent_link - world_to_object = obj.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), + world_to_object = parent.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") + p.resetBasePositionAndOrientation(child.id, world_to_object.position_as_list(), world_to_object.orientation_as_list(), physicsClientId=self.client_id) - att_obj._current_pose = world_to_object - self._set_attached_objects(att_obj, prev_object + [obj]) + child._current_pose = world_to_object + self._set_attached_objects(child, prev_object + [parent]) def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ @@ -868,7 +881,7 @@ def add_constraint(self, constraint: Constraint) -> int: constraint.child_obj_id, constraint.child_link_id, constraint.joint_type, - constraint.joint_axis, + constraint.joint_axis_in_child_link_frame, constraint.joint_frame_position_wrt_parent_origin, constraint.joint_frame_position_wrt_child_origin, constraint.joint_frame_orientation_wrt_parent_origin, @@ -879,11 +892,11 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): p.removeConstraint(constraint_id, physicsClientId=self.client_id) - def attach_objects(self, - parent_obj: Object, - child_obj: Object, - parent_link: Optional[str] = None, - loose: Optional[bool] = False) -> None: + def attach_child_object_base_to_parent_object_link(self, + parent_obj: Object, + child_obj: Object, + parent_link: Optional[str] = None, + loose: Optional[bool] = False) -> None: """ Attaches another object to this object. This is done by saving the transformation between the given link, if there is one, and @@ -1855,7 +1868,7 @@ def attach(self, obj: Object, link: Optional[str] = None, loose: Optional[bool] :param link: The link of this object to which the other object should be :param loose: If the attachment should be a loose attachment. """ - self.world.attach_objects(self, obj, link, loose) + self.world.attach_child_object_base_to_parent_object_link(self, obj, link, loose) def detach(self, obj: Object) -> None: """ @@ -2045,7 +2058,7 @@ def get_joint_id(self, name: str) -> int: def get_link_id(self, name: str) -> int: """ - Returns a unique id for a link name. As used by PyBullet. + Returns a unique id for a link name. If the name is None return -1. :param name: The link name :return: The unique id @@ -2054,9 +2067,9 @@ def get_link_id(self, name: str) -> int: def get_link_by_id(self, id: int) -> str: """ - Returns the name of a link for a given unique PyBullet id + Returns the name of a link for a given unique link id - :param id: PyBullet id for link + :param id: id for link :return: The link name """ return dict(zip(self.links.values(), self.links.keys()))[id] From 3b365a865e1206f93df28dec3b173892304f1351 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 8 Dec 2023 20:13:13 +0100 Subject: [PATCH 008/195] [WorldAbstractClass] Updated local transformer class to not depend on Object Class (still need to remove world dependency if needed), The attachment refactoring still needs to be completed. --- src/pycram/designator.py | 2 +- src/pycram/designators/action_designator.py | 2 +- src/pycram/local_transformer.py | 99 +++--------- .../process_modules/boxy_process_modules.py | 2 +- .../process_modules/donbot_process_modules.py | 2 +- src/pycram/world.py | 141 +++++------------- 6 files changed, 60 insertions(+), 188 deletions(-) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index e902df6e4..289ebe498 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -690,7 +690,7 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: :return: The adjusted grasp pose """ lt = LocalTransformer() - pose_in_object = lt.transform_pose_to_object_base_frame(pose, self.bullet_world_object) + pose_in_object = lt.transform_pose_to_target_frame(pose, self.bullet_world_object.tf_frame) special_knowledge = [] # Initialize as an empty list if self.type in SPECIAL_KNOWLEDGE: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 5f1a8c5cc..2e7e4f2db 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -310,7 +310,7 @@ def perform(self) -> None: # oTm = Object Pose in Frame map oTm = object.get_pose() # Transform the object pose to the object frame, basically the origin of the object frame - mTo = object.local_transformer.transform_pose_to_object_base_frame(oTm, object) + mTo = object.local_transformer.transform_pose_to_target_frame(oTm, object.tf_frame) # Adjust the pose according to the special knowledge of the object designator adjusted_pose = self.object_designator.special_knowledge_adjustment_pose(self.grasp, mTo) # Transform the adjusted pose to the map frame diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 23bcb3cdc..5570f10af 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -1,23 +1,16 @@ import sys import logging -import tf - if 'world' in sys.modules: logging.warning("(publisher) Make sure that you are not loading this module from pycram.world.") -import rospkg import rospy -import atexit -from threading import Thread, currentThread -from tf import TransformerROS, transformations -from rospy import Duration, logerr, Rate, is_shutdown -from urdf_parser_py.urdf import URDF +from tf import TransformerROS +from rospy import Duration from geometry_msgs.msg import TransformStamped from .pose import Pose, Transform -from .robot_descriptions import robot_description -from typing import List, Optional, Tuple, Union, Callable +from typing import List, Optional, Union, Iterable class LocalTransformer(TransformerROS): @@ -47,7 +40,7 @@ def __init__(self): if self._initialized: return super().__init__(interpolate=True, cache_time=Duration(10)) - # TF tf_stampeds and static_tf_stampeds of the Robot in the BulletWorld: + # TF tf_stampeds and static_tf_stampeds of the Robot in the World: # These are initialized with the function init_transforms_from_urdf and are # used to update the local transformer with the function update_local_transformer_from_btr self.tf_stampeds: List[TransformStamped] = [] @@ -60,14 +53,6 @@ def __init__(self): # If the singelton was already initialized self._initialized = True - def update_objects_for_current_world(self) -> None: - """ - Updates transformations for all objects that are currently in :py:attr:`~pycram.world.World.current_world` - """ - curr_time = rospy.Time.now() - for obj in list(self.world.current_bullet_world.objects): - self.update_transforms_for_object(obj, curr_time) - def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union[Pose, None]: """ Transforms a given pose to the target frame. @@ -76,7 +61,7 @@ def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union :param target_frame: Name of the TF frame into which the Pose should be transformed :return: A transformed pose in the target frame """ - self.update_objects_for_current_world() + self.world.update_transforms_for_objects_in_current_world() copy_pose = pose.copy() copy_pose.header.stamp = rospy.Time(0) if not self.canTransform(target_frame, pose.frame, rospy.Time(0)): @@ -91,74 +76,28 @@ def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union return Pose(*copy_pose.to_list(), frame=new_pose.header.frame_id) - def transform_pose_to_object_base_frame(self, pose: Pose, world_object: 'world.Object') -> Union[Pose, None]: - """ - Transforms the given pose to the base frame of the given BulletWorld object. - - :param pose: Pose that should be transformed - :param world_object: World Object with frame to which the pose should be transformed - :return: The new pose transformed to the base coordinate frame of the object - """ - return self.transform_pose_to_target_frame(pose, world_object.tf_frame) - - def transform_pose_to_object_link_frame(self, pose: Pose, world_object: 'world.Object', link_name: str) -> Union[Pose, None]: - """ - Transforms the given pose to the link frame of the given BulletWorld object. - - :param pose: Pose that should be transformed - :param world_object: World Object with frame to which the pose should be transformed - :param link_name: Name of the link of the object to which the pose should be transformed - :return: The new pose transformed to the link coordinate frame of the object - """ - target_frame = world_object.get_link_tf_frame(link_name) - return self.transform_pose_to_target_frame(pose, target_frame) - - def transform_to_object_frame(self, pose: Pose, - world_object: 'world.Object', link_name: str = None) -> Union[Pose, None]: - """ - Transforms the given pose to the coordinate frame of the given BulletWorld object. If no link name is given the - base frame of the Object is used, otherwise the link frame is used as target for the transformation. - - :param pose: Pose that should be transformed - :param world_object: World Object in which frame the pose should be transformed - :param link_name: A link of the World Object which will be used as target coordinate frame instead - :return: The new pose the in coordinate frame of the object + def lookup_transform_from_source_to_target_frame(self, source_frame: str, target_frame: str, + time: Optional[rospy.rostime.Time] = None) -> Transform: """ - if link_name: - target_frame = world_object.get_link_tf_frame(link_name) - else: - target_frame = world_object.tf_frame - return self.transform_pose_to_target_frame(pose, target_frame) - - def tf_transform(self, source_frame: str, target_frame: str, - time: Optional[rospy.rostime.Time] = None) -> Transform: + Look up for the latest known transform that transforms a point from source frame to target frame. + If no time is given the last common time between the two frames is used. + :param time: Time at which the transform should be looked up """ - Returns the latest known transform between the 'source_frame' and 'target_frame'. If no time is given the last - common time between the two frames is used. - - :param source_frame: Source frame of the transform - :param target_frame: Target frame of the transform - :param time: Time at which the transform should be - :return: - """ - self.update_objects_for_current_world() + self.world.update_transforms_for_objects_in_current_world() tf_time = time if time else self.getLatestCommonTime(source_frame, target_frame) translation, rotation = self.lookupTransform(source_frame, target_frame, tf_time) return Transform(translation, rotation, source_frame, target_frame) - def update_transforms_for_object(self, world_object: 'world.Object', time: rospy.Time = None) -> None: + def update_transforms(self, transforms: Iterable[Transform], time: rospy.Time = None) -> None: """ - Updates local transforms for a Bullet Object, this includes the base as well as all links - - :param world_object: Object for which the Transforms should be updated - :param time: a specific time that should be used + Updates transforms by updating the time stamps of the header of each transform. If no time is given the current + time is used. """ time = time if time else rospy.Time.now() - for transform in world_object._current_link_transforms.values(): + for transform in transforms: transform.header.stamp = time self.setTransform(transform) - def get_all_frames(self) -> List[str]: """ Returns all know coordinate frames as a list with human-readable entries. @@ -171,12 +110,8 @@ def get_all_frames(self) -> List[str]: def transformPose(self, target_frame, ps) -> Pose: """ - Alias for :func:`~LocalTransformer.transform_pose` to avoid confusion since a similar method exists in the - super class. - - :param target_frame: Frame into which the pose should be transformer - :param ps: Pose that should be transformed - :return: Input pose in the target_frame + Alias for :func:`~LocalTransformer.transform_pose_to_target_frame` to avoid confusion since a similar method + exists in the super class. """ return self.transform_pose_to_target_frame(ps, target_frame) diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index f8c3e5d17..45a163e84 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -156,7 +156,7 @@ def _execute(self, desig): neck_base_frame = local_tf.projection_namespace + '/' + robot_description.chains["neck"].base_link if type(solutions['target']) is str: target = local_tf.projection_namespace + '/' + solutions['target'] - pose_in_neck_base = local_tf.tf_transform(neck_base_frame, target) + pose_in_neck_base = local_tf.lookup_transform_from_source_to_target_frame(neck_base_frame, target) elif helper_deprecated.is_list_pose(solutions['target']) or helper_deprecated.is_list_position(solutions['target']): pose = helper_deprecated.ensure_pose(solutions['target']) pose_in_neck_base = local_tf.tf_pose_transform(local_tf.map_frame, neck_base_frame, pose) diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 44db2771f..81e12caa1 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -135,7 +135,7 @@ def _execute(self, desig): target = local_transformer.projection_namespace + '/' + solutions['target'] if \ local_transformer.projection_namespace else \ solutions['target'] - pose_in_neck_base = local_transformer.tf_transform(neck_base_frame, target) + pose_in_neck_base = local_transformer.lookup_transform_from_source_to_target_frame(neck_base_frame, target) elif helper_deprecated.is_list_pose(solutions['target']) or helper_deprecated.is_list_position(solutions['target']): pose = helper_deprecated.ensure_pose(solutions['target']) pose_in_neck_base = local_transformer.tf_pose_transform(local_transformer.map_frame, neck_base_frame, pose) diff --git a/src/pycram/world.py b/src/pycram/world.py index 9dfffabc5..531923e1d 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -53,7 +53,8 @@ class Attachment: def __init__(self, parent_object: Object, child_object: Object, - parent_link: Optional[str] = None, + parent_link: str, + child_link: str, bidirectional: Optional[bool] = False): """ Creates an attachment between the parent object and the child object. @@ -61,16 +62,12 @@ def __init__(self, self.parent_object = parent_object self.child_object = child_object self.parent_link = parent_link - self.child_link = None + self.child_link = child_link self.bidirectional = bidirectional self.child_base_to_parent_link_transform = self._calculate_transforms() def _calculate_transforms(self): - # TODO: need to handle inverse case where there is a child link but no parent link - if self.parent_link is None: - return self.parent_object._calculate_transform_from_other_object_base_to_this_object_base(self.child_object) - else: - return self.parent_object._calculate_transform_from_other_object_base_to_this_object_link(self.child_object, + return self.parent_object._calculate_transform_from_other_object_base_to_this_object_link(self.child_object, self.parent_link) def update_transforms(self): @@ -797,6 +794,15 @@ def reset_bullet_world(self) -> None: obj.set_positions_of_all_joints(dict(zip(joint_names, joint_poses))) obj.set_pose(obj.original_pose) + def update_transforms_for_objects_in_current_world(self) -> None: + """ + Updates transformations for all objects that are currently in :py:attr:`~pycram.world.World.current_world`. + """ + curr_time = rospy.Time.now() + for obj in list(self.current_world.objects): + obj._update_link_transforms(curr_time) + + class BulletWorld(World): # Check is for sphinx autoAPI to be able to work in a CI workflow @@ -892,39 +898,6 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): p.removeConstraint(constraint_id, physicsClientId=self.client_id) - def attach_child_object_base_to_parent_object_link(self, - parent_obj: Object, - child_obj: Object, - parent_link: Optional[str] = None, - loose: Optional[bool] = False) -> None: - """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a constraint of pybullet will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. - For example, if the parent object moves, the child object will also move, but not the other way around. - - :param parent_obj: The parent object (jf loose, then this would not move when child moves) - :param child_obj: The child object - :param parent_link: The link of the parent object to which the child object should be attached - :param loose: If the attachment should be a loose attachment. - """ - link_id = parent_obj.get_link_id(parent_link) if parent_link else -1 - link_to_object = parent_obj._calculate_transform(child_obj, parent_link) - parent_obj.attachments[child_obj] = [link_to_object, parent_link, loose] - child_obj.attachments[parent_obj] = [link_to_object.invert(), None, False] - - cid = p.createConstraint(parent_obj.id, link_id, child_obj.id, -1, p.JOINT_FIXED, - [0, 1, 0], link_to_object.translation_as_list(), [0, 0, 0], - link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - parent_obj.cids[child_obj] = cid - child_obj.cids[parent_obj] = cid - self.attachment_event(parent_obj, [parent_obj, child_obj]) - def detach_objects(self, obj1: Object, obj2: Object) -> None: """ Detaches obj2 from obj1. This is done by @@ -944,44 +917,6 @@ def detach_objects(self, obj1: Object, obj2: Object) -> None: del obj2.cids[obj1] obj1.world.detachment_event(obj1, [obj1, obj2]) - def _set_attached_objects(self, obj, prev_object: List[Object]) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param prev_object: A list of Objects that were already moved, - these will be excluded to prevent loops in the update. - """ - for att_obj in obj.attachments: - if att_obj in prev_object: - continue - if obj.attachments[att_obj][2]: - # Updates the attachment transformation and constraint if the - # attachment is loose, instead of updating the position of all attached objects - link_to_object = obj._calculate_transform(att_obj, obj.attachments[att_obj][1]) - link_id = obj.get_link_id(obj.attachments[att_obj][1]) if obj.attachments[att_obj][1] else -1 - obj.attachments[att_obj][0] = link_to_object - att_obj.attachments[obj][0] = link_to_object.invert() - p.removeConstraint(obj.cids[att_obj], physicsClientId=self.client_id) - cid = p.createConstraint(obj.id, link_id, att_obj.id, -1, p.JOINT_FIXED, [0, 0, 0], - link_to_object.translation_as_list(), - [0, 0, 0], link_to_object.rotation_as_list(), - physicsClientId=self.client_id) - obj.cids[att_obj] = cid - att_obj.cids[obj] = cid - else: - link_to_object = obj.attachments[att_obj][0] - - world_to_object = obj.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(att_obj.id, world_to_object.position_as_list(), - world_to_object.orientation_as_list(), - physicsClientId=self.client_id) - att_obj._current_pose = world_to_object - self._set_attached_objects(att_obj, prev_object + [obj]) - def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ Get the joint limits of an articulated object @@ -1816,14 +1751,14 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self.links[self.urdf_object.get_root()] = -1 self._current_pose = pose_in_map - self._current_link_poses = {} - self._current_link_transforms = {} + self._current_link_poses: Dict[str, Pose] = {} + self._current_link_transforms: Dict[str, Transform] = {} self._current_joints_positions = {} self._init_current_positions_of_joint() self._update_link_poses() self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) - self.local_transformer.update_transforms_for_object(self) + self._update_link_transforms() self.link_to_geometry = self._get_geometry_for_link() self.world.objects.append(self) @@ -1967,29 +1902,22 @@ def _set_attached_objects(self, prev_object: List[Object]) -> None: self.world._set_attached_objects(self, prev_object) def _calculate_transform_from_other_object_base_to_this_object_base(self, other_object: Object): - pose_wrt_this_object_base = self.local_transformer.transform_pose_to_object_base_frame(other_object.pose, self) + pose_wrt_this_object_base = self.local_transformer.transform_pose_to_target_frame(other_object.pose, + self.tf_frame) return Transform.from_pose_and_child_frame(pose_wrt_this_object_base, other_object.tf_frame) def _calculate_transform_from_other_object_base_to_this_object_link(self, other_object: Object, this_object_link_name: str): - pose_wrt_this_object_link = self.local_transformer.transform_pose_to_object_link_frame(other_object.pose, - self, - this_object_link_name) + pose_wrt_this_object_link = self.transform_pose_to_link_frame(other_object.pose, this_object_link_name) return Transform.from_pose_and_child_frame(pose_wrt_this_object_link, other_object.tf_frame) - def _calculate_transform(self, obj: Object, link: str = None) -> Transform: + def transform_pose_to_link_frame(self, pose: Pose, link_name: str) -> Union[Pose, None]: """ - Calculates the transformation between another object and the given - link of this object. If no link is provided then the base position will be used. - - :param obj: The other object for which the transformation should be calculated - :param link: The optional link name - :return: The transformation from the link (or base position) to the other objects base position + :return: The new pose transformed to be relative to the link coordinate frame. """ - transform = self.local_transformer.transform_to_object_frame(obj.pose, self, link) - - return Transform(transform.position_as_list(), transform.orientation_as_list(), transform.frame, obj.tf_frame) + target_frame = self.get_link_tf_frame(link_name) + return self.local_transformer.transform_pose_to_target_frame(pose, target_frame) def set_position(self, position: Union[Pose, Point], base=False) -> None: """ @@ -2083,16 +2011,22 @@ def get_joint_by_id(self, joint_id: int) -> str: """ return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] - def get_link_relative_to_other_link(self, source_frame: str, target_frame: str) -> Pose: + def get_link_pose_relative_to_other_link(self, child_link_name: str, parent_link_name: str) -> Pose: """ - Calculates the position of a link in the coordinate frame of another link. - - :param source_frame: The name of the source frame - :param target_frame: The name of the target frame + Calculates the pose of a link (child_link) in the coordinate frame of another link (parent_link). :return: The pose of the source frame in the target frame """ - source_pose = self.get_link_pose(source_frame) - return self.local_transformer.transform_to_object_frame(source_pose, self, target_frame) + child_link_pose = self.get_link_pose(child_link_name) + parent_link_frame = self.get_link_tf_frame(parent_link_name) + return self.local_transformer.transform_pose_to_target_frame(child_link_pose, parent_link_frame) + + def get_transform_between_two_links(self, source_link_name: str, target_link_name: str) -> Transform: + """ + Calculates the transform from source link frame to target link frame. + """ + source_tf_frame = self.get_link_tf_frame(source_link_name) + target_tf_frame = self.get_link_tf_frame(target_link_name) + return self.local_transformer.lookup_transform_from_source_to_target_frame(source_tf_frame, target_tf_frame) def get_link_position(self, name: str) -> Point: """ @@ -2365,6 +2299,9 @@ def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: link_to_geometry[link] = link_obj.collision.geometry return link_to_geometry + def _update_link_transforms(self, transform_time: Optional[rospy.Time] = None): + self.local_transformer.update_transforms(self._current_link_transforms.values(), transform_time) + def _update_link_poses(self) -> None: """ Updates the cached poses and transforms for each link of this Object From bac3a4b5d23d03103f7fe523e0f5ad84bdc522e0 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sat, 9 Dec 2023 20:24:59 +0100 Subject: [PATCH 009/195] [RefactoringAttachments] Improved attachment class to handle bidirectional and unidirectional attachments. --- src/pycram/local_transformer.py | 8 +- src/pycram/world.py | 307 +++++++++++++++++--------------- 2 files changed, 169 insertions(+), 146 deletions(-) diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 5570f10af..05d149277 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -43,11 +43,13 @@ def __init__(self): # TF tf_stampeds and static_tf_stampeds of the Robot in the World: # These are initialized with the function init_transforms_from_urdf and are # used to update the local transformer with the function update_local_transformer_from_btr + # TODO: Ask Jonas if this is still needed self.tf_stampeds: List[TransformStamped] = [] self.static_tf_stampeds: List[TransformStamped] = [] # Since this file can't import world.py this holds the reference to the current_bullet_world self.world = None + # TODO: Ask Jonas if this is still needed self.prospection_world = None # If the singelton was already initialized @@ -55,7 +57,7 @@ def __init__(self): def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union[Pose, None]: """ - Transforms a given pose to the target frame. + Transforms a given pose to the target frame after updating the transforms for all objects in the current world. :param pose: Pose that should be transformed :param target_frame: Name of the TF frame into which the Pose should be transformed @@ -79,8 +81,8 @@ def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union def lookup_transform_from_source_to_target_frame(self, source_frame: str, target_frame: str, time: Optional[rospy.rostime.Time] = None) -> Transform: """ - Look up for the latest known transform that transforms a point from source frame to target frame. - If no time is given the last common time between the two frames is used. + Update the transforms for all world objects then Look up for the latest known transform that transforms a point + from source frame to target frame. If no time is given the last common time between the two frames is used. :param time: Time at which the transform should be looked up """ self.world.update_transforms_for_objects_in_current_world() diff --git a/src/pycram/world.py b/src/pycram/world.py index 531923e1d..a587bc09d 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -35,53 +35,92 @@ from dataclasses import dataclass -@dataclass -class Constraint: - parent_obj_id: int - parent_link_id: int - child_obj_id: int - child_link_id: int - joint_type: JointType - joint_axis_in_child_link_frame: List[int] - joint_frame_position_wrt_parent_origin: List[float] - joint_frame_position_wrt_child_origin: List[float] - joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None - joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None - - class Attachment: def __init__(self, parent_object: Object, child_object: Object, - parent_link: str, - child_link: str, + constraint_id: int, + parent_link_id: Optional[int] = -1, # -1 means base link + child_link_id: Optional[int] = -1, bidirectional: Optional[bool] = False): """ Creates an attachment between the parent object and the child object. """ self.parent_object = parent_object self.child_object = child_object - self.parent_link = parent_link - self.child_link = child_link + self.constraint_id = constraint_id + self.parent_link_id = parent_link_id + self.child_link_id = child_link_id self.bidirectional = bidirectional - self.child_base_to_parent_link_transform = self._calculate_transforms() + self.child_to_parent_transform = self.calculate_transforms() + self._loose = False and not self.bidirectional - def _calculate_transforms(self): - return self.parent_object._calculate_transform_from_other_object_base_to_this_object_link(self.child_object, - self.parent_link) + def update_attachment(self): + self.update_transforms() + self.update_constraint() + self.update_objects_constraints_collection() + self.update_objects_attachments_collection() def update_transforms(self): - self.child_base_to_parent_link_transform = self._calculate_transforms() + self.child_to_parent_transform = self.calculate_transforms() - def get_inverse(self): - attachment = Attachment(self.child_object, self.parent_object, None, self.bidirectional) - attachment.child_link = self.parent_link - return attachment + def update_constraint(self): + self.parent_object.world.remove_constraint(self.constraint_id) + self.constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, + self.child_object.id, + self.child_to_parent_transform, + self.parent_link_id, + self.child_link_id) - def add_to_objects_attachments_collection(self): + def update_objects_constraints_collection(self): + self.parent_object.cids[self.child_object] = self.constraint_id + self.child_object.cids[self.parent_object] = self.constraint_id + + def update_objects_attachments_collection(self): self.parent_object.attachments[self.child_object] = self self.child_object.attachments[self.parent_object] = self.get_inverse() + def get_inverse(self): + attachment = Attachment(self.child_object, self.parent_object, self.constraint_id, self.child_link_id, + self.parent_link_id, self.bidirectional) + attachment.loose = False if self.loose else True + return attachment + + def calculate_transforms(self): + return self.parent_object.get_transform_between_two_links(self.parent_link_id, self.child_link_id) + + @property + def loose(self) -> bool: + """ + If true, then the child object will not move when parent moves. + """ + return self._loose + + @loose.setter + def loose(self, loose: bool): + self._loose = loose and not self.bidirectional + + @property + def is_reversed(self) -> bool: + """ + If true means that when child moves, parent moves not the other way around. + """ + return self.loose + + +@dataclass +class Constraint: + parent_obj_id: int + parent_link_id: int + child_obj_id: int + child_link_id: int + joint_type: JointType + joint_axis_in_child_link_frame: List[int] + joint_frame_position_wrt_parent_origin: List[float] + joint_frame_position_wrt_child_origin: List[float] + joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None + joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None + class World(ABC): """ @@ -119,7 +158,7 @@ def __init__(self, mode: str, is_prospection_world: bool): self.objects: List[Object] = [] self.client_id: int = -1 self.mode: str = mode - self._initialize_events() + self._init_events() World.current_world = self if World.current_world is None else World.current_world self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} self.local_transformer = LocalTransformer() @@ -133,6 +172,11 @@ def __init__(self, mode: str, is_prospection_world: bool): self._init_and_sync_prospection_world() self._update_local_transformer_worlds() + def _init_events(self): + self.detachment_event: Event = Event() + self.attachment_event: Event = Event() + self.manipulation_event: Event = Event() + def _init_and_sync_prospection_world(self): self._init_prospection_world() self._sync_prospection_world() @@ -148,13 +192,8 @@ def _sync_prospection_world(self): self.world_sync: WorldSync = WorldSync(self, self.prospection_world) self.world_sync.start() - def _initialize_events(self): - self.detachment_event: Event = Event() - self.attachment_event: Event = Event() - self.manipulation_event: Event = Event() - @abstractmethod - def load_urdf_with_pose_and_get_world_object_id(self, path: str, pose: Pose) -> int: + def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: pass def get_objects_by_name(self, name: str) -> List[Object]: @@ -193,67 +232,37 @@ def remove_object(self, obj_id: int) -> None: """ pass - @abstractmethod - def add_constraint(self, constraint: Constraint) -> int: - """ - Add a constraint between two objects so that they become attached - """ - pass - - @abstractmethod - def remove_constraint(self, constraint_id): - pass - - def add_fixed_constraint_between_parent_link_and_child_base(self, - parent_object: Object, - child_object: Object, - child_base_wrt_parent_link: Transform, - parent_link: Optional[str] = None) -> int: + def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: """ - Creates a fixed joint constraint between the given parent link and the base of the child object, - the joint frame will be at the origin of the parent link and the child base, and would have the same orientation - as the child base frame. + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. - returns the constraint id + :param prev_object: A list of Objects that were already moved, + these will be excluded to prevent loops in the update. """ + for child in parent.attachments: + if child in prev_object: + continue + if not parent.attachments[child].bidirectional: + parent.attachments[child].update_attachment() + else: + link_to_object = parent.attachments[child].child_to_parent_transform - constraint = Constraint(parent_obj_id=parent_object.id, - parent_link_id=parent_object.get_link_id(parent_link) if parent_link else -1, - child_obj_id=child_object.id, - child_link_id=-1, # -1 means use the base link - joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=[0, 0, 0], - joint_frame_position_wrt_parent_origin=child_base_wrt_parent_link.translation_as_list(), - joint_frame_position_wrt_child_origin=[0, 0, 0], - joint_frame_orientation_wrt_parent_origin=child_base_wrt_parent_link.rotation_as_list(), - ) - constraint_id = self.add_constraint(constraint) - return constraint_id + world_to_object = parent.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") + p.resetBasePositionAndOrientation(child.id, world_to_object.position_as_list(), + world_to_object.orientation_as_list(), + physicsClientId=self.client_id) + child._current_pose = world_to_object + self._set_attached_objects(child, prev_object + [parent]) def attach_child_object_base_to_parent_object_base(self, parent_obj: Object, child_obj: Object, loose: Optional[bool] = False) -> None: pass # TODO: implement this function - def _create_attachment_and_constraint(self, - parent_object: Object, - child_object: Object, - parent_link: str, - loose: Optional[bool] = False) -> None: - - # Add the attachment to the attachment dictionary of both objects - attachment = Attachment(parent_object, child_object, parent_link, loose) - - # Create the constraint - constraint_id = self.add_fixed_constraint_between_parent_link_and_child_base(parent_object, - child_object, - attachment.transform_from_child_base_to_parent_link, - parent_link) - - # Update the attachment and constraint dictionary in both objects - parent_object.cids[child_object] = constraint_id - child_object.cids[parent_object] = constraint_id - def attach_child_object_base_to_parent_object_link(self, parent_obj: Object, child_obj: Object, @@ -278,6 +287,64 @@ def attach_child_object_base_to_parent_object_link(self, self._create_attachment_and_constraint(parent_obj, child_obj, parent_link, loose) self.attachment_event(parent_obj, [parent_obj, child_obj]) + def _create_attachment_and_constraint(self, + parent_object: Object, + child_object: Object, + parent_link_id: Optional[int] = -1, + child_link_id: Optional[int] = -1, + loose: Optional[bool] = False) -> None: + + # Add the attachment to the attachment dictionary of both objects + attachment = Attachment(parent_object, child_object, parent_link_id, loose) + + # Create the constraint + constraint_id = self.add_fixed_constraint(parent_object.id, + child_object.id, + attachment.child_to_parent_transform, + parent_object.get_link_id(parent_link_id)) + + # Update the attachment and constraint dictionary in both objects + parent_object.cids[child_object] = constraint_id + child_object.cids[parent_object] = constraint_id + + def add_fixed_constraint(self, + parent_object_id: int, + child_object_id: int, + child_to_parent_transform: Transform, + parent_link_id: Optional[int] = -1, + child_link_id: Optional[int] = -1) -> int: + """ + Creates a fixed joint constraint between the given parent and child links, + the joint frame will be at the origin of the child link, and would have the same orientation + as the child base frame. if no link is given, the base link will be used (id = -1). + + returns the constraint id + """ + # -1 in link id means use the base link of the object + constraint = Constraint(parent_obj_id=parent_object_id, + parent_link_id=parent_link_id, + child_obj_id=child_object_id, + child_link_id=child_link_id, + joint_type=JointType.FIXED, + joint_axis_in_child_link_frame=[0, 0, 0], + joint_frame_position_wrt_parent_origin=child_to_parent_transform.translation_as_list(), + joint_frame_position_wrt_child_origin=[0, 0, 0], + joint_frame_orientation_wrt_parent_origin=child_to_parent_transform.rotation_as_list(), + ) + constraint_id = self.add_constraint(constraint) + return constraint_id + + @abstractmethod + def add_constraint(self, constraint: Constraint) -> int: + """ + Add a constraint between two objects so that they become attached + """ + pass + + @abstractmethod + def remove_constraint(self, constraint_id): + pass + def detach_objects(self, obj1: Object, obj2: Object) -> None: """ Detaches obj2 from obj1. This is done by @@ -297,51 +364,6 @@ def detach_objects(self, obj1: Object, obj2: Object) -> None: del obj2.cids[obj1] obj1.world.detachment_event(obj1, [obj1, obj2]) - def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param prev_object: A list of Objects that were already moved, - these will be excluded to prevent loops in the update. - """ - for child in parent.attachments: - if child in prev_object: - continue - if parent.attachments[child].loose: - parent_link = parent.attachments[child].parent_link - # Updates the attachment transformation and constraint if the - # attachment is loose, instead of updating the position of all attached objects - - # Update the attachment transformation - # link_to_object = ( - # parent._calculate_transform_from_other_object_base_to_this_object_link(child, parent_link)) - # link_id = parent.get_link_id(parent.attachments[child].parent_link) if parent.attachments[child].parent_link else -1 - # parent.attachments[child].transform_from_child_base_to_parent_link = link_to_object - # child.attachments[parent].transform_from_child_base_to_parent_link = link_to_object.invert() - - # Update the constraint - self.remove_constraint(parent.cids[child]) - constraint_id = self.add_fixed_constraint_between_parent_link_and_child_base(parent, child, parent_link) - # cid = p.createConstraint(parent.id, link_id, child.id, -1, p.JOINT_FIXED, [0, 0, 0], - # link_to_object.translation_as_list(), - # [0, 0, 0], link_to_object.rotation_as_list(), - # physicsClientId=self.client_id) - parent.cids[child] = constraint_id - child.cids[parent] = constraint_id - else: - link_to_object = parent.attachments[child].transform_from_child_base_to_parent_link - - world_to_object = parent.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(child.id, world_to_object.position_as_list(), - world_to_object.orientation_as_list(), - physicsClientId=self.client_id) - child._current_pose = world_to_object - self._set_attached_objects(child, prev_object + [parent]) - def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ Get the joint limits of an articulated object @@ -837,7 +859,7 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - def load_urdf_with_pose_and_get_world_object_id(self, path: str, pose: Pose) -> int: + def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: return p.loadURDF(path, basePosition=pose.position_as_list(), baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) @@ -1906,12 +1928,6 @@ def _calculate_transform_from_other_object_base_to_this_object_base(self, other_ self.tf_frame) return Transform.from_pose_and_child_frame(pose_wrt_this_object_base, other_object.tf_frame) - def _calculate_transform_from_other_object_base_to_this_object_link(self, - other_object: Object, - this_object_link_name: str): - pose_wrt_this_object_link = self.transform_pose_to_link_frame(other_object.pose, this_object_link_name) - return Transform.from_pose_and_child_frame(pose_wrt_this_object_link, other_object.tf_frame) - def transform_pose_to_link_frame(self, pose: Pose, link_name: str) -> Union[Pose, None]: """ :return: The new pose transformed to be relative to the link coordinate frame. @@ -2020,12 +2036,12 @@ def get_link_pose_relative_to_other_link(self, child_link_name: str, parent_link parent_link_frame = self.get_link_tf_frame(parent_link_name) return self.local_transformer.transform_pose_to_target_frame(child_link_pose, parent_link_frame) - def get_transform_between_two_links(self, source_link_name: str, target_link_name: str) -> Transform: + def get_transform_between_two_links(self, source_link_id: int, target_link_id: int) -> Transform: """ Calculates the transform from source link frame to target link frame. """ - source_tf_frame = self.get_link_tf_frame(source_link_name) - target_tf_frame = self.get_link_tf_frame(target_link_name) + source_tf_frame = self.get_link_tf_frame_by_id(source_link_id) + target_tf_frame = self.get_link_tf_frame_by_id(target_link_id) return self.local_transformer.lookup_transform_from_source_to_target_frame(source_tf_frame, target_tf_frame) def get_link_position(self, name: str) -> Point: @@ -2056,7 +2072,9 @@ def get_link_pose(self, name: str) -> Pose: if name in self.links.keys() and self.links[name] == -1: return self.get_pose() return self._current_link_poses[name] - # return Pose(*p.getLinkState(self.id, self.links[name], physicsClientId=self.world.client_id)[4:6]) + + def get_link_pose_by_id(self, link_id: int) -> Pose: + return self.get_link_pose(self.get_link_by_id(link_id)) def set_joint_position(self, joint_name: str, joint_pose: float) -> None: """ @@ -2284,6 +2302,9 @@ def get_link_tf_frame(self, link_name: str) -> str: """ return self.tf_frame + "/" + link_name + def get_link_tf_frame_by_id(self, link_id: int) -> str: + return self.get_link_tf_frame(self.get_link_by_id(link_id)) + def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: """ Extracts the geometry information for each collision of each link and links them to the respective link. @@ -2436,7 +2457,7 @@ def _load_object(name: str, path = cach_dir + name + ".urdf" try: - obj = world.load_urdf_with_pose_and_get_world_object_id(path, Pose(position, orientation)) + obj = world.load_urdf_at_pose_and_get_object_id(path, Pose(position, orientation)) return obj, path except p.error as e: logging.error( From 5b61daa7f631c339e710c66ce018e2b6c3769534 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sat, 9 Dec 2023 23:30:51 +0100 Subject: [PATCH 010/195] [RefactoringAttachments] Improved attachment class, needs to better implement the inverse attachment (changes are not synced) --- src/pycram/world.py | 122 +++++++++++++++++++------------------------- 1 file changed, 53 insertions(+), 69 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index a587bc09d..1afe260c4 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -39,50 +39,55 @@ class Attachment: def __init__(self, parent_object: Object, child_object: Object, - constraint_id: int, parent_link_id: Optional[int] = -1, # -1 means base link child_link_id: Optional[int] = -1, - bidirectional: Optional[bool] = False): + bidirectional: Optional[bool] = False, + constraint_id: Optional[int] = None): """ Creates an attachment between the parent object and the child object. """ self.parent_object = parent_object self.child_object = child_object - self.constraint_id = constraint_id self.parent_link_id = parent_link_id self.child_link_id = child_link_id self.bidirectional = bidirectional self.child_to_parent_transform = self.calculate_transforms() self._loose = False and not self.bidirectional + self.constraint_id = self.update_constraint() if constraint_id is None else constraint_id def update_attachment(self): self.update_transforms() self.update_constraint() - self.update_objects_constraints_collection() self.update_objects_attachments_collection() def update_transforms(self): self.child_to_parent_transform = self.calculate_transforms() def update_constraint(self): - self.parent_object.world.remove_constraint(self.constraint_id) - self.constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, - self.child_object.id, - self.child_to_parent_transform, - self.parent_link_id, - self.child_link_id) - - def update_objects_constraints_collection(self): - self.parent_object.cids[self.child_object] = self.constraint_id - self.child_object.cids[self.parent_object] = self.constraint_id + if self.constraint_id is not None: + self.parent_object.world.remove_constraint(self.constraint_id) + self.constraint_id = self.add_fixed_constraint() + self.update_objects_constraints_collection() def update_objects_attachments_collection(self): self.parent_object.attachments[self.child_object] = self self.child_object.attachments[self.parent_object] = self.get_inverse() + def add_fixed_constraint(self): + constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, + self.child_object.id, + self.child_to_parent_transform, + self.parent_link_id, + self.child_link_id) + return constraint_id + + def update_objects_constraints_collection(self): + self.parent_object.cids[self.child_object] = self.constraint_id + self.child_object.cids[self.parent_object] = self.constraint_id + def get_inverse(self): - attachment = Attachment(self.child_object, self.parent_object, self.constraint_id, self.child_link_id, - self.parent_link_id, self.bidirectional) + attachment = Attachment(self.child_object, self.parent_object, self.child_link_id, + self.parent_link_id, self.bidirectional, self.constraint_id) attachment.loose = False if self.loose else True return attachment @@ -258,54 +263,22 @@ def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: child._current_pose = world_to_object self._set_attached_objects(child, prev_object + [parent]) - def attach_child_object_base_to_parent_object_base(self, parent_obj: Object, - child_obj: Object, - loose: Optional[bool] = False) -> None: - pass # TODO: implement this function - - def attach_child_object_base_to_parent_object_link(self, - parent_obj: Object, - child_obj: Object, - parent_link: Optional[str] = None, - loose: Optional[bool] = False) -> None: + def attach_objects(self, + parent_object: Object, + child_object: Object, + parent_link_id: Optional[int] = -1, + child_link_id: Optional[int] = -1, + bidirectional: Optional[bool] = True) -> None: """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a constraint will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. - For example, if the parent object moves, the child object will also move, but not the other way around. + Attaches two objects together by saving the current transformation between the links coordinate frames. + Furthermore, a constraint will be created so the attachment also works while in simulation. - :param parent_obj: The parent object (jf loose, then this would not move when child moves) - :param child_obj: The child object - :param parent_link: The link of the parent object to which the child object should be attached - :param loose: If the attachment should be a loose attachment. + :param bidirectional: If the parent should also follow the child. """ - self._create_attachment_and_constraint(parent_obj, child_obj, parent_link, loose) - self.attachment_event(parent_obj, [parent_obj, child_obj]) - - def _create_attachment_and_constraint(self, - parent_object: Object, - child_object: Object, - parent_link_id: Optional[int] = -1, - child_link_id: Optional[int] = -1, - loose: Optional[bool] = False) -> None: - # Add the attachment to the attachment dictionary of both objects - attachment = Attachment(parent_object, child_object, parent_link_id, loose) - - # Create the constraint - constraint_id = self.add_fixed_constraint(parent_object.id, - child_object.id, - attachment.child_to_parent_transform, - parent_object.get_link_id(parent_link_id)) - - # Update the attachment and constraint dictionary in both objects - parent_object.cids[child_object] = constraint_id - child_object.cids[parent_object] = constraint_id + Attachment(parent_object, child_object, parent_link_id, child_link_id, bidirectional) + self.attachment_event(parent_object, [parent_object, child_object]) def add_fixed_constraint(self, parent_object_id: int, @@ -315,8 +288,8 @@ def add_fixed_constraint(self, child_link_id: Optional[int] = -1) -> int: """ Creates a fixed joint constraint between the given parent and child links, - the joint frame will be at the origin of the child link, and would have the same orientation - as the child base frame. if no link is given, the base link will be used (id = -1). + the joint frame will be at the origin of the child link frame, and would have the same orientation + as the child link frame. if no link is given, the base link will be used (id = -1). returns the constraint id """ @@ -1810,7 +1783,11 @@ def remove(self) -> None: if World.robot == self: World.robot = None - def attach(self, obj: Object, link: Optional[str] = None, loose: Optional[bool] = False) -> None: + def attach(self, + child_object: Object, + parent_link: Optional[str] = None, + child_link: Optional[str] = None, + bidirectional: Optional[bool] = True) -> None: """ Attaches another object to this object. This is done by saving the transformation between the given link, if there is one, and @@ -1821,22 +1798,27 @@ def attach(self, obj: Object, link: Optional[str] = None, loose: Optional[bool] Loose attachments means that the attachment will only be one-directional. For example, if this object moves the other, attached, object will also move but not the other way around. - :param object: The other object that should be attached - :param link: The link of this object to which the other object should be - :param loose: If the attachment should be a loose attachment. + :param child_object: The other object that should be attached. + :param parent_link: The link name of this object. + :param child_link: The link name of the other object. + :param bidirectional: If the attachment should be a loose attachment. """ - self.world.attach_child_object_base_to_parent_object_link(self, obj, link, loose) + self.world.attach_objects(self, + child_object, + self.get_link_id(parent_link), + child_object.get_link_id(child_link), + bidirectional) - def detach(self, obj: Object) -> None: + def detach(self, child_object: Object) -> None: """ Detaches another object from this object. This is done by deleting the attachment from the attachments dictionary of both objects and deleting the constraint of pybullet. Afterward the detachment event of the corresponding World will be fired. - :param object: The object which should be detached + :param child_object: The object which should be detached """ - self.world.detach_objects(self, obj) + self.world.detach_objects(self, child_object) def detach_all(self) -> None: """ @@ -2007,6 +1989,8 @@ def get_link_id(self, name: str) -> int: :param name: The link name :return: The unique id """ + if name is None: + return -1 return self.links[name] def get_link_by_id(self, id: int) -> str: From 7fb3524c204d6bc259b3486e23f44293e00a7844 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sun, 10 Dec 2023 12:57:07 +0100 Subject: [PATCH 011/195] [AbstractWorld] Added a WorldState dataclass, Implemented saving and resotring of state, Implemented exiting the world and other methods. --- src/pycram/costmaps.py | 2 +- src/pycram/world.py | 703 +++++++++++++++++++++++------------------ 2 files changed, 395 insertions(+), 310 deletions(-) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 586758694..3d6f63451 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -732,7 +732,7 @@ def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: link_orientation_trans = link_orientation.to_transform(self.object.get_link_tf_frame(self.link)) inverse_orientation = link_orientation_trans.invert() shadow_obj.set_orientation(inverse_orientation.to_pose()) - return shadow_obj.get_AABB(self.link) + return shadow_obj.get_link_AABB(self.link) cmap = colors.ListedColormap(['white', 'black', 'green', 'red', 'blue']) diff --git a/src/pycram/world.py b/src/pycram/world.py index 1afe260c4..6e3d75b1c 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -127,6 +127,13 @@ class Constraint: joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None +@dataclass +class WorldState: + state_id: int + attachments: Dict[Object, Dict[Object, Attachment]] + constraint_ids: Dict[Object, Dict[Object, int]] + + class World(ABC): """ The World Class represents the physics Simulation and belief state. @@ -151,7 +158,7 @@ class World(ABC): Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ - def __init__(self, mode: str, is_prospection_world: bool): + def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: float): """ Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. @@ -177,6 +184,10 @@ def __init__(self, mode: str, is_prospection_world: bool): self._init_and_sync_prospection_world() self._update_local_transformer_worlds() + self.simulation_time_step = simulation_time_step + self.simulation_frequency = int(1/self.simulation_time_step) + self._saved_states: Dict[int, WorldState] = {} # Different states of the world indexed by int state id. + def _init_events(self): self.detachment_event: Event = Event() self.attachment_event: Event = Event() @@ -257,9 +268,9 @@ def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: link_to_object = parent.attachments[child].child_to_parent_transform world_to_object = parent.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") - p.resetBasePositionAndOrientation(child.id, world_to_object.position_as_list(), - world_to_object.orientation_as_list(), - physicsClientId=self.client_id) + self.reset_object_base_pose(child, + world_to_object.position_as_list(), + world_to_object.orientation_as_list()) child._current_pose = world_to_object self._set_attached_objects(child, prev_object + [parent]) @@ -314,10 +325,6 @@ def add_constraint(self, constraint: Constraint) -> int: """ pass - @abstractmethod - def remove_constraint(self, constraint_id): - pass - def detach_objects(self, obj1: Object, obj2: Object) -> None: """ Detaches obj2 from obj1. This is done by @@ -331,23 +338,50 @@ def detach_objects(self, obj1: Object, obj2: Object) -> None: del obj1.attachments[obj2] del obj2.attachments[obj1] - p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) + self.remove_constraint(obj1.cids[obj2]) del obj1.cids[obj2] del obj2.cids[obj1] + obj1.world.detachment_event(obj1, [obj1, obj2]) + @abstractmethod + def remove_constraint(self, constraint_id): + pass + def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ Get the joint limits of an articulated object - :param obj: The object - :param joint_name: The name of the joint + :param obj: The object. + :param joint_name: The name of the joint. :return: A tuple containing the upper and the lower limits of the joint. """ - up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] - return up_lim, low_lim + return self.get_object_joint_upper_limit(obj, joint_name), self.get_object_joint_lower_limit(obj, joint_name) + + @abstractmethod + def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: + """ + Get the joint upper limit of an articulated object + + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint upper limit as a float. + """ + pass + @abstractmethod + def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: + """ + Get the joint lower limit of an articulated object + + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint lower limit as a float. + """ + pass + + @abstractmethod def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ Returns the axis along which a joint is moving. The given joint_name has to be part of this object. @@ -356,8 +390,9 @@ def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: :param joint_name: Name of the joint for which the axis should be returned. :return: The axis a vector of xyz """ - return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + pass + @abstractmethod def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: """ Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. @@ -366,9 +401,9 @@ def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: :param joint_name: Joint name for which the type should be returned :return: The type of the joint """ - joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] - return JointType(joint_type) + pass + @abstractmethod def get_object_joint_position(self, obj: Object, joint_name: str) -> float: """ Get the state of a joint of an articulated object @@ -376,8 +411,9 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: :param obj: The object :param joint_name: The name of the joint """ - return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + pass + @abstractmethod def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: """ Get the pose of a link of an articulated object with respect to the world frame. @@ -386,18 +422,51 @@ def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List] :param obj: The object :param link_name: The name of the link """ - return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + pass + def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + """ + Simulates Physics in the World for a given amount of seconds. Usually this simulation is faster than real + time. By setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal + to real time. + + :param seconds: The amount of seconds that should be simulated. + :param real_time: If the simulation should happen in real time or faster. + """ + for i in range(0, int(seconds * self.simulation_frequency)): + self.step() + for objects, callback in self.coll_callbacks.items(): + contact_points = self.get_contact_points_between_two_objects(objects[0], objects[1]) + if contact_points != (): + callback[0]() + elif callback[1] is not None: # Call no collision callback + callback[1]() + if real_time: + # Simulation runs at 240 Hz + time.sleep(self.simulation_time_step) + + @abstractmethod def get_object_contact_points(self, obj: Object) -> List: """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ + Returns a list of contact points of this Object with other Objects. :param obj: The object. :return: A list of all contact points with other objects """ - return p.getContactPoints(obj.id) + pass + + @abstractmethod + def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: + """ + Returns a list of contact points between obj1 and obj2. + + :param obj1: The first object. + :param obj2: The second object. + :return: A list of all contact points between the two objects. + """ + pass + @abstractmethod def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: """ Get the ID of a joint in an articulated object. @@ -405,8 +474,9 @@ def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: :param obj: The object :param joint_idx: The index of the joint (would indicate order). """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + pass + @abstractmethod def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: """ Get the name of a joint in an articulated object. @@ -414,8 +484,9 @@ def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: :param obj: The object :param joint_idx: The index of the joint (would indicate order). """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + pass + @abstractmethod def get_object_link_name(self, obj: Object, link_idx: int) -> str: """ Get the name of a link in an articulated object. @@ -423,16 +494,18 @@ def get_object_link_name(self, obj: Object, link_idx: int) -> str: :param obj: The object :param link_idx: The index of the link (would indicate order). """ - return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + pass + @abstractmethod def get_object_number_of_joints(self, obj: Object) -> int: """ Get the number of joints of an articulated object :param obj: The object """ - return p.getNumJoints(obj.id, self.client_id) + pass + @abstractmethod def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -441,8 +514,9 @@ def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) :param joint_name: The name of the joint :param joint_pose: The new joint pose """ - p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + pass + @abstractmethod def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): """ Reset the world position and orientation of the base of the object instantaneously, @@ -452,13 +526,14 @@ def reset_object_base_pose(self, obj: Object, position: List[float], orientation :param position: The new position of the object as a vector of x,y,z :param orientation: The new orientation of the object as a quaternion of x,y,z,w """ - p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + pass + @abstractmethod def step(self): """ Step the world simulation using forward dynamics """ - p.stepSimulation(self.client_id) + pass def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): """ @@ -475,11 +550,23 @@ def set_object_color(self, obj: Object, color: List[float], link: Optional[str] # forms or if loaded from an .stl or .obj file if obj.links != {}: for link_id in obj.links.values(): - p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) + self.set_object_link_color(obj, link_id, color) else: - p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) + self.set_object_link_color(obj, -1, color) else: - p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) + self.set_object_link_color(obj, obj.links[link], color) + + @abstractmethod + def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): + """ + Changes the color of a link of this object, the color has to be given as a 4 element list + of RGBA values. + + :param obj: The object which should be colored + :param link_id: The link id of the link which should be colored + :param rgba_color: The color as RGBA values between 0 and 1 + """ + pass def get_object_color(self, obj: Object, @@ -501,15 +588,11 @@ def get_object_color(self, :param link: the link name for which the color should be returned. :return: The color of the object or link, or a dictionary containing every colored link with its color """ - visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) - swap = {v: k for k, v in obj.links.items()} - links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = list(map(lambda x: x[7], visual_data)) - link_to_color = dict(zip(links, colors)) + link_to_color_dict = self.get_object_colors(obj) if link: - if link in link_to_color.keys(): - return link_to_color[link] + if link in link_to_color_dict.keys(): + return link_to_color_dict[link] elif link not in obj.links.keys(): rospy.logerr(f"The link '{link}' is not part of this obejct") return None @@ -517,25 +600,43 @@ def get_object_color(self, rospy.logerr(f"The link '{link}' has no color") return None - if len(visual_data) == 1: - return list(visual_data[0][7]) + if len(link_to_color_dict) == 1: + return list(link_to_color_dict.values())[0] else: - return link_to_color + return link_to_color_dict - def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + @abstractmethod + def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in + Get the RGBA colors of each link in the object as a dictionary from link name to color. + + :param obj: The object + :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. + """ + pass + + @abstractmethod + def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. :param obj: The object for which the bounding box should be returned. - :param link_name: The Optional name of a link of this object. :return: Two lists of x,y,z which define the bounding box. """ - if link_name: - return p.getAABB(obj.id, obj.links[link_name], self.client_id) - else: - return p.getAABB(obj.id, physicsClientId=self.client_id) + pass + + @abstractmethod + def get_object_link_AABB(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of the link. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :param link_name: The name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + pass def get_attachment_event(self) -> Event: """ @@ -561,102 +662,156 @@ def get_manipulation_event(self) -> Event: """ return self.manipulation_event + @abstractmethod def set_realtime(self, real_time: bool) -> None: """ - Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only + Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only simulated to reason about it. - :param real_time: Whether the BulletWorld should simulate Physic in real time. + :param real_time: Whether the World should simulate Physics in real time. """ - p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + pass - def set_gravity(self, velocity: List[float]) -> None: + @abstractmethod + def set_gravity(self, gravity_vector: List[float]) -> None: """ - Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity - is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]). + Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - :param velocity: The gravity vector that should be used in the BulletWorld. + :param gravity_vector: The gravity vector that should be used in the World. """ - p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) + pass - def set_robot(self, robot: Object) -> None: + @classmethod + @abstractmethod + def set_robot(cls, robot: Object) -> None: """ Sets the global variable for the robot Object. This should be set on spawning the robot. :param robot: The Object reference to the Object representing the robot. """ - BulletWorld.robot = robot + pass - def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: + """ + Closes the World as well as the shadow world, also collects any other thread that is running. """ - Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real - time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By - setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real - time. + if wait_time_before_exit_in_secs is not None: + time.sleep(wait_time_before_exit_in_secs) + self.exit_prospection_world_if_exists() + self.disconnect_from_physics_server() + self.reset_current_world() + self.reset_robot() + self.join_threads() - :param seconds: The amount of seconds that should be simulated. - :param real_time: If the simulation should happen in real time or faster. + def exit_prospection_world_if_exists(self): + if self.prospection_world: + self.terminate_world_sync() + self.prospection_world.exit() + + @abstractmethod + def disconnect_from_physics_server(self): """ - for i in range(0, int(seconds * 240)): - p.stepSimulation(self.client_id) - for objects, callback in self.coll_callbacks.items(): - contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) - # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) - # print(contact_points[0][5]) - if contact_points != (): - callback[0]() - elif callback[1] != None: # Call no collision callback - callback[1]() - if real_time: - # Simulation runs at 240 Hz - time.sleep(0.004167) + Disconnects the world from the physics server. + """ + pass + + def reset_current_world(self): + if self.current_world == self: + self.current_world = None - def exit(self) -> None: + def reset_robot(self): + self.set_robot(None) + + @abstractmethod + def join_threads(self): """ - Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the - preferred method to close the BulletWorld. + Join any running threads. Useful for example when exiting the world. """ - # True if this is NOT the shadow world since it has a reference to the - # Shadow world - time.sleep(0.1) - if self.prospection_world: - self.world_sync.terminate = True - self.world_sync.join() - self.prospection_world.exit() - p.disconnect(self.client_id) - if self._gui_thread: - self._gui_thread.join() - if BulletWorld.current_bullet_world == self: - BulletWorld.current_bullet_world = None - BulletWorld.robot = None + pass - def save_state(self) -> Tuple[int, Dict]: + def terminate_world_sync(self): + self.world_sync.terminate = True + self.world_sync.join() + + def save_state(self) -> int: """ - Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint - position of every Object in the BulletWorld. + Returns the id of the saved state of the World. The saved state contains the position, orientation and joint + position of every Object in the World, the objects attachments and the constraint ids. :return: A unique id of the state """ - objects2attached = {} - # ToDo find out what this is for and where it is used + state_id = self.save_physics_simulator_state() + self._saved_states[state_id] = WorldState(state_id, + self.get_objects_attachments(), + self.get_objects_constraint_ids()) + return state_id + + def restore_state(self, state_id) -> None: + """ + Restores the state of the World according to the given state using the unique state id. This includes position, + orientation, and joint states. However, restore can not respawn objects if there are objects that were deleted + between creation of the state and restoring, they will be skipped. + + :param state_id: The unique id representing the state, as returned by :func:`~save_state` + """ + self.restore_physics_simulator_state(state_id) + self.restore_attachments_and_constraints_from_saved_world_state(state_id) + + @abstractmethod + def save_physics_simulator_state(self) -> int: + """ + Saves the state of the physics simulator and returns the unique id of the state. + """ + pass + + def get_objects_attachments(self) -> Dict[Object, Dict[Object, Attachment]]: + """ + Get The attachments collections that is stored in each object. + """ + attachments = {} for o in self.objects: - objects2attached[o] = (o.attachments.copy(), o.cids.copy()) - return p.saveState(self.client_id), objects2attached + attachments[o] = o.attachments.copy() + return attachments - def restore_state(self, state, objects2attached: Optional[Dict] = None) -> None: + def get_objects_constraint_ids(self) -> Dict[Object, Dict[Object, int]]: """ - Restores the state of the BulletWorld according to the given state id. This includes position, orientation and - joint states. However, restore can not respawn objects if there are objects that were deleted between creation of - the state and restoring they will be skiped. + Get the constraint ids collection that is stored in each object. + """ + constraint_ids = {} + for o in self.objects: + constraint_ids[o] = o.cids.copy() + return constraint_ids - :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` + @abstractmethod + def restore_physics_simulator_state(self, state_id): """ - p.restoreState(state, physicsClientId=self.client_id) - objects2attached = {} if objects2attached is None else objects2attached + Restores the objects and environment state in the physics simulator according to + the given state using the unique state id. + """ + pass + + def restore_attachments_and_constraints_from_saved_world_state(self, state_id: int): + """ + Restores the attachments and constraints of the objects in the World. This is done by setting the attachments, + and the cids attributes of each object in the World to the given attachments and constraint_ids. + """ + self.restore_attachments_from_saved_world_state(state_id) + self.restore_constraints_from_saved_world_state(state_id) + + def restore_attachments_from_saved_world_state(self, state_id: int): + attachments = self._saved_states[state_id].attachments for obj in self.objects: try: - obj.attachments, obj.cids = objects2attached[obj] + obj.attachments = attachments[obj] + except KeyError: + continue + + def restore_constraints_from_saved_world_state(self, state_id: int): + constraint_ids = self._saved_states[state_id].constraint_ids + for obj in self.objects: + try: + obj.cids = constraint_ids[obj] except KeyError: continue @@ -799,6 +954,30 @@ def update_transforms_for_objects_in_current_world(self) -> None: class BulletWorld(World): + """ + This class represents a BulletWorld, which is a simulation environment that uses the Bullet Physics Engine. This + class is the main interface to the Bullet Physics Engine and should be used to spawn Objects, simulate Physic and + manipulate the Bullet World. + """ + + current_world: World = None + """ + Global reference to the currently used World, usually this is the + graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the + shadow world. In this way you can comfortably use the current_world, which should point towards the World + used at the moment. + """ + + robot: Object = None + """ + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name + in the URDF with the name of the URDF on the parameter server. + """ + + data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} + """ + Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. + """ # Check is for sphinx autoAPI to be able to work in a CI workflow if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): @@ -813,7 +992,7 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. """ - super().__init__(mode=mode, is_prospection_world=is_prospection_world) + super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=0.004167) # 240 Hz self._gui_thread: Gui = Gui(self, mode) self._gui_thread.start() @@ -837,33 +1016,6 @@ def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: basePosition=pose.position_as_list(), baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) - def get_objects_by_name(self, name: str) -> List[Object]: - """ - Returns a list of all Objects in this BulletWorld with the same name as the given one. - - :param name: The name of the returned Objects. - :return: A list of all Objects with the name 'name'. - """ - return list(filter(lambda obj: obj.name == name, self.objects)) - - def get_objects_by_type(self, obj_type: str) -> List[Object]: - """ - Returns a list of all Objects which have the type 'obj_type'. - - :param obj_type: The type of the returned Objects. - :return: A list of all Objects that have the type 'obj_type'. - """ - return list(filter(lambda obj: obj.type == obj_type, self.objects)) - - def get_object_by_id(self, id: int) -> Object: - """ - Returns the single Object that has the unique id. - - :param id: The unique id for which the Object should be returned. - :return: The Object with the id 'id'. - """ - return list(filter(lambda obj: obj.id == id, self.objects))[0] - def remove_object(self, obj_id: int) -> None: """ Remove an object by its ID. @@ -893,35 +1045,25 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): p.removeConstraint(constraint_id, physicsClientId=self.client_id) - def detach_objects(self, obj1: Object, obj2: Object) -> None: + def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: """ - Detaches obj2 from obj1. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of pybullet. - Afterward the detachment event of the corresponding BulletWorld will be fired. + Get the joint upper limit of an articulated object - :param obj1: The object from which an object should be detached. - :param obj2: The object which should be detached. + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint upper limit as a float. """ - del obj1.attachments[obj2] - del obj2.attachments[obj1] - - p.removeConstraint(obj1.cids[obj2], physicsClientId=self.client_id) + return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8] - del obj1.cids[obj2] - del obj2.cids[obj1] - obj1.world.detachment_event(obj1, [obj1, obj2]) - - def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: + def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: """ - Get the joint limits of an articulated object + Get the joint lower limit of an articulated object - :param obj: The object - :param joint_name: The name of the joint - :return: A tuple containing the upper and the lower limits of the joint. + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint lower limit as a float. """ - up_lim, low_lim = p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8:10] - return up_lim, low_lim + return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[9] def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ @@ -973,6 +1115,16 @@ def get_object_contact_points(self, obj: Object) -> List: """ return p.getContactPoints(obj.id) + def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: + """ + Returns a list of contact points between obj1 and obj2. + + :param obj1: The first object. + :param obj2: The second object. + :return: A list of all contact points between the two objects. + """ + return p.getContactPoints(obj1.id, obj2.id) + def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: """ Get the ID of a joint in an articulated object. @@ -1035,205 +1187,130 @@ def step(self): """ p.stepSimulation(self.client_id) - def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): + def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): """ - Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. + Changes the color of a link of this object, the color has to be given as a 4 element list + of RGBA values. :param obj: The object which should be colored - :param color: The color as RGBA values between 0 and 1 - :param link: The link name of the link which should be colored + :param link_id: The link id of the link which should be colored + :param rgba_color: The color as RGBA values between 0 and 1 """ - if link == "": - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if obj.links != {}: - for link_id in obj.links.values(): - p.changeVisualShape(obj.id, link_id, rgbaColor=color, physicsClientId=self.client_id) - else: - p.changeVisualShape(obj.id, -1, rgbaColor=color, physicsClientId=self.client_id) - else: - p.changeVisualShape(obj.id, obj.links[link], rgbaColor=color, physicsClientId=self.client_id) + p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) - def get_object_color(self, - obj: Object, - link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: - - 1. A list with the color as RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the - object is spawned. - - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. + Get the RGBA colors of each link in the object as a dictionary from link name to color. - :param obj: The object for which the color should be returned. - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color + :param obj: The object + :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. """ visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) swap = {v: k for k, v in obj.links.items()} links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) colors = list(map(lambda x: x[7], visual_data)) link_to_color = dict(zip(links, colors)) + return link_to_color - if link: - if link in link_to_color.keys(): - return link_to_color[link] - elif link not in obj.links.keys(): - rospy.logerr(f"The link '{link}' is not part of this obejct") - return None - else: - rospy.logerr(f"The link '{link}' has no color") - return None - - if len(visual_data) == 1: - return list(visual_data[0][7]) - else: - return link_to_color - - def get_object_AABB(self, obj: Object, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in + Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. :param obj: The object for which the bounding box should be returned. - :param link_name: The Optional name of a link of this object. :return: Two lists of x,y,z which define the bounding box. """ - if link_name: - return p.getAABB(obj.id, obj.links[link_name], self.client_id) - else: - return p.getAABB(obj.id, physicsClientId=self.client_id) - - def get_attachment_event(self) -> Event: - """ - Returns the event reference that is fired if an attachment occurs. - - :return: The reference to the attachment event - """ - return self.attachment_event - - def get_detachment_event(self) -> Event: - """ - Returns the event reference that is fired if a detachment occurs. + return p.getAABB(obj.id, physicsClientId=self.client_id) - :return: The event reference for the detachment event. + def get_object_link_AABB(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: """ - return self.detachment_event - - def get_manipulation_event(self) -> Event: - """ - Returns the event reference that is fired if any manipulation occurs. + Returns the axis aligned bounding box of the link. The return of this method are two points in + world coordinate frame which define a bounding box. - :return: The event reference for the manipulation event. + :param obj: The object for which the bounding box should be returned. + :param link_name: The name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. """ - return self.manipulation_event + return p.getAABB(obj.id, obj.links[link_name], self.client_id) def set_realtime(self, real_time: bool) -> None: """ - Enables the real time simulation of Physic in the BulletWorld. By default this is disabled and Physic is only + Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only simulated to reason about it. - :param real_time: Whether the BulletWorld should simulate Physic in real time. + :param real_time: Whether the World should simulate Physics in real time. """ p.setRealTimeSimulation(1 if real_time else 0, self.client_id) - def set_gravity(self, velocity: List[float]) -> None: + def set_gravity(self, gravity_vector: List[float]) -> None: """ - Sets the gravity that is used in the BullteWorld, by default the is the gravity on earth ([0, 0, -9.8]). Gravity - is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]). + Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - :param velocity: The gravity vector that should be used in the BulletWorld. + :param gravity_vector: The gravity vector that should be used in the World. """ - p.setGravity(velocity[0], velocity[1], velocity[2], physicsClientId=self.client_id) + p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) - def set_robot(self, robot: Object) -> None: + @classmethod + def set_robot(cls, robot: Object) -> None: """ Sets the global variable for the robot Object. This should be set on spawning the robot. :param robot: The Object reference to the Object representing the robot. """ - BulletWorld.robot = robot - - def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: - """ - Simulates Physic in the BulletWorld for a given amount of seconds. Usually this simulation is faster than real - time, meaning you can simulate for example 10 seconds of Physic in the BulletWorld in 1 second real time. By - setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal to real - time. - - :param seconds: The amount of seconds that should be simulated. - :param real_time: If the simulation should happen in real time or faster. - """ - for i in range(0, int(seconds * 240)): - p.stepSimulation(self.client_id) - for objects, callback in self.coll_callbacks.items(): - contact_points = p.getContactPoints(objects[0].id, objects[1].id, physicsClientId=self.client_id) - # contact_points = p.getClosestPoints(objects[0].id, objects[1].id, 0.02) - # print(contact_points[0][5]) - if contact_points != (): - callback[0]() - elif callback[1] != None: # Call no collision callback - callback[1]() - if real_time: - # Simulation runs at 240 Hz - time.sleep(0.004167) + cls.robot = robot - def exit(self) -> None: + def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: """ Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the preferred method to close the BulletWorld. """ - # True if this is NOT the shadow world since it has a reference to the - # Shadow world - time.sleep(0.1) + super().exit(wait_time_before_exit_in_secs) + + def exit_prospection_world_if_exists(self): if self.prospection_world: - self.world_sync.terminate = True - self.world_sync.join() + self.terminate_world_sync() self.prospection_world.exit() + + def disconnect_from_physics_server(self): + """ + Disconnects the world from the physics server. + """ p.disconnect(self.client_id) + + def reset_current_world(self): + if self.current_world == self: + self.current_world = None + + def reset_robot(self): + self.set_robot(None) + + def join_threads(self): + """ + Join any running threads. Useful for example when exiting the world. + """ + self.join_gui_thread_if_exists() + + def join_gui_thread_if_exists(self): if self._gui_thread: self._gui_thread.join() - if BulletWorld.current_bullet_world == self: - BulletWorld.current_bullet_world = None - BulletWorld.robot = None - def save_state(self) -> Tuple[int, Dict]: - """ - Returns the id of the saved state of the BulletWorld. The saved state contains the position, orientation and joint - position of every Object in the BulletWorld. + def terminate_world_sync(self): + self.world_sync.terminate = True + self.world_sync.join() - :return: A unique id of the state + def save_physics_simulator_state(self) -> int: """ - objects2attached = {} - # ToDo find out what this is for and where it is used - for o in self.objects: - objects2attached[o] = (o.attachments.copy(), o.cids.copy()) - return p.saveState(self.client_id), objects2attached - - def restore_state(self, state, objects2attached: Optional[Dict] = None) -> None: + Saves the state of the physics simulator and returns the unique id of the state. """ - Restores the state of the BulletWorld according to the given state id. This includes position, orientation and - joint states. However, restore can not respawn objects if there are objects that were deleted between creation of - the state and restoring they will be skiped. + return p.saveState(self.client_id) - :param state: The unique id representing the state, as returned by :func:`~save_state` - :param objects2attached: A dictionary of attachments, as saved in :py:attr:`~world.Object.attachments` + def restore_physics_simulator_state(self, state_id): """ - p.restoreState(state, physicsClientId=self.client_id) - objects2attached = {} if objects2attached is None else objects2attached - for obj in self.objects: - try: - obj.attachments, obj.cids = objects2attached[obj] - except KeyError: - continue + Restores the objects and environment state in the physics simulator according to + the given state using the unique state id. + """ + p.restoreState(state_id, self.client_id) def copy(self) -> BulletWorld: """ @@ -2192,16 +2269,24 @@ def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, """ return self.world.get_object_color(self, link) - def get_AABB(self, link_name: Optional[str] = None) -> Tuple[List[float], List[float]]: + def get_AABB(self) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object. The return of this method are two points in + world coordinate frame which define a bounding box. + + :return: Two lists of x,y,z which define the bounding box. + """ + return self.world.get_object_AABB(self) + + def get_link_AABB(self, link_name: str) -> Tuple[List[float], List[float]]: """ - Returns the axis aligned bounding box of this object, optionally a link name can be provided in this case - the axis aligned bounding box of the link will be returned. The return of this method are two points in + Returns the axis aligned bounding box of the given link name. The return of this method are two points in world coordinate frame which define a bounding box. - :param link_name: The Optional name of a link of this object. + :param link_name: The name of a link of this object. :return: Two lists of x,y,z which define the bounding box. """ - return self.world.get_object_AABB(self, link_name) + return self.world.get_object_link_AABB(self, link_name) def get_base_origin(self, link_name: Optional[str] = None) -> Pose: """ @@ -2210,7 +2295,7 @@ def get_base_origin(self, link_name: Optional[str] = None) -> Pose: :param link_name: The link name for which the bottom position should be returned :return: The position of the bottom of this Object or link """ - aabb = self.get_AABB(link_name=link_name) + aabb = self.get_link_AABB(link_name=link_name) base_width = np.absolute(aabb[0][0] - aabb[1][0]) base_length = np.absolute(aabb[0][1] - aabb[1][1]) return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], From 0f1133ba0d3363c044caee28096bb59bffb924da Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 11 Dec 2023 01:22:09 +0100 Subject: [PATCH 012/195] [AbstractWorld] Finished defining AbstractWorld, and correcting all classes defined in the world.py file. --- src/pycram/costmaps.py | 32 +- src/pycram/designator.py | 2 +- src/pycram/designators/action_designator.py | 8 +- src/pycram/designators/location_designator.py | 14 +- src/pycram/external_interfaces/giskard.py | 6 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/pose_generator_and_validator.py | 6 +- .../process_modules/boxy_process_modules.py | 4 +- .../process_modules/donbot_process_modules.py | 4 +- .../process_modules/hsr_process_modules.py | 4 +- .../process_modules/pr2_process_modules.py | 6 +- .../resolver/location/giskard_location.py | 6 +- src/pycram/ros/force_torque_sensor.py | 2 +- src/pycram/ros/joint_state_publisher.py | 2 +- src/pycram/ros/tf_broadcaster.py | 2 +- src/pycram/ros/viz_marker_publisher.py | 2 +- src/pycram/task.py | 4 +- src/pycram/world.py | 336 ++++++------------ src/pycram/world_reasoning.py | 70 ++-- test/test_bullet_world.py | 4 +- test/test_database_resolver.py | 2 +- test/test_jpt_resolver.py | 2 +- test/test_task_tree.py | 2 +- 23 files changed, 196 insertions(+), 326 deletions(-) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 3d6f63451..86017cdbd 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -8,7 +8,7 @@ from matplotlib import colors import psutil import time -from .world import BulletWorld, Use_shadow_world, Object +from .world import BulletWorld, UseProspectionWorld, Object from .world_reasoning import _get_images_for_target from nav_msgs.msg import OccupancyGrid, MapMetaData from typing import Tuple, List, Union, Optional @@ -385,17 +385,17 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: i = 0 j = 0 for n in self._chunks(np.array(rays), 16380): - with Use_shadow_world(): + with UseProspectionWorld(BulletWorld): r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=BulletWorld.current_bullet_world.client_id) + physicsClientId=BulletWorld.current_world.client_id) while r_t is None: r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=BulletWorld.current_bullet_world.client_id) + physicsClientId=BulletWorld.current_world.client_id) j += len(n) if BulletWorld.robot: - shadow_robot = BulletWorld.current_bullet_world.get_shadow_object(BulletWorld.robot) + shadow_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) attached_objs = BulletWorld.robot.attachments.keys() - attached_objs_shadow_id = [BulletWorld.current_bullet_world.get_shadow_object(x).id for x in + attached_objs_shadow_id = [BulletWorld.current_world.get_prospection_object(x).id for x in attached_objs] res[i:j] = [ 1 if ray[0] == -1 or ray[0] == shadow_robot.id or ray[0] in attached_objs_shadow_id else 0 for @@ -470,7 +470,7 @@ def __init__(self, min_height: float, if (11 * size ** 2 + size ** 3) * 2 > psutil.virtual_memory().available: raise OSError("Not enough free RAM to calculate a costmap of this size") - self.world = world if world else BulletWorld.current_bullet_world + self.world = world if world else BulletWorld.current_world self.map = np.zeros((size, size)) self.size = size self.resolution = resolution @@ -494,26 +494,26 @@ def _create_images(self) -> List[np.ndarray]: images = [] camera_pose = self.origin - with Use_shadow_world(): + with UseProspectionWorld(BulletWorld): origin_copy = self.origin.copy() origin_copy.position.y += 1 images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_bullet_world, size=self.size)[1]) + _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.x -= 1 images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_bullet_world, size=self.size)[1]) + _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.y -= 1 images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_bullet_world, size=self.size)[1]) + _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.x += 1 images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_bullet_world, size=self.size)[1]) + _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) for i in range(0, 4): images[i] = self._depth_buffer_to_meter(images[i]) @@ -695,7 +695,7 @@ def __init__(self, object, urdf_link_name, size=100, resolution=0.02, world=None :param resolution: Resolution of the final costmap :param world: The BulletWorld from which the costmap should be created """ - self.world: BulletWorld = world if world else BulletWorld.current_bullet_world + self.world: BulletWorld = world if world else BulletWorld.current_world self.object: Object = object self.link: str = urdf_link_name self.resolution: float = resolution @@ -725,14 +725,14 @@ def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: :return: Two points in world coordinate space, which span a rectangle """ - shadow_obj = BulletWorld.current_bullet_world.get_shadow_object(self.object) - with Use_shadow_world(): + shadow_obj = BulletWorld.current_world.get_prospection_object(self.object) + with UseProspectionWorld(BulletWorld): shadow_obj.set_orientation(Pose(orientation=[0, 0, 0, 1])) link_orientation = shadow_obj.get_link_pose(self.link) link_orientation_trans = link_orientation.to_transform(self.object.get_link_tf_frame(self.link)) inverse_orientation = link_orientation_trans.invert() shadow_obj.set_orientation(inverse_orientation.to_pose()) - return shadow_obj.get_link_AABB(self.link) + return shadow_obj.get_link_aabb(self.link) cmap = colors.ListedColormap(['white', 'black', 'green', 'red', 'blue']) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 289ebe498..3329fba27 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -753,7 +753,7 @@ def __iter__(self) -> Iterable[Object]: :yield: A resolved object designator """ # for every bullet world object - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: # skip if name does not match specification if self.names and obj.name not in self.names: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 2e7e4f2db..b92363bf1 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -345,12 +345,12 @@ def perform(self) -> None: prepose = object.local_transformer.transform_pose_to_target_frame(oTg, "map") # Perform the motion with the prepose and open gripper - BulletWorld.current_bullet_world.add_vis_axis(prepose) + BulletWorld.current_world.add_vis_axis(prepose) MoveTCPMotion(prepose, self.arm).resolve().perform() MoveGripperMotion(motion="open", gripper=self.arm).resolve().perform() # Perform the motion with the adjusted pose -> actual grasp and close gripper - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + BulletWorld.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() adjusted_oTm.pose.position.z += 0.03 MoveGripperMotion(motion="close", gripper=self.arm).resolve().perform() @@ -358,11 +358,11 @@ def perform(self) -> None: robot.attach(object, tool_frame) # Lift object - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + BulletWorld.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() # Remove the vis axis from the world - BulletWorld.current_bullet_world.remove_vis_axis() + BulletWorld.current_world.remove_vis_axis() def to_sql(self) -> ORMPickUpAction: return ORMPickUpAction(self.arm, self.grasp) diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 7b62fb27c..99c2a4b0e 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -3,7 +3,7 @@ from typing import List, Tuple, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..world import Object, BulletWorld, Use_shadow_world +from ..world import Object, BulletWorld, UseProspectionWorld from ..world_reasoning import link_pose_for_joint_config from ..designator import Designator, DesignatorError, LocationDesignatorDescription from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap @@ -180,16 +180,16 @@ def __iter__(self): if self.visible_for or self.reachable_for: robot_object = self.visible_for.bullet_world_object if self.visible_for else self.reachable_for.bullet_world_object - test_robot = BulletWorld.current_bullet_world.get_shadow_object(robot_object) + test_robot = BulletWorld.current_world.get_prospection_object(robot_object) - with Use_shadow_world(): + with UseProspectionWorld(BulletWorld): for maybe_pose in pose_generator(final_map, number_of_samples=600): res = True arms = None if self.visible_for: res = res and visibility_validator(maybe_pose, test_robot, target_pose, - BulletWorld.current_bullet_world) + BulletWorld.current_world) if self.reachable_for: hand_links = [] for name, chain in robot_description.chains.items(): @@ -256,7 +256,7 @@ def __iter__(self) -> Location: final_map = occupancy + gaussian - test_robot = BulletWorld.current_bullet_world.get_shadow_object(self.robot) + test_robot = BulletWorld.current_world.get_prospection_object(self.robot) # Find a Joint of type prismatic which is above the handle in the URDF tree container_joint = self.handle.bullet_world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) @@ -275,7 +275,7 @@ def __iter__(self) -> Location: container_joint: self.handle.bullet_world_object.get_joint_limits(container_joint)[1] / 1.5}, self.handle.name) - with Use_shadow_world(): + with UseProspectionWorld(BulletWorld): for maybe_pose in pose_generator(final_map, number_of_samples=600, orientation_generator=lambda p, o: generate_orientation(p, half_pose)): @@ -338,7 +338,7 @@ def __iter__(self): sem_costmap = SemanticCostmap(self.part_of.bullet_world_object, self.urdf_link_name) height_offset = 0 if self.for_object: - min, max = self.for_object.bullet_world_object.get_AABB() + min, max = self.for_object.bullet_world_object.get_aabb() height_offset = (max[2] - min[2]) / 2 for maybe_pose in pose_generator(sem_costmap): maybe_pose.position.z += height_offset diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 98f15d55a..7c4c5f4c6 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -69,7 +69,7 @@ def initial_adding_objects() -> None: Adds object that are loaded in the BulletWorld to the Giskard belief state, if they are not present at the moment. """ groups = giskard_wrapper.get_group_names() - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if obj == BulletWorld.robot: continue name = obj.name + "_" + str(obj.id) @@ -84,7 +84,7 @@ def removing_of_objects() -> None: """ groups = giskard_wrapper.get_group_names() object_names = list( - map(lambda obj: object_names.name + "_" + str(obj.id), BulletWorld.current_bullet_world.objects)) + map(lambda obj: object_names.name + "_" + str(obj.id), BulletWorld.current_world.objects)) diff = list(set(groups) - set(object_names)) for grp in diff: giskard_wrapper.remove_group(grp) @@ -99,7 +99,7 @@ def sync_worlds() -> None: """ add_gripper_groups() bullet_object_names = set() - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if obj.name != robot_description.name and len(obj.links) != 1: bullet_object_names.add(obj.name + "_" + str(obj.id)) diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index d092dbe2a..c6e897af8 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -125,7 +125,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti for i in range(0, len(query_result.res[0].pose)): pose = Pose.from_pose_stamped(query_result.res[0].pose[i]) - pose.frame = BulletWorld.current_bullet_world.robot.get_link_tf_frame(pose.frame) + pose.frame = BulletWorld.current_world.robot.get_link_tf_frame(pose.frame) source = query_result.res[0].poseSource[i] lt = LocalTransformer() diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index a836034d1..ae3f9994d 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -3,7 +3,7 @@ import rospy import pybullet as p -from .world import Object, BulletWorld, Use_shadow_world +from .world import Object, BulletWorld, UseProspectionWorld from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform @@ -157,7 +157,7 @@ def reachability_validator(pose: Pose, _apply_ik(robot, resp, left_joints) - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if obj.name == "floor": continue in_contact, contact_links = contact(robot, obj, return_links=True) @@ -181,7 +181,7 @@ def reachability_validator(pose: Pose, _apply_ik(robot, resp, right_joints) - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if obj.name == "floor": continue in_contact, contact_links = contact(robot, obj, return_links=True) diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 45a163e84..e1314e41c 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -225,7 +225,7 @@ def _execute(self, desig): cam_frame_name = solution['cam_frame'] front_facing_axis = solution['front_facing_axis'] - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): return obj @@ -283,7 +283,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] class BoxyManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 81e12caa1..d893d8048 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -188,7 +188,7 @@ def _execute(self, desig): cam_frame_name = solution['cam_frame'] front_facing_axis = solution['front_facing_axis'] - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): return obj @@ -240,7 +240,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] class DonbotManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 594f355f1..09b715e1c 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -161,7 +161,7 @@ def _execute(self, desig): cam_frame_name = solution['cam_frame'] front_facing_axis = solution['front_facing_axis'] - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): return obj @@ -213,7 +213,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] class HSRManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index c446b1463..3432533d0 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -156,7 +156,7 @@ def _execute(self, desig: DetectingMotion.Motion): # should be [0, 0, 1] front_facing_axis = robot_description.front_facing_axis - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): return obj @@ -205,7 +205,7 @@ class Pr2WorldStateDetecting(ProcessModule): def _execute(self, desig: WorldStateDetectingMotion.Motion): obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] class Pr2Open(ProcessModule): @@ -325,7 +325,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 - bullet_obj = BulletWorld.current_bullet_world.get_objects_by_type(designator.object_type) + bullet_obj = BulletWorld.current_world.get_objects_by_type(designator.object_type) if bullet_obj: bullet_obj[0].set_pose(obj_pose) return bullet_obj[0] diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index cd2c76430..2a2840f36 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,6 +1,6 @@ from pycram.external_interfaces.giskard import achieve_cartesian_goal from pycram.designators.location_designator import CostmapLocation -from pycram.world import Use_shadow_world, BulletWorld +from pycram.world import UseProspectionWorld, BulletWorld from pycram.helper import _apply_ik from pycram.pose import Pose from pycram.robot_descriptions import robot_description @@ -28,8 +28,8 @@ def __iter__(self) -> CostmapLocation.Location: pose_left, end_config_left = self._get_reachable_pose_for_arm(self.target, robot_description.get_tool_frame("left")) - test_robot = BulletWorld.current_bullet_world.get_shadow_object(BulletWorld.robot) - with Use_shadow_world(): + test_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) + with UseProspectionWorld(BulletWorld): valid, arms = reachability_validator(pose_right, test_robot, self.target, {}) if valid: yield CostmapLocation.Location(pose_right, arms) diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index 314a9239a..c67c2bca2 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -25,7 +25,7 @@ def __init__(self, joint_name, fts_topic="/pycram/fts", interval=0.1): :param fts_topic: Name of the ROS topic to which should be published :param interval: Interval at which the messages should be published, in seconds """ - self.world = BulletWorld.current_bullet_world + self.world = BulletWorld.current_world self.fts_joint_idx = None self.joint_name = joint_name if joint_name in self.world.robot.joints.keys(): diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index f771b5565..4f72e3a61 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -21,7 +21,7 @@ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): :param joint_state_topic: Topic name to which the joint states should be published :param interval: Interval at which the joint states should be published, in seconds """ - self.world = BulletWorld.current_bullet_world + self.world = BulletWorld.current_world self.joint_state_pub = rospy.Publisher(joint_state_topic, JointState, queue_size=10) self.interval = interval diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index ec0ab9cc3..907119275 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -21,7 +21,7 @@ def __init__(self, projection_namespace="simulated", odom_frame="odom", interval :param odom_frame: Name of the statically published odom frame :param interval: Interval at which the TFs should be published, in seconds """ - self.world = BulletWorld.current_bullet_world + self.world = BulletWorld.current_world self.tf_static_publisher = rospy.Publisher("/tf_static", TFMessage, queue_size=10) self.tf_publisher = rospy.Publisher("/tf", TFMessage, queue_size=10) diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 90278afd4..f4a815df3 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -56,7 +56,7 @@ def _make_marker_array(self) -> MarkerArray: :return: An Array of Visualization Marker """ marker_array = MarkerArray() - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if obj.name == "floor": continue for link in obj.links.keys(): diff --git a/src/pycram/task.py b/src/pycram/task.py index 74df58952..7ec966918 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -254,7 +254,7 @@ def __enter__(self): def simulation(): return None self.suspended_tree = task_tree - self.world_state, self.objects2attached = BulletWorld.current_bullet_world.save_state() + self.world_state, self.objects2attached = BulletWorld.current_world.save_state() self.simulated_root = TaskTreeNode(code=Code(simulation)) task_tree = self.simulated_root pybullet.addUserDebugText("Simulating...", [0, 0, 1.75], textColorRGB=[0, 0, 0], @@ -267,7 +267,7 @@ def __exit__(self, exc_type, exc_val, exc_tb): """ global task_tree task_tree = self.suspended_tree - BulletWorld.current_bullet_world.restore_state(self.world_state, self.objects2attached) + BulletWorld.current_world.restore_state(self.world_state, self.objects2attached) pybullet.removeAllUserDebugItems() diff --git a/src/pycram/world.py b/src/pycram/world.py index 6e3d75b1c..c78b1eeb5 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,7 +10,7 @@ import xml.etree.ElementTree from queue import Queue import tf -from typing import List, Optional, Dict, Tuple, Callable, Set +from typing import List, Optional, Dict, Tuple, Callable, Set, Type, TypeVar from typing import Union import numpy as np @@ -158,6 +158,8 @@ class World(ABC): Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ + simulation_time_step: float = None + def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: float): """ Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the @@ -184,7 +186,7 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self._init_and_sync_prospection_world() self._update_local_transformer_worlds() - self.simulation_time_step = simulation_time_step + World.simulation_time_step = simulation_time_step self.simulation_frequency = int(1/self.simulation_time_step) self._saved_states: Dict[int, WorldState] = {} # Different states of the world indexed by int state id. @@ -815,7 +817,7 @@ def restore_constraints_from_saved_world_state(self, state_id: int): except KeyError: continue - def copy(self) -> BulletWorld: + def _copy(self) -> World: """ Copies this Bullet World into another and returns it. The other BulletWorld will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. @@ -831,103 +833,66 @@ def copy(self) -> BulletWorld: o.set_joint_position(joint, obj.get_joint_position(joint)) return world - def add_vis_axis(self, pose: Pose, - length: Optional[float] = 0.2) -> None: - """ - Creates a Visual object which represents the coordinate frame at the given - position and orientation. There can be an unlimited amount of vis axis objects. - - :param pose: The pose at which the axis should be spawned - :param length: Optional parameter to configure the length of the axes - """ - - position, orientation = pose.to_list() - - vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) - vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) - vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) - - obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], - basePosition=position, baseOrientation=orientation, - linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkParentIndices=[0, 0, 0], - linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], - linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1]) - - self.vis_axis.append(obj) - - def remove_vis_axis(self) -> None: - """ - Removes all spawned vis axis objects that are currently in this BulletWorld. - """ - for id in self.vis_axis: - p.removeBody(id) - self.vis_axis = [] - - def register_collision_callback(self, objectA: Object, objectB: Object, - callback_collision: Callable, - callback_no_collision: Optional[Callable] = None) -> None: + def register_two_objects_collision_callbacks(self, object_a: Object, object_b: Object, + on_collision_callback: Callable, + on_collision_removal_callback: Optional[Callable] = None) -> None: """ Registers callback methods for contact between two Objects. There can be a callback for when the two Objects get in contact and, optionally, for when they are not in contact anymore. - :param objectA: An object in the BulletWorld - :param objectB: Another object in the BulletWorld - :param callback_collision: A function that should be called if the objects are in contact - :param callback_no_collision: A function that should be called if the objects are not in contact + :param object_a: An object in the World + :param object_b: Another object in the World + :param on_collision_callback: A function that should be called if the objects are in contact + :param on_collision_removal_callback: A function that should be called if the objects are not in contact """ - self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) + self.coll_callbacks[(object_a, object_b)] = (on_collision_callback, on_collision_removal_callback) - def add_additional_resource_path(self, path: str) -> None: + @classmethod + def add_additional_resource_path(cls, path: str) -> None: """ Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an Object is spawned only with a filename. :param path: A path in the filesystem in which to search for files. """ - World.data_directory.append(path) + cls.data_directory.append(path) - def get_shadow_object(self, object: Object) -> Object: + def get_prospection_object(self, obj: Object) -> Object: """ - Returns the corresponding object from the shadow world for the given object. If the given Object is already in - the shadow world it is returned. + Returns the corresponding object from the prospection world for a given object in the main world. + If the given Object is already in the prospection world, it is returned. - :param object: The object for which the shadow worlds object should be returned. - :return: The corresponding object in the shadow world. + :param obj: The object for which the corresponding object in the prospection World should be found. + :return: The corresponding object in the prospection world. """ try: - return self.world_sync.object_mapping[object] + return self.world_sync.object_mapping[obj] except KeyError: - shadow_world = self if self.is_prospection_world else self.prospection_world - if object in shadow_world.objects: - return object + prospection_world = self if self.is_prospection_world else self.prospection_world + if obj in prospection_world.objects: + return obj else: raise ValueError( - f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") + f"There is no prospection object for the given object: {obj}, this could be the case if" + f" the object isn't anymore in the main (graphical) World" + f" or if the given object is already a prospection object. ") - def get_bullet_object_for_shadow(self, object: Object) -> Object: + def get_object_from_prospection(self, prospection_object: Object) -> Object: """ - Returns the corresponding object from the main Bullet World for a given + Returns the corresponding object from the main World for a given object in the shadow world. If the given object is not in the shadow world an error will be raised. - :param object: The object for which the corresponding object in the main Bullet World should be found - :return: The object in the main Bullet World + :param prospection_object: The object for which the corresponding object in the main World should be found. + :return: The object in the main World. """ - map = self.world_sync.object_mapping + object_map = self.world_sync.object_mapping try: - return list(map.keys())[list(map.values()).index(object)] + return list(object_map.keys())[list(object_map.values()).index(prospection_object)] except ValueError: raise ValueError("The given object is not in the shadow world.") - def reset_bullet_world(self) -> None: + def reset_world(self) -> None: """ Resets the BulletWorld to the state it was first spawned in. All attached objects will be detached, all joints will be set to the @@ -960,7 +925,7 @@ class is the main interface to the Bullet Physics Engine and should be used to s manipulate the Bullet World. """ - current_world: World = None + current_world: BulletWorld = None """ Global reference to the currently used World, usually this is the graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the @@ -1267,24 +1232,12 @@ def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: """ super().exit(wait_time_before_exit_in_secs) - def exit_prospection_world_if_exists(self): - if self.prospection_world: - self.terminate_world_sync() - self.prospection_world.exit() - def disconnect_from_physics_server(self): """ Disconnects the world from the physics server. """ p.disconnect(self.client_id) - def reset_current_world(self): - if self.current_world == self: - self.current_world = None - - def reset_robot(self): - self.set_robot(None) - def join_threads(self): """ Join any running threads. Useful for example when exiting the world. @@ -1295,10 +1248,6 @@ def join_gui_thread_if_exists(self): if self._gui_thread: self._gui_thread.join() - def terminate_world_sync(self): - self.world_sync.terminate = True - self.world_sync.join() - def save_physics_simulator_state(self) -> int: """ Saves the state of the physics simulator and returns the unique id of the state. @@ -1312,22 +1261,6 @@ def restore_physics_simulator_state(self, state_id): """ p.restoreState(state_id, self.client_id) - def copy(self) -> BulletWorld: - """ - Copies this Bullet World into another and returns it. The other BulletWorld - will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. - This method should only be used if necessary since there can be unforeseen problems. - - :return: The reference to the new BulletWorld - """ - world = BulletWorld("DIRECT") - for obj in self.objects: - o = Object(obj.name, obj.type, obj.path, Pose(obj.get_position(), obj.get_orientation()), - world, obj.color) - for joint in obj.joints: - o.set_joint_position(joint, obj.get_joint_position(joint)) - return world - def add_vis_axis(self, pose: Pose, length: Optional[float] = 0.2) -> None: """ @@ -1368,113 +1301,49 @@ def remove_vis_axis(self) -> None: p.removeBody(id) self.vis_axis = [] - def register_collision_callback(self, objectA: Object, objectB: Object, - callback_collision: Callable, - callback_no_collision: Optional[Callable] = None) -> None: - """ - Registers callback methods for contact between two Objects. There can be a callback for when the two Objects - get in contact and, optionally, for when they are not in contact anymore. - - :param objectA: An object in the BulletWorld - :param objectB: Another object in the BulletWorld - :param callback_collision: A function that should be called if the objects are in contact - :param callback_no_collision: A function that should be called if the objects are not in contact - """ - self.coll_callbacks[(objectA, objectB)] = (callback_collision, callback_no_collision) - - def get_shadow_object(self, object: Object) -> Object: - """ - Returns the corresponding object from the shadow world for the given object. If the given Object is already in - the shadow world it is returned. - - :param object: The object for which the shadow worlds object should be returned. - :return: The corresponding object in the shadow world. - """ - try: - return self.world_sync.object_mapping[object] - except KeyError: - shadow_world = self if self.is_prospection_world else self.prospection_world - if object in shadow_world.objects: - return object - else: - raise ValueError( - f"There is no shadow object for the given object: {object}, this could be the case if the object isn't anymore in the main (graphical) BulletWorld or if the given object is already a shadow object. ") - - def get_bullet_object_for_shadow(self, object: Object) -> Object: - """ - Returns the corresponding object from the main Bullet World for a given - object in the shadow world. If the given object is not in the shadow - world an error will be raised. - - :param object: The object for which the corresponding object in the main Bullet World should be found - :return: The object in the main Bullet World - """ - map = self.world_sync.object_mapping - try: - return list(map.keys())[list(map.values()).index(object)] - except ValueError: - raise ValueError("The given object is not in the shadow world.") - def reset_bullet_world(self) -> None: - """ - Resets the BulletWorld to the state it was first spawned in. - All attached objects will be detached, all joints will be set to the - default position of 0 and all objects will be set to the position and - orientation in which they were spawned. - """ - for obj in self.objects: - if obj.attachments: - attached_objects = list(obj.attachments.keys()) - for att_obj in attached_objects: - obj.detach(att_obj) - joint_names = list(obj.joints.keys()) - joint_poses = [0 for j in joint_names] - obj.set_positions_of_all_joints(dict(zip(joint_names, joint_poses))) - obj.set_pose(obj.original_pose) - - -class Use_shadow_world(): +class UseProspectionWorld: """ - An environment for using the shadow world, while in this environment the :py:attr:`~BulletWorld.current_bullet_world` - variable will point to the shadow world. + An environment for using the prospection world, while in this environment the :py:attr:`~World.current_world` + variable will point to the prospection world. Example: - with Use_shadow_world(): + with UseProspectionWorld(): NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() """ - def __init__(self): - self.prev_world: BulletWorld = None + def __init__(self, world_impl: Type[World]): + """ + :param world_impl: A class that implements a World (for example BulletWorld). + """ + self.world_impl = world_impl + self.prev_world: type(world_impl) = None def __enter__(self): - if not BulletWorld.current_bullet_world.is_prospection_world: - time.sleep(20 / 240) + if not self.world_impl.current_world.is_prospection_world: + time.sleep(20 * self.world_impl.simulation_time_step) # blocks until the adding queue is ready - BulletWorld.current_bullet_world.world_sync.add_obj_queue.join() - # **This is currently not used since the sleep(20/240) seems to be enough, but on weaker hardware this might - # not be a feasible solution** - # while not BulletWorld.current_bullet_world.world_sync.equal_states: - # time.sleep(0.1) + self.world_impl.current_world.world_sync.add_obj_queue.join() - self.prev_world = BulletWorld.current_bullet_world - BulletWorld.current_bullet_world.world_sync.pause_sync = True - BulletWorld.current_bullet_world = BulletWorld.current_bullet_world.prospection_world + self.prev_world = self.world_impl.current_world + self.world_impl.current_world.world_sync.pause_sync = True + self.world_impl.current_world = self.world_impl.current_world.prospection_world def __exit__(self, *args): - if not self.prev_world == None: - BulletWorld.current_bullet_world = self.prev_world - BulletWorld.current_bullet_world.world_sync.pause_sync = False + if self.prev_world is not None: + self.world_impl.current_world = self.prev_world + self.world_impl.current_world.world_sync.pause_sync = False class WorldSync(threading.Thread): """ - Synchronizes the state between the BulletWorld and its shadow world. - Meaning the cartesian and joint position of everything in the shadow world will be - synchronized with the main BulletWorld. + Synchronizes the state between the World and its prospection world. + Meaning the cartesian and joint position of everything in the prospection world will be + synchronized with the main World. Adding and removing objects is done via queues, such that loading times of objects - in the shadow world does not affect the BulletWorld. + in the prospection world does not affect the World. The class provides the possibility to pause the synchronization, this can be used - if reasoning should be done in the shadow world. + if reasoning should be done in the prospection world. """ def __init__(self, world: World, prospection_world: World): @@ -1487,7 +1356,7 @@ def __init__(self, world: World, prospection_world: World): self.add_obj_queue: Queue = Queue() self.remove_obj_queue: Queue = Queue() self.pause_sync: bool = False - # Maps bullet to shadow world objects + # Maps bullet to prospection world objects self.object_mapping: Dict[Object, Object] = {} self.equal_states = False @@ -1496,8 +1365,8 @@ def run(self): Main method of the synchronization, this thread runs in a loop until the terminate flag is set. While this loop runs it continuously checks the cartesian and joint position of - every object in the BulletWorld and updates the corresponding object in the - shadow world. When there are entries in the adding or removing queue the corresponding objects will be added + every object in the World and updates the corresponding object in the + prospection world. When there are entries in the adding or removing queue the corresponding objects will be added or removed in the same iteration. """ while not self.terminate: @@ -1507,28 +1376,28 @@ def run(self): obj = self.add_obj_queue.get() # [name, type, path, position, orientation, self.world.prospection_world, color, bulletworld object] o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) - # Maps the BulletWorld object to the shadow world object + # Maps the World object to the prospection world object self.object_mapping[obj[7]] = o self.add_obj_queue.task_done() for i in range(self.remove_obj_queue.qsize()): obj = self.remove_obj_queue.get() - # Get shadow world object reference from object mapping - shadow_obj = self.object_mapping[obj] - shadow_obj.remove() + # Get prospection world object reference from object mapping + prospection_obj = self.object_mapping[obj] + prospection_obj.remove() del self.object_mapping[obj] self.remove_obj_queue.task_done() - for bulletworld_obj, shadow_obj in self.object_mapping.items(): + for bulletworld_obj, prospection_obj in self.object_mapping.items(): b_pose = bulletworld_obj.get_pose() - s_pose = shadow_obj.get_pose() + s_pose = prospection_obj.get_pose() if b_pose.dist(s_pose) != 0.0: - shadow_obj.set_pose(bulletworld_obj.get_pose()) + prospection_obj.set_pose(bulletworld_obj.get_pose()) # Manage joint positions if len(bulletworld_obj.joints) > 2: for joint_name in bulletworld_obj.joints.keys(): - if shadow_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): - shadow_obj.set_positions_of_all_joints(bulletworld_obj.get_positions_of_all_joints()) + if prospection_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): + prospection_obj.set_positions_of_all_joints(bulletworld_obj.get_positions_of_all_joints()) break self.check_for_pause() @@ -1547,25 +1416,25 @@ def check_for_pause(self) -> None: def check_for_equal(self) -> None: """ - Checks if both BulletWorlds have the same state, meaning all objects are in the same position. + Checks if both Worlds have the same state, meaning all objects are in the same position. This is currently not used, but might be used in the future if synchronization issues worsen. """ eql = True - for obj, shadow_obj in self.object_mapping.items(): - eql = eql and obj.get_pose() == shadow_obj.get_pose() + for obj, prospection_obj in self.object_mapping.items(): + eql = eql and obj.get_pose() == prospection_obj.get_pose() self.equal_states = eql class Gui(threading.Thread): """ - For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~BulletWorld.exit` + For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~World.exit` Also contains the code for controlling the camera. """ - def __init__(self, world, type): + def __init__(self, world: World, mode: str): threading.Thread.__init__(self) - self.world: BulletWorld = world - self.type: str = type + self.world = world + self.mode: str = mode def run(self): """ @@ -1573,7 +1442,7 @@ def run(self): if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. """ - if self.type != "GUI": + if self.mode != "GUI": self.world.client_id = p.connect(p.DIRECT) else: self.world.client_id = p.connect(p.GUI) @@ -1808,9 +1677,9 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self.cids: Dict[Object, int] = {} self.original_pose = pose_in_map - self.tf_frame = ("shadow/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) + self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) - # This means "world" is not the shadow world since it has a reference to a shadow world + # This means "world" is not the prospection world since it has a reference to a prospection world if self.world.prospection_world is not None: self.world.world_sync.add_obj_queue.put( [name, type, path, position, orientation, self.world.prospection_world, color, self]) @@ -1851,8 +1720,8 @@ def remove(self) -> None: for obj in self.attachments.keys(): self.world.detach_objects(self, obj) self.world.objects.remove(self) - # This means the current world of the object is not the shadow world, since it - # has a reference to the shadow world + # This means the current world of the object is not the prospection world, since it + # has a reference to the prospection world if self.world.prospection_world is not None: self.world.world_sync.remove_obj_queue.put(self) self.world.world_sync.remove_obj_queue.join() @@ -1905,7 +1774,7 @@ def detach_all(self) -> None: for att in attachments.keys(): self.world.detach_objects(self, att) - def get_position(self) -> Pose: + def get_position(self) -> Pose.position: """ Returns the position of this Object as a list of xyz. @@ -1913,7 +1782,7 @@ def get_position(self) -> Pose: """ return self.get_pose().position - def get_orientation(self) -> Quaternion: + def get_orientation(self) -> Pose.orientation: """ Returns the orientation of this object as a list of xyzw, representing a quaternion. @@ -2105,7 +1974,7 @@ def get_transform_between_two_links(self, source_link_id: int, target_link_id: i target_tf_frame = self.get_link_tf_frame_by_id(target_link_id) return self.local_transformer.lookup_transform_from_source_to_target_frame(source_tf_frame, target_tf_frame) - def get_link_position(self, name: str) -> Point: + def get_link_position(self, name: str) -> Pose.position: """ Returns the position of a link of this Object. Position is returned as a list of xyz. @@ -2269,7 +2138,7 @@ def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, """ return self.world.get_object_color(self, link) - def get_AABB(self) -> Tuple[List[float], List[float]]: + def get_aabb(self) -> Tuple[List[float], List[float]]: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. @@ -2278,7 +2147,7 @@ def get_AABB(self) -> Tuple[List[float], List[float]]: """ return self.world.get_object_AABB(self) - def get_link_AABB(self, link_name: str) -> Tuple[List[float], List[float]]: + def get_link_aabb(self, link_name: str) -> Tuple[List[float], List[float]]: """ Returns the axis aligned bounding box of the given link name. The return of this method are two points in world coordinate frame which define a bounding box. @@ -2295,7 +2164,7 @@ def get_base_origin(self, link_name: Optional[str] = None) -> Pose: :param link_name: The link name for which the bottom position should be returned :return: The position of the bottom of this Object or link """ - aabb = self.get_link_AABB(link_name=link_name) + aabb = self.get_link_aabb(link_name=link_name) base_width = np.absolute(aabb[0][0] - aabb[1][0]) base_length = np.absolute(aabb[0][1] - aabb[1][1]) return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], @@ -2374,7 +2243,7 @@ def get_link_tf_frame(self, link_name: str) -> str: def get_link_tf_frame_by_id(self, link_id: int) -> str: return self.get_link_tf_frame(self.get_link_by_id(link_id)) - def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.Geometry]: + def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: """ Extracts the geometry information for each collision of each link and links them to the respective link. @@ -2450,7 +2319,8 @@ def _get_robot_name_from_urdf(urdf_string: str) -> str: begin = res[0].find("\"") end = res[0][begin + 1:].find("\"") robot = res[0][begin + 1:begin + 1 + end].lower() - return robot + return robot + raise Exception("Robot Name not Found") def _load_object(name: str, @@ -2459,7 +2329,7 @@ def _load_object(name: str, orientation: List[float], world: World, color: List[float], - ignoreCachedFiles: bool) -> Tuple[int, str]: + ignore_cached_files: bool) -> Tuple[int, str]: """ Loads an object to the given World with the given position and orientation. The color will only be used when an .obj or .stl file is given. @@ -2475,7 +2345,7 @@ def _load_object(name: str, :param orientation: The orientation in which the object should be spawned :param world: The World to which the Object should be spawned :param color: The color of the object, only used when .obj or .stl file is given - :param ignoreCachedFiles: Whether to ignore files in the cache directory. + :param ignore_cached_files: Whether to ignore files in the cache directory. :return: The unique id of the object and the path to the file used for spawning """ pa = pathlib.Path(path) @@ -2496,7 +2366,7 @@ def _load_object(name: str, os.mkdir(cach_dir) # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path, name, cach_dir) or ignoreCachedFiles: + if not _is_cached(path, name, cach_dir) or ignore_cached_files: if extension == ".obj" or extension == ".stl": path = _generate_urdf_file(name, path, color, cach_dir) elif extension == ".urdf": @@ -2564,7 +2434,7 @@ def _correct_urdf_string(urdf_string: str) -> str: Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS package paths. - :param urdf_name: The name of the URDf on the parameter server + :param urdf_string: The name of the URDf on the parameter server :return: The URDF string with paths in the filesystem instead of ROS packages """ r = rospkg.RosPack() @@ -2684,13 +2554,13 @@ def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) return cach_dir + pathlib_obj.stem + ".urdf" -def _world_and_id(world: BulletWorld) -> Tuple[BulletWorld, int]: +def _world_and_id(world: World) -> Tuple[World, int]: """ - Selects the world to be used. If the given world is None the 'current_bullet_world' is used. + Selects the world to be used. If the given world is None the 'current_world' is used. - :param world: The world which should be used or None if 'current_bullet_world' should be used - :return: The BulletWorld object and the id of this BulletWorld + :param world: The world which should be used or None if 'current_world' should be used + :return: The World object and the id of this World """ - world = world if world is not None else BulletWorld.current_bullet_world - id = world.client_id if world is not None else BulletWorld.current_bullet_world.client_id + world = world if world is not None else World.current_world + id = world.client_id if world is not None else World.current_world.client_id return world, id diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index d655b8f8c..a849f8a10 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -3,7 +3,7 @@ import numpy as np import rospy -from .world import _world_and_id, Object, Use_shadow_world, BulletWorld +from .world import _world_and_id, Object, UseProspectionWorld, BulletWorld from .external_interfaces.ik import request_ik from .local_transformer import LocalTransformer from .plan_failures import IKError @@ -97,14 +97,14 @@ def stable(object: Object, :return: True if the given object is stable in the world False else """ world, world_id = _world_and_id(world) - shadow_obj = BulletWorld.current_bullet_world.get_shadow_object(object) - with Use_shadow_world(): + shadow_obj = BulletWorld.current_world.get_prospection_object(object) + with UseProspectionWorld(BulletWorld): coords_prev = shadow_obj.pose.position_as_list() - state = p.saveState(physicsClientId=BulletWorld.current_bullet_world.client_id) - p.setGravity(0, 0, -9.8, BulletWorld.current_bullet_world.client_id) + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) # one Step is approximately 1/240 seconds - BulletWorld.current_bullet_world.simulate(2) + BulletWorld.current_world.simulate(2) # coords_past = p.getBasePositionAndOrientation(object.id, physicsClientId=world_id)[0] coords_past = shadow_obj.pose.position_as_list() @@ -128,12 +128,12 @@ def contact(object1: Object, :return: True if the two objects are in contact False else. If links should be returned a list of links in contact """ - with Use_shadow_world(): - shadow_obj1 = BulletWorld.current_bullet_world.get_shadow_object(object1) - shadow_obj2 = BulletWorld.current_bullet_world.get_shadow_object(object2) - p.performCollisionDetection(BulletWorld.current_bullet_world.client_id) + with UseProspectionWorld(BulletWorld): + shadow_obj1 = BulletWorld.current_world.get_prospection_object(object1) + shadow_obj2 = BulletWorld.current_world.get_prospection_object(object2) + p.performCollisionDetection(BulletWorld.current_world.client_id) con_points = p.getContactPoints(shadow_obj1.id, shadow_obj2.id, - physicsClientId=BulletWorld.current_bullet_world.client_id) + physicsClientId=BulletWorld.current_world.client_id) if return_links: contact_links = [] @@ -163,12 +163,12 @@ def visible(object: Object, :return: True if the object is visible from the camera_position False if not """ front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - with Use_shadow_world(): - shadow_obj = BulletWorld.current_bullet_world.get_shadow_object(object) + with UseProspectionWorld(BulletWorld): + shadow_obj = BulletWorld.current_world.get_prospection_object(object) if BulletWorld.robot: - shadow_robot = BulletWorld.current_bullet_world.get_shadow_object(BulletWorld.robot) - state = p.saveState(physicsClientId=BulletWorld.current_bullet_world.client_id) - for obj in BulletWorld.current_bullet_world.objects: + shadow_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + for obj in BulletWorld.current_world.objects: if obj == shadow_obj or BulletWorld.robot and obj == shadow_robot: continue else: @@ -180,15 +180,15 @@ def visible(object: Object, # target_point = p.multiplyTransforms(world_to_cam.translation_as_list(), world_to_cam.rotation_as_list(), cam_to_point.translation_as_list(), [0, 0, 0, 1]) # print(target_point) - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_bullet_world)[2] + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] flat_list = list(itertools.chain.from_iterable(seg_mask)) max_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) - p.restoreState(state, physicsClientId=BulletWorld.current_bullet_world.client_id) + p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) if max_pixel == 0: # Object is not visible return False - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_bullet_world)[2] + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] flat_list = list(itertools.chain.from_iterable(seg_mask)) real_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) @@ -215,9 +215,9 @@ def occluding(object: Object, world, world_id = _world_and_id(world) # occ_world = world.copy() # state = p.saveState(physicsClientId=occ_world.client_id) - with Use_shadow_world(): - state = p.saveState(physicsClientId=BulletWorld.current_bullet_world.client_id) - for obj in BulletWorld.current_bullet_world.objects: + with UseProspectionWorld(BulletWorld): + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + for obj in BulletWorld.current_world.objects: if obj.name == BulletWorld.robot.name: continue elif object.get_pose() == obj.get_pose(): @@ -229,22 +229,22 @@ def occluding(object: Object, cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") target_point = (world_to_cam * cam_to_point).to_pose() - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_bullet_world)[2] + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] # All indices where the object that could be occluded is in the image # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension pix = np.dstack((seg_mask == object.id).nonzero())[0] - p.restoreState(state, physicsClientId=BulletWorld.current_bullet_world.client_id) + p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) occluding = [] - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_bullet_world)[2] + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] for c in pix: if not seg_mask[c[0]][c[1]] == object.id: occluding.append(seg_mask[c[0]][c[1]]) - occ_objects = list(set(map(BulletWorld.current_bullet_world.get_object_by_id, occluding))) - occ_objects = list(map(world.get_bullet_object_for_shadow, occ_objects)) + occ_objects = list(set(map(BulletWorld.current_world.get_object_by_id, occluding))) + occ_objects = list(map(world.get_object_from_prospection, occ_objects)) return occ_objects @@ -267,8 +267,8 @@ def reachable(pose: Union[Object, Pose], if type(pose) == Object: pose = pose.get_pose() - shadow_robot = BulletWorld.current_bullet_world.get_shadow_object(robot) - with Use_shadow_world(): + shadow_robot = BulletWorld.current_world.get_prospection_object(robot) + with UseProspectionWorld(BulletWorld): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints try: @@ -305,8 +305,8 @@ def blocking(pose_or_object: Union[Object, Pose], else: input_pose = pose_or_object - shadow_robot = BulletWorld.current_bullet_world.get_shadow_object(robot) - with Use_shadow_world(): + shadow_robot = BulletWorld.current_world.get_prospection_object(robot) + with UseProspectionWorld(BulletWorld): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints local_transformer = LocalTransformer() @@ -327,9 +327,9 @@ def blocking(pose_or_object: Union[Object, Pose], _apply_ik(shadow_robot, inv, joints) block = [] - for obj in BulletWorld.current_bullet_world.objects: + for obj in BulletWorld.current_world.objects: if contact(shadow_robot, obj): - block.append(BulletWorld.current_bullet_world.get_bullet_object_for_shadow(obj)) + block.append(BulletWorld.current_world.get_object_from_prospection(obj)) return block @@ -357,8 +357,8 @@ def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], l :param link_name: Name of the link for which the pose should be returned :return: The pose of the link after applying the joint configuration """ - shadow_object = BulletWorld.current_bullet_world.get_shadow_object(object) - with Use_shadow_world(): + shadow_object = BulletWorld.current_world.get_prospection_object(object) + with UseProspectionWorld(BulletWorld): for joint, pose in joint_config.items(): shadow_object.set_joint_position(joint, pose) return shadow_object.get_link_pose(link_name) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index fbe4d3605..704711756 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -25,7 +25,7 @@ def setUpClass(cls): ProcessModule.execution_delay = False def setUp(self): - self.world.reset_bullet_world() + self.world.reset_world() def test_object_movement(self): self.milk.set_position(Pose([0, 1, 1])) @@ -39,7 +39,7 @@ def test_robot_orientation(self): self.assertEqual(self.robot.get_link_position('head_pan_link').z, head_position) def tearDown(self): - self.world.reset_bullet_world() + self.world.reset_world() @classmethod def tearDownClass(cls): diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 124057c4d..993dea9bc 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -79,7 +79,7 @@ def test_costmap_with_obstacles(self): raise pycram.plan_failures.PlanFailure() def tearDown(self) -> None: - self.world.reset_bullet_world() + self.world.reset_world() @classmethod def tearDownClass(cls) -> None: diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 5a9101ebe..9da659e5b 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -89,7 +89,7 @@ def test_costmap_with_obstacles(self): raise pycram.plan_failures.PlanFailure() def tearDown(self) -> None: - self.world.reset_bullet_world() + self.world.reset_world() @classmethod def tearDownClass(cls) -> None: diff --git a/test/test_task_tree.py b/test/test_task_tree.py index abe3f3ab8..5648ddf00 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -65,7 +65,7 @@ def failing_plan(): def test_execution(self): self.plan() - self.world.reset_bullet_world() + self.world.reset_world() tt = pycram.task.task_tree # self.setUpBulletWorld(False) with simulated_robot: From 2d834a42352f618313f3113397e493072d8b3812 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 11 Dec 2023 16:51:33 +0100 Subject: [PATCH 013/195] [AbstractWorld] Completed world.py refactoring, tests are passing except test_attachment_exclusion in test_costmap.py. --- src/pycram/costmaps.py | 6 +- src/pycram/designator.py | 16 +- src/pycram/designators/action_designator.py | 8 +- src/pycram/designators/location_designator.py | 4 +- src/pycram/designators/motion_designator.py | 6 +- src/pycram/designators/object_designator.py | 9 +- src/pycram/enums.py | 3 + src/pycram/external_interfaces/robokudo.py | 4 +- src/pycram/orm/object_designator.py | 2 +- .../process_modules/boxy_process_modules.py | 2 +- .../process_modules/donbot_process_modules.py | 2 +- .../process_modules/hsr_process_modules.py | 2 +- .../process_modules/pr2_process_modules.py | 2 +- .../resolver/location/database_location.py | 2 +- .../resolver/location/giskard_location.py | 2 +- src/pycram/resolver/location/jpt_location.py | 2 +- src/pycram/task.py | 4 +- src/pycram/world.py | 228 ++++++++++-------- src/pycram/world_reasoning.py | 14 +- test/local_transformer_tests.py | 8 +- test/test_action_designator.py | 3 +- test/test_object_designator.py | 2 +- 22 files changed, 175 insertions(+), 156 deletions(-) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 86017cdbd..080d31c71 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -385,7 +385,7 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: i = 0 j = 0 for n in self._chunks(np.array(rays), 16380): - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, physicsClientId=BulletWorld.current_world.client_id) while r_t is None: @@ -494,7 +494,7 @@ def _create_images(self) -> List[np.ndarray]: images = [] camera_pose = self.origin - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): origin_copy = self.origin.copy() origin_copy.position.y += 1 images.append( @@ -726,7 +726,7 @@ def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: :return: Two points in world coordinate space, which span a rectangle """ shadow_obj = BulletWorld.current_world.get_prospection_object(self.object) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): shadow_obj.set_orientation(Pose(orientation=[0, 0, 0, 1])) link_orientation = shadow_obj.get_link_pose(self.link) link_orientation_trans = link_orientation.to_transform(self.object.get_link_tf_frame(self.link)) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 3329fba27..d7c7a670d 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -487,7 +487,7 @@ class Action: def __post_init__(self): self.robot_position = BulletWorld.robot.get_pose() self.robot_torso_height = BulletWorld.robot.get_joint_position(robot_description.torso_joint) - self.robot_type = BulletWorld.robot.type + self.robot_type = BulletWorld.robot.obj_type @with_tree def perform(self) -> Any: @@ -596,7 +596,7 @@ class Object: Name of the object """ - type: str + obj_type: str """ Type of the object """ @@ -622,7 +622,7 @@ def to_sql(self) -> ORMObjectDesignator: :return: The created ORM object. """ - return ORMObjectDesignator(self.type, self.name) + return ORMObjectDesignator(self.obj_type, self.name) def insert(self, session: Session) -> ORMObjectDesignator: """ @@ -651,7 +651,7 @@ def data_copy(self) -> 'ObjectDesignatorDescription.Object': object is not copied. The _pose gets set to a method that statically returns the pose of the object when this method was called. """ - result = ObjectDesignatorDescription.Object(self.name, self.type, None) + result = ObjectDesignatorDescription.Object(self.name, self.obj_type, None) # get current object pose and set resulting pose to always be that pose = self.pose result.pose = lambda: pose @@ -693,8 +693,8 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: pose_in_object = lt.transform_pose_to_target_frame(pose, self.bullet_world_object.tf_frame) special_knowledge = [] # Initialize as an empty list - if self.type in SPECIAL_KNOWLEDGE: - special_knowledge = SPECIAL_KNOWLEDGE[self.type] + if self.obj_type in SPECIAL_KNOWLEDGE: + special_knowledge = SPECIAL_KNOWLEDGE[self.obj_type] for key, value in special_knowledge: if key == grasp: @@ -760,7 +760,7 @@ def __iter__(self) -> Iterable[Object]: continue # skip if type does not match specification - if self.types and obj.type not in self.types: + if self.types and obj.obj_type not in self.types: continue - yield self.Object(obj.name, obj.type, obj) \ No newline at end of file + yield self.Object(obj.name, obj.obj_type, obj) \ No newline at end of file diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index b92363bf1..c44f496ab 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -401,8 +401,10 @@ def ground(self) -> Action: :return: A performable designator """ - obj_desig = self.object_designator_description if isinstance(self.object_designator_description, - ObjectDesignatorDescription.Object) else self.object_designator_description.resolve() + if isinstance(self.object_designator_description, ObjectDesignatorDescription.Object): + obj_desig = self.object_designator_description + else: + obj_desig = self.object_designator_description.resolve() return self.Action(obj_desig, self.arms[0], self.grasps[0]) @@ -702,7 +704,7 @@ class Action(ActionDesignatorDescription.Action): @with_tree def perform(self) -> Any: - return DetectingMotion(object_type=self.object_designator.type).resolve().perform() + return DetectingMotion(object_type=self.object_designator.obj_type).resolve().perform() def to_sql(self) -> ORMDetectAction: return ORMDetectAction() diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 99c2a4b0e..aae10e4b7 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -182,7 +182,7 @@ def __iter__(self): robot_object = self.visible_for.bullet_world_object if self.visible_for else self.reachable_for.bullet_world_object test_robot = BulletWorld.current_world.get_prospection_object(robot_object) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): for maybe_pose in pose_generator(final_map, number_of_samples=600): res = True @@ -275,7 +275,7 @@ def __iter__(self) -> Location: container_joint: self.handle.bullet_world_object.get_joint_limits(container_joint)[1] / 1.5}, self.handle.name) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): for maybe_pose in pose_generator(final_map, number_of_samples=600, orientation_generator=lambda p, o: generate_orientation(p, half_pose)): diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 8d618ed20..f148aee18 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -385,10 +385,10 @@ def perform(self): raise PerceptionObjectNotFound( f"Could not find an object with the type {self.object_type} in the FOV of the robot") if ProcessModuleManager.execution_type == "real": - return RealObject.Object(bullet_world_object.name, bullet_world_object.type, - bullet_world_object, bullet_world_object.get_pose()) + return RealObject.Object(bullet_world_object.name, bullet_world_object.obj_type, + bullet_world_object, bullet_world_object.get_pose()) - return ObjectDesignatorDescription.Object(bullet_world_object.name, bullet_world_object.type, + return ObjectDesignatorDescription.Object(bullet_world_object.name, bullet_world_object.obj_type, bullet_world_object) def to_sql(self) -> ORMDetectingMotion: diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 0b063ac9f..8d87c4936 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -21,7 +21,7 @@ class Object(ObjectDesignatorDescription.Object): """ def to_sql(self) -> ORMBelieveObject: - return ORMBelieveObject(self.type, self.name) + return ORMBelieveObject(self.obj_type, self.name) def insert(self, session: sqlalchemy.orm.session.Session) -> ORMBelieveObject: self_ = self.to_sql() @@ -44,7 +44,7 @@ class Object(ObjectDesignatorDescription.Object): part_pose: Pose def to_sql(self) -> ORMObjectPart: - return ORMObjectPart(self.type, self.name) + return ORMObjectPart(self.obj_type, self.name) def insert(self, session: sqlalchemy.orm.session.Session) -> ORMObjectPart: obj = self.to_sql() @@ -169,9 +169,6 @@ def __iter__(self): """ object_candidates = query(self) for obj_desig in object_candidates: - for bullet_obj in BulletWorld.get_objects_by_type(obj_desig.type): + for bullet_obj in BulletWorld.get_objects_by_type(obj_desig.obj_type): obj_desig.bullet_world_object = bullet_obj yield obj_desig - # if bullet_obj.get_pose().dist(obj_deisg.pose) < 0.05: - # obj_deisg.bullet_world_object = bullet_obj - # yield obj_deisg diff --git a/src/pycram/enums.py b/src/pycram/enums.py index dc0dc6ed5..40257a3c2 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -30,6 +30,9 @@ class JointType(Enum): PLANAR = 3 FIXED = 4 + def as_int(self): + return self.value + class Grasp(Enum): """ diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index c6e897af8..9e0164978 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -85,7 +85,7 @@ def msg_from_obj_desig(obj_desc: ObjectDesignatorDescription) -> 'robokudo_Objet """ obj_msg = robokudo_ObjetDesignator() obj_msg.uid = str(id(obj_desc)) - obj_msg.type = obj_desc.types[0] # For testing purposes + obj_msg.obj_type = obj_desc.types[0] # For testing purposes return obj_msg @@ -99,7 +99,7 @@ def make_query_goal_msg(obj_desc: ObjectDesignatorDescription) -> 'QueryGoal': """ goal_msg = QueryGoal() goal_msg.obj.uid = str(id(obj_desc)) - goal_msg.obj.type = str(obj_desc.types[0].name) # For testing purposes + goal_msg.obj.obj_type = str(obj_desc.types[0].name) # For testing purposes if ObjectType.JEROEN_CUP == obj_desc.types[0]: goal_msg.obj.color.append("blue") elif ObjectType.BOWL == obj_desc.types[0]: diff --git a/src/pycram/orm/object_designator.py b/src/pycram/orm/object_designator.py index 78a584282..fad1d3c6e 100644 --- a/src/pycram/orm/object_designator.py +++ b/src/pycram/orm/object_designator.py @@ -26,7 +26,7 @@ class Object(PoseMixin, Base): """ORM class of pycram.designators.object_designator.ObjectDesignator""" dtype: Mapped[str] = mapped_column(init=False) - type: Mapped[ObjectType] + obj_type: Mapped[ObjectType] name: Mapped[str] __mapper_args__ = { diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index e1314e41c..41c93f0fe 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -283,7 +283,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] class BoxyManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index d893d8048..1d1320cfd 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -240,7 +240,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] class DonbotManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 09b715e1c..62120af7c 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -213,7 +213,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] class HSRManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 3432533d0..bcadb46ec 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -205,7 +205,7 @@ class Pr2WorldStateDetecting(ProcessModule): def _execute(self, desig: WorldStateDetectingMotion.Motion): obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] class Pr2Open(ProcessModule): diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index b4e92c075..392fab35c 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -54,7 +54,7 @@ def create_query_from_occupancy_costmap(self) -> sqlalchemy.orm.Query: join(filtered_tasks, filtered_tasks.c.code == filtered_code.c.id).subquery() # filter all objects that have the same type as the target - filtered_objects = self.session.query(Object).filter(Object.type == self.target.type).\ + filtered_objects = self.session.query(Object).filter(Object.obj_type == self.target.obj_type).\ subquery() query = self.session.query(PickUpAction.arm, PickUpAction.grasp, diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 2a2840f36..5c891b4e0 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -29,7 +29,7 @@ def __iter__(self) -> CostmapLocation.Location: robot_description.get_tool_frame("left")) test_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): valid, arms = reachability_validator(pose_right, test_robot, self.target, {}) if valid: yield CostmapLocation.Location(pose_right, arms) diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 5c7bf1bae..748f559bb 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -116,7 +116,7 @@ def create_evidence(self, use_success=True) -> jpt.variables.LabelAssignment: """ evidence = dict() - evidence["type"] = {self.target.type} + evidence["type"] = {self.target.obj_type} if use_success: evidence["status"] = {"SUCCEEDED"} diff --git a/src/pycram/task.py b/src/pycram/task.py index 7ec966918..aa21f41a0 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -254,7 +254,7 @@ def __enter__(self): def simulation(): return None self.suspended_tree = task_tree - self.world_state, self.objects2attached = BulletWorld.current_world.save_state() + self.world_state = BulletWorld.current_world.save_state() self.simulated_root = TaskTreeNode(code=Code(simulation)) task_tree = self.simulated_root pybullet.addUserDebugText("Simulating...", [0, 0, 1.75], textColorRGB=[0, 0, 0], @@ -267,7 +267,7 @@ def __exit__(self, exc_type, exc_val, exc_tb): """ global task_tree task_tree = self.suspended_tree - BulletWorld.current_world.restore_state(self.world_state, self.objects2attached) + BulletWorld.current_world.restore_state(self.world_state) pybullet.removeAllUserDebugItems() diff --git a/src/pycram/world.py b/src/pycram/world.py index c78b1eeb5..413a44492 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -42,6 +42,7 @@ def __init__(self, parent_link_id: Optional[int] = -1, # -1 means base link child_link_id: Optional[int] = -1, bidirectional: Optional[bool] = False, + child_to_parent_transform: Optional[Transform] = None, constraint_id: Optional[int] = None): """ Creates an attachment between the parent object and the child object. @@ -51,28 +52,41 @@ def __init__(self, self.parent_link_id = parent_link_id self.child_link_id = child_link_id self.bidirectional = bidirectional - self.child_to_parent_transform = self.calculate_transforms() self._loose = False and not self.bidirectional - self.constraint_id = self.update_constraint() if constraint_id is None else constraint_id + + self.child_to_parent_transform = child_to_parent_transform + if self.child_to_parent_transform is None: + self.update_transform() + + self.constraint_id = constraint_id + if self.constraint_id is None: + self.add_constraint_and_update_objects_constraints_collection() def update_attachment(self): - self.update_transforms() + self.update_transform() self.update_constraint() - self.update_objects_attachments_collection() - def update_transforms(self): - self.child_to_parent_transform = self.calculate_transforms() + def update_transform(self): + self.child_to_parent_transform = self.calculate_transform() def update_constraint(self): + self.remove_constraint_if_exists() + self.add_constraint_and_update_objects_constraints_collection() + + def calculate_transform(self): + relative_pose = self.parent_object.get_other_object_link_pose_relative_to_my_link(self.parent_link_id, + self.child_link_id, + self.child_object) + return relative_pose.to_transform(self.child_object.get_link_tf_frame_by_id(self.child_link_id)) + + def remove_constraint_if_exists(self): if self.constraint_id is not None: self.parent_object.world.remove_constraint(self.constraint_id) + + def add_constraint_and_update_objects_constraints_collection(self): self.constraint_id = self.add_fixed_constraint() self.update_objects_constraints_collection() - def update_objects_attachments_collection(self): - self.parent_object.attachments[self.child_object] = self - self.child_object.attachments[self.parent_object] = self.get_inverse() - def add_fixed_constraint(self): constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, self.child_object.id, @@ -87,13 +101,11 @@ def update_objects_constraints_collection(self): def get_inverse(self): attachment = Attachment(self.child_object, self.parent_object, self.child_link_id, - self.parent_link_id, self.bidirectional, self.constraint_id) + self.parent_link_id, self.bidirectional, self.child_to_parent_transform.invert(), + self.constraint_id) attachment.loose = False if self.loose else True return attachment - def calculate_transforms(self): - return self.parent_object.get_transform_between_two_links(self.parent_link_id, self.child_link_id) - @property def loose(self) -> bool: """ @@ -153,7 +165,7 @@ class World(ABC): URDF with the name of the URDF on the parameter server. """ - data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} + data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] """ Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ @@ -169,16 +181,19 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" :param is_prospection_world: For internal usage, decides if this World should be used as a prospection world. """ + + self._init_current_world_and_simulation_time_step(simulation_time_step) + # init the current world and simulation time step which are class variables. + self.objects: List[Object] = [] self.client_id: int = -1 self.mode: str = mode + self._init_events() - World.current_world = self if World.current_world is None else World.current_world self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} self.local_transformer = LocalTransformer() self.is_prospection_world: bool = is_prospection_world - if is_prospection_world: # then no need to add another prospection world self.prospection_world = None self.world_sync = None @@ -186,9 +201,12 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self._init_and_sync_prospection_world() self._update_local_transformer_worlds() + self._saved_states: Dict[int, WorldState] = {} + # Different states of the world indexed by int state id. + + def _init_current_world_and_simulation_time_step(self, simulation_time_step): + World.current_world = self if World.current_world is None else World.current_world World.simulation_time_step = simulation_time_step - self.simulation_frequency = int(1/self.simulation_time_step) - self._saved_states: Dict[int, WorldState] = {} # Different states of the world indexed by int state id. def _init_events(self): self.detachment_event: Event = Event() @@ -203,13 +221,18 @@ def _update_local_transformer_worlds(self): self.local_transformer.world = self self.local_transformer.prospection_world = self.prospection_world - def _init_prospection_world(self): - self.prospection_world: World = World("DIRECT", True) + @classmethod + def _init_prospection_world(cls): + cls.prospection_world: World = cls("DIRECT", True) def _sync_prospection_world(self): self.world_sync: WorldSync = WorldSync(self, self.prospection_world) self.world_sync.start() + @property + def simulation_frequency(self): + return int(1/World.simulation_time_step) + @abstractmethod def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: pass @@ -230,7 +253,7 @@ def get_objects_by_type(self, obj_type: str) -> List[Object]: :param obj_type: The type of the returned Objects. :return: A list of all Objects that have the type 'obj_type'. """ - return list(filter(lambda obj: obj.type == obj_type, self.objects)) + return list(filter(lambda obj: obj.obj_type == obj_type, self.objects)) def get_object_by_id(self, id: int) -> Object: """ @@ -266,6 +289,7 @@ def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: continue if not parent.attachments[child].bidirectional: parent.attachments[child].update_attachment() + child.attachments[parent].update_attachment() else: link_to_object = parent.attachments[child].child_to_parent_transform @@ -290,9 +314,17 @@ def attach_objects(self, """ # Add the attachment to the attachment dictionary of both objects - Attachment(parent_object, child_object, parent_link_id, child_link_id, bidirectional) + attachment = Attachment(parent_object, child_object, parent_link_id, child_link_id, bidirectional) + self.update_objects_attachments_collection(parent_object, child_object, attachment) self.attachment_event(parent_object, [parent_object, child_object]) + def update_objects_attachments_collection(self, + parent_object: Object, + child_object: Object, + attachment: Attachment) -> None: + parent_object.attachments[child_object] = attachment + child_object.attachments[parent_object] = attachment.get_inverse() + def add_fixed_constraint(self, parent_object_id: int, child_object_id: int, @@ -629,7 +661,7 @@ def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: pass @abstractmethod - def get_object_link_AABB(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -827,7 +859,7 @@ def _copy(self) -> World: """ world = BulletWorld("DIRECT") for obj in self.objects: - o = Object(obj.name, obj.type, obj.path, Pose(obj.get_position(), obj.get_orientation()), + o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), world, obj.color) for joint in obj.joints: o.set_joint_position(joint, obj.get_joint_position(joint)) @@ -915,7 +947,7 @@ def update_transforms_for_objects_in_current_world(self) -> None: """ curr_time = rospy.Time.now() for obj in list(self.current_world.objects): - obj._update_link_transforms(curr_time) + obj.update_link_transforms(curr_time) class BulletWorld(World): @@ -925,25 +957,6 @@ class is the main interface to the Bullet Physics Engine and should be used to s manipulate the Bullet World. """ - current_world: BulletWorld = None - """ - Global reference to the currently used World, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the - shadow world. In this way you can comfortably use the current_world, which should point towards the World - used at the moment. - """ - - robot: Object = None - """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name - in the URDF with the name of the URDF on the parameter server. - """ - - data_directory: List[str] = {os.path.dirname(__file__) + "/../../resources"} - """ - Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. - """ - # Check is for sphinx autoAPI to be able to work in a CI workflow if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): rospy.init_node('pycram') @@ -998,7 +1011,7 @@ def add_constraint(self, constraint: Constraint) -> int: constraint.parent_link_id, constraint.child_obj_id, constraint.child_link_id, - constraint.joint_type, + constraint.joint_type.as_int(), constraint.joint_axis_in_child_link_frame, constraint.joint_frame_position_wrt_parent_origin, constraint.joint_frame_position_wrt_child_origin, @@ -1071,7 +1084,7 @@ def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List] return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] def get_object_contact_points(self, obj: Object) -> List: - """ + """l.update_transforms_for_object(self.milk) Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned list please look at `PyBullet Doc `_ @@ -1187,7 +1200,7 @@ def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: """ return p.getAABB(obj.id, physicsClientId=self.client_id) - def get_object_link_AABB(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -1259,7 +1272,7 @@ def restore_physics_simulator_state(self, state_id): Restores the objects and environment state in the physics simulator according to the given state using the unique state id. """ - p.restoreState(state_id, self.client_id) + p.restoreState(state_id, physicsClientId=self.client_id) def add_vis_axis(self, pose: Pose, length: Optional[float] = 0.2) -> None: @@ -1312,27 +1325,23 @@ class UseProspectionWorld: NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() """ - def __init__(self, world_impl: Type[World]): - """ - :param world_impl: A class that implements a World (for example BulletWorld). - """ - self.world_impl = world_impl - self.prev_world: type(world_impl) = None + def __init__(self): + self.prev_world: World = None def __enter__(self): - if not self.world_impl.current_world.is_prospection_world: - time.sleep(20 * self.world_impl.simulation_time_step) + if not World.current_world.is_prospection_world: + time.sleep(20 * World.simulation_time_step) # blocks until the adding queue is ready - self.world_impl.current_world.world_sync.add_obj_queue.join() + World.current_world.world_sync.add_obj_queue.join() - self.prev_world = self.world_impl.current_world - self.world_impl.current_world.world_sync.pause_sync = True - self.world_impl.current_world = self.world_impl.current_world.prospection_world + self.prev_world = World.current_world + World.current_world.world_sync.pause_sync = True + World.current_world = World.current_world.prospection_world def __exit__(self, *args): if self.prev_world is not None: - self.world_impl.current_world = self.prev_world - self.world_impl.current_world.world_sync.pause_sync = False + World.current_world = self.prev_world + World.current_world.world_sync.pause_sync = False class WorldSync(threading.Thread): @@ -1643,34 +1652,35 @@ class Object: Represents a spawned Object in the World. """ - def __init__(self, name: str, type: Union[str, ObjectType], path: str, + # TODO: make a color dataclass or change initialization of color to be non mutable + def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: Pose = None, world: World = None, color: Optional[List[float]] = [1, 1, 1, 1], - ignoreCachedFiles: Optional[bool] = False): + ignore_cached_files: Optional[bool] = False): """ The constructor loads the urdf file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object - :param type: The type of the object + :param obj_type: The type of the object :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched :param pose: The pose at which the Object should be spawned :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used :param color: The color with which the object should be spawned. - :param ignoreCachedFiles: If true the file will be spawned while ignoring cached files. + :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ if not pose: pose = Pose() self.world: World = world if world is not None else World.current_world self.local_transformer = LocalTransformer() self.name: str = name - self.type: str = type + self.obj_type: Union[str, ObjectType] = obj_type self.color: List[float] = color pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() - self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignoreCachedFiles) + self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") self.attachments: Dict[Object, Attachment] = {} @@ -1682,7 +1692,7 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, # This means "world" is not the prospection world since it has a reference to a prospection world if self.world.prospection_world is not None: self.world.world_sync.add_obj_queue.put( - [name, type, path, position, orientation, self.world.prospection_world, color, self]) + [name, obj_type, path, position, orientation, self.world.prospection_world, color, self]) with open(self.path) as f: self.urdf_object = URDF.from_xml_string(f.read()) @@ -1696,14 +1706,21 @@ def __init__(self, name: str, type: Union[str, ObjectType], path: str, self._current_link_transforms: Dict[str, Transform] = {} self._current_joints_positions = {} self._init_current_positions_of_joint() - self._update_link_poses() + self._update_current_link_poses_and_transforms() self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) - self._update_link_transforms() - self.link_to_geometry = self._get_geometry_for_link() + self.update_link_transforms() + self.link_to_geometry = self.get_geometry_for_link() self.world.objects.append(self) + def _init_current_positions_of_joint(self) -> None: + """ + Initialize the cached joint position for each joint. + """ + for joint_name in self.joints.keys(): + self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) + def __repr__(self): skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", "_current_link_transforms", "link_to_geometry"] @@ -1811,7 +1828,7 @@ def set_pose(self, pose: Pose, base: bool = False) -> None: position = np.array(position) + self.base_origin_shift self.world.reset_object_base_pose(self, position, orientation) self._current_pose = pose_in_map - self._update_link_poses() + self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) @property @@ -1957,21 +1974,28 @@ def get_joint_by_id(self, joint_id: int) -> str: """ return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] - def get_link_pose_relative_to_other_link(self, child_link_name: str, parent_link_name: str) -> Pose: + def get_other_object_link_pose_relative_to_my_link(self, + my_link_id: int, + other_link_id: int, + other_object: Object) -> Pose: """ Calculates the pose of a link (child_link) in the coordinate frame of another link (parent_link). :return: The pose of the source frame in the target frame """ - child_link_pose = self.get_link_pose(child_link_name) - parent_link_frame = self.get_link_tf_frame(parent_link_name) + + child_link_pose = other_object.get_link_pose(other_object.get_link_by_id(other_link_id)) + parent_link_frame = self.get_link_tf_frame(self.get_link_by_id(my_link_id)) return self.local_transformer.transform_pose_to_target_frame(child_link_pose, parent_link_frame) - def get_transform_between_two_links(self, source_link_id: int, target_link_id: int) -> Transform: + def get_transform_of_other_object_link_relative_to_my_link(self, + my_link_id: int, + other_object: Object, + other_link_id: int) -> Transform: """ Calculates the transform from source link frame to target link frame. """ - source_tf_frame = self.get_link_tf_frame_by_id(source_link_id) - target_tf_frame = self.get_link_tf_frame_by_id(target_link_id) + source_tf_frame = self.get_link_tf_frame_by_id(my_link_id) + target_tf_frame = other_object.get_link_tf_frame_by_id(other_link_id) return self.local_transformer.lookup_transform_from_source_to_target_frame(source_tf_frame, target_tf_frame) def get_link_position(self, name: str) -> Pose.position: @@ -2026,8 +2050,7 @@ def set_joint_position(self, joint_name: str, joint_pose: float) -> None: # return self.world.reset_joint_position(self, joint_name, joint_pose) self._current_joints_positions[joint_name] = joint_pose - # self.local_transformer.update_transforms_for_object(self) - self._update_link_poses() + self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) def set_positions_of_all_joints(self, joint_poses: dict) -> None: @@ -2041,7 +2064,7 @@ def set_positions_of_all_joints(self, joint_poses: dict) -> None: for joint_name, joint_pose in joint_poses.items(): self.world.reset_joint_position(self, joint_name, joint_pose) self._current_joints_positions[joint_name] = joint_pose - self._update_link_poses() + self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) def get_joint_position(self, joint_name: str) -> float: @@ -2155,16 +2178,15 @@ def get_link_aabb(self, link_name: str) -> Tuple[List[float], List[float]]: :param link_name: The name of a link of this object. :return: Two lists of x,y,z which define the bounding box. """ - return self.world.get_object_link_AABB(self, link_name) + return self.world.get_object_link_aabb(self, link_name) - def get_base_origin(self, link_name: Optional[str] = None) -> Pose: + def get_base_origin(self) -> Pose: """ - Returns the origin of the base/bottom of an object/link + Returns the origin of the base/bottom of an object - :param link_name: The link name for which the bottom position should be returned - :return: The position of the bottom of this Object or link + :return: The position of the bottom of this Object """ - aabb = self.get_link_aabb(link_name=link_name) + aabb = self.get_link_aabb(link_name=self.urdf_object.get_root()) base_width = np.absolute(aabb[0][0] - aabb[1][0]) base_length = np.absolute(aabb[0][1] - aabb[1][1]) return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], @@ -2243,7 +2265,7 @@ def get_link_tf_frame(self, link_name: str) -> str: def get_link_tf_frame_by_id(self, link_id: int) -> str: return self.get_link_tf_frame(self.get_link_by_id(link_id)) - def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: + def get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: """ Extracts the geometry information for each collision of each link and links them to the respective link. @@ -2258,28 +2280,28 @@ def _get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType] link_to_geometry[link] = link_obj.collision.geometry return link_to_geometry - def _update_link_transforms(self, transform_time: Optional[rospy.Time] = None): + def update_link_transforms(self, transform_time: Optional[rospy.Time] = None): self.local_transformer.update_transforms(self._current_link_transforms.values(), transform_time) - def _update_link_poses(self) -> None: + def _update_current_link_poses_and_transforms(self) -> None: """ Updates the cached poses and transforms for each link of this Object """ for link_name in self.links.keys(): if link_name == self.urdf_object.get_root(): - self._current_link_poses[link_name] = self._current_pose - self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) + self._update_root_link_pose_and_transform() else: - self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) - self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( - self.get_link_tf_frame(link_name)) + self._update_link_pose_and_transform(link_name) - def _init_current_positions_of_joint(self) -> None: - """ - Initialize the cached joint position for each joint. - """ - for joint_name in self.joints.keys(): - self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) + def _update_root_link_pose_and_transform(self) -> None: + link_name = self.urdf_object.get_root() + self._current_link_poses[link_name] = self._current_pose + self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) + + def _update_link_pose_and_transform(self, link_name: str) -> None: + self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) + self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( + self.get_link_tf_frame(link_name)) def filter_contact_points(contact_points, exclude_ids) -> List: diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index a849f8a10..369760991 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -98,7 +98,7 @@ def stable(object: Object, """ world, world_id = _world_and_id(world) shadow_obj = BulletWorld.current_world.get_prospection_object(object) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): coords_prev = shadow_obj.pose.position_as_list() state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) @@ -128,7 +128,7 @@ def contact(object1: Object, :return: True if the two objects are in contact False else. If links should be returned a list of links in contact """ - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): shadow_obj1 = BulletWorld.current_world.get_prospection_object(object1) shadow_obj2 = BulletWorld.current_world.get_prospection_object(object2) p.performCollisionDetection(BulletWorld.current_world.client_id) @@ -163,7 +163,7 @@ def visible(object: Object, :return: True if the object is visible from the camera_position False if not """ front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): shadow_obj = BulletWorld.current_world.get_prospection_object(object) if BulletWorld.robot: shadow_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) @@ -215,7 +215,7 @@ def occluding(object: Object, world, world_id = _world_and_id(world) # occ_world = world.copy() # state = p.saveState(physicsClientId=occ_world.client_id) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) for obj in BulletWorld.current_world.objects: if obj.name == BulletWorld.robot.name: @@ -268,7 +268,7 @@ def reachable(pose: Union[Object, Pose], pose = pose.get_pose() shadow_robot = BulletWorld.current_world.get_prospection_object(robot) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints try: @@ -306,7 +306,7 @@ def blocking(pose_or_object: Union[Object, Pose], input_pose = pose_or_object shadow_robot = BulletWorld.current_world.get_prospection_object(robot) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints local_transformer = LocalTransformer() @@ -358,7 +358,7 @@ def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], l :return: The pose of the link after applying the joint configuration """ shadow_object = BulletWorld.current_world.get_prospection_object(object) - with UseProspectionWorld(BulletWorld): + with UseProspectionWorld(): for joint, pose in joint_config.items(): shadow_object.set_joint_position(joint, pose) return shadow_object.get_link_pose(link_name) diff --git a/test/local_transformer_tests.py b/test/local_transformer_tests.py index b3f3b8bd1..d39296395 100644 --- a/test/local_transformer_tests.py +++ b/test/local_transformer_tests.py @@ -1,11 +1,7 @@ -import unittest import rospy -from time import sleep -from src.pycram.world import BulletWorld, Object -from src.pycram.local_transformer import LocalTransformer -from pycram.robot_descriptions import robot_description +from pycram.local_transformer import LocalTransformer from pycram.pose import Pose, Transform import test_bullet_world @@ -44,7 +40,7 @@ def test_transform_pose_position(self): def test_update_for_object(self): l = LocalTransformer() self.milk.set_pose(Pose([1, 2, 1])) - l.update_transforms_for_object(self.milk) + self.milk.update_link_transforms() self.assertTrue(l.canTransform("map", self.milk.tf_frame, rospy.Time(0))) diff --git a/test/test_action_designator.py b/test/test_action_designator.py index e196bb51e..e5bf75c46 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -87,14 +87,13 @@ def test_look_at(self): def test_detect(self): self.kitchen.set_pose(Pose([10, 10, 0])) self.milk.set_pose(Pose([1.5, 0, 1.2])) - # time.sleep(1) object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) description = action_designator.DetectAction(object_description) self.assertEqual(description.ground().object_designator.name, "milk") with simulated_robot: detected_object = description.resolve().perform() self.assertEqual(detected_object.name, "milk") - self.assertEqual(detected_object.mode, ObjectType.MILK) + self.assertEqual(detected_object.obj_type, ObjectType.MILK) self.assertEqual(detected_object.bullet_world_object, self.milk) # Skipped since open and close work only in the apartment at the moment diff --git a/test/test_object_designator.py b/test/test_object_designator.py index fa2079e5b..ae7ff0c52 100644 --- a/test/test_object_designator.py +++ b/test/test_object_designator.py @@ -11,7 +11,7 @@ def test_object_grounding(self): obj = description.ground() self.assertEqual(obj.name, "milk") - self.assertEqual(obj.type, ObjectType.MILK) + self.assertEqual(obj.obj_type, ObjectType.MILK) def test_data_copy(self): description = ObjectDesignatorDescription(["milk"], [ObjectType.MILK]) From 534390d3d1f6d2d373729b42372b57796c290c47 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 11 Dec 2023 17:04:47 +0100 Subject: [PATCH 014/195] [AbstractWorld] some cleaning up. --- src/pycram/local_transformer.py | 2 ++ src/pycram/world.py | 19 +++++++------------ 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 05d149277..7ed2c3fd7 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -78,6 +78,8 @@ def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union return Pose(*copy_pose.to_list(), frame=new_pose.header.frame_id) + # TODO: This is not working correctly, the lookup fails to find the frames, + # this is probably because the frames are not published. def lookup_transform_from_source_to_target_frame(self, source_frame: str, target_frame: str, time: Optional[rospy.rostime.Time] = None) -> Transform: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index 413a44492..0b234aae1 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -74,10 +74,9 @@ def update_constraint(self): self.add_constraint_and_update_objects_constraints_collection() def calculate_transform(self): - relative_pose = self.parent_object.get_other_object_link_pose_relative_to_my_link(self.parent_link_id, - self.child_link_id, - self.child_object) - return relative_pose.to_transform(self.child_object.get_link_tf_frame_by_id(self.child_link_id)) + return self.parent_object.get_transform_of_other_object_link_relative_to_my_link(self.parent_link_id, + self.child_link_id, + self.child_object) def remove_constraint_if_exists(self): if self.constraint_id is not None: @@ -1989,14 +1988,10 @@ def get_other_object_link_pose_relative_to_my_link(self, def get_transform_of_other_object_link_relative_to_my_link(self, my_link_id: int, - other_object: Object, - other_link_id: int) -> Transform: - """ - Calculates the transform from source link frame to target link frame. - """ - source_tf_frame = self.get_link_tf_frame_by_id(my_link_id) - target_tf_frame = other_object.get_link_tf_frame_by_id(other_link_id) - return self.local_transformer.lookup_transform_from_source_to_target_frame(source_tf_frame, target_tf_frame) + other_link_id: int, + other_object: Object) -> Transform: + pose = self.get_other_object_link_pose_relative_to_my_link(my_link_id, other_link_id, other_object) + return pose.to_transform(other_object.get_link_tf_frame_by_id(other_link_id)) def get_link_position(self, name: str) -> Pose.position: """ From e2e2f12045bd5576765397ff8f12346909bd89f5 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 11 Dec 2023 17:58:48 +0100 Subject: [PATCH 015/195] [AbstractWorld] Moved BulletWorld and GUI classes to bullet_world.py, removed pybullet dependency from world.py, tests are running except test_attachment_exclusion in test_costmaps.py --- demos/pycram_bullet_world_demo/demo.py | 2 +- demos/pycram_ur5_demo/demo.py | 3 +- doc/source/notebooks/bullet_world.ipynb | 2 +- src/pycram/bullet_world.py | 593 +++++++++++++ src/pycram/costmaps.py | 3 +- src/pycram/designator.py | 3 +- src/pycram/designators/action_designator.py | 2 +- src/pycram/designators/location_designator.py | 3 +- src/pycram/designators/motion_designator.py | 3 +- src/pycram/designators/object_designator.py | 3 +- src/pycram/external_interfaces/giskard.py | 3 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/pose_generator_and_validator.py | 3 +- .../process_modules/boxy_process_modules.py | 2 +- .../process_modules/donbot_process_modules.py | 2 +- .../process_modules/hsr_process_modules.py | 2 +- .../process_modules/pr2_process_modules.py | 2 +- src/pycram/resolver/location/jpt_location.py | 3 +- src/pycram/ros/force_torque_sensor.py | 2 +- src/pycram/ros/joint_state_publisher.py | 2 +- src/pycram/ros/robot_state_updater.py | 2 +- src/pycram/ros/tf_broadcaster.py | 2 +- src/pycram/ros/viz_marker_publisher.py | 2 +- src/pycram/task.py | 2 +- src/pycram/world.py | 836 +++--------------- src/pycram/world_reasoning.py | 3 +- test/test_bullet_world.py | 3 +- test/test_database_resolver.py | 3 +- test/test_jpt_resolver.py | 3 +- 29 files changed, 761 insertions(+), 735 deletions(-) create mode 100755 src/pycram/bullet_world.py diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 0216c5474..c19ad349c 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -2,7 +2,7 @@ from pycram.designators.location_designator import * from pycram.designators.object_designator import * from pycram.pose import Pose -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld, Object from pycram.process_module import simulated_robot, with_simulated_robot from pycram.enums import ObjectType diff --git a/demos/pycram_ur5_demo/demo.py b/demos/pycram_ur5_demo/demo.py index 2fc87dc42..f8fe23198 100644 --- a/demos/pycram_ur5_demo/demo.py +++ b/demos/pycram_ur5_demo/demo.py @@ -5,7 +5,8 @@ import pybullet as pb from pycram import robot_description -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world import Object from pycram.pose import Pose from pycram.ros.force_torque_sensor import ForceTorqueSensor from pycram.ros.joint_state_publisher import JointStatePublisher diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index cf736fd77..538c2a475 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -41,7 +41,7 @@ } ], "source": [ - "from pycram.world import BulletWorld\n", + "from pycram.bullet_world import BulletWorld\n", "from pycram.pose import Pose\n", "from pycram.enums import ObjectType\n", "\n", diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py new file mode 100755 index 000000000..a60bcedb3 --- /dev/null +++ b/src/pycram/bullet_world.py @@ -0,0 +1,593 @@ +# used for delayed evaluation of typing until python 3.11 becomes mainstream +from __future__ import annotations + +import threading +import time +from typing import List, Optional, Dict, Tuple + +import numpy as np +import pybullet as p +import rospy +import rosgraph + +from .enums import JointType, ObjectType +from .pose import Pose +from .world import World, Object, Constraint + + +class BulletWorld(World): + """ + This class represents a BulletWorld, which is a simulation environment that uses the Bullet Physics Engine. This + class is the main interface to the Bullet Physics Engine and should be used to spawn Objects, simulate Physic and + manipulate the Bullet World. + """ + + # Check is for sphinx autoAPI to be able to work in a CI workflow + if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): + rospy.init_node('pycram') + + def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): + """ + Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the + background. There can only be one rendered simulation. + The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. + + :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. + """ + super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=0.004167) # 240 Hz + + self._gui_thread: Gui = Gui(self, mode) + self._gui_thread.start() + + # This disables file caching from PyBullet, since this would also cache + # files that can not be loaded + p.setPhysicsEngineParameter(enableFileCaching=0) + + # Needed to let the other thread start the simulation, before Objects are spawned. + time.sleep(0.1) + self.vis_axis: List[Object] = [] + + # Some default settings + self.set_gravity([0, 0, -9.8]) + + if not is_prospection_world: + plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) + + def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: + return p.loadURDF(path, + basePosition=pose.position_as_list(), + baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) + + def remove_object(self, obj_id: int) -> None: + """ + Remove an object by its ID. + + :param obj_id: The unique id of the object to be removed. + """ + + p.removeBody(obj_id, self.client_id) + + def add_constraint(self, constraint: Constraint) -> int: + """ + Add a constraint between two objects so that attachment they become attached + """ + constraint_id = p.createConstraint(constraint.parent_obj_id, + constraint.parent_link_id, + constraint.child_obj_id, + constraint.child_link_id, + constraint.joint_type.as_int(), + constraint.joint_axis_in_child_link_frame, + constraint.joint_frame_position_wrt_parent_origin, + constraint.joint_frame_position_wrt_child_origin, + constraint.joint_frame_orientation_wrt_parent_origin, + constraint.joint_frame_orientation_wrt_child_origin, + physicsClientId=self.client_id) + return constraint_id + + def remove_constraint(self, constraint_id): + p.removeConstraint(constraint_id, physicsClientId=self.client_id) + + def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: + """ + Get the joint upper limit of an articulated object + + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint upper limit as a float. + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8] + + def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: + """ + Get the joint lower limit of an articulated object + + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint lower limit as a float. + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[9] + + def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: + """ + Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + + :param obj: The object + :param joint_name: Name of the joint for which the axis should be returned. + :return: The axis a vector of xyz + """ + return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + + def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: + """ + Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. + + :param obj: The object + :param joint_name: Joint name for which the type should be returned + :return: The type of the joint + """ + joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] + return JointType(joint_type) + + def get_object_joint_position(self, obj: Object, joint_name: str) -> float: + """ + Get the state of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + + def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + """ + Get the pose of a link of an articulated object with respect to the world frame. + The pose is given as a tuple of position and orientation. + + :param obj: The object + :param link_name: The name of the link + """ + return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + + def get_object_contact_points(self, obj: Object) -> List: + """l.update_transforms_for_object(self.milk) + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned + list please look at `PyBullet Doc `_ + + :param obj: The object. + :return: A list of all contact points with other objects + """ + return p.getContactPoints(obj.id) + + def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: + """ + Returns a list of contact points between obj1 and obj2. + + :param obj1: The first object. + :param obj2: The second object. + :return: A list of all contact points between the two objects. + """ + return p.getContactPoints(obj1.id, obj2.id) + + def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + """ + Get the ID of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + + def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + """ + Get the name of a joint in an articulated object. + + :param obj: The object + :param joint_idx: The index of the joint (would indicate order). + """ + return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + + def get_object_link_name(self, obj: Object, link_idx: int) -> str: + """ + Get the name of a link in an articulated object. + + :param obj: The object + :param link_idx: The index of the link (would indicate order). + """ + return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + + def get_object_number_of_joints(self, obj: Object) -> int: + """ + Get the number of joints of an articulated object + + :param obj: The object + """ + return p.getNumJoints(obj.id, self.client_id) + + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + """ + Reset the joint position instantly without physics simulation + + :param obj: The object + :param joint_name: The name of the joint + :param joint_pose: The new joint pose + """ + p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + + def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): + """ + Reset the world position and orientation of the base of the object instantaneously, + not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. + + :param obj: The object + :param position: The new position of the object as a vector of x,y,z + :param orientation: The new orientation of the object as a quaternion of x,y,z,w + """ + p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + + def step(self): + """ + Step the world simulation using forward dynamics + """ + p.stepSimulation(self.client_id) + + def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): + """ + Changes the color of a link of this object, the color has to be given as a 4 element list + of RGBA values. + + :param obj: The object which should be colored + :param link_id: The link id of the link which should be colored + :param rgba_color: The color as RGBA values between 0 and 1 + """ + p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) + + def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: + """ + Get the RGBA colors of each link in the object as a dictionary from link name to color. + + :param obj: The object + :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. + """ + visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) + swap = {v: k for k, v in obj.links.items()} + links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) + colors = list(map(lambda x: x[7], visual_data)) + link_to_color = dict(zip(links, colors)) + return link_to_color + + def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of this object. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :return: Two lists of x,y,z which define the bounding box. + """ + return p.getAABB(obj.id, physicsClientId=self.client_id) + + def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + """ + Returns the axis aligned bounding box of the link. The return of this method are two points in + world coordinate frame which define a bounding box. + + :param obj: The object for which the bounding box should be returned. + :param link_name: The name of a link of this object. + :return: Two lists of x,y,z which define the bounding box. + """ + return p.getAABB(obj.id, obj.links[link_name], self.client_id) + + def set_realtime(self, real_time: bool) -> None: + """ + Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only + simulated to reason about it. + + :param real_time: Whether the World should simulate Physics in real time. + """ + p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + + def set_gravity(self, gravity_vector: List[float]) -> None: + """ + Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]). + Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic. + + :param gravity_vector: The gravity vector that should be used in the World. + """ + p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) + + @classmethod + def set_robot(cls, robot: Object) -> None: + """ + Sets the global variable for the robot Object. This should be set on spawning the robot. + + :param robot: The Object reference to the Object representing the robot. + """ + cls.robot = robot + + def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: + """ + Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the + preferred method to close the BulletWorld. + """ + super().exit(wait_time_before_exit_in_secs) + + def disconnect_from_physics_server(self): + """ + Disconnects the world from the physics server. + """ + p.disconnect(self.client_id) + + def join_threads(self): + """ + Join any running threads. Useful for example when exiting the world. + """ + self.join_gui_thread_if_exists() + + def join_gui_thread_if_exists(self): + if self._gui_thread: + self._gui_thread.join() + + def save_physics_simulator_state(self) -> int: + """ + Saves the state of the physics simulator and returns the unique id of the state. + """ + return p.saveState(self.client_id) + + def restore_physics_simulator_state(self, state_id): + """ + Restores the objects and environment state in the physics simulator according to + the given state using the unique state id. + """ + p.restoreState(state_id, physicsClientId=self.client_id) + + def add_vis_axis(self, pose: Pose, + length: Optional[float] = 0.2) -> None: + """ + Creates a Visual object which represents the coordinate frame at the given + position and orientation. There can be an unlimited amount of vis axis objects. + + :param pose: The pose at which the axis should be spawned + :param length: Optional parameter to configure the length of the axes + """ + + position, orientation = pose.to_list() + + vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], + rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) + vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], + rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) + vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], + rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) + + obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], + basePosition=position, baseOrientation=orientation, + linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], + linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], + linkParentIndices=[0, 0, 0], + linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], + linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], + linkCollisionShapeIndices=[-1, -1, -1]) + + self.vis_axis.append(obj) + + def remove_vis_axis(self) -> None: + """ + Removes all spawned vis axis objects that are currently in this BulletWorld. + """ + for id in self.vis_axis: + p.removeBody(id) + self.vis_axis = [] + + +class Gui(threading.Thread): + """ + For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~World.exit` + Also contains the code for controlling the camera. + """ + + def __init__(self, world: World, mode: str): + threading.Thread.__init__(self) + self.world = world + self.mode: str = mode + + def run(self): + """ + Initializes the new simulation and checks in an endless loop + if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and + thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. + """ + if self.mode != "GUI": + self.world.client_id = p.connect(p.DIRECT) + else: + self.world.client_id = p.connect(p.GUI) + + # Disable the side windows of the GUI + p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) + # Change the init camera pose + p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, + cameraTargetPosition=[-2, 0, 1]) + + # Get the initial camera target location + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) + + # Create a sphere with a radius of 0.05 and a mass of 0 + sphereUid = p.createMultiBody(baseMass=0.0, + baseInertialFramePosition=[0, 0, 0], + baseVisualShapeIndex=sphereVisualId, + basePosition=cameraTargetPosition) + + # Define the maxSpeed, used in calculations + maxSpeed = 16 + + # Set initial Camera Rotation + cameraYaw = 50 + cameraPitch = -35 + + # Keep track of the mouse state + mouseState = [0, 0, 0] + oldMouseX, oldMouseY = 0, 0 + + # Determines if the sphere at cameraTargetPosition is visible + visible = 1 + + # Loop to update the camera position based on keyboard events + while p.isConnected(self.world.client_id): + # Monitor user input + keys = p.getKeyboardEvents() + mouse = p.getMouseEvents() + + # Get infos about the camera + width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ + p.getDebugVisualizerCamera()[10] + cameraTargetPosition = p.getDebugVisualizerCamera()[11] + + # Get vectors used for movement on x,y,z Vector + xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] + yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] + + # Check the mouse state + if mouse: + for m in mouse: + + mouseX = m[2] + mouseY = m[1] + + # update mouseState + # Left Mouse button + if m[0] == 2 and m[3] == 0: + mouseState[0] = m[4] + # Middle mouse butto (scroll wheel) + if m[0] == 2 and m[3] == 1: + mouseState[1] = m[4] + # right mouse button + if m[0] == 2 and m[3] == 2: + mouseState[2] = m[4] + + # change visibility by clicking the mousewheel + if m[4] == 6 and m[3] == 1 and visible == 1: + visible = 0 + elif m[4] == 6 and visible == 0: + visible = 1 + + # camera movement when the left mouse button is pressed + if mouseState[0] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed + + # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) + if mouseX < oldMouseX: + if (cameraPitch + speedX) < 89.5: + cameraPitch += (speedX / 4) + 1 + elif mouseX > oldMouseX: + if (cameraPitch - speedX) > -89.5: + cameraPitch -= (speedX / 4) + 1 + + if mouseY < oldMouseY: + cameraYaw += (speedY / 4) + 1 + elif mouseY > oldMouseY: + cameraYaw -= (speedY / 4) + 1 + + if mouseState[1] == 3: + speedX = abs(oldMouseX - mouseX) + factor = 0.05 + + if mouseX < oldMouseX: + dist = dist - speedX * factor + elif mouseX > oldMouseX: + dist = dist + speedX * factor + dist = max(dist, 0.1) + + # camera movement when the right mouse button is pressed + if mouseState[2] == 3: + speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 + speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 + factor = 0.05 + + if mouseX < oldMouseX: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + elif mouseX > oldMouseX: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, factor), speedX)) + + if mouseY < oldMouseY: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + elif mouseY > oldMouseY: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, factor), speedY)) + # update oldMouse values + oldMouseY, oldMouseX = mouseY, mouseX + + # check the keyboard state + if keys: + # if shift is pressed, double the speed + if p.B3G_SHIFT in keys: + speedMult = 5 + else: + speedMult = 2.5 + + # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key + # change + if p.B3G_CONTROL in keys: + + # the up and down arrowkeys cause the targetPos to move along the z axis of the map + if p.B3G_DOWN_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + elif p.B3G_UP_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(zVec, 0.03), speedMult)) + + # left and right arrowkeys cause the targetPos to move horizontally relative to the camera + if p.B3G_LEFT_ARROW in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + elif p.B3G_RIGHT_ARROW in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(xVec, 0.03), speedMult)) + + # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera + # while the camera stays at a constant distance. SHIFT + '=' is for US layout + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + cameraTargetPosition = np.subtract(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + elif ord("-") in keys: + cameraTargetPosition = np.add(cameraTargetPosition, + np.multiply(np.multiply(yVec, 0.03), speedMult)) + + # standard bindings for thearrowkeys, the '+' as well as the '-' key + else: + + # left and right arrowkeys cause the camera to rotate around the yaw axis + if p.B3G_RIGHT_ARROW in keys: + cameraYaw += (360 / width) * speedMult + elif p.B3G_LEFT_ARROW in keys: + cameraYaw -= (360 / width) * speedMult + + # the up and down arrowkeys cause the camera to rotate around the pitch axis + if p.B3G_DOWN_ARROW in keys: + if (cameraPitch + (360 / height) * speedMult) < 89.5: + cameraPitch += (360 / height) * speedMult + elif p.B3G_UP_ARROW in keys: + if (cameraPitch - (360 / height) * speedMult) > -89.5: + cameraPitch -= (360 / height) * speedMult + + # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without + # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something + if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: + if (dist - (dist * 0.02) * speedMult) > 0.1: + dist -= dist * 0.02 * speedMult + elif ord("-") in keys: + dist += dist * 0.02 * speedMult + + p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, + cameraTargetPosition=cameraTargetPosition) + if visible == 0: + cameraTargetPosition = (0.0, -50, 50) + p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) + time.sleep(1. / 80.) \ No newline at end of file diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 080d31c71..85579203c 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -8,7 +8,8 @@ from matplotlib import colors import psutil import time -from .world import BulletWorld, UseProspectionWorld, Object +from .bullet_world import BulletWorld +from pycram.world import UseProspectionWorld, Object from .world_reasoning import _get_images_for_target from nav_msgs.msg import OccupancyGrid, MapMetaData from typing import Tuple, List, Union, Optional diff --git a/src/pycram/designator.py b/src/pycram/designator.py index d7c7a670d..017008d05 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -9,7 +9,8 @@ from sqlalchemy.orm.session import Session import rospy -from .world import (Object as BulletWorldObject, BulletWorld) +from .world import Object as BulletWorldObject +from pycram.bullet_world import BulletWorld from .helper import GeneratorList, bcolors from threading import Lock from time import time diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index c44f496ab..deeb06d68 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -23,7 +23,7 @@ from ..task import with_tree from ..enums import Arms from ..designator import ActionDesignatorDescription -from ..world import BulletWorld +from ..bullet_world import BulletWorld from ..pose import Pose from ..helper import multiply_quaternions diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index aae10e4b7..1a95ec346 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -3,7 +3,8 @@ from typing import List, Tuple, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..world import Object, BulletWorld, UseProspectionWorld +from ..world import Object, UseProspectionWorld +from ..bullet_world import BulletWorld from ..world_reasoning import link_pose_for_joint_config from ..designator import Designator, DesignatorError, LocationDesignatorDescription from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index f148aee18..c602227c2 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -2,7 +2,8 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..world import Object, BulletWorld +from ..world import Object +from pycram.bullet_world import BulletWorld from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 8d87c4936..8f5f5200c 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,7 +1,8 @@ import dataclasses from typing import List, Union, Optional, Callable, Tuple, Iterable import sqlalchemy.orm -from ..world import BulletWorld, Object as BulletWorldObject +from ..bullet_world import BulletWorld +from pycram.world import Object as BulletWorldObject from ..designator import DesignatorDescription, ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 7c4c5f4c6..f556a7ab0 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -6,7 +6,8 @@ from ..pose import Pose from ..robot_descriptions import robot_description -from ..world import BulletWorld, Object +from ..bullet_world import BulletWorld +from pycram.world import Object from ..robot_description import ManipulatorDescription from typing import List, Tuple, Dict, Callable diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index 9e0164978..bbfcadd50 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -9,7 +9,7 @@ from ..designator import ObjectDesignatorDescription from ..pose import Pose from ..local_transformer import LocalTransformer -from ..world import BulletWorld +from ..bullet_world import BulletWorld from ..enums import ObjectType try: diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index ae3f9994d..5ae4b0b9d 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -3,7 +3,8 @@ import rospy import pybullet as p -from .world import Object, BulletWorld, UseProspectionWorld +from .world import Object +from .bullet_world import BulletWorld from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 41c93f0fe..2e8fc74f3 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -5,7 +5,7 @@ import pycram.world_reasoning as btr import pycram.helper as helper -from ..world import BulletWorld +from ..bullet_world import BulletWorld from ..external_interfaces.ik import request_ik from ..local_transformer import LocalTransformer as local_tf from ..process_module import ProcessModule, ProcessModuleManager diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 1d1320cfd..dfc5dc7ed 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -5,7 +5,7 @@ import pycram.world_reasoning as btr import pycram.helper as helper -from ..world import BulletWorld +from ..bullet_world import BulletWorld from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 62120af7c..974ef8ac3 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -2,7 +2,7 @@ from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..world import BulletWorld +from ..bullet_world import BulletWorld from ..helper import _apply_ik import pycram.world_reasoning as btr import pybullet as p diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index bcadb46ec..253d37df1 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -13,7 +13,7 @@ from ..plan_failures import EnvironmentManipulationImpossible from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..world import BulletWorld, Object +from ..bullet_world import BulletWorld, Object from ..helper import transform from ..external_interfaces.ik import request_ik, IKError from ..helper import _transform_to_torso, _apply_ik, calculate_wrist_tool_offset, inverseTimes diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 748f559bb..b9de0ccb2 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -12,7 +12,8 @@ from ...costmaps import OccupancyCostmap, plot_grid from ...plan_failures import PlanFailure from ...pose import Pose -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world import Object class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index c67c2bca2..74b48024f 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -7,7 +7,7 @@ from geometry_msgs.msg import WrenchStamped from std_msgs.msg import Header -from..world import BulletWorld +from..bullet_world import BulletWorld class ForceTorqueSensor: diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index 4f72e3a61..efc51334d 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -6,7 +6,7 @@ from sensor_msgs.msg import JointState from std_msgs.msg import Header -from ..world import BulletWorld +from ..bullet_world import BulletWorld class JointStatePublisher: diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index 845d20351..f8f8bab82 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -6,7 +6,7 @@ from geometry_msgs.msg import TransformStamped from sensor_msgs.msg import JointState -from pycram.world import BulletWorld +from pycram.bullet_world import BulletWorld from pycram.robot_descriptions import robot_description from pycram.pose import Transform, Pose diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index 907119275..6880949f6 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -4,7 +4,7 @@ import atexit from ..pose import Pose -from ..world import BulletWorld +from ..bullet_world import BulletWorld from tf2_msgs.msg import TFMessage diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index f4a815df3..83193c80e 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -5,7 +5,7 @@ from geometry_msgs.msg import Vector3 from std_msgs.msg import ColorRGBA -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld from visualization_msgs.msg import MarkerArray, Marker import rospy import urdf_parser_py diff --git a/src/pycram/task.py b/src/pycram/task.py index aa21f41a0..92b80628d 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -14,7 +14,7 @@ import sqlalchemy.orm.session import tqdm -from .world import BulletWorld +from .bullet_world import BulletWorld from .orm.task import (Code as ORMCode, TaskTreeNode as ORMTaskTreeNode) from .orm.base import ProcessMetaData from .plan_failures import PlanFailure diff --git a/src/pycram/world.py b/src/pycram/world.py index 0b234aae1..d87a82349 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,14 +10,12 @@ import xml.etree.ElementTree from queue import Queue import tf -from typing import List, Optional, Dict, Tuple, Callable, Set, Type, TypeVar +from typing import List, Optional, Dict, Tuple, Callable from typing import Union import numpy as np -import pybullet as p import rospkg import rospy -import rosgraph import urdf_parser_py.urdf from geometry_msgs.msg import Quaternion, Point @@ -31,120 +29,10 @@ from .pose import Pose, Transform -from abc import ABC, abstractproperty, abstractmethod +from abc import ABC, abstractmethod from dataclasses import dataclass -class Attachment: - def __init__(self, - parent_object: Object, - child_object: Object, - parent_link_id: Optional[int] = -1, # -1 means base link - child_link_id: Optional[int] = -1, - bidirectional: Optional[bool] = False, - child_to_parent_transform: Optional[Transform] = None, - constraint_id: Optional[int] = None): - """ - Creates an attachment between the parent object and the child object. - """ - self.parent_object = parent_object - self.child_object = child_object - self.parent_link_id = parent_link_id - self.child_link_id = child_link_id - self.bidirectional = bidirectional - self._loose = False and not self.bidirectional - - self.child_to_parent_transform = child_to_parent_transform - if self.child_to_parent_transform is None: - self.update_transform() - - self.constraint_id = constraint_id - if self.constraint_id is None: - self.add_constraint_and_update_objects_constraints_collection() - - def update_attachment(self): - self.update_transform() - self.update_constraint() - - def update_transform(self): - self.child_to_parent_transform = self.calculate_transform() - - def update_constraint(self): - self.remove_constraint_if_exists() - self.add_constraint_and_update_objects_constraints_collection() - - def calculate_transform(self): - return self.parent_object.get_transform_of_other_object_link_relative_to_my_link(self.parent_link_id, - self.child_link_id, - self.child_object) - - def remove_constraint_if_exists(self): - if self.constraint_id is not None: - self.parent_object.world.remove_constraint(self.constraint_id) - - def add_constraint_and_update_objects_constraints_collection(self): - self.constraint_id = self.add_fixed_constraint() - self.update_objects_constraints_collection() - - def add_fixed_constraint(self): - constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, - self.child_object.id, - self.child_to_parent_transform, - self.parent_link_id, - self.child_link_id) - return constraint_id - - def update_objects_constraints_collection(self): - self.parent_object.cids[self.child_object] = self.constraint_id - self.child_object.cids[self.parent_object] = self.constraint_id - - def get_inverse(self): - attachment = Attachment(self.child_object, self.parent_object, self.child_link_id, - self.parent_link_id, self.bidirectional, self.child_to_parent_transform.invert(), - self.constraint_id) - attachment.loose = False if self.loose else True - return attachment - - @property - def loose(self) -> bool: - """ - If true, then the child object will not move when parent moves. - """ - return self._loose - - @loose.setter - def loose(self, loose: bool): - self._loose = loose and not self.bidirectional - - @property - def is_reversed(self) -> bool: - """ - If true means that when child moves, parent moves not the other way around. - """ - return self.loose - - -@dataclass -class Constraint: - parent_obj_id: int - parent_link_id: int - child_obj_id: int - child_link_id: int - joint_type: JointType - joint_axis_in_child_link_frame: List[int] - joint_frame_position_wrt_parent_origin: List[float] - joint_frame_position_wrt_child_origin: List[float] - joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None - joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None - - -@dataclass -class WorldState: - state_id: int - attachments: Dict[Object, Dict[Object, Attachment]] - constraint_ids: Dict[Object, Dict[Object, int]] - - class World(ABC): """ The World Class represents the physics Simulation and belief state. @@ -222,7 +110,7 @@ def _update_local_transformer_worlds(self): @classmethod def _init_prospection_world(cls): - cls.prospection_world: World = cls("DIRECT", True) + cls.prospection_world: World = cls("DIRECT", True, World.simulation_time_step) def _sync_prospection_world(self): self.world_sync: WorldSync = WorldSync(self, self.prospection_world) @@ -856,7 +744,7 @@ def _copy(self) -> World: :return: The reference to the new BulletWorld """ - world = BulletWorld("DIRECT") + world = World("DIRECT", False, World.simulation_time_step) for obj in self.objects: o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), world, obj.color) @@ -949,371 +837,6 @@ def update_transforms_for_objects_in_current_world(self) -> None: obj.update_link_transforms(curr_time) -class BulletWorld(World): - """ - This class represents a BulletWorld, which is a simulation environment that uses the Bullet Physics Engine. This - class is the main interface to the Bullet Physics Engine and should be used to spawn Objects, simulate Physic and - manipulate the Bullet World. - """ - - # Check is for sphinx autoAPI to be able to work in a CI workflow - if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): - rospy.init_node('pycram') - - def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): - """ - Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the - background. There can only be one rendered simulation. - The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. - - :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" - :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. - """ - super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=0.004167) # 240 Hz - - self._gui_thread: Gui = Gui(self, mode) - self._gui_thread.start() - - # This disables file caching from PyBullet, since this would also cache - # files that can not be loaded - p.setPhysicsEngineParameter(enableFileCaching=0) - - # Needed to let the other thread start the simulation, before Objects are spawned. - time.sleep(0.1) - self.vis_axis: List[Object] = [] - - # Some default settings - self.set_gravity([0, 0, -9.8]) - - if not is_prospection_world: - plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - - def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: - return p.loadURDF(path, - basePosition=pose.position_as_list(), - baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) - - def remove_object(self, obj_id: int) -> None: - """ - Remove an object by its ID. - - :param obj_id: The unique id of the object to be removed. - """ - - p.removeBody(obj_id, self.client_id) - - def add_constraint(self, constraint: Constraint) -> int: - """ - Add a constraint between two objects so that attachment they become attached - """ - constraint_id = p.createConstraint(constraint.parent_obj_id, - constraint.parent_link_id, - constraint.child_obj_id, - constraint.child_link_id, - constraint.joint_type.as_int(), - constraint.joint_axis_in_child_link_frame, - constraint.joint_frame_position_wrt_parent_origin, - constraint.joint_frame_position_wrt_child_origin, - constraint.joint_frame_orientation_wrt_parent_origin, - constraint.joint_frame_orientation_wrt_child_origin, - physicsClientId=self.client_id) - return constraint_id - - def remove_constraint(self, constraint_id): - p.removeConstraint(constraint_id, physicsClientId=self.client_id) - - def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint upper limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint upper limit as a float. - """ - return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8] - - def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint lower limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint lower limit as a float. - """ - return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[9] - - def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param obj: The object - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ - return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] - - def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param obj: The object - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ - joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] - return JointType(joint_type) - - def get_object_joint_position(self, obj: Object, joint_name: str) -> float: - """ - Get the state of a joint of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - """ - return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] - - def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: - """ - Get the pose of a link of an articulated object with respect to the world frame. - The pose is given as a tuple of position and orientation. - - :param obj: The object - :param link_name: The name of the link - """ - return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] - - def get_object_contact_points(self, obj: Object) -> List: - """l.update_transforms_for_object(self.milk) - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ - - :param obj: The object. - :return: A list of all contact points with other objects - """ - return p.getContactPoints(obj.id) - - def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: - """ - Returns a list of contact points between obj1 and obj2. - - :param obj1: The first object. - :param obj2: The second object. - :return: A list of all contact points between the two objects. - """ - return p.getContactPoints(obj1.id, obj2.id) - - def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: - """ - Get the ID of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). - """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] - - def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: - """ - Get the name of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). - """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') - - def get_object_link_name(self, obj: Object, link_idx: int) -> str: - """ - Get the name of a link in an articulated object. - - :param obj: The object - :param link_idx: The index of the link (would indicate order). - """ - return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') - - def get_object_number_of_joints(self, obj: Object) -> int: - """ - Get the number of joints of an articulated object - - :param obj: The object - """ - return p.getNumJoints(obj.id, self.client_id) - - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: - """ - Reset the joint position instantly without physics simulation - - :param obj: The object - :param joint_name: The name of the joint - :param joint_pose: The new joint pose - """ - p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) - - def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): - """ - Reset the world position and orientation of the base of the object instantaneously, - not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. - - :param obj: The object - :param position: The new position of the object as a vector of x,y,z - :param orientation: The new orientation of the object as a quaternion of x,y,z,w - """ - p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) - - def step(self): - """ - Step the world simulation using forward dynamics - """ - p.stepSimulation(self.client_id) - - def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): - """ - Changes the color of a link of this object, the color has to be given as a 4 element list - of RGBA values. - - :param obj: The object which should be colored - :param link_id: The link id of the link which should be colored - :param rgba_color: The color as RGBA values between 0 and 1 - """ - p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) - - def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: - """ - Get the RGBA colors of each link in the object as a dictionary from link name to color. - - :param obj: The object - :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. - """ - visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) - swap = {v: k for k, v in obj.links.items()} - links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = list(map(lambda x: x[7], visual_data)) - link_to_color = dict(zip(links, colors)) - return link_to_color - - def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of this object. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :return: Two lists of x,y,z which define the bounding box. - """ - return p.getAABB(obj.id, physicsClientId=self.client_id) - - def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of the link. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :param link_name: The name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. - """ - return p.getAABB(obj.id, obj.links[link_name], self.client_id) - - def set_realtime(self, real_time: bool) -> None: - """ - Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only - simulated to reason about it. - - :param real_time: Whether the World should simulate Physics in real time. - """ - p.setRealTimeSimulation(1 if real_time else 0, self.client_id) - - def set_gravity(self, gravity_vector: List[float]) -> None: - """ - Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]). - Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - - :param gravity_vector: The gravity vector that should be used in the World. - """ - p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) - - @classmethod - def set_robot(cls, robot: Object) -> None: - """ - Sets the global variable for the robot Object. This should be set on spawning the robot. - - :param robot: The Object reference to the Object representing the robot. - """ - cls.robot = robot - - def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: - """ - Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the - preferred method to close the BulletWorld. - """ - super().exit(wait_time_before_exit_in_secs) - - def disconnect_from_physics_server(self): - """ - Disconnects the world from the physics server. - """ - p.disconnect(self.client_id) - - def join_threads(self): - """ - Join any running threads. Useful for example when exiting the world. - """ - self.join_gui_thread_if_exists() - - def join_gui_thread_if_exists(self): - if self._gui_thread: - self._gui_thread.join() - - def save_physics_simulator_state(self) -> int: - """ - Saves the state of the physics simulator and returns the unique id of the state. - """ - return p.saveState(self.client_id) - - def restore_physics_simulator_state(self, state_id): - """ - Restores the objects and environment state in the physics simulator according to - the given state using the unique state id. - """ - p.restoreState(state_id, physicsClientId=self.client_id) - - def add_vis_axis(self, pose: Pose, - length: Optional[float] = 0.2) -> None: - """ - Creates a Visual object which represents the coordinate frame at the given - position and orientation. There can be an unlimited amount of vis axis objects. - - :param pose: The pose at which the axis should be spawned - :param length: Optional parameter to configure the length of the axes - """ - - position, orientation = pose.to_list() - - vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) - vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) - vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) - - obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], - basePosition=position, baseOrientation=orientation, - linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkParentIndices=[0, 0, 0], - linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], - linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1]) - - self.vis_axis.append(obj) - - def remove_vis_axis(self) -> None: - """ - Removes all spawned vis axis objects that are currently in this BulletWorld. - """ - for id in self.vis_axis: - p.removeBody(id) - self.vis_axis = [] - - class UseProspectionWorld: """ An environment for using the prospection world, while in this environment the :py:attr:`~World.current_world` @@ -1395,17 +918,17 @@ def run(self): del self.object_mapping[obj] self.remove_obj_queue.task_done() - for bulletworld_obj, prospection_obj in self.object_mapping.items(): - b_pose = bulletworld_obj.get_pose() + for world_obj, prospection_obj in self.object_mapping.items(): + b_pose = world_obj.get_pose() s_pose = prospection_obj.get_pose() if b_pose.dist(s_pose) != 0.0: - prospection_obj.set_pose(bulletworld_obj.get_pose()) + prospection_obj.set_pose(world_obj.get_pose()) # Manage joint positions - if len(bulletworld_obj.joints) > 2: - for joint_name in bulletworld_obj.joints.keys(): - if prospection_obj.get_joint_position(joint_name) != bulletworld_obj.get_joint_position(joint_name): - prospection_obj.set_positions_of_all_joints(bulletworld_obj.get_positions_of_all_joints()) + if len(world_obj.joints) > 2: + for joint_name in world_obj.joints.keys(): + if prospection_obj.get_joint_position(joint_name) != world_obj.get_joint_position(joint_name): + prospection_obj.set_positions_of_all_joints(world_obj.get_positions_of_all_joints()) break self.check_for_pause() @@ -1433,217 +956,11 @@ def check_for_equal(self) -> None: self.equal_states = eql -class Gui(threading.Thread): - """ - For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~World.exit` - Also contains the code for controlling the camera. - """ - - def __init__(self, world: World, mode: str): - threading.Thread.__init__(self) - self.world = world - self.mode: str = mode - - def run(self): - """ - Initializes the new simulation and checks in an endless loop - if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and - thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. - """ - if self.mode != "GUI": - self.world.client_id = p.connect(p.DIRECT) - else: - self.world.client_id = p.connect(p.GUI) - - # Disable the side windows of the GUI - p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) - # Change the init camera pose - p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1]) - - # Get the initial camera target location - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) - - # Create a sphere with a radius of 0.05 and a mass of 0 - sphereUid = p.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=sphereVisualId, - basePosition=cameraTargetPosition) - - # Define the maxSpeed, used in calculations - maxSpeed = 16 - - # Set initial Camera Rotation - cameraYaw = 50 - cameraPitch = -35 - - # Keep track of the mouse state - mouseState = [0, 0, 0] - oldMouseX, oldMouseY = 0, 0 - - # Determines if the sphere at cameraTargetPosition is visible - visible = 1 - - # Loop to update the camera position based on keyboard events - while p.isConnected(self.world.client_id): - # Monitor user input - keys = p.getKeyboardEvents() - mouse = p.getMouseEvents() - - # Get infos about the camera - width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ - p.getDebugVisualizerCamera()[10] - cameraTargetPosition = p.getDebugVisualizerCamera()[11] - - # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] - zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] - - # Check the mouse state - if mouse: - for m in mouse: - - mouseX = m[2] - mouseY = m[1] - - # update mouseState - # Left Mouse button - if m[0] == 2 and m[3] == 0: - mouseState[0] = m[4] - # Middle mouse butto (scroll wheel) - if m[0] == 2 and m[3] == 1: - mouseState[1] = m[4] - # right mouse button - if m[0] == 2 and m[3] == 2: - mouseState[2] = m[4] - - # change visibility by clicking the mousewheel - if m[4] == 6 and m[3] == 1 and visible == 1: - visible = 0 - elif m[4] == 6 and visible == 0: - visible = 1 - - # camera movement when the left mouse button is pressed - if mouseState[0] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed - - # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) - if mouseX < oldMouseX: - if (cameraPitch + speedX) < 89.5: - cameraPitch += (speedX / 4) + 1 - elif mouseX > oldMouseX: - if (cameraPitch - speedX) > -89.5: - cameraPitch -= (speedX / 4) + 1 - - if mouseY < oldMouseY: - cameraYaw += (speedY / 4) + 1 - elif mouseY > oldMouseY: - cameraYaw -= (speedY / 4) + 1 - - if mouseState[1] == 3: - speedX = abs(oldMouseX - mouseX) - factor = 0.05 - - if mouseX < oldMouseX: - dist = dist - speedX * factor - elif mouseX > oldMouseX: - dist = dist + speedX * factor - dist = max(dist, 0.1) - - # camera movement when the right mouse button is pressed - if mouseState[2] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 - factor = 0.05 - - if mouseX < oldMouseX: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - elif mouseX > oldMouseX: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - - if mouseY < oldMouseY: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - elif mouseY > oldMouseY: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - # update oldMouse values - oldMouseY, oldMouseX = mouseY, mouseX - - # check the keyboard state - if keys: - # if shift is pressed, double the speed - if p.B3G_SHIFT in keys: - speedMult = 5 - else: - speedMult = 2.5 - - # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key - # change - if p.B3G_CONTROL in keys: - - # the up and down arrowkeys cause the targetPos to move along the z axis of the map - if p.B3G_DOWN_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - elif p.B3G_UP_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) - - # left and right arrowkeys cause the targetPos to move horizontally relative to the camera - if p.B3G_LEFT_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - elif p.B3G_RIGHT_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) - - # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera - # while the camera stays at a constant distance. SHIFT + '=' is for US layout - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - elif ord("-") in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) - - # standard bindings for thearrowkeys, the '+' as well as the '-' key - else: - - # left and right arrowkeys cause the camera to rotate around the yaw axis - if p.B3G_RIGHT_ARROW in keys: - cameraYaw += (360 / width) * speedMult - elif p.B3G_LEFT_ARROW in keys: - cameraYaw -= (360 / width) * speedMult - - # the up and down arrowkeys cause the camera to rotate around the pitch axis - if p.B3G_DOWN_ARROW in keys: - if (cameraPitch + (360 / height) * speedMult) < 89.5: - cameraPitch += (360 / height) * speedMult - elif p.B3G_UP_ARROW in keys: - if (cameraPitch - (360 / height) * speedMult) > -89.5: - cameraPitch -= (360 / height) * speedMult - - # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without - # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something - if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - if (dist - (dist * 0.02) * speedMult) > 0.1: - dist -= dist * 0.02 * speedMult - elif ord("-") in keys: - dist += dist * 0.02 * speedMult - - p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition) - if visible == 0: - cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) - time.sleep(1. / 80.) +@dataclass +class WorldState: + state_id: int + attachments: Dict[Object, Dict[Object, Attachment]] + constraint_ids: Dict[Object, Dict[Object, int]] class Object: @@ -2088,10 +1405,10 @@ def contact_points_simulated(self) -> List: :return: A list of contact points between this Object and other Objects """ - s = self.world.save_state() + state_id = self.world.save_state() self.world.step() contact_points = self.contact_points() - self.world.restore_state(*s) + self.world.restore_state(state_id) return contact_points def update_joints_from_topic(self, topic_name: str) -> None: @@ -2340,6 +1657,109 @@ def _get_robot_name_from_urdf(urdf_string: str) -> str: raise Exception("Robot Name not Found") +class Attachment: + def __init__(self, + parent_object: Object, + child_object: Object, + parent_link_id: Optional[int] = -1, # -1 means base link + child_link_id: Optional[int] = -1, + bidirectional: Optional[bool] = False, + child_to_parent_transform: Optional[Transform] = None, + constraint_id: Optional[int] = None): + """ + Creates an attachment between the parent object and the child object. + """ + self.parent_object = parent_object + self.child_object = child_object + self.parent_link_id = parent_link_id + self.child_link_id = child_link_id + self.bidirectional = bidirectional + self._loose = False and not self.bidirectional + + self.child_to_parent_transform = child_to_parent_transform + if self.child_to_parent_transform is None: + self.update_transform() + + self.constraint_id = constraint_id + if self.constraint_id is None: + self.add_constraint_and_update_objects_constraints_collection() + + def update_attachment(self): + self.update_transform() + self.update_constraint() + + def update_transform(self): + self.child_to_parent_transform = self.calculate_transform() + + def update_constraint(self): + self.remove_constraint_if_exists() + self.add_constraint_and_update_objects_constraints_collection() + + def calculate_transform(self): + return self.parent_object.get_transform_of_other_object_link_relative_to_my_link(self.parent_link_id, + self.child_link_id, + self.child_object) + + def remove_constraint_if_exists(self): + if self.constraint_id is not None: + self.parent_object.world.remove_constraint(self.constraint_id) + + def add_constraint_and_update_objects_constraints_collection(self): + self.constraint_id = self.add_fixed_constraint() + self.update_objects_constraints_collection() + + def add_fixed_constraint(self): + constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, + self.child_object.id, + self.child_to_parent_transform, + self.parent_link_id, + self.child_link_id) + return constraint_id + + def update_objects_constraints_collection(self): + self.parent_object.cids[self.child_object] = self.constraint_id + self.child_object.cids[self.parent_object] = self.constraint_id + + def get_inverse(self): + attachment = Attachment(self.child_object, self.parent_object, self.child_link_id, + self.parent_link_id, self.bidirectional, self.child_to_parent_transform.invert(), + self.constraint_id) + attachment.loose = False if self.loose else True + return attachment + + @property + def loose(self) -> bool: + """ + If true, then the child object will not move when parent moves. + """ + return self._loose + + @loose.setter + def loose(self, loose: bool): + self._loose = loose and not self.bidirectional + + @property + def is_reversed(self) -> bool: + """ + If true means that when child moves, parent moves not the other way around. + """ + return self.loose + + +@dataclass +class Constraint: + parent_obj_id: int + parent_link_id: int + child_obj_id: int + child_link_id: int + joint_type: JointType + joint_axis_in_child_link_frame: List[int] + joint_frame_position_wrt_parent_origin: List[float] + joint_frame_position_wrt_child_origin: List[float] + joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None + joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None + + def _load_object(name: str, path: str, position: List[float], @@ -2415,7 +1835,7 @@ def _load_object(name: str, try: obj = world.load_urdf_at_pose_and_get_object_id(path, Pose(position, orientation)) return obj, path - except p.error as e: + except Exception as e: logging.error( "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") os.remove(path) @@ -2435,13 +1855,13 @@ def _is_cached(path: str, name: str, cach_dir: str) -> bool: :return: True if there already exists a chached file, False in any other case. """ file_name = pathlib.Path(path).name - p = pathlib.Path(cach_dir + file_name) - if p.exists(): + full_path = pathlib.Path(cach_dir + file_name) + if full_path.exists(): return True # Returns filename without the filetype, e.g. returns "test" for "test.txt" file_stem = pathlib.Path(path).stem - p = pathlib.Path(cach_dir + file_stem + ".urdf") - if p.exists(): + full_path = pathlib.Path(cach_dir + file_stem + ".urdf") + if full_path.exists(): return True return False @@ -2579,5 +1999,5 @@ def _world_and_id(world: World) -> Tuple[World, int]: :return: The World object and the id of this World """ world = world if world is not None else World.current_world - id = world.client_id if world is not None else World.current_world.client_id - return world, id + client_id = world.client_id if world is not None else World.current_world.client_id + return world, client_id diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 369760991..7950741ee 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -3,7 +3,8 @@ import numpy as np import rospy -from .world import _world_and_id, Object, UseProspectionWorld, BulletWorld +from .world import _world_and_id, Object, UseProspectionWorld +from .bullet_world import BulletWorld from .external_interfaces.ik import request_ik from .local_transformer import LocalTransformer from .plan_failures import IKError diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 704711756..b32256c8c 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -1,7 +1,8 @@ import unittest import numpy as np -from pycram.world import BulletWorld, Object, fix_missing_inertial +from pycram.bullet_world import BulletWorld +from pycram.world import Object, fix_missing_inertial from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 993dea9bc..5bdf72c3e 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -5,7 +5,8 @@ import sqlalchemy.orm import pycram.plan_failures -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world import Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 9da659e5b..ff80a0714 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -5,7 +5,8 @@ import requests import pycram.plan_failures -from pycram.world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world import Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot From f05ef6459b048130434e64fe2ca31ff9939e758e Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 12 Dec 2023 14:55:14 +0100 Subject: [PATCH 016/195] [WorldAbstractClass] Tests are running after using object.tf_frame instead of root link tf frame. --- src/pycram/bullet_world.py | 4 ++-- src/pycram/local_transformer.py | 2 -- src/pycram/world.py | 38 +++++++++++++++++++-------------- 3 files changed, 24 insertions(+), 20 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index a60bcedb3..ba7e76aec 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -26,7 +26,7 @@ class is the main interface to the Bullet Physics Engine and should be used to s if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): rospy.init_node('pycram') - def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): + def __init__(self, mode: str = "GUI", is_prospection_world: bool = False, sim_time_step=0.004167): # 240 Hz """ Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. @@ -35,7 +35,7 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False): :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. """ - super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=0.004167) # 240 Hz + super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=sim_time_step) self._gui_thread: Gui = Gui(self, mode) self._gui_thread.start() diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 7ed2c3fd7..05d149277 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -78,8 +78,6 @@ def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union return Pose(*copy_pose.to_list(), frame=new_pose.header.frame_id) - # TODO: This is not working correctly, the lookup fails to find the frames, - # this is probably because the frames are not published. def lookup_transform_from_source_to_target_frame(self, source_frame: str, target_frame: str, time: Optional[rospy.rostime.Time] = None) -> Transform: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index d87a82349..5d3b2683c 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,7 +10,7 @@ import xml.etree.ElementTree from queue import Queue import tf -from typing import List, Optional, Dict, Tuple, Callable +from typing import List, Optional, Dict, Tuple, Callable, Type from typing import Union import numpy as np @@ -33,6 +33,13 @@ from dataclasses import dataclass +@dataclass +class WorldState: + state_id: int + attachments: Dict[Object, Dict[Object, Attachment]] + constraint_ids: Dict[Object, Dict[Object, int]] + + class World(ABC): """ The World Class represents the physics Simulation and belief state. @@ -58,6 +65,10 @@ class World(ABC): """ simulation_time_step: float = None + """ + Global reference for the simulation time step, this is used to calculate the frequency of the simulation, + and also for calculating the equivalent real time for the simulation. + """ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: float): """ @@ -110,7 +121,7 @@ def _update_local_transformer_worlds(self): @classmethod def _init_prospection_world(cls): - cls.prospection_world: World = cls("DIRECT", True, World.simulation_time_step) + cls.prospection_world: World = cls("DIRECT", True, cls.simulation_time_step) def _sync_prospection_world(self): self.world_sync: WorldSync = WorldSync(self, self.prospection_world) @@ -956,13 +967,6 @@ def check_for_equal(self) -> None: self.equal_states = eql -@dataclass -class WorldState: - state_id: int - attachments: Dict[Object, Dict[Object, Attachment]] - constraint_ids: Dict[Object, Dict[Object, int]] - - class Object: """ Represents a spawned Object in the World. @@ -1303,10 +1307,10 @@ def get_other_object_link_pose_relative_to_my_link(self, parent_link_frame = self.get_link_tf_frame(self.get_link_by_id(my_link_id)) return self.local_transformer.transform_pose_to_target_frame(child_link_pose, parent_link_frame) - def get_transform_of_other_object_link_relative_to_my_link(self, - my_link_id: int, - other_link_id: int, - other_object: Object) -> Transform: + def get_transform_from_my_link_to_other_object_link(self, + my_link_id: int, + other_link_id: int, + other_object: Object) -> Transform: pose = self.get_other_object_link_pose_relative_to_my_link(my_link_id, other_link_id, other_object) return pose.to_transform(other_object.get_link_tf_frame_by_id(other_link_id)) @@ -1572,6 +1576,8 @@ def get_link_tf_frame(self, link_name: str) -> str: :param link_name: Name of a link for which the tf frame should be returned :return: A TF frame name for a specific link """ + if link_name == self.urdf_object.get_root(): + return self.tf_frame return self.tf_frame + "/" + link_name def get_link_tf_frame_by_id(self, link_id: int) -> str: @@ -1696,9 +1702,9 @@ def update_constraint(self): self.add_constraint_and_update_objects_constraints_collection() def calculate_transform(self): - return self.parent_object.get_transform_of_other_object_link_relative_to_my_link(self.parent_link_id, - self.child_link_id, - self.child_object) + return self.parent_object.get_transform_from_my_link_to_other_object_link(self.parent_link_id, + self.child_link_id, + self.child_object) def remove_constraint_if_exists(self): if self.constraint_id is not None: From a81c48900776172ee7a53e2dbd8256d2fcbfac81 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 12 Dec 2023 16:05:34 +0100 Subject: [PATCH 017/195] [WorldAbstractClass] Added Color and AxisAlignedBoundingBox datalcasses and used them instead of Lists (changed function signatures to use them). --- src/pycram/bullet_world.py | 19 +++--- src/pycram/world.py | 105 +++++++++----------------------- src/pycram/world_dataclasses.py | 95 +++++++++++++++++++++++++++++ 3 files changed, 135 insertions(+), 84 deletions(-) create mode 100644 src/pycram/world_dataclasses.py diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index ba7e76aec..159fba0df 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -12,7 +12,8 @@ from .enums import JointType, ObjectType from .pose import Pose -from .world import World, Object, Constraint +from .world import World, Object +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox class BulletWorld(World): @@ -230,7 +231,7 @@ def step(self): """ p.stepSimulation(self.client_id) - def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): + def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): """ Changes the color of a link of this object, the color has to be given as a 4 element list of RGBA values. @@ -241,7 +242,7 @@ def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[floa """ p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) - def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: + def get_object_colors(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to color. @@ -251,21 +252,21 @@ def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) swap = {v: k for k, v in obj.links.items()} links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = list(map(lambda x: x[7], visual_data)) + colors = Color.from_rgba(list(map(lambda x: x[7], visual_data))) link_to_color = dict(zip(links, colors)) return link_to_color - def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: + def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. :param obj: The object for which the bounding box should be returned. - :return: Two lists of x,y,z which define the bounding box. + :return: AxisAlignedBoundingBox object with min and max box points. """ - return p.getAABB(obj.id, physicsClientId=self.client_id) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.client_id)) - def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + def get_object_link_aabb(self, obj: Object, link_name: str) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -274,7 +275,7 @@ def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float] :param link_name: The name of a link of this object. :return: Two lists of x,y,z which define the bounding box. """ - return p.getAABB(obj.id, obj.links[link_name], self.client_id) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, obj.links[link_name], self.client_id)) def set_realtime(self, real_time: bool) -> None: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index 5d3b2683c..3e77e4f93 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,7 +10,7 @@ import xml.etree.ElementTree from queue import Queue import tf -from typing import List, Optional, Dict, Tuple, Callable, Type +from typing import List, Optional, Dict, Tuple, Callable from typing import Union import numpy as np @@ -31,6 +31,7 @@ from abc import ABC, abstractmethod from dataclasses import dataclass +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox @dataclass @@ -467,14 +468,14 @@ def step(self): """ pass - def set_object_color(self, obj: Object, color: List[float], link: Optional[str] = ""): + def set_object_color(self, obj: Object, color: Color, link: Optional[str] = ""): """ Changes the color of this object, the color has to be given as a list of RGBA values. Optionally a link name can can be provided, if no link name is provided all links of this object will be colored. :param obj: The object which should be colored - :param color: The color as RGBA values between 0 and 1 + :param color: The color as Color object with RGBA values between 0 and 1 :param link: The link name of the link which should be colored """ if link == "": @@ -489,27 +490,26 @@ def set_object_color(self, obj: Object, color: List[float], link: Optional[str] self.set_object_link_color(obj, obj.links[link], color) @abstractmethod - def set_object_link_color(self, obj: Object, link_id: int, rgba_color: List[float]): + def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): """ - Changes the color of a link of this object, the color has to be given as a 4 element list - of RGBA values. + Changes the color of a link of this object, the color has to be given as Color object. :param obj: The object which should be colored :param link_id: The link id of the link which should be colored - :param rgba_color: The color as RGBA values between 0 and 1 + :param rgba_color: The color as Color object with RGBA values between 0 and 1 """ pass def get_object_color(self, obj: Object, - link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: + link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: """ This method returns the color of this object or a link of this object. If no link is given then the return is either: - 1. A list with the color as RGBA values, this is the case if the object only has one link (this + 1. A Color object with RGBA values, this is the case if the object only has one link (this happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. + 2. A dict with the link name as key and the color as value. The color is given as a Color Object. Please keep in mind that not every link may have a color. This is dependent on the URDF from which the object is spawned. @@ -538,35 +538,35 @@ def get_object_color(self, return link_to_color_dict @abstractmethod - def get_object_colors(self, obj: Object) -> Dict[str, List[float]]: + def get_object_colors(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to color. :param obj: The object - :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. + :return: A dictionary with link names as keys and a Color object for each link as value. """ pass @abstractmethod - def get_object_AABB(self, obj: Object) -> Tuple[List[float], List[float]]: + def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. :param obj: The object for which the bounding box should be returned. - :return: Two lists of x,y,z which define the bounding box. + :return: AxisAlignedBoundingBox object containing the min and max points of the bounding box. """ pass @abstractmethod - def get_object_link_aabb(self, obj: Object, link_name: str) -> Tuple[List[float], List[float]]: + def get_object_link_aabb(self, obj: Object, link_name: str) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. :param obj: The object for which the bounding box should be returned. :param link_name: The name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. + :return: AxisAlignedBoundingBox object containing the min and max points of the bounding box. """ pass @@ -916,7 +916,7 @@ def run(self): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.prospection_world, color, bulletworld object] + # [name, type, path, position, orientation, self.world.prospection_world, color, world object] o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) # Maps the World object to the prospection world object self.object_mapping[obj[7]] = o @@ -972,11 +972,10 @@ class Object: Represents a spawned Object in the World. """ - # TODO: make a color dataclass or change initialization of color to be non mutable def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: Pose = None, world: World = None, - color: Optional[List[float]] = [1, 1, 1, 1], + color: Optional[Color] = Color(), ignore_cached_files: Optional[bool] = False): """ The constructor loads the urdf file into the given World, if no World is specified the @@ -997,7 +996,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.local_transformer = LocalTransformer() self.name: str = name self.obj_type: Union[str, ObjectType] = obj_type - self.color: List[float] = color + self.color: Color = color pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) @@ -1447,7 +1446,7 @@ def update_pose_from_tf(self, frame: str) -> None: position[0][2]] self.set_position(Pose(position, orientation)) - def set_color(self, color: List[float], link: Optional[str] = "") -> None: + def set_color(self, color: Color, link: Optional[str] = "") -> None: """ Changes the color of this object, the color has to be given as a list of RGBA values. Optionally a link name can can be provided, if no link @@ -1458,42 +1457,13 @@ def set_color(self, color: List[float], link: Optional[str] = "") -> None: """ self.world.set_object_color(self, color, link) - def get_color(self, link: Optional[str] = None) -> Union[List[float], Dict[str, List[float]], None]: - """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: - - 1. A list with the color as RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as RGBA values. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the - object is spawned. - - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. - - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color - """ + def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: return self.world.get_object_color(self, link) - def get_aabb(self) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of this object. The return of this method are two points in - world coordinate frame which define a bounding box. - - :return: Two lists of x,y,z which define the bounding box. - """ - return self.world.get_object_AABB(self) - - def get_link_aabb(self, link_name: str) -> Tuple[List[float], List[float]]: - """ - Returns the axis aligned bounding box of the given link name. The return of this method are two points in - world coordinate frame which define a bounding box. + def get_aabb(self) -> AxisAlignedBoundingBox: + return self.world.get_object_aabb(self) - :param link_name: The name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. - """ + def get_link_aabb(self, link_name: str) -> AxisAlignedBoundingBox: return self.world.get_object_link_aabb(self, link_name) def get_base_origin(self) -> Pose: @@ -1503,9 +1473,9 @@ def get_base_origin(self) -> Pose: :return: The position of the bottom of this Object """ aabb = self.get_link_aabb(link_name=self.urdf_object.get_root()) - base_width = np.absolute(aabb[0][0] - aabb[1][0]) - base_length = np.absolute(aabb[0][1] - aabb[1][1]) - return Pose([aabb[0][0] + base_width / 2, aabb[0][1] + base_length / 2, aabb[0][2]], + base_width = np.absolute(aabb.min_x - aabb.max_x) + base_length = np.absolute(aabb.min_y - aabb.max_y) + return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], self.get_pose().orientation_as_list()) def get_joint_limits(self, joint: str) -> Tuple[float, float]: @@ -1752,26 +1722,12 @@ def is_reversed(self) -> bool: return self.loose -@dataclass -class Constraint: - parent_obj_id: int - parent_link_id: int - child_obj_id: int - child_link_id: int - joint_type: JointType - joint_axis_in_child_link_frame: List[int] - joint_frame_position_wrt_parent_origin: List[float] - joint_frame_position_wrt_child_origin: List[float] - joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None - joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None - - def _load_object(name: str, path: str, position: List[float], orientation: List[float], world: World, - color: List[float], + color: Color, ignore_cached_files: bool) -> Tuple[int, str]: """ Loads an object to the given World with the given position and orientation. The color will only be @@ -1846,7 +1802,6 @@ def _load_object(name: str, "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") os.remove(path) raise (e) - # print(f"{bcolors.BOLD}{bcolors.WARNING}The path has to be either a path to a URDf file, stl file, obj file or the name of a URDF on the parameter server.{bcolors.ENDC}") def _is_cached(path: str, name: str, cach_dir: str) -> bool: @@ -1957,7 +1912,7 @@ def fix_link_attributes(urdf_string: str) -> str: return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') -def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) -> str: +def _generate_urdf_file(name: str, path: str, color: Color, cach_dir: str) -> str: """ Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name @@ -1988,7 +1943,7 @@ def _generate_urdf_file(name: str, path: str, color: List[float], cach_dir: str) \n \ ' urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, color))) + rgb = " ".join(list(map(str, color.get_rgba()))) pathlib_obj = pathlib.Path(path) path = str(pathlib_obj.resolve()) content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py new file mode 100644 index 000000000..d91d396bb --- /dev/null +++ b/src/pycram/world_dataclasses.py @@ -0,0 +1,95 @@ +from dataclasses import dataclass +from typing import List, Optional, Tuple +from .enums import JointType + + +@dataclass +class Color: + """ + Dataclass for storing color as an RGBA value. + """ + R: float = 1 + G: float = 1 + B: float = 1 + A: float = 1 + + @classmethod + def from_rgba(cls, rgba: List[float]): + """ + Sets the color from a list of RGBA values. + + :param rgba: The list of RGBA values + """ + return cls(rgba[0], rgba[1], rgba[2], rgba[3]) + + def get_rgba(self) -> List[float]: + """ + Returns the color as a list of RGBA values. + + :return: The color as a list of RGBA values + """ + return [self.R, self.G, self.B, self.A] + + +@dataclass +class Constraint: + """ + Dataclass for storing a constraint between two objects. + """ + parent_obj_id: int + parent_link_id: int + child_obj_id: int + child_link_id: int + joint_type: JointType + joint_axis_in_child_link_frame: List[int] + joint_frame_position_wrt_parent_origin: List[float] + joint_frame_position_wrt_child_origin: List[float] + joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None + joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None + + +@dataclass +class AxisAlignedBoundingBox: + """ + Dataclass for storing an axis-aligned bounding box. + """ + min_x: float + min_y: float + min_z: float + max_x: float + max_y: float + max_z: float + + @classmethod + def from_min_max(cls, min_point: List[float], max_point: List[float]): + """ + Sets the axis-aligned bounding box from a minimum and maximum point. + + :param min_point: The minimum point + :param max_point: The maximum point + """ + return cls(min_point[0], min_point[1], min_point[2], max_point[0], max_point[1], max_point[2]) + + def get_min_max(self) -> Tuple[List[float], List[float]]: + """ + Returns the axis-aligned bounding box as a tuple of minimum and maximum points. + + :return: The axis-aligned bounding box as a tuple of minimum and maximum points + """ + return self.get_min_point(), self.get_max_point() + + def get_min_point(self) -> List[float]: + """ + Returns the minimum point of the axis-aligned bounding box. + + :return: The minimum point of the axis-aligned bounding box + """ + return [self.min_x, self.min_y, self.min_z] + + def get_max_point(self) -> List[float]: + """ + Returns the maximum point of the axis-aligned bounding box. + + :return: The maximum point of the axis-aligned bounding box + """ + return [self.max_x, self.max_y, self.max_z] From 278a7fee49d05625907644fb147867665fb0876d Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 13 Dec 2023 20:13:02 +0100 Subject: [PATCH 018/195] [WorldAbstractClass] Some cleaning up and refactoring of method names. --- demos/pycram_bullet_world_demo/demo.py | 3 +- demos/pycram_ur5_demo/demo.py | 2 +- src/pycram/bullet_world.py | 11 +- src/pycram/costmaps.py | 6 +- src/pycram/designators/location_designator.py | 4 +- .../resolver/location/giskard_location.py | 2 +- src/pycram/world.py | 145 ++++++++++-------- src/pycram/world_reasoning.py | 20 +-- 8 files changed, 103 insertions(+), 90 deletions(-) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index c19ad349c..36f908fbb 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -11,7 +11,8 @@ apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([2.5, 2, 1.02]), color=[1, 0, 0, 1]) -cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([2.5, 2.3, 1.05]), color=[0, 1, 0, 1]) +cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([2.5, 2.3, 1.05]), + color=[0, 1, 0, 1]) spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", pose=Pose([2.4, 2.2, 0.85]), color=[0, 0, 1, 1]) bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=Pose([2.5, 2.2, 1.02]), color=[1, 1, 0, 1]) apartment.attach(spoon, 'cabinet10_drawer_top') diff --git a/demos/pycram_ur5_demo/demo.py b/demos/pycram_ur5_demo/demo.py index f8fe23198..b54b5b6d7 100644 --- a/demos/pycram_ur5_demo/demo.py +++ b/demos/pycram_ur5_demo/demo.py @@ -38,7 +38,7 @@ lab = Object("kitchen", "environment", kitchen_urdf_path) robot = Object("ur", "robot", robot_urdf_path, pose=SPAWNING_POSES["robot"]) cereal = Object("cereal", "object", os.path.join(RESOURCE_DIR, "breakfast_cereal.stl"), - pose=SPAWNING_POSES["cereal"]) + pose=SPAWNING_POSES["cereal"]) BulletWorld.robot = robot tf_broadcaster = TFBroadcaster("projection", "odom", 1.0) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 159fba0df..13cc510df 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -204,7 +204,7 @@ def get_object_number_of_joints(self, obj: Object) -> int: """ return p.getNumJoints(obj.id, self.client_id) - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -295,15 +295,6 @@ def set_gravity(self, gravity_vector: List[float]) -> None: """ p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) - @classmethod - def set_robot(cls, robot: Object) -> None: - """ - Sets the global variable for the robot Object. This should be set on spawning the robot. - - :param robot: The Object reference to the Object representing the robot. - """ - cls.robot = robot - def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: """ Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 85579203c..ca7136a6f 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -394,9 +394,9 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: physicsClientId=BulletWorld.current_world.client_id) j += len(n) if BulletWorld.robot: - shadow_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) attached_objs = BulletWorld.robot.attachments.keys() - attached_objs_shadow_id = [BulletWorld.current_world.get_prospection_object(x).id for x in + attached_objs_shadow_id = [BulletWorld.current_world.get_prospection_object_from_object(x).id for x in attached_objs] res[i:j] = [ 1 if ray[0] == -1 or ray[0] == shadow_robot.id or ray[0] in attached_objs_shadow_id else 0 for @@ -726,7 +726,7 @@ def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: :return: Two points in world coordinate space, which span a rectangle """ - shadow_obj = BulletWorld.current_world.get_prospection_object(self.object) + shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(self.object) with UseProspectionWorld(): shadow_obj.set_orientation(Pose(orientation=[0, 0, 0, 1])) link_orientation = shadow_obj.get_link_pose(self.link) diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 1a95ec346..a8f2ab689 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -181,7 +181,7 @@ def __iter__(self): if self.visible_for or self.reachable_for: robot_object = self.visible_for.bullet_world_object if self.visible_for else self.reachable_for.bullet_world_object - test_robot = BulletWorld.current_world.get_prospection_object(robot_object) + test_robot = BulletWorld.current_world.get_prospection_object_from_object(robot_object) with UseProspectionWorld(): @@ -257,7 +257,7 @@ def __iter__(self) -> Location: final_map = occupancy + gaussian - test_robot = BulletWorld.current_world.get_prospection_object(self.robot) + test_robot = BulletWorld.current_world.get_prospection_object_from_object(self.robot) # Find a Joint of type prismatic which is above the handle in the URDF tree container_joint = self.handle.bullet_world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 5c891b4e0..88479c50d 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -28,7 +28,7 @@ def __iter__(self) -> CostmapLocation.Location: pose_left, end_config_left = self._get_reachable_pose_for_arm(self.target, robot_description.get_tool_frame("left")) - test_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) + test_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) with UseProspectionWorld(): valid, arms = reachability_validator(pose_right, test_robot, self.target, {}) if valid: diff --git a/src/pycram/world.py b/src/pycram/world.py index 3e77e4f93..0203716e1 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -258,7 +258,8 @@ def add_constraint(self, constraint: Constraint) -> int: """ pass - def detach_objects(self, obj1: Object, obj2: Object) -> None: + @staticmethod + def detach_objects(obj1: Object, obj2: Object) -> None: """ Detaches obj2 from obj1. This is done by deleting the attachment from the attachments dictionary of both objects @@ -270,9 +271,6 @@ def detach_objects(self, obj1: Object, obj2: Object) -> None: """ del obj1.attachments[obj2] del obj2.attachments[obj1] - - self.remove_constraint(obj1.cids[obj2]) - del obj1.cids[obj2] del obj2.cids[obj1] @@ -439,7 +437,7 @@ def get_object_number_of_joints(self, obj: Object) -> int: pass @abstractmethod - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -614,15 +612,32 @@ def set_gravity(self, gravity_vector: List[float]) -> None: """ pass - @classmethod - @abstractmethod - def set_robot(cls, robot: Object) -> None: + def set_robot_if_not_set(self, robot: Object) -> None: + """ + Sets the robot if it is not set yet. + + :param robot: The Object reference to the Object representing the robot. + """ + if not self.robot_is_set(): + self.set_robot(robot) + + @staticmethod + def set_robot(robot: Union[Object, None]) -> None: """ Sets the global variable for the robot Object. This should be set on spawning the robot. :param robot: The Object reference to the Object representing the robot. """ - pass + World.robot = robot + + @staticmethod + def robot_is_set() -> bool: + """ + Returns whether the robot has been set or not. + + :return: True if the robot has been set, False otherwise. + """ + return World.robot is not None def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: """ @@ -649,8 +664,8 @@ def disconnect_from_physics_server(self): pass def reset_current_world(self): - if self.current_world == self: - self.current_world = None + if World.current_world == self: + World.current_world = None def reset_robot(self): self.set_robot(None) @@ -749,16 +764,16 @@ def restore_constraints_from_saved_world_state(self, state_id: int): def _copy(self) -> World: """ - Copies this Bullet World into another and returns it. The other BulletWorld - will be in Direct mode. The shadow world should always be preferred instead of creating a new BulletWorld. + Copies this World into another and returns it. The other World + will be in Direct mode. The prospection world should always be preferred instead of creating a new World. This method should only be used if necessary since there can be unforeseen problems. - :return: The reference to the new BulletWorld + :return: The reference to the new World """ world = World("DIRECT", False, World.simulation_time_step) for obj in self.objects: - o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), - world, obj.color) + o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), world, + obj.color) for joint in obj.joints: o.set_joint_position(joint, obj.get_joint_position(joint)) return world @@ -778,7 +793,7 @@ def register_two_objects_collision_callbacks(self, object_a: Object, object_b: O self.coll_callbacks[(object_a, object_b)] = (on_collision_callback, on_collision_removal_callback) @classmethod - def add_additional_resource_path(cls, path: str) -> None: + def add_resource_path(cls, path: str) -> None: """ Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an Object is spawned only with a filename. @@ -787,7 +802,7 @@ def add_additional_resource_path(cls, path: str) -> None: """ cls.data_directory.append(path) - def get_prospection_object(self, obj: Object) -> Object: + def get_prospection_object_from_object(self, obj: Object) -> Object: """ Returns the corresponding object from the prospection world for a given object in the main world. If the given Object is already in the prospection world, it is returned. @@ -807,7 +822,7 @@ def get_prospection_object(self, obj: Object) -> Object: f" the object isn't anymore in the main (graphical) World" f" or if the given object is already a prospection object. ") - def get_object_from_prospection(self, prospection_object: Object) -> Object: + def get_object_from_prospection_object(self, prospection_object: Object) -> Object: """ Returns the corresponding object from the main World for a given object in the shadow world. If the given object is not in the shadow @@ -824,19 +839,14 @@ def get_object_from_prospection(self, prospection_object: Object) -> Object: def reset_world(self) -> None: """ - Resets the BulletWorld to the state it was first spawned in. + Resets the World to the state it was first spawned in. All attached objects will be detached, all joints will be set to the default position of 0 and all objects will be set to the position and orientation in which they were spawned. """ for obj in self.objects: - if obj.attachments: - attached_objects = list(obj.attachments.keys()) - for att_obj in attached_objects: - obj.detach(att_obj) - joint_names = list(obj.joints.keys()) - joint_poses = [0 for j in joint_names] - obj.set_positions_of_all_joints(dict(zip(joint_names, joint_poses))) + obj.detach_all() + obj.reset_all_joints_positions() obj.set_pose(obj.original_pose) def update_transforms_for_objects_in_current_world(self) -> None: @@ -972,11 +982,8 @@ class Object: Represents a spawned Object in the World. """ - def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, - pose: Pose = None, - world: World = None, - color: Optional[Color] = Color(), - ignore_cached_files: Optional[bool] = False): + def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: Pose = None, world: World = None, + color: Optional[Color] = Color(), ignore_cached_files: Optional[bool] = False): """ The constructor loads the urdf file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. @@ -990,7 +997,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, :param color: The color with which the object should be spawned. :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ - if not pose: + if pose is None: pose = Pose() self.world: World = world if world is not None else World.current_world self.local_transformer = LocalTransformer() @@ -1008,15 +1015,14 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) - # This means "world" is not the prospection world since it has a reference to a prospection world - if self.world.prospection_world is not None: + if not self.world.is_prospection_world: self.world.world_sync.add_obj_queue.put( [name, obj_type, path, position, orientation, self.world.prospection_world, color, self]) with open(self.path) as f: self.urdf_object = URDF.from_xml_string(f.read()) - if self.urdf_object.name == robot_description.name and not World.robot: - World.robot = self + if self.urdf_object.name == robot_description.name: + self.world.set_robot_if_not_set(self) self.links[self.urdf_object.get_root()] = -1 @@ -1050,18 +1056,21 @@ def remove(self) -> None: """ Removes this object from the World it currently resides in. For the object to be removed it has to be detached from all objects it - is currently attached to. After this is done a call to PyBullet is done - to remove this Object from the simulation. + is currently attached to. After this is done a call to world remove object is done + to remove this Object from the simulation/world. """ - for obj in self.attachments.keys(): - self.world.detach_objects(self, obj) + self.detach_all() + self.world.objects.remove(self) + # This means the current world of the object is not the prospection world, since it # has a reference to the prospection world if self.world.prospection_world is not None: self.world.world_sync.remove_obj_queue.put(self) self.world.world_sync.remove_obj_queue.join() + self.world.remove_object(self.id) + if World.robot == self: World.robot = None @@ -1345,40 +1354,49 @@ def get_link_pose(self, name: str) -> Pose: def get_link_pose_by_id(self, link_id: int) -> Pose: return self.get_link_pose(self.get_link_by_id(link_id)) - def set_joint_position(self, joint_name: str, joint_pose: float) -> None: + def reset_all_joints_positions(self) -> None: + """ + Sets the current position of all joints to 0. This is useful if the joints should be reset to their default + """ + joint_names = list(self.joints.keys()) + joint_positions = [0] * len(joint_names) + self.set_positions_of_all_joints(dict(zip(joint_names, joint_positions))) + + def set_positions_of_all_joints(self, joint_poses: dict) -> None: + """ + Sets the current position of multiple joints at once, this method should be preferred when setting + multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. + + :param joint_poses: + :return: + """ + for joint_name, joint_position in joint_poses.items(): + self.world.reset_object_joint_position(self, joint_name, joint_position) + self._current_joints_positions[joint_name] = joint_position + self._update_current_link_poses_and_transforms() + self.world._set_attached_objects(self, [self]) + + def set_joint_position(self, joint_name: str, joint_position: float) -> None: """ Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated in the URDF, an error will be printed. However, the joint will be set either way. :param joint_name: The name of the joint - :param joint_pose: The target pose for this joint + :param joint_position: The target pose for this joint """ # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly up_lim, low_lim = self.world.get_object_joint_limits(self, joint_name) if low_lim > up_lim: low_lim, up_lim = up_lim, low_lim - if not low_lim <= joint_pose <= up_lim: + if not low_lim <= joint_position <= up_lim: logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {joint_name} are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_pose}") + f"The joint position has to be within the limits of the joint. The joint limits for {joint_name}" + f" are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_position}") # Temporarily disabled because kdl outputs values exciting joint limits # return - self.world.reset_joint_position(self, joint_name, joint_pose) - self._current_joints_positions[joint_name] = joint_pose - self._update_current_link_poses_and_transforms() - self.world._set_attached_objects(self, [self]) - - def set_positions_of_all_joints(self, joint_poses: dict) -> None: - """ - Sets the current position of multiple joints at once, this method should be preferred when setting multiple joints - at once instead of running :func:`~Object.set_joint_position` in a loop. - - :param joint_poses: - :return: - """ - for joint_name, joint_pose in joint_poses.items(): - self.world.reset_joint_position(self, joint_name, joint_pose) - self._current_joints_positions[joint_name] = joint_pose + self.world.reset_object_joint_position(self, joint_name, joint_position) + self._current_joints_positions[joint_name] = joint_position self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) @@ -1721,6 +1739,9 @@ def is_reversed(self) -> bool: """ return self.loose + def __del__(self): + self.remove_constraint_if_exists() + def _load_object(name: str, path: str, diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 7950741ee..9847100ba 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -98,7 +98,7 @@ def stable(object: Object, :return: True if the given object is stable in the world False else """ world, world_id = _world_and_id(world) - shadow_obj = BulletWorld.current_world.get_prospection_object(object) + shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) with UseProspectionWorld(): coords_prev = shadow_obj.pose.position_as_list() state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) @@ -130,8 +130,8 @@ def contact(object1: Object, """ with UseProspectionWorld(): - shadow_obj1 = BulletWorld.current_world.get_prospection_object(object1) - shadow_obj2 = BulletWorld.current_world.get_prospection_object(object2) + shadow_obj1 = BulletWorld.current_world.get_prospection_object_from_object(object1) + shadow_obj2 = BulletWorld.current_world.get_prospection_object_from_object(object2) p.performCollisionDetection(BulletWorld.current_world.client_id) con_points = p.getContactPoints(shadow_obj1.id, shadow_obj2.id, physicsClientId=BulletWorld.current_world.client_id) @@ -165,9 +165,9 @@ def visible(object: Object, """ front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis with UseProspectionWorld(): - shadow_obj = BulletWorld.current_world.get_prospection_object(object) + shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) if BulletWorld.robot: - shadow_robot = BulletWorld.current_world.get_prospection_object(BulletWorld.robot) + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) for obj in BulletWorld.current_world.objects: if obj == shadow_obj or BulletWorld.robot and obj == shadow_robot: @@ -245,7 +245,7 @@ def occluding(object: Object, occluding.append(seg_mask[c[0]][c[1]]) occ_objects = list(set(map(BulletWorld.current_world.get_object_by_id, occluding))) - occ_objects = list(map(world.get_object_from_prospection, occ_objects)) + occ_objects = list(map(world.get_object_from_prospection_object, occ_objects)) return occ_objects @@ -268,7 +268,7 @@ def reachable(pose: Union[Object, Pose], if type(pose) == Object: pose = pose.get_pose() - shadow_robot = BulletWorld.current_world.get_prospection_object(robot) + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) with UseProspectionWorld(): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints @@ -306,7 +306,7 @@ def blocking(pose_or_object: Union[Object, Pose], else: input_pose = pose_or_object - shadow_robot = BulletWorld.current_world.get_prospection_object(robot) + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) with UseProspectionWorld(): arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" joints = robot_description.chains[arm].joints @@ -330,7 +330,7 @@ def blocking(pose_or_object: Union[Object, Pose], block = [] for obj in BulletWorld.current_world.objects: if contact(shadow_robot, obj): - block.append(BulletWorld.current_world.get_object_from_prospection(obj)) + block.append(BulletWorld.current_world.get_object_from_prospection_object(obj)) return block @@ -358,7 +358,7 @@ def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], l :param link_name: Name of the link for which the pose should be returned :return: The pose of the link after applying the joint configuration """ - shadow_object = BulletWorld.current_world.get_prospection_object(object) + shadow_object = BulletWorld.current_world.get_prospection_object_from_object(object) with UseProspectionWorld(): for joint, pose in joint_config.items(): shadow_object.set_joint_position(joint, pose) From 205c9f2da2f51cb72a0dcddd36ee12c6cb8fb809 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 14 Dec 2023 20:12:01 +0100 Subject: [PATCH 019/195] [ClassForLinks] Created Link class. --- src/pycram/bullet_world.py | 70 ++++---- src/pycram/costmaps.py | 19 +- src/pycram/designators/object_designator.py | 2 +- src/pycram/external_interfaces/giskard.py | 4 +- src/pycram/pose.py | 3 +- src/pycram/ros/force_torque_sensor.py | 4 +- src/pycram/ros/joint_state_publisher.py | 2 +- src/pycram/ros/tf_broadcaster.py | 2 +- src/pycram/ros/viz_marker_publisher.py | 6 +- src/pycram/world.py | 190 +++++++++++++------- src/pycram/world_dataclasses.py | 45 ++++- 11 files changed, 222 insertions(+), 125 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 13cc510df..1828de269 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -97,7 +97,7 @@ def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: :param joint_name: The name of the joint. :return: The joint upper limit as a float. """ - return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[8] + return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[8] def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: """ @@ -107,7 +107,7 @@ def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: :param joint_name: The name of the joint. :return: The joint lower limit as a float. """ - return p.getJointInfo(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[9] + return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[9] def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ @@ -117,7 +117,7 @@ def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: :param joint_name: Name of the joint for which the axis should be returned. :return: The axis a vector of xyz """ - return p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[13] + return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], self.client_id)[13] def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: """ @@ -127,7 +127,7 @@ def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: :param joint_name: Joint name for which the type should be returned :return: The type of the joint """ - joint_type = p.getJointInfo(obj.id, obj.joints[joint_name], self.client_id)[2] + joint_type = p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], self.client_id)[2] return JointType(joint_type) def get_object_joint_position(self, obj: Object, joint_name: str) -> float: @@ -137,17 +137,17 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: :param obj: The object :param joint_name: The name of the joint """ - return p.getJointState(obj.id, obj.joints[joint_name], physicsClientId=self.client_id)[0] + return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] - def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. The pose is given as a tuple of position and orientation. - :param obj: The object - :param link_name: The name of the link + :param obj_id: The object + :param link_id: The name of the link """ - return p.getLinkState(obj.id, obj.links[link_name], physicsClientId=self.client_id)[4:6] + return Pose(*p.getLinkState(obj_id, link_id, physicsClientId=self.client_id)[4:6]) def get_object_contact_points(self, obj: Object) -> List: """l.update_transforms_for_object(self.milk) @@ -169,40 +169,44 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> """ return p.getContactPoints(obj1.id, obj2.id) - def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + def get_object_joint_names(self, obj_id: int) -> List[str]: + """ + Get the names of all joints of an articulated object. """ - Get the ID of a joint in an articulated object. + num_joints = self.get_object_number_of_joints(obj_id) + return [p.getJointInfo(obj_id, i, self.client_id)[1].decode('utf-8') for i in range(num_joints)] - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). + def get_object_link_names(self, obj_id: int) -> List[str]: + """ + Get the names of all joints of an articulated object. """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[0] + num_links = self.get_object_number_of_links(obj_id) + return [p.getJointInfo(obj_id, i, self.client_id)[12].decode('utf-8') for i in range(num_links)] - def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + def get_object_number_of_links(self, obj_id: int) -> int: """ - Get the name of a joint in an articulated object. + Get the number of links of an articulated object - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). + :param obj_id: The object """ - return p.getJointInfo(obj.id, joint_idx, self.client_id)[1].decode('utf-8') + return self.get_object_number_of_joints(obj_id) - def get_object_link_name(self, obj: Object, link_idx: int) -> str: + def get_object_number_of_joints(self, obj_id: int) -> int: """ - Get the name of a link in an articulated object. + Get the number of joints of an articulated object - :param obj: The object - :param link_idx: The index of the link (would indicate order). + :param obj_id: The object """ - return p.getJointInfo(obj.id, link_idx, self.client_id)[12].decode('utf-8') + return p.getNumJoints(obj_id, self.client_id) - def get_object_number_of_joints(self, obj: Object) -> int: + def get_object_link_id(self, obj_id: int, link_name: str) -> int: """ - Get the number of joints of an articulated object + Get the ID of a link in an articulated object. :param obj: The object + :param link_name: The name of the link """ - return p.getNumJoints(obj.id, self.client_id) + return self.get_object_by_id(obj_id).link_name_to_id[link_name] def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ @@ -212,7 +216,7 @@ def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: :param joint_name: The name of the joint :param joint_pose: The new joint pose """ - p.resetJointState(obj.id, obj.joints[joint_name], joint_pose, physicsClientId=self.client_id) + p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.client_id) def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): """ @@ -250,7 +254,7 @@ def get_object_colors(self, obj: Object) -> Dict[str, Color]: :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. """ visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) - swap = {v: k for k, v in obj.links.items()} + swap = {v: k for k, v in obj.link_name_to_id.items()} links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) colors = Color.from_rgba(list(map(lambda x: x[7], visual_data))) link_to_color = dict(zip(links, colors)) @@ -266,16 +270,12 @@ def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: """ return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.client_id)) - def get_object_link_aabb(self, obj: Object, link_name: str) -> AxisAlignedBoundingBox: + def get_object_link_aabb(self, obj_id: int, link_id: int) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :param link_name: The name of a link of this object. - :return: Two lists of x,y,z which define the bounding box. """ - return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, obj.links[link_name], self.client_id)) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj_id, link_id, self.client_id)) def set_realtime(self, real_time: bool) -> None: """ diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index ca7136a6f..bc21b122d 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -11,6 +11,7 @@ from .bullet_world import BulletWorld from pycram.world import UseProspectionWorld, Object from .world_reasoning import _get_images_for_target +from .world_dataclasses import AxisAlignedBoundingBox from nav_msgs.msg import OccupancyGrid, MapMetaData from typing import Tuple, List, Union, Optional @@ -713,12 +714,12 @@ def generate_map(self) -> None: Generates the semantic costmap according to the provided parameters. To do this the axis aligned bounding box (AABB) for the link name will be used. Height and width of the final Costmap will be the x and y sizes of the AABB. """ - min, max = self.get_aabb_for_link() - self.height = int((max[0] - min[0]) // self.resolution) - self.width = int((max[1] - min[1]) // self.resolution) + min_p, max_p = self.get_aabb_for_link().get_min_max_points() + self.height = int((max_p.x - min_p.x) // self.resolution) + self.width = int((max_p.y - min_p.y) // self.resolution) self.map = np.ones((self.height, self.width)) - def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: + def get_aabb_for_link(self) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box (AABB) of the link provided when creating this costmap. To try and let the AABB as close to the actual object as possible, the Object will be rotated such that the link will be in the @@ -726,14 +727,14 @@ def get_aabb_for_link(self) -> Tuple[List[float], List[float]]: :return: Two points in world coordinate space, which span a rectangle """ - shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(self.object) + prospection_object = BulletWorld.current_world.get_prospection_object_from_object(self.object) with UseProspectionWorld(): - shadow_obj.set_orientation(Pose(orientation=[0, 0, 0, 1])) - link_orientation = shadow_obj.get_link_pose(self.link) + prospection_object.set_orientation(Pose(orientation=[0, 0, 0, 1])) + link_orientation = prospection_object.get_link_pose(self.link) link_orientation_trans = link_orientation.to_transform(self.object.get_link_tf_frame(self.link)) inverse_orientation = link_orientation_trans.invert() - shadow_obj.set_orientation(inverse_orientation.to_pose()) - return shadow_obj.get_link_aabb(self.link) + prospection_object.set_orientation(inverse_orientation.to_pose()) + return prospection_object.get_link_aabb(self.object.get_link_id(self.link)) cmap = colors.ListedColormap(['white', 'black', 'green', 'red', 'blue']) diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 8f5f5200c..28f0e8cc9 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -95,7 +95,7 @@ def __iter__(self): :yield: A resolved Object designator """ for name in self.names: - if name in self.part_of.bullet_world_object.links.keys(): + if name in self.part_of.bullet_world_object.link_name_to_id.keys(): yield self.Object(name, self.type, self.part_of.bullet_world_object, self.part_of.bullet_world_object.get_link_pose(name)) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index f556a7ab0..691a62617 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -101,7 +101,7 @@ def sync_worlds() -> None: add_gripper_groups() bullet_object_names = set() for obj in BulletWorld.current_world.objects: - if obj.name != robot_description.name and len(obj.links) != 1: + if obj.name != robot_description.name and len(obj.link_name_to_id) != 1: bullet_object_names.add(obj.name + "_" + str(obj.id)) giskard_object_names = set(giskard_wrapper.get_group_names()) @@ -130,7 +130,7 @@ def spawn_object(object: Object) -> None: :param object: BulletWorld object that should be spawned """ - if len(object.links) == 1: + if len(object.link_name_to_id) == 1: geometry = object.urdf_object.link_map[object.urdf_object.get_root()].collision.geometry if isinstance(geometry, urdf_parser_py.urdf.Mesh): filename = geometry.filename diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 0b9feeaca..2ddbbfe7c 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -87,7 +87,7 @@ def frame(self, value: str) -> None: self.header.frame_id = value @property - def position(self) -> GeoPose: + def position(self) -> Union[Point,GeoPose]: """ Property that points to the position of this pose """ @@ -109,6 +109,7 @@ def position(self, value) -> None: self.pose.position.y = value[1] self.pose.position.z = value[2] else: + # TODO: Check if this is correct or if it should be handled as an error self.pose.position = value @property diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index 74b48024f..3b9b21af4 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -28,8 +28,8 @@ def __init__(self, joint_name, fts_topic="/pycram/fts", interval=0.1): self.world = BulletWorld.current_world self.fts_joint_idx = None self.joint_name = joint_name - if joint_name in self.world.robot.joints.keys(): - self.fts_joint_idx = self.world.robot.joints[joint_name] + if joint_name in self.world.robot.joint_name_to_id.keys(): + self.fts_joint_idx = self.world.robot.joint_name_to_id[joint_name] else: raise RuntimeError(f"Could not register ForceTorqueSensor: Joint {joint_name} does not exist in robot object") pb.enableJointForceTorqueSensor(self.world.robot.id, self.fts_joint_idx, enableSensor=1) diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index efc51334d..fb7682e19 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -37,7 +37,7 @@ def _publish(self) -> None: The joint states are published as long as the kill_event is not set by :py:meth:`~JointStatePublisher._stop_publishing` """ robot = BulletWorld.robot - joint_names = [joint_name for joint_name in robot.joints.keys()] + joint_names = [joint_name for joint_name in robot.joint_name_to_id.keys()] seq = 0 while not self.kill_event.is_set(): diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index 6880949f6..1eb0e5943 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -53,7 +53,7 @@ def _update_objects(self) -> None: for obj in self.world.objects: pose = obj.get_pose() self._publish_pose(obj.tf_frame, pose) - for link in obj.links.keys(): + for link in obj.link_name_to_id.keys(): link_pose = obj.get_link_pose(link) self._publish_pose(obj.get_link_tf_frame(link), link_pose) diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 83193c80e..b91ed879a 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -59,14 +59,14 @@ def _make_marker_array(self) -> MarkerArray: for obj in BulletWorld.current_world.objects: if obj.name == "floor": continue - for link in obj.links.keys(): + for link in obj.link_name_to_id.keys(): geom = obj.link_to_geometry[link] if not geom: continue msg = Marker() msg.header.frame_id = "map" msg.ns = obj.name - msg.id = obj.links[link] + msg.id = obj.link_name_to_id[link] msg.type = Marker.MESH_RESOURCE msg.action = Marker.ADD link_pose = obj.get_link_pose(link).to_transform(link) @@ -78,7 +78,7 @@ def _make_marker_array(self) -> MarkerArray: link_pose_with_origin = link_pose * link_origin msg.pose = link_pose_with_origin.to_pose().pose - color = [1, 1, 1, 1] if obj.links[link] == -1 else obj.get_color(link) + color = [1, 1, 1, 1] if obj.link_name_to_id[link] == -1 else obj.get_color(link) msg.color = ColorRGBA(*color) msg.lifetime = rospy.Duration(1) diff --git a/src/pycram/world.py b/src/pycram/world.py index 0203716e1..a8dd25aaa 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -19,7 +19,7 @@ import urdf_parser_py.urdf from geometry_msgs.msg import Quaternion, Point -from urdf_parser_py.urdf import URDF +from urdf_parser_py.urdf import URDF, Collision, GeometricType from .event import Event from .robot_descriptions import robot_description @@ -345,13 +345,10 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: pass @abstractmethod - def get_object_link_pose(self, obj: Object, link_name: str) -> Tuple[List, List]: + def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. The pose is given as a tuple of position and orientation. - - :param obj: The object - :param link_name: The name of the link """ pass @@ -398,27 +395,20 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> pass @abstractmethod - def get_object_joint_id(self, obj: Object, joint_idx: int) -> int: + def get_object_joint_names(self, obj_id: int) -> List[str]: """ - Get the ID of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). + Get the names of all joints of an articulated object. """ pass @abstractmethod - def get_object_joint_name(self, obj: Object, joint_idx: int) -> str: + def get_object_link_names(self, obj_id: int) -> List[str]: """ - Get the name of a joint in an articulated object. - - :param obj: The object - :param joint_idx: The index of the joint (would indicate order). + Get the names of all links of an articulated object. """ pass - @abstractmethod - def get_object_link_name(self, obj: Object, link_idx: int) -> str: + def get_object_link_id(self, obj: Object, link_idx: int) -> str: """ Get the name of a link in an articulated object. @@ -428,11 +418,15 @@ def get_object_link_name(self, obj: Object, link_idx: int) -> str: pass @abstractmethod - def get_object_number_of_joints(self, obj: Object) -> int: + def get_object_number_of_joints(self, obj_id: int) -> int: """ Get the number of joints of an articulated object + """ + pass - :param obj: The object + def get_object_number_of_links(self, obj_id: int) -> int: + """ + Get the number of links of an articulated object """ pass @@ -479,13 +473,13 @@ def set_object_color(self, obj: Object, color: Color, link: Optional[str] = ""): if link == "": # Check if there is only one link, this is the case for primitive # forms or if loaded from an .stl or .obj file - if obj.links != {}: - for link_id in obj.links.values(): + if obj.link_name_to_id != {}: + for link_id in obj.link_name_to_id.values(): self.set_object_link_color(obj, link_id, color) else: self.set_object_link_color(obj, -1, color) else: - self.set_object_link_color(obj, obj.links[link], color) + self.set_object_link_color(obj, obj.link_name_to_id[link], color) @abstractmethod def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): @@ -523,7 +517,7 @@ def get_object_color(self, if link: if link in link_to_color_dict.keys(): return link_to_color_dict[link] - elif link not in obj.links.keys(): + elif link not in obj.link_name_to_id.keys(): rospy.logerr(f"The link '{link}' is not part of this obejct") return None else: @@ -557,14 +551,10 @@ def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: pass @abstractmethod - def get_object_link_aabb(self, obj: Object, link_name: str) -> AxisAlignedBoundingBox: + def get_object_link_aabb(self, obj_id: int, link_id: int) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :param link_name: The name of a link of this object. - :return: AxisAlignedBoundingBox object containing the min and max points of the bounding box. """ pass @@ -774,7 +764,7 @@ def _copy(self) -> World: for obj in self.objects: o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), world, obj.color) - for joint in obj.joints: + for joint in obj.joint_name_to_id: o.set_joint_position(joint, obj.get_joint_position(joint)) return world @@ -946,8 +936,8 @@ def run(self): prospection_obj.set_pose(world_obj.get_pose()) # Manage joint positions - if len(world_obj.joints) > 2: - for joint_name in world_obj.joints.keys(): + if len(world_obj.joint_name_to_id) > 2: + for joint_name in world_obj.joint_name_to_id.keys(): if prospection_obj.get_joint_position(joint_name) != world_obj.get_joint_position(joint_name): prospection_obj.set_positions_of_all_joints(world_obj.get_positions_of_all_joints()) break @@ -977,13 +967,81 @@ def check_for_equal(self) -> None: self.equal_states = eql +class Link: + + def __init__(self, + _id: int, + obj_id: int, + obj_tf_frame: str, + urdf_link: urdf_parser_py.urdf.Link, + world: World, + is_root: Optional[bool] = False): + self.id = _id + self.obj_id = obj_id + self.tf_frame = f"{obj_tf_frame}/{self.name}" if not is_root else obj_tf_frame + self.urdf_link = urdf_link + self.world = world + self.object = world.get_object_by_id(obj_id) + self.local_transformer = self.object.local_transformer + + @property + def transform(self) -> Transform: + """ + The transformation from the world frame to this link frame. + """ + return self.pose.to_transform(self.tf_frame) + + def get_transform_to_other_link(self, other_link: Link): + new_pose = self.local_transformer.transform_pose_to_target_frame(other_link.pose, self.tf_frame) + return new_pose.to_transform(other_link.tf_frame) + + def get_pose_wrt_other_link(self, other_link: Link): + return self.local_transformer.transform_pose_to_target_frame(self.pose, other_link.tf_frame) + + def get_aabb(self) -> AxisAlignedBoundingBox: + return self.world.get_object_link_aabb(self.obj_id, self.id) + + @property + def position(self) -> Point: + return self.pose.position + + @property + def orientation(self): + return self.pose.orientation + + @property + def pose(self): + """ + The pose of the link relative to the world frame. + """ + return self.world.get_object_link_pose(self.obj_id, self.id) + + @property + def name(self): + return self.urdf_link.name + + def get_geometry(self) -> GeometricType: + return None if not self.collision else self.collision.geometry + + @property + def collision(self): + return self.urdf_link.collision + + + + + + class Object: """ Represents a spawned Object in the World. """ - def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: Pose = None, world: World = None, - color: Optional[Color] = Color(), ignore_cached_files: Optional[bool] = False): + def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, + pose: Pose = None, + world: World = None, + color: Optional[Color] = Color(), + ignore_cached_files: Optional[bool] = False): """ The constructor loads the urdf file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. @@ -1007,8 +1065,8 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) - self.joints: Dict[str, int] = self._joint_or_link_name_to_id("joint") - self.links: Dict[str, int] = self._joint_or_link_name_to_id("link") + self.joint_name_to_id: Dict[str, int] = self._get_joint_name_to_id_map() + self.link_name_to_id: Dict[str, int] = self._get_link_name_to_id_map() self.attachments: Dict[Object, Attachment] = {} self.cids: Dict[Object, int] = {} self.original_pose = pose_in_map @@ -1024,7 +1082,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, pose: if self.urdf_object.name == robot_description.name: self.world.set_robot_if_not_set(self) - self.links[self.urdf_object.get_root()] = -1 + self.link_name_to_id[self.urdf_object.get_root()] = -1 self._current_pose = pose_in_map self._current_link_poses: Dict[str, Pose] = {} @@ -1043,7 +1101,7 @@ def _init_current_positions_of_joint(self) -> None: """ Initialize the cached joint position for each joint. """ - for joint_name in self.joints.keys(): + for joint_name in self.joint_name_to_id.keys(): self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) def __repr__(self): @@ -1246,23 +1304,21 @@ def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: pose.pose.orientation = target_orientation self.set_pose(pose) - def _joint_or_link_name_to_id(self, name_type: str) -> Dict[str, int]: + def _get_joint_name_to_id_map(self) -> Dict[str, int]: + """ + Creates a dictionary which maps the joint names to their unique ids. """ - Creates a dictionary which maps the link or joint name to the unique ids used by pybullet. + joint_names = self.world.get_object_joint_names(self.id) + n_joints = len(joint_names) + return dict(zip(joint_names, range(n_joints))) - :param name_type: Determines if the dictionary should be for joints or links - :return: A dictionary that maps joint or link names to unique ids + def _get_link_name_to_id_map(self) -> Dict[str, int]: """ - n_joints = self.world.get_object_number_of_joints(self) - joint_name_to_id = {} - for i in range(0, n_joints): - _id = self.world.get_object_joint_id(self, i) - if name_type == "joint": - _name = self.world.get_object_joint_name(self, i) - else: - _name = self.world.get_object_link_name(self, i) - joint_name_to_id[_name] = _id - return joint_name_to_id + Creates a dictionary which maps the link names to their unique ids. + """ + link_names = self.world.get_object_link_names(self.id) + n_links = len(link_names) + return dict(zip(link_names, range(n_links))) def get_joint_id(self, name: str) -> int: """ @@ -1271,7 +1327,7 @@ def get_joint_id(self, name: str) -> int: :param name: The joint name :return: The unique id """ - return self.joints[name] + return self.joint_name_to_id[name] def get_link_id(self, name: str) -> int: """ @@ -1282,7 +1338,7 @@ def get_link_id(self, name: str) -> int: """ if name is None: return -1 - return self.links[name] + return self.link_name_to_id[name] def get_link_by_id(self, id: int) -> str: """ @@ -1291,7 +1347,7 @@ def get_link_by_id(self, id: int) -> str: :param id: id for link :return: The link name """ - return dict(zip(self.links.values(), self.links.keys()))[id] + return dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys()))[id] def get_joint_by_id(self, joint_id: int) -> str: """ @@ -1300,7 +1356,7 @@ def get_joint_by_id(self, joint_id: int) -> str: :param joint_id: The Pybullet id of for joint :return: The joint name """ - return dict(zip(self.joints.values(), self.joints.keys()))[joint_id] + return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] def get_other_object_link_pose_relative_to_my_link(self, my_link_id: int, @@ -1347,7 +1403,7 @@ def get_link_pose(self, name: str) -> Pose: :param name: Link name for which a Pose should be returned :return: The pose of the link """ - if name in self.links.keys() and self.links[name] == -1: + if name in self.link_name_to_id.keys() and self.link_name_to_id[name] == -1: return self.get_pose() return self._current_link_poses[name] @@ -1358,7 +1414,7 @@ def reset_all_joints_positions(self) -> None: """ Sets the current position of all joints to 0. This is useful if the joints should be reset to their default """ - joint_names = list(self.joints.keys()) + joint_names = list(self.joint_name_to_id.keys()) joint_positions = [0] * len(joint_names) self.set_positions_of_all_joints(dict(zip(joint_names, joint_positions))) @@ -1442,11 +1498,11 @@ def update_joints_from_topic(self, topic_name: str) -> None: msg = rospy.wait_for_message(topic_name, JointState) joint_names = msg.name joint_positions = msg.position - if set(joint_names).issubset(self.joints.keys()): + if set(joint_names).issubset(self.joint_name_to_id.keys()): for i in range(len(joint_names)): self.set_joint_position(joint_names[i], joint_positions[i]) else: - add_joints = set(joint_names) - set(self.joints.keys()) + add_joints = set(joint_names) - set(self.joint_name_to_id.keys()) rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") @@ -1481,8 +1537,8 @@ def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color] def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_aabb(self) - def get_link_aabb(self, link_name: str) -> AxisAlignedBoundingBox: - return self.world.get_object_link_aabb(self, link_name) + def get_link_aabb(self, link_id: int) -> AxisAlignedBoundingBox: + return self.world.get_object_link_aabb(self.id, link_id) def get_base_origin(self) -> Pose: """ @@ -1490,7 +1546,7 @@ def get_base_origin(self) -> Pose: :return: The position of the bottom of this Object """ - aabb = self.get_link_aabb(link_name=self.urdf_object.get_root()) + aabb = self.get_link_aabb(-1) base_width = np.absolute(aabb.min_x - aabb.max_x) base_length = np.absolute(aabb.min_y - aabb.max_y) return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], @@ -1504,7 +1560,7 @@ def get_joint_limits(self, joint: str) -> Tuple[float, float]: :param joint: The name of the joint for which the limits should be found. :return: The lower and upper limit of the joint. """ - if joint not in self.joints.keys(): + if joint not in self.joint_name_to_id.keys(): raise KeyError(f"The given Joint: {joint} is not part of this object") lower, upper = self.world.get_object_joint_limits(self, joint) if lower > upper: @@ -1541,7 +1597,7 @@ def find_joint_above(self, link_name: str, joint_type: JointType) -> str: reversed_chain = reversed(chain) container_joint = None for element in reversed_chain: - if element in self.joints and self.get_joint_type(element) == joint_type: + if element in self.joint_name_to_id and self.get_joint_type(element) == joint_type: container_joint = element break if not container_joint: @@ -1578,7 +1634,7 @@ def get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: :return: A dictionary with link name as key and geometry information as value """ link_to_geometry = {} - for link in self.links.keys(): + for link in self.link_name_to_id.keys(): link_obj = self.urdf_object.link_map[link] if not link_obj.collision: link_to_geometry[link] = None @@ -1593,7 +1649,7 @@ def _update_current_link_poses_and_transforms(self) -> None: """ Updates the cached poses and transforms for each link of this Object """ - for link_name in self.links.keys(): + for link_name in self.link_name_to_id.keys(): if link_name == self.urdf_object.get_root(): self._update_root_link_pose_and_transform() else: @@ -1605,7 +1661,7 @@ def _update_root_link_pose_and_transform(self) -> None: self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) def _update_link_pose_and_transform(self, link_name: str) -> None: - self._current_link_poses[link_name] = Pose(*self.world.get_object_link_pose(self, link_name)) + self._current_link_poses[link_name] = self.world.get_object_link_pose(self.id, self.get_link_id(link_name)) self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( self.get_link_tf_frame(link_name)) diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index d91d396bb..6598c511a 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -48,6 +48,21 @@ class Constraint: joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None +@dataclass +class Point: + x: float + y: float + z: float + + @classmethod + def from_list(cls, point: List[float]): + """ + Sets the point from a list of x, y, z values. + + :param point: The list of x, y, z values + """ + return cls(point[0], point[1], point[2]) + @dataclass class AxisAlignedBoundingBox: """ @@ -70,7 +85,7 @@ def from_min_max(cls, min_point: List[float], max_point: List[float]): """ return cls(min_point[0], min_point[1], min_point[2], max_point[0], max_point[1], max_point[2]) - def get_min_max(self) -> Tuple[List[float], List[float]]: + def get_min_max_points(self) -> Tuple[Point, Point]: """ Returns the axis-aligned bounding box as a tuple of minimum and maximum points. @@ -78,7 +93,31 @@ def get_min_max(self) -> Tuple[List[float], List[float]]: """ return self.get_min_point(), self.get_max_point() - def get_min_point(self) -> List[float]: + def get_min_point(self) -> Point: + """ + Returns the axis-aligned bounding box as a minimum point. + + :return: The axis-aligned bounding box as a minimum point + """ + return Point(self.min_x, self.min_y, self.min_z) + + def get_max_point(self) -> Point: + """ + Returns the axis-aligned bounding box as a maximum point. + + :return: The axis-aligned bounding box as a maximum point + """ + return Point(self.max_x, self.max_y, self.max_z) + + def get_min_max(self) -> Tuple[List[float], List[float]]: + """ + Returns the axis-aligned bounding box as a tuple of minimum and maximum points. + + :return: The axis-aligned bounding box as a tuple of minimum and maximum points + """ + return self.get_min(), self.get_max() + + def get_min(self) -> List[float]: """ Returns the minimum point of the axis-aligned bounding box. @@ -86,7 +125,7 @@ def get_min_point(self) -> List[float]: """ return [self.min_x, self.min_y, self.min_z] - def get_max_point(self) -> List[float]: + def get_max(self) -> List[float]: """ Returns the maximum point of the axis-aligned bounding box. From 17ed78f9c4a35f26195c6f1d9ba52f311c0574a1 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 15 Dec 2023 12:01:37 +0100 Subject: [PATCH 020/195] [WorldAbstractClass] Created links dictionary inside Object class to point to link objects. Removed _current_link_poses and _current_link_transforms --- src/pycram/bullet_world.py | 4 -- src/pycram/world.py | 104 +++++++++++++++++-------------------- 2 files changed, 47 insertions(+), 61 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 1828de269..af139e7ed 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -142,10 +142,6 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. - The pose is given as a tuple of position and orientation. - - :param obj_id: The object - :param link_id: The name of the link """ return Pose(*p.getLinkState(obj_id, link_id, physicsClientId=self.client_id)[4:6]) diff --git a/src/pycram/world.py b/src/pycram/world.py index a8dd25aaa..7e4afdd55 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -348,7 +348,6 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. - The pose is given as a tuple of position and orientation. """ pass @@ -971,18 +970,21 @@ class Link: def __init__(self, _id: int, - obj_id: int, - obj_tf_frame: str, urdf_link: urdf_parser_py.urdf.Link, - world: World, - is_root: Optional[bool] = False): + obj: Object): self.id = _id - self.obj_id = obj_id - self.tf_frame = f"{obj_tf_frame}/{self.name}" if not is_root else obj_tf_frame self.urdf_link = urdf_link - self.world = world - self.object = world.get_object_by_id(obj_id) - self.local_transformer = self.object.local_transformer + self.object = obj + self.world = obj.world + self.tf_frame = f"{obj.tf_frame}/{urdf_link.name}" if not self.is_root else obj.tf_frame + self.local_transformer = LocalTransformer() + + @property + def is_root(self) -> bool: + return self.object.urdf_object.get_root() == self.urdf_link.name + + def update_transform(self, transform_time: Optional[rospy.Time] = None): + self.local_transformer.update_transforms([self.transform], transform_time) @property def transform(self) -> Transform: @@ -991,47 +993,47 @@ def transform(self) -> Transform: """ return self.pose.to_transform(self.tf_frame) - def get_transform_to_other_link(self, other_link: Link): - new_pose = self.local_transformer.transform_pose_to_target_frame(other_link.pose, self.tf_frame) - return new_pose.to_transform(other_link.tf_frame) + def calc_transform_to_link(self, link: Link): + return link.calc_transform_from_link(self) - def get_pose_wrt_other_link(self, other_link: Link): - return self.local_transformer.transform_pose_to_target_frame(self.pose, other_link.tf_frame) + def calc_transform_from_link(self, link: Link) -> Transform: + return self.calc_pose_wrt_link(link).to_transform(self.tf_frame) - def get_aabb(self) -> AxisAlignedBoundingBox: - return self.world.get_object_link_aabb(self.obj_id, self.id) + def calc_pose_wrt_link(self, link: Link) -> Pose: + return self.local_transformer.transform_pose_to_target_frame(self.pose, link.tf_frame) + + def calc_aabb(self) -> AxisAlignedBoundingBox: + return self.world.get_object_link_aabb(self.object.id, self.id) @property def position(self) -> Point: return self.pose.position @property - def orientation(self): + def orientation(self) -> Quaternion: return self.pose.orientation @property - def pose(self): + def pose(self) -> Pose: """ The pose of the link relative to the world frame. """ - return self.world.get_object_link_pose(self.obj_id, self.id) + if self.is_root: + return self.object.get_pose() + return self.world.get_object_link_pose(self.object.id, self.id) @property - def name(self): + def name(self) -> str: return self.urdf_link.name def get_geometry(self) -> GeometricType: return None if not self.collision else self.collision.geometry @property - def collision(self): + def collision(self) -> Collision: return self.urdf_link.collision - - - - class Object: """ Represents a spawned Object in the World. @@ -1045,13 +1047,16 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, """ The constructor loads the urdf file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. - The color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. + The color parameter is only used when loading .stl or .obj files, + for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object :param obj_type: The type of the object - :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched + :param path: The path to the source file, if only a filename is provided then the resourcer directories will be + searched :param pose: The pose at which the Object should be spawned - :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used + :param world: The World in which the object should be spawned, + if no world is specified the :py:attr:`~World.current_world` will be used. :param color: The color with which the object should be spawned. :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ @@ -1083,13 +1088,13 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.world.set_robot_if_not_set(self) self.link_name_to_id[self.urdf_object.get_root()] = -1 + self.links = self._init_links() self._current_pose = pose_in_map self._current_link_poses: Dict[str, Pose] = {} self._current_link_transforms: Dict[str, Transform] = {} self._current_joints_positions = {} self._init_current_positions_of_joint() - self._update_current_link_poses_and_transforms() self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) self.update_link_transforms() @@ -1097,6 +1102,14 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.world.objects.append(self) + def _init_links(self): + links = {} + for urdf_link in self.urdf_object.links: + link_name = urdf_link.name + link_id = self.link_name_to_id[link_name] + links[link_name] = Link(link_id, urdf_link, self) + return links + def _init_current_positions_of_joint(self) -> None: """ Initialize the cached joint position for each joint. @@ -1214,7 +1227,6 @@ def set_pose(self, pose: Pose, base: bool = False) -> None: position = np.array(position) + self.base_origin_shift self.world.reset_object_base_pose(self, position, orientation) self._current_pose = pose_in_map - self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) @property @@ -1403,9 +1415,8 @@ def get_link_pose(self, name: str) -> Pose: :param name: Link name for which a Pose should be returned :return: The pose of the link """ - if name in self.link_name_to_id.keys() and self.link_name_to_id[name] == -1: - return self.get_pose() - return self._current_link_poses[name] + link = self.links[name] + return link.pose if not link.is_root else self.get_pose() def get_link_pose_by_id(self, link_id: int) -> Pose: return self.get_link_pose(self.get_link_by_id(link_id)) @@ -1429,7 +1440,6 @@ def set_positions_of_all_joints(self, joint_poses: dict) -> None: for joint_name, joint_position in joint_poses.items(): self.world.reset_object_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position - self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) def set_joint_position(self, joint_name: str, joint_position: float) -> None: @@ -1453,7 +1463,6 @@ def set_joint_position(self, joint_name: str, joint_position: float) -> None: # return self.world.reset_object_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position - self._update_current_link_poses_and_transforms() self.world._set_attached_objects(self, [self]) def get_joint_position(self, joint_name: str) -> float: @@ -1643,27 +1652,8 @@ def get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: return link_to_geometry def update_link_transforms(self, transform_time: Optional[rospy.Time] = None): - self.local_transformer.update_transforms(self._current_link_transforms.values(), transform_time) - - def _update_current_link_poses_and_transforms(self) -> None: - """ - Updates the cached poses and transforms for each link of this Object - """ - for link_name in self.link_name_to_id.keys(): - if link_name == self.urdf_object.get_root(): - self._update_root_link_pose_and_transform() - else: - self._update_link_pose_and_transform(link_name) - - def _update_root_link_pose_and_transform(self) -> None: - link_name = self.urdf_object.get_root() - self._current_link_poses[link_name] = self._current_pose - self._current_link_transforms[link_name] = self._current_pose.to_transform(self.tf_frame) - - def _update_link_pose_and_transform(self, link_name: str) -> None: - self._current_link_poses[link_name] = self.world.get_object_link_pose(self.id, self.get_link_id(link_name)) - self._current_link_transforms[link_name] = self._current_link_poses[link_name].to_transform( - self.get_link_tf_frame(link_name)) + for link in self.links.values(): + link.update_transform(transform_time) def filter_contact_points(contact_points, exclude_ids) -> List: From 0e70fe2793cbe6136be8cf701bebab3d7ebb8fc4 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 15 Dec 2023 20:04:49 +0100 Subject: [PATCH 021/195] [WorldAbstractClass] removed all link related functionality from Object class to Link class. --- demos/pycram_bullet_world_demo/demo.py | 2 +- doc/source/notebooks/bullet_world.ipynb | 6 +- doc/source/notebooks/intro.ipynb | 1072 ++++++++++++++++- examples/bullet_world.ipynb | 6 +- examples/cram_plan_tutorial.ipynb | 14 +- examples/intro.ipynb | 2 +- examples/local_transformer.ipynb | 4 +- src/pycram/costmaps.py | 15 +- src/pycram/designators/action_designator.py | 8 +- src/pycram/designators/location_designator.py | 4 +- src/pycram/designators/object_designator.py | 2 +- src/pycram/external_interfaces/ik.py | 4 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/helper.py | 9 +- src/pycram/pose.py | 2 +- src/pycram/pose_generator_and_validator.py | 12 +- .../process_modules/boxy_process_modules.py | 10 +- .../process_modules/donbot_process_modules.py | 6 +- .../process_modules/hsr_process_modules.py | 6 +- .../process_modules/pr2_process_modules.py | 15 +- src/pycram/ros/tf_broadcaster.py | 4 +- src/pycram/ros/viz_marker_publisher.py | 9 +- src/pycram/world.py | 190 +-- src/pycram/world_reasoning.py | 4 +- test/test_action_designator.py | 2 +- test/test_bullet_world.py | 4 +- test/test_bullet_world_reasoning.py | 4 +- 27 files changed, 1199 insertions(+), 219 deletions(-) mode change 120000 => 100644 doc/source/notebooks/intro.ipynb diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 36f908fbb..837c3a359 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -61,7 +61,7 @@ def move_and_detect(obj_type): spoon.detach(apartment) # Detect and pickup the spoon - LookAtAction([apartment.get_link_pose("handle_cab10_t")]).resolve().perform() + LookAtAction([apartment.links["handle_cab10_t"].pose]).resolve().perform() spoon_desig = DetectAction(BelieveObject(types=[ObjectType.SPOON])).resolve().perform() diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index 538c2a475..39a9e1d8f 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -409,11 +409,11 @@ } ], "source": [ - "print(f\"Position: \\n{pr2.get_link_position('torso_lift_link')}\")\n", + "print(f\"Position: \\n{pr2.links['torso_lift_link'].position}\")\n", "\n", - "print(f\"Orientation: \\n{pr2.get_link_orientation('torso_lift_link')}\")\n", + "print(f\"Orientation: \\n{pr2.links['torso_lift_link'].orientation}\")\n", "\n", - "print(f\"Pose: \\n{pr2.get_link_pose('torso_lift_link')}\")" + "print(f\"Pose: \\n{pr2.links['torso_lift_link'].pose}\")" ] }, { diff --git a/doc/source/notebooks/intro.ipynb b/doc/source/notebooks/intro.ipynb deleted file mode 120000 index 31a4f6830..000000000 --- a/doc/source/notebooks/intro.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/intro.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/intro.ipynb b/doc/source/notebooks/intro.ipynb new file mode 100644 index 000000000..f5875cb3a --- /dev/null +++ b/doc/source/notebooks/intro.ipynb @@ -0,0 +1,1071 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PyCRAM Presentation" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "ExecuteTime": { + "end_time": "2023-04-05T16:37:51.973404Z", + "start_time": "2023-04-05T16:37:51.483749Z" + } + }, + "outputs": [], + "source": [ + "import pycram" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Bullet World\n", + "\n", + "The BulletWorld is the internal simulation of PyCRAM. You can simulate different actions and reason about the outcome of different actions. \n", + "\n", + "It is possible to spawn objects and robots into the BulletWorld, these objects can come from URDF, OBJ or STL files. \n", + "\n", + "A BulletWorld can be created by simply creating an object of the BulletWorld class. " + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": { + "ExecuteTime": { + "end_time": "2023-04-05T16:37:59.788099Z", + "start_time": "2023-04-05T16:37:57.586879Z" + } + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" + ] + } + ], + "source": [ + "from pycram.bullet_world import BulletWorld, Object\n", + "from pycram.enums import ObjectType\n", + "from pycram.pose import Pose\n", + "\n", + "world = BulletWorld()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The world can also be closed with the 'exit' method" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": { + "ExecuteTime": { + "end_time": "2023-04-05T16:38:04.800655Z", + "start_time": "2023-04-05T16:38:03.943911Z" + } + }, + "outputs": [], + "source": [ + "world.exit()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The BulletWorld allows to render images from arbitrary positoins. In the following example we render images with the camera at the position [0.3, 0, 1] and pointing towards [1, 0, 1], so we are looking upwards along the x-axis. \n", + "\n", + "The renderer returns 3 different kinds of images which are also shown at the left side of the BulletWorld window. These images are:\n", + "* A RGB image which shows everything like it is rendered in the BulletWorld window, just from another perspective. \n", + "* A depth image which consists of distance values from the camera towards the objects in the field of view. \n", + "* A segmentation mask image which segments the image into the different objects displayed. The segmentation is done by assigning every pixel the unique id of the object that is displayed there. " + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[array([[[255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " ...,\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255]],\n", + " \n", + " [[255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " ...,\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255]],\n", + " \n", + " [[255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " ...,\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255],\n", + " [255, 255, 255, 255]],\n", + " \n", + " ...,\n", + " \n", + " [[239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " ...,\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255]],\n", + " \n", + " [[239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " ...,\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255]],\n", + " \n", + " [[239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " ...,\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255],\n", + " [239, 239, 239, 255]]], dtype=uint8),\n", + " array([[0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", + " 0.99999994],\n", + " [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", + " 0.99999994],\n", + " [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", + " 0.99999994],\n", + " ...,\n", + " [0.80473447, 0.80473447, 0.80473447, ..., 0.80473447, 0.80473447,\n", + " 0.80473447],\n", + " [0.8031688 , 0.8031688 , 0.8031688 , ..., 0.8031688 , 0.8031688 ,\n", + " 0.8031688 ],\n", + " [0.80160314, 0.80160314, 0.80160314, ..., 0.80160314, 0.80160314,\n", + " 0.80160314]], dtype=float32),\n", + " array([[-1, -1, -1, ..., -1, -1, -1],\n", + " [-1, -1, -1, ..., -1, -1, -1],\n", + " [-1, -1, -1, ..., -1, -1, -1],\n", + " ...,\n", + " [ 1, 1, 1, ..., 1, 1, 1],\n", + " [ 1, 1, 1, ..., 1, 1, 1],\n", + " [ 1, 1, 1, ..., 1, 1, 1]], dtype=int32)]" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from pycram.bullet_world_reasoning import _get_images_for_target\n", + "\n", + "_get_images_for_target(Pose([1, 0, 1], [0, 0, 0, 1]), Pose([0.3, 0, 1], [0, 0, 0, 1]))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Objects\n", + "Everything that is located inside the BulletWorld is an Object. \n", + "Objects can be created from URDF, OBJ or STL files. Since everything is of type Object a robot might share the same methods as a milk (with some limitations).\n", + "\n", + "Signature:\n", + "Object:\n", + "* Name \n", + "* Type\n", + "* Filename or Filepath\n", + "\n", + " Optional:\n", + " * Position\n", + " * Orientation\n", + " * World \n", + " * Color \n", + " * Ignore Cached Files\n", + "\n", + "If there is only a filename and no path PyCRAM will check in the resource directory if there is a matching file. \n" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "milk = Object(\"Milk\", ObjectType.MILK, \"milk.stl\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Objects provide methods to change the position and rotation, change the color, attach other objects, set the state of joints if the objects has any or get the position and orientation of a link. \n", + "\n", + "These methods are the same for every Object, however since some Objects may not have joints or more than one link methods related to these will not work. " + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "milk.set_position(Pose([1, 0, 0]))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "To remove an Object from the BulletWorld just call the 'remove' method on the Object." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "milk.remove()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Since everything inside the BulletWorld is an Object, even a complex environment Object like the kitchen can be spawned in the same way as the milk." + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Scalar element defined multiple times: limit\n", + "Scalar element defined multiple times: limit\n" + ] + } + ], + "source": [ + "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"kitchen.urdf\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Costmaps\n", + "\n", + "Costmaps are a way to get positions with respect to certain criterias. \n", + "The currently available costmaps are:\n", + "* Occupancy Costmap\n", + "* Visibility Costmap\n", + "* Semantic Costmap \n", + "* Gaussian Costmap\n", + "\n", + "It is also possible to merge multiple costmaps to combine different criteria." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Visibility Costmaps\n", + "Visibility costmaps determine every position, around a target position, from which the target is visible. Visibility Costmaps are able to work with cameras that are moveable in height, for example if the robot has a movable torso. " + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [], + "source": [ + "import pycram.costmaps as cm\n", + "v = cm.VisibilityCostmap(1.27, 1.60, size=300, resolution=0.02, origin=Pose([0, 0, 0.1], [0, 0, 0, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "v.visualize()" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "v.close_visualization()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Occupancy Costmap\n", + "Is valid for every position where the robot can be placed without colliding with an object." + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "o = cm.OccupancyCostmap(0.2, from_ros=False, size=300, resolution=0.02, origin=Pose([0, 0, 0.1], [0, 0, 0, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [], + "source": [ + "s = cm.SemanticCostmap(kitchen, \"kitchen_island_surface\", size=100, resolution=0.02)\n", + "\n", + "g = cm.GaussianCostmap(200, 15, resolution=0.02)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "You can visualize the costmap in the BulletWorld to get an impression what information is actually contained in the costmap. With this you could also check if the costmap was created correctly. \n", + "Visualization can be done via the 'visualize' method of each costmap." + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "o.visualize()" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [], + "source": [ + "o.close_visualization()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "It is also possible to combine two costmap, this will result in a new costmap with the same size which contains the information of both previous costmaps. Combination is done by checking for each position in the two costmaps if they are zero, in this case to same position in the new costmap will also be zero in any other case the new position will be the normalized product of the two combined costmaps." + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "ov = o + v" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [], + "source": [ + "ov.visualize()" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [], + "source": [ + "ov.close_visualization()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Bullet World Reasoning \n", + "Allows for geometric reasoning in the BulletWorld. At the moment the following types of reasoning are supported:\n", + "* Stable\n", + "* Contact\n", + "* Visible \n", + "* Occluding \n", + "* Reachable \n", + "* Blocking\n", + "* Supporting\n", + "\n", + "To show the geometric reasoning we first a robot as well as the milk Object again." + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" + ] + } + ], + "source": [ + "import pycram.bullet_world_reasoning as btr\n", + "milk = Object(\"Milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([1, 0, 1]))\n", + "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We start with testing for visibility " + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Milk visible: True\n" + ] + } + ], + "source": [ + "milk.set_position(Pose([1,0,1]))\n", + "visible = btr.visible(milk, pr2.links[\"wide_stereo_optical_frame\"].pose)\n", + "print(f\"Milk visible: {visible}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Milk is in contact with the floor: True\n" + ] + } + ], + "source": [ + "milk.set_position(Pose([1, 0, 0.05]))\n", + "\n", + "plane = BulletWorld.current_bullet_world.objects[0]\n", + "contact = btr.contact(milk, plane)\n", + "print(f\"Milk is in contact with the floor: {contact}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Milk is reachable for the PR2: True\n" + ] + } + ], + "source": [ + "milk.set_position(Pose([0.6, -0.5, 0.7]))\n", + "\n", + "reachable = btr.reachable(milk, pr2, \"r_gripper_tool_frame\")\n", + "print(f\"Milk is reachable for the PR2: {reachable}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Designator\n", + "Designator are symbolic descriptions of Actions, Motions, Objects or Locations. In PyCRAM the different types of designators are representet by a class which takes a description, the description then tells the designator what to do. \n", + "\n", + "For example, let's look at a Motion Designator to move the robot to a specific location. \n", + "\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Motion Designator\n", + "\n", + "When using a Motion Designator you need to specify which Process Module needs to be used, either the Process Module for the real or the simulated robot. This can be done either with a decorator which can be added to a function and then executes every designator in this function on the specified robot. The other possibility is a \"with\" scope which wraps a code piece. \n", + "\n", + "These two ways can also be combined, you could write a function which should be executed on the real robot and in the function is a \"with\" scope which executes something on the simulated robot for reasoning purposes. " + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.designators.motion_designator import *\n", + "from pycram.process_module import simulated_robot, with_simulated_robot\n", + "\n", + "description = MoveMotion(target=Pose([1, 0, 0], [0, 0, 0, 1]))\n", + "\n", + "with simulated_robot:\n", + " description.resolve().perform()\n", + " \n" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "from pycram.process_module import with_simulated_robot\n", + "\n", + "@with_simulated_robot\n", + "def move():\n", + " MoveMotion(target=Pose([0, 0, 0], [0, 0, 0, 1])).resolve().perform()\n", + "\n", + "move()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Other implemented Motion Designator descriptions are:\n", + "* Pick up\n", + "* Place\n", + "* Accessing\n", + "* Move TCP\n", + "* Looking\n", + "* Move Gripper\n", + "* Detecting\n", + "* Move Arm Joint \n", + "* World State Detecting " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Object Designator\n", + "\n", + "Object Designator represent objects, these objects could either be from the BulletWorld or the real world. Object Designator are used, for example, by the PickUpAction to know which object should be picked up." + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \n", + "local_transformer=, \n", + "name=Milk, \n", + "type=ObjectType.MILK, \n", + "color=[1, 1, 1, 1], \n", + "id=4, \n", + "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", + "joints: ..., \n", + "links: ..., \n", + "attachments: ..., \n", + "cids: ..., \n", + "original_pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448180\n", + " nsecs: 830921888\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 1.0\n", + " y: 0.0\n", + " z: 1.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0, \n", + "tf_frame=Milk_4, \n", + "urdf_object: ..., \n", + "_current_pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448184\n", + " nsecs: 735546827\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0, \n", + "_current_link_poses={'milk_main': header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448184\n", + " nsecs: 735546827\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0}, \n", + "_current_link_transforms={'milk_main': header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448185\n", + " nsecs: 354960680\n", + " frame_id: \"map\"\n", + "child_frame_id: \"Milk_4\"\n", + "transform: \n", + " translation: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " rotation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0}, \n", + "_current_joint_states={}, \n", + "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", + "link_to_geometry={'milk_main': }), _pose=, \n", + "local_transformer=, \n", + "name=Milk, \n", + "type=ObjectType.MILK, \n", + "color=[1, 1, 1, 1], \n", + "id=4, \n", + "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", + "joints: ..., \n", + "links: ..., \n", + "attachments: ..., \n", + "cids: ..., \n", + "original_pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448180\n", + " nsecs: 830921888\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 1.0\n", + " y: 0.0\n", + " z: 1.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0, \n", + "tf_frame=Milk_4, \n", + "urdf_object: ..., \n", + "_current_pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448184\n", + " nsecs: 735546827\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0, \n", + "_current_link_poses={'milk_main': header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448184\n", + " nsecs: 735546827\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0}, \n", + "_current_link_transforms={'milk_main': header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1699448185\n", + " nsecs: 354960680\n", + " frame_id: \"map\"\n", + "child_frame_id: \"Milk_4\"\n", + "transform: \n", + " translation: \n", + " x: 0.6\n", + " y: -0.5\n", + " z: 0.7\n", + " rotation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0\n", + " w: 1.0}, \n", + "_current_joint_states={}, \n", + "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", + "link_to_geometry={'milk_main': })>)" + ] + }, + "execution_count": 25, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from pycram.designators.object_designator import *\n", + "\n", + "milk_desig = BelieveObject(names=[\"Milk\"])\n", + "milk_desig.resolve()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Location Designator\n", + "Location Designator can create a position in cartisian space from a symbolic desctiption" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "scrolled": false + }, + "outputs": [], + "source": [ + "from pycram.designators.location_designator import *\n", + "from pycram.designators.object_designator import *\n", + "\n", + "robot_desig = BelieveObject(types=[ObjectType.ROBOT]).resolve()\n", + "milk_desig = BelieveObject(names=[\"Milk\"]).resolve()\n", + "location_desig = CostmapLocation(target=milk_desig, visible_for=robot_desig)\n", + "\n", + "print(f\"Resolved: {location_desig.resolve()}\")\n", + "print()\n", + "\n", + "for pose in location_desig:\n", + " print(pose)\n", + " " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Action Designator\n", + "Action Designator are used to describe high-level actions. Action Designator are usually composed of other Designators to describe the high-level action in detail. " + ] + }, + { + "cell_type": "code", + "execution_count": 29, + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.designators.action_designator import *\n", + "from pycram.enums import Arms\n", + "\n", + "with simulated_robot:\n", + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Making a simple plan\n", + "To get familiar with the PyCRAM Framework we will write a simple pick and place plan. This plan will let the robot grab a cereal box from the kitchen counter and place it on the kitchen island. This is a simple pick and place plan." + ] + }, + { + "cell_type": "code", + "execution_count": 30, + "metadata": {}, + "outputs": [], + "source": [ + "from pycram.designators.object_designator import *\n", + "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", pose=Pose([1.4, 1, 0.95]))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 31, + "metadata": {}, + "outputs": [], + "source": [ + "cereal_desig = ObjectDesignatorDescription(names=[\"cereal\"])\n", + "kitchen_desig = ObjectDesignatorDescription(names=[\"kitchen\"])\n", + "robot_desig = ObjectDesignatorDescription(names=[\"pr2\"]).resolve()\n", + "with simulated_robot:\n", + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n", + "\n", + " MoveTorsoAction([0.3]).resolve().perform()\n", + "\n", + " pickup_pose = CostmapLocation(target=cereal_desig.resolve(), reachable_for=robot_desig).resolve()\n", + " pickup_arm = pickup_pose.reachable_arms[0]\n", + "\n", + " NavigateAction(target_locations=[pickup_pose.pose]).resolve().perform()\n", + "\n", + " PickUpAction(object_designator_description=cereal_desig, arms=[pickup_arm], grasps=[\"front\"]).resolve().perform()\n", + "\n", + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n", + "\n", + " place_island = SemanticCostmapLocation(\"kitchen_island_surface\", kitchen_desig.resolve(), cereal_desig.resolve()).resolve()\n", + "\n", + " place_stand = CostmapLocation(place_island.pose, reachable_for=robot_desig, reachable_arm=pickup_arm).resolve()\n", + "\n", + " NavigateAction(target_locations=[place_stand.pose]).resolve().perform()\n", + "\n", + " PlaceAction(cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform()\n", + "\n", + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n", + " \n", + " \n", + " " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Task Trees\n", + "Task trees are a hirachical representation of all Actions involved in a plan. The Task tree can later be used to inspect and restructre the execution order of Actions in the plan." + ] + }, + { + "cell_type": "code", + "execution_count": 32, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "no_operation()\n", + "├── perform(ParkArmsAction, )\n", + "├── perform(ParkArmsAction, )\n", + "├── perform(MoveTorsoAction, )\n", + "├── perform(NavigateAction, )\n", + "├── perform(PickUpAction, )\n", + "├── perform(ParkArmsAction, )\n", + "├── perform(NavigateAction, )\n", + "├── perform(PlaceAction, )\n", + "└── perform(ParkArmsAction, )\n" + ] + } + ], + "source": [ + "import pycram.task\n", + "import anytree\n", + "tt = pycram.task.task_tree\n", + "print(anytree.RenderTree(tt))" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [], + "source": [ + "from anytree.dotexport import RenderTreeGraph, DotExporter\n", + "RenderTreeGraph(tt).to_picture(\"tree.png\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ORM\n" + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Inserting TaskTree into database: 100%|██████████| 10/10 [00:00<00:00, 143.50it/s]\n" + ] + }, + { + "data": { + "text/plain": [ + "pycram.orm.task.TaskTreeNode(1, 2023-11-08 13:55:09.816577, None, TaskStatus.RUNNING, None, None, 1, 1)" + ] + }, + "execution_count": 34, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import sqlalchemy\n", + "import sqlalchemy.orm\n", + "import pycram.orm.base\n", + "import pycram.orm.task\n", + "import pycram.orm.object_designator\n", + "import pycram.orm.motion_designator\n", + "import pycram.orm.action_designator\n", + "\n", + "# set description of what we are doing\n", + "pycram.orm.base.MetaData().description = \"Tutorial for getting familiar with the ORM.\"\n", + "\n", + "engine = sqlalchemy.create_engine(\"sqlite+pysqlite:///:memory:\", echo=False)\n", + "session = sqlalchemy.orm.Session(bind=engine)\n", + "pycram.orm.base.Base.metadata.create_all(engine)\n", + "session.commit()\n", + "\n", + "\n", + "tt.insert(session)" + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "pycram.orm.action_designator.NavigateAction(Navigate, 4, 4, 1, 4, 4)\n", + "pycram.orm.action_designator.NavigateAction(Navigate, 7, 7, 1, 9, 9)\n" + ] + } + ], + "source": [ + "navigations = session.query(pycram.orm.action_designator.NavigateAction).all()\n", + "print(*navigations, sep=\"\\n\")" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "(pycram.orm.action_designator.NavigateAction(Navigate, 4, 4, 1, 4, 4), pycram.orm.base.Position(0.5799999999999998, 1.28, 0.0, 4, None), pycram.orm.base.Quaternion(0.0, 0.0, 0.16378361324016077, -0.9864962889104031, 4, None))\n", + "(pycram.orm.action_designator.NavigateAction(Navigate, 7, 7, 1, 9, 9), pycram.orm.base.Position(-1.9074999952316287, 0.779200015068054, 0.0, 9, None), pycram.orm.base.Quaternion(0.0, 0.0, 0.16439898730535735, 0.9863939238321437, 9, None))\n" + ] + } + ], + "source": [ + "navigations = session.query(pycram.orm.action_designator.NavigateAction, \n", + " pycram.orm.base.Position, \n", + " pycram.orm.base.Quaternion).\\\n", + " join(pycram.orm.base.Position).\\\n", + " join(pycram.orm.base.Quaternion).all()\n", + "print(*navigations, sep=\"\\n\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index 67016f4d2..110886ce6 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -351,11 +351,11 @@ } ], "source": [ - "print(f\"Position: \\n{pr2.get_link_position('torso_lift_link')}\")\n", + "print(f\"Position: \\n{pr2.links['torso_lift_link'].position}\")\n", "\n", - "print(f\"Orientation: \\n{pr2.get_link_orientation('torso_lift_link')}\")\n", + "print(f\"Orientation: \\n{pr2.links['torso_lift_link'].orientation}\")\n", "\n", - "print(f\"Pose: \\n{pr2.get_link_pose('torso_lift_link')}\")" + "print(f\"Pose: \\n{pr2.links['torso_lift_link'].pose}\")" ] }, { diff --git a/examples/cram_plan_tutorial.ipynb b/examples/cram_plan_tutorial.ipynb index d322d7be3..1777b511e 100644 --- a/examples/cram_plan_tutorial.ipynb +++ b/examples/cram_plan_tutorial.ipynb @@ -81,7 +81,7 @@ "robot_desig = ObjectDesignatorDescription(names=['pr2']).resolve()\n", "apartment = Object(\"apartment\", \"environment\", \"/home/abassi/cram_ws/src/iai_maps/iai_apartment/urdf/apartment.urdf\", position=[-1.5, -2.5, 0])\n", "apartment_desig = ObjectDesignatorDescription(names=['apartment']).resolve()\n", - "table_top = apartment.get_link_position(\"cooktop\")\n", + "table_top = apartment.links[\"cooktop\"].position\n", "# milk = Object(\"milk\", \"milk\", \"milk.stl\", position=[table_top[0]-0.15, table_top[1], table_top[2]])\n", "# milk.set_position(position=milk.get_position(), base=True)\n", "# cereal = Object(\"cereal\", \"cereal\", \"breakfast_cereal.stl\", position=table_top)\n", @@ -213,8 +213,8 @@ "source": [ "import pybullet as p\n", "for link_name in apartment.links.keys():\n", - " world.add_vis_axis(apartment.get_link_position_and_orientation(link_name))\n", - " p.addUserDebugText(link_name, apartment.get_link_position(link_name))" + " world.add_vis_axis(apartment.links[link_name].pose)\n", + " p.addUserDebugText(link_name, apartment.links[link_name].position)" ] }, { @@ -720,10 +720,10 @@ "evalue": "name 'world' is not defined", "output_type": "error", "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", - "Cell \u001b[0;32mIn[1], line 1\u001b[0m\n\u001b[0;32m----> 1\u001b[0m \u001b[43mworld\u001b[49m\u001b[38;5;241m.\u001b[39mexit()\n", - "\u001b[0;31mNameError\u001b[0m: name 'world' is not defined" + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mNameError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[1], line 1\u001B[0m\n\u001B[0;32m----> 1\u001B[0m \u001B[43mworld\u001B[49m\u001B[38;5;241m.\u001B[39mexit()\n", + "\u001B[0;31mNameError\u001B[0m: name 'world' is not defined" ] } ], diff --git a/examples/intro.ipynb b/examples/intro.ipynb index aea7c14fb..f5875cb3a 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -491,7 +491,7 @@ ], "source": [ "milk.set_position(Pose([1,0,1]))\n", - "visible = btr.visible(milk, pr2.get_link_pose(\"wide_stereo_optical_frame\"))\n", + "visible = btr.visible(milk, pr2.links[\"wide_stereo_optical_frame\"].pose)\n", "print(f\"Milk visible: {visible}\")" ] }, diff --git a/examples/local_transformer.ipynb b/examples/local_transformer.ipynb index 31017bebb..4ff40178e 100644 --- a/examples/local_transformer.ipynb +++ b/examples/local_transformer.ipynb @@ -298,7 +298,7 @@ "\n", "Furthermore, links of an Object are represented by the Object frame_id + '/' + link name. Since link names need to be unique for an URDF this is no problem.\n", "\n", - "These frames need to be used in whenever you are transforming something with the local transformer. To get the base frame of an Object, meaning the frame name without any link there is the attribute tf_frame and for the frame of a link there is the method get_link_tf_frame. " + "These frames need to be used in whenever you are transforming something with the local transformer. To get the base frame of an Object, meaning the frame name without any link there is the attribute tf_frame and for the frame of a link there is the collection links from which you can access all link objects by name, link objects also have the attribute tf_frame which gives the tf_frame of the link. " ] }, { @@ -319,7 +319,7 @@ "source": [ "print(milk.tf_frame)\n", "\n", - "print(kitchen.get_link_tf_frame(\"kitchen_island_surface\"))" + "print(kitchen.links[\"kitchen_island_surface\"].tf_frame)" ] } ], diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index bc21b122d..b0d2f5ccb 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -9,7 +9,7 @@ import psutil import time from .bullet_world import BulletWorld -from pycram.world import UseProspectionWorld, Object +from pycram.world import UseProspectionWorld, Object, Link from .world_reasoning import _get_images_for_target from .world_dataclasses import AxisAlignedBoundingBox from nav_msgs.msg import OccupancyGrid, MapMetaData @@ -699,9 +699,9 @@ def __init__(self, object, urdf_link_name, size=100, resolution=0.02, world=None """ self.world: BulletWorld = world if world else BulletWorld.current_world self.object: Object = object - self.link: str = urdf_link_name + self.link: Link = object.links[urdf_link_name] self.resolution: float = resolution - self.origin: Pose = object.get_link_pose(urdf_link_name) + self.origin: Pose = object.links[urdf_link_name].pose self.height: int = 0 self.width: int = 0 self.map: np.ndarray = [] @@ -730,11 +730,10 @@ def get_aabb_for_link(self) -> AxisAlignedBoundingBox: prospection_object = BulletWorld.current_world.get_prospection_object_from_object(self.object) with UseProspectionWorld(): prospection_object.set_orientation(Pose(orientation=[0, 0, 0, 1])) - link_orientation = prospection_object.get_link_pose(self.link) - link_orientation_trans = link_orientation.to_transform(self.object.get_link_tf_frame(self.link)) - inverse_orientation = link_orientation_trans.invert() - prospection_object.set_orientation(inverse_orientation.to_pose()) - return prospection_object.get_link_aabb(self.object.get_link_id(self.link)) + link_pose_trans = self.link.transform + inverse_trans = link_pose_trans.invert() + prospection_object.set_orientation(inverse_trans.to_pose()) + return self.link.get_aabb() cmap = colors.ListedColormap(['white', 'black', 'green', 'red', 'blue']) diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index deeb06d68..1bb027ca0 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -328,7 +328,7 @@ def perform(self) -> None: # prepose depending on the gripper (its annoying we have to put pr2_1 here tbh # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" - gripper_frame = robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm)) + gripper_frame = robot.links[robot_description.get_tool_frame(self.arm)].tf_frame # First rotate the gripper, so the further calculations makes sense tmp_for_rotate_pose = object.local_transformer.transform_pose_to_target_frame(adjusted_oTm, gripper_frame) tmp_for_rotate_pose.pose.position.x = 0 @@ -436,9 +436,9 @@ def perform(self) -> None: local_tf = LocalTransformer() # Transformations such that the target position is the position of the object and not the tcp + tool_name = robot_description.get_tool_frame(self.arm) tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, - BulletWorld.robot.get_link_tf_frame( - robot_description.get_tool_frame(self.arm))) + BulletWorld.robot.links[tool_name].tf_frame) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() @@ -887,7 +887,7 @@ def perform(self) -> Any: gripper_name = robot_description.get_tool_frame(self.arm) object_pose_in_gripper = lt.transform_pose_to_target_frame(object_pose, - BulletWorld.robot.get_link_tf_frame(gripper_name)) + BulletWorld.robot.links[gripper_name].tf_frame) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index a8f2ab689..d726f8957 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -339,8 +339,8 @@ def __iter__(self): sem_costmap = SemanticCostmap(self.part_of.bullet_world_object, self.urdf_link_name) height_offset = 0 if self.for_object: - min, max = self.for_object.bullet_world_object.get_aabb() - height_offset = (max[2] - min[2]) / 2 + min_p, max_p = self.for_object.bullet_world_object.get_aabb().get_min_max_points() + height_offset = (max_p.z - min_p.z) / 2 for maybe_pose in pose_generator(sem_costmap): maybe_pose.position.z += height_offset yield self.Location(maybe_pose) diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 28f0e8cc9..7ba1491b3 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -97,7 +97,7 @@ def __iter__(self): for name in self.names: if name in self.part_of.bullet_world_object.link_name_to_id.keys(): yield self.Object(name, self.type, self.part_of.bullet_world_object, - self.part_of.bullet_world_object.get_link_pose(name)) + self.part_of.bullet_world_object.links[name].pose) class LocatedObject(ObjectDesignatorDescription): diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 8a5dc60bb..f0aeaac94 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -45,7 +45,7 @@ def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_ob :return: A moveit_msgs/PositionIKRequest message containing all the information from the parameter """ local_transformer = LocalTransformer() - target_pose = local_transformer.transform_pose_to_target_frame(target_pose, robot_object.get_link_tf_frame(root_link)) + target_pose = local_transformer.transform_pose_to_target_frame(target_pose, robot_object.links[root_link].tf_frame) robot_state = RobotState() joint_state = JointState() @@ -124,7 +124,7 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str # Get link after last joint in chain end_effector = robot_description.get_child(joints[-1]) - target_torso = local_transformer.transform_pose_to_target_frame(target_pose, robot.get_link_tf_frame(base_link)) + target_torso = local_transformer.transform_pose_to_target_frame(target_pose, robot.links[base_link].tf_frame) # target_torso = _transform_to_torso(pose, shadow_robot) diff = calculate_wrist_tool_offset(end_effector, gripper, robot) diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index bbfcadd50..b2574b55b 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -125,7 +125,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti for i in range(0, len(query_result.res[0].pose)): pose = Pose.from_pose_stamped(query_result.res[0].pose[i]) - pose.frame = BulletWorld.current_world.robot.get_link_tf_frame(pose.frame) + pose.frame = BulletWorld.current_world.robot.links[pose.frame].tf_frame # TODO: pose.frame is a link name? source = query_result.res[0].poseSource[i] lt = LocalTransformer() diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 719fd040c..c098eca99 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -61,9 +61,7 @@ def _apply_ik(robot: BulletWorldObject, joint_poses: List[float], joints: List[s def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robot: BulletWorldObject) -> Tuple[ List[float], List[float]]: - # map_T_torso = robot.get_link_position_and_orientation("base_footprint") - # map_T_torso = robot.get_position_and_orientation() - map_T_torso = robot.get_link_pose(robot_description.torso_link).to_list() + map_T_torso = robot.links[robot_description.torso_link].pose_as_list torso_T_map = p.invertTransform(map_T_torso[0], map_T_torso[1]) map_T_target = pose_and_rotation torso_T_target = p.multiplyTransforms(torso_T_map[0], torso_T_map[1], map_T_target[0], map_T_target[1]) @@ -71,10 +69,7 @@ def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robo def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: BulletWorldObject) -> Transform: - local_transformer = LocalTransformer() - tool_pose = robot.get_link_pose(tool_frame) - wrist_to_tool = local_transformer.transform_pose_to_target_frame(tool_pose, robot.get_link_tf_frame(wrist_frame)) - return wrist_to_tool.to_transform(robot.get_link_tf_frame(tool_frame)) + return robot.links[wrist_frame].get_transform_to_link(robot.links[tool_frame]) def inverseTimes(transform1: Tuple[List[float], List[float]], transform2: Tuple[List[float], List[float]]) -> Tuple[ diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 2ddbbfe7c..e707aaa61 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -87,7 +87,7 @@ def frame(self, value: str) -> None: self.header.frame_id = value @property - def position(self) -> Union[Point,GeoPose]: + def position(self) -> GeoPose: """ Property that points to the position of this pose """ diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 5ae4b0b9d..e94805a29 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -97,14 +97,14 @@ def visibility_validator(pose: Pose, robot_pose = robot.get_pose() if type(object_or_pose) == Object: robot.set_pose(pose) - camera_pose = robot.get_link_pose(robot_description.get_camera_frame()) + camera_pose = robot.links[robot_description.get_camera_frame()].pose robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) ray = p.rayTest(camera_pose.position_as_list(), object_or_pose.get_pose().position_as_list(), physicsClientId=world.client_id) res = ray[0][0] == object_or_pose.id else: robot.set_pose(pose) - camera_pose = robot.get_link_pose(robot_description.get_camera_frame()) + camera_pose = robot.links[robot_description.get_camera_frame()].pose robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) ray = p.rayTest(camera_pose.position_as_list(), object_or_pose, physicsClientId=world.client_id) res = ray[0][0] == -1 @@ -155,7 +155,6 @@ def reachability_validator(pose: Pose, try: # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) resp = request_ik(target, robot, left_joints, left_gripper) - _apply_ik(robot, resp, left_joints) for obj in BulletWorld.current_world.objects: @@ -166,8 +165,7 @@ def reachability_validator(pose: Pose, if in_contact: for link in contact_links: - - if link[0] in allowed_robot_links or link[1] in allowed_links: + if link[0].name in allowed_robot_links or link[1].name in allowed_links: in_contact = False if not in_contact: @@ -179,7 +177,6 @@ def reachability_validator(pose: Pose, try: # resp = request_ik(base_link, end_effector, target_diff, robot, right_joints) resp = request_ik(target, robot, right_joints, right_gripper) - _apply_ik(robot, resp, right_joints) for obj in BulletWorld.current_world.objects: @@ -190,8 +187,7 @@ def reachability_validator(pose: Pose, if in_contact: for link in contact_links: - - if link[0] in allowed_robot_links or link[1] in allowed_links: + if link[0].name in allowed_robot_links or link[1].name in allowed_links: in_contact = False if not in_contact: diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 2e8fc74f3..ad2932322 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -113,16 +113,14 @@ def _execute(self, desig): robot.set_joint_position(robot_description.torso_joint, -0.1) arm = "left" if solution['gripper'] == robot_description.get_tool_frame("left") else "right" joints = robot_description._safely_access_chains(arm).joints - #inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), kitchen.get_link_position(drawer_handle)) - target = helper._transform_to_torso(kitchen.get_link_position_and_orientation(drawer_handle), robot) - #target = (target[0], [0, 0, 0, 1]) + target = helper._transform_to_torso(kitchen.links[drawer_handle].pose, robot) inv = request_ik(robot_description.base_frame, gripper, target , robot, joints ) helper._apply_ik(robot, inv, gripper) time.sleep(0.2) cur_pose = robot.get_pose() robot.set_position([cur_pose[0]-dis, cur_pose[1], cur_pose[2]]) - han_pose = kitchen.get_link_position(drawer_handle) - new_p = [[han_pose[0] - dis, han_pose[1], han_pose[2]], kitchen.get_link_orientation(drawer_handle)] + han_pose = kitchen.links[drawer_handle].position + new_p = [[han_pose[0] - dis, han_pose[1], han_pose[2]], kitchen.links[drawer_handle].orientation] new_p = helper._transform_to_torso(new_p, robot) inv = request_ik(robot_description.base_frame, gripper, new_p, robot, joints) helper._apply_ik(robot, inv, gripper) @@ -227,7 +225,7 @@ def _execute(self, desig): objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): + if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): return obj diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index dfc5dc7ed..fd103e5eb 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -95,10 +95,10 @@ def _execute(self, desig): drawer_joint = solution['drawer_joint'] dis = solution['distance'] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), - kitchen.get_link_position(drawer_handle)) + kitchen.links[drawer_handle].position) helper._apply_ik(robot, inv) time.sleep(0.2) - han_pose = kitchen.get_link_position(drawer_handle) + han_pose = kitchen.links[drawer_handle].position new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) helper._apply_ik(robot, inv) @@ -190,7 +190,7 @@ def _execute(self, desig): objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): + if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): return obj diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 974ef8ac3..02ca0edcf 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -89,10 +89,10 @@ def _execute(self, desig): drawer_joint = solution['drawer_joint'] dis = solution['distance'] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), - kitchen.get_link_position(drawer_handle)) + kitchen.links[drawer_handle].position) _apply_ik(robot, inv) time.sleep(0.2) - han_pose = kitchen.get_link_position(drawer_handle) + han_pose = kitchen.links[drawer_handle].position new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) _apply_ik(robot, inv) @@ -163,7 +163,7 @@ def _execute(self, desig): objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): + if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): return obj diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 253d37df1..8c96af6e7 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -97,7 +97,8 @@ def _execute(self, desig: PlaceMotion.Motion): # Transformations such that the target position is the position of the object and not the tcp object_pose = object.get_pose() local_tf = LocalTransformer() - tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) + tool_name = robot_description.get_tool_frame(arm) + tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, robot.links[tool_name].tf_frame) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) @@ -115,8 +116,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_pan_link")) - pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_tilt_link")) + pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.links["head_pan_link"].tf_frame) + pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.links["head_tilt_link"].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -158,7 +159,7 @@ def _execute(self, desig: DetectingMotion.Motion): objects = BulletWorld.current_world.get_objects_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): + if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis): return obj @@ -295,8 +296,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_pan_link")) - pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.get_link_tf_frame("head_tilt_link")) + pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.links["head_pan_link"].tf_frame) + pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.links["head_tilt_link"].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -321,7 +322,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose_to_target_frame(obj_pose, BulletWorld.robot.get_link_tf_frame("torso_lift_link")) + obj_pose = lt.transform_pose_to_target_frame(obj_pose, BulletWorld.robot.links["torso_lift_link"].tf_frame) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index 1eb0e5943..cde266ef1 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -54,8 +54,8 @@ def _update_objects(self) -> None: pose = obj.get_pose() self._publish_pose(obj.tf_frame, pose) for link in obj.link_name_to_id.keys(): - link_pose = obj.get_link_pose(link) - self._publish_pose(obj.get_link_tf_frame(link), link_pose) + link_pose = obj.links[link].pose + self._publish_pose(obj.links[link].tf_frame, link_pose) def _update_static_odom(self) -> None: """ diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index b91ed879a..9d629aa52 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -60,7 +60,7 @@ def _make_marker_array(self) -> MarkerArray: if obj.name == "floor": continue for link in obj.link_name_to_id.keys(): - geom = obj.link_to_geometry[link] + geom = obj.links[link].get_geometry() if not geom: continue msg = Marker() @@ -69,10 +69,9 @@ def _make_marker_array(self) -> MarkerArray: msg.id = obj.link_name_to_id[link] msg.type = Marker.MESH_RESOURCE msg.action = Marker.ADD - link_pose = obj.get_link_pose(link).to_transform(link) - if obj.urdf_object.link_map[link].collision.origin: - link_origin = Transform(obj.urdf_object.link_map[link].collision.origin.xyz, - list(quaternion_from_euler(*obj.urdf_object.link_map[link].collision.origin.rpy))) + link_pose = obj.links[link].transform + if obj.links[link].origin: + link_origin = obj.links[link].get_origin_transform() else: link_origin = Transform() link_pose_with_origin = link_pose * link_origin diff --git a/src/pycram/world.py b/src/pycram/world.py index 7e4afdd55..671fbfaf3 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -10,6 +10,7 @@ import xml.etree.ElementTree from queue import Queue import tf +from tf.transformations import quaternion_from_euler from typing import List, Optional, Dict, Tuple, Callable from typing import Union @@ -993,26 +994,34 @@ def transform(self) -> Transform: """ return self.pose.to_transform(self.tf_frame) - def calc_transform_to_link(self, link: Link): - return link.calc_transform_from_link(self) + def get_transform_to_link(self, link: Link): + return link.get_transform_from_link(self) - def calc_transform_from_link(self, link: Link) -> Transform: - return self.calc_pose_wrt_link(link).to_transform(self.tf_frame) + def get_transform_from_link(self, link: Link) -> Transform: + return self.get_pose_wrt_link(link).to_transform(self.tf_frame) - def calc_pose_wrt_link(self, link: Link) -> Pose: + def get_pose_wrt_link(self, link: Link) -> Pose: return self.local_transformer.transform_pose_to_target_frame(self.pose, link.tf_frame) - def calc_aabb(self) -> AxisAlignedBoundingBox: + def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_link_aabb(self.object.id, self.id) @property def position(self) -> Point: return self.pose.position + @property + def position_as_list(self) -> List[float]: + return self.pose.position_as_list() + @property def orientation(self) -> Quaternion: return self.pose.orientation + @property + def orientation_as_list(self) -> List[float]: + return self.pose.orientation_as_list() + @property def pose(self) -> Pose: """ @@ -1022,6 +1031,10 @@ def pose(self) -> Pose: return self.object.get_pose() return self.world.get_object_link_pose(self.object.id, self.id) + @property + def pose_as_list(self) -> List[List[float]]: + return self.pose.to_list() + @property def name(self) -> str: return self.urdf_link.name @@ -1029,6 +1042,13 @@ def name(self) -> str: def get_geometry(self) -> GeometricType: return None if not self.collision else self.collision.geometry + def get_origin_transform(self): + return Transform(self.origin.xyz, list(quaternion_from_euler(*self.origin.rpy))) + + @property + def origin(self): + return self.collision.origin + @property def collision(self) -> Collision: return self.urdf_link.collision @@ -1072,6 +1092,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) self.joint_name_to_id: Dict[str, int] = self._get_joint_name_to_id_map() self.link_name_to_id: Dict[str, int] = self._get_link_name_to_id_map() + self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) self.attachments: Dict[Object, Attachment] = {} self.cids: Dict[Object, int] = {} self.original_pose = pose_in_map @@ -1088,17 +1109,13 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.world.set_robot_if_not_set(self) self.link_name_to_id[self.urdf_object.get_root()] = -1 + self.link_id_to_name[-1] = self.urdf_object.get_root() self.links = self._init_links() self._current_pose = pose_in_map - self._current_link_poses: Dict[str, Pose] = {} - self._current_link_transforms: Dict[str, Transform] = {} self._current_joints_positions = {} self._init_current_positions_of_joint() - - self.base_origin_shift = np.array(position) - np.array(self.get_base_origin().position_as_list()) self.update_link_transforms() - self.link_to_geometry = self.get_geometry_for_link() self.world.objects.append(self) @@ -1117,9 +1134,15 @@ def _init_current_positions_of_joint(self) -> None: for joint_name in self.joint_name_to_id.keys(): self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) + @property + def base_origin_shift(self) -> np.ndarray: + """ + The shift between the base of the object and the origin of the object. + """ + return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) + def __repr__(self): - skip_attr = ["links", "joints", "urdf_object", "attachments", "cids", "_current_link_poses", - "_current_link_transforms", "link_to_geometry"] + skip_attr = ["links", "joints", "urdf_object", "attachments", "cids"] return self.__class__.__qualname__ + f"(" + ', \n'.join( [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" @@ -1266,18 +1289,6 @@ def _set_attached_objects(self, prev_object: List[Object]) -> None: """ self.world._set_attached_objects(self, prev_object) - def _calculate_transform_from_other_object_base_to_this_object_base(self, other_object: Object): - pose_wrt_this_object_base = self.local_transformer.transform_pose_to_target_frame(other_object.pose, - self.tf_frame) - return Transform.from_pose_and_child_frame(pose_wrt_this_object_base, other_object.tf_frame) - - def transform_pose_to_link_frame(self, pose: Pose, link_name: str) -> Union[Pose, None]: - """ - :return: The new pose transformed to be relative to the link coordinate frame. - """ - target_frame = self.get_link_tf_frame(link_name) - return self.local_transformer.transform_pose_to_target_frame(pose, target_frame) - def set_position(self, position: Union[Pose, Point], base=False) -> None: """ Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position @@ -1341,25 +1352,22 @@ def get_joint_id(self, name: str) -> int: """ return self.joint_name_to_id[name] - def get_link_id(self, name: str) -> int: + def get_link_id(self, link_name: str) -> int: """ - Returns a unique id for a link name. If the name is None return -1. - - :param name: The link name - :return: The unique id + Returns a unique id for a link name. """ - if name is None: - return -1 - return self.link_name_to_id[name] + if link_name is None: + return self.get_root_link_id() + return self.link_name_to_id[link_name] - def get_link_by_id(self, id: int) -> str: - """ - Returns the name of a link for a given unique link id + def get_root_link_id(self) -> int: + return self.get_link_id(self.urdf_object.get_root()) - :param id: id for link - :return: The link name + def get_link_by_id(self, link_id: int) -> Link: + """ + Returns the link for a given unique link id """ - return dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys()))[id] + return self.links[self.link_id_to_name[link_id]] def get_joint_by_id(self, joint_id: int) -> str: """ @@ -1370,57 +1378,6 @@ def get_joint_by_id(self, joint_id: int) -> str: """ return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] - def get_other_object_link_pose_relative_to_my_link(self, - my_link_id: int, - other_link_id: int, - other_object: Object) -> Pose: - """ - Calculates the pose of a link (child_link) in the coordinate frame of another link (parent_link). - :return: The pose of the source frame in the target frame - """ - - child_link_pose = other_object.get_link_pose(other_object.get_link_by_id(other_link_id)) - parent_link_frame = self.get_link_tf_frame(self.get_link_by_id(my_link_id)) - return self.local_transformer.transform_pose_to_target_frame(child_link_pose, parent_link_frame) - - def get_transform_from_my_link_to_other_object_link(self, - my_link_id: int, - other_link_id: int, - other_object: Object) -> Transform: - pose = self.get_other_object_link_pose_relative_to_my_link(my_link_id, other_link_id, other_object) - return pose.to_transform(other_object.get_link_tf_frame_by_id(other_link_id)) - - def get_link_position(self, name: str) -> Pose.position: - """ - Returns the position of a link of this Object. Position is returned as a list of xyz. - - :param name: The link name - :return: The link position as xyz - """ - return self.get_link_pose(name).position - - def get_link_orientation(self, name: str) -> Quaternion: - """ - Returns the orientation of a link of this Object. Orientation is returned as a quaternion. - - :param name: The name of the link - :return: The orientation of the link as a quaternion - """ - return self.get_link_pose(name).orientation - - def get_link_pose(self, name: str) -> Pose: - """ - Returns a Pose of the link corresponding to the given name. The returned Pose will be in world coordinate frame. - - :param name: Link name for which a Pose should be returned - :return: The pose of the link - """ - link = self.links[name] - return link.pose if not link.is_root else self.get_pose() - - def get_link_pose_by_id(self, link_id: int) -> Pose: - return self.get_link_pose(self.get_link_by_id(link_id)) - def reset_all_joints_positions(self) -> None: """ Sets the current position of all joints to 0. This is useful if the joints should be reset to their default @@ -1546,16 +1503,13 @@ def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color] def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_aabb(self) - def get_link_aabb(self, link_id: int) -> AxisAlignedBoundingBox: - return self.world.get_object_link_aabb(self.id, link_id) - def get_base_origin(self) -> Pose: """ Returns the origin of the base/bottom of an object :return: The position of the bottom of this Object """ - aabb = self.get_link_aabb(-1) + aabb = self.get_link_by_id(-1).get_aabb() base_width = np.absolute(aabb.min_x - aabb.max_x) base_length = np.absolute(aabb.min_y - aabb.max_y) return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], @@ -1621,36 +1575,6 @@ def get_positions_of_all_joints(self) -> Dict[str: float]: """ return self._current_joints_positions - def get_link_tf_frame(self, link_name: str) -> str: - """ - Returns the name of the tf frame for the given link name. This method does not check if the given name is - actually a link of this object. - - :param link_name: Name of a link for which the tf frame should be returned - :return: A TF frame name for a specific link - """ - if link_name == self.urdf_object.get_root(): - return self.tf_frame - return self.tf_frame + "/" + link_name - - def get_link_tf_frame_by_id(self, link_id: int) -> str: - return self.get_link_tf_frame(self.get_link_by_id(link_id)) - - def get_geometry_for_link(self) -> Dict[str, urdf_parser_py.urdf.GeometricType]: - """ - Extracts the geometry information for each collision of each link and links them to the respective link. - - :return: A dictionary with link name as key and geometry information as value - """ - link_to_geometry = {} - for link in self.link_name_to_id.keys(): - link_obj = self.urdf_object.link_map[link] - if not link_obj.collision: - link_to_geometry[link] = None - else: - link_to_geometry[link] = link_obj.collision.geometry - return link_to_geometry - def update_link_transforms(self, transform_time: Optional[rospy.Time] = None): for link in self.links.values(): link.update_transform(transform_time) @@ -1711,10 +1635,10 @@ def __init__(self, """ self.parent_object = parent_object self.child_object = child_object - self.parent_link_id = parent_link_id - self.child_link_id = child_link_id + self.parent_link = parent_object.get_link_by_id(parent_link_id) + self.child_link = child_object.get_link_by_id(child_link_id) self.bidirectional = bidirectional - self._loose = False and not self.bidirectional + self._loose = False and not bidirectional self.child_to_parent_transform = child_to_parent_transform if self.child_to_parent_transform is None: @@ -1736,9 +1660,7 @@ def update_constraint(self): self.add_constraint_and_update_objects_constraints_collection() def calculate_transform(self): - return self.parent_object.get_transform_from_my_link_to_other_object_link(self.parent_link_id, - self.child_link_id, - self.child_object) + return self.parent_link.get_transform_to_link(self.child_link) def remove_constraint_if_exists(self): if self.constraint_id is not None: @@ -1752,8 +1674,8 @@ def add_fixed_constraint(self): constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, self.child_object.id, self.child_to_parent_transform, - self.parent_link_id, - self.child_link_id) + self.parent_link.id, + self.child_link.id) return constraint_id def update_objects_constraints_collection(self): @@ -1761,8 +1683,8 @@ def update_objects_constraints_collection(self): self.child_object.cids[self.parent_object] = self.constraint_id def get_inverse(self): - attachment = Attachment(self.child_object, self.parent_object, self.child_link_id, - self.parent_link_id, self.bidirectional, self.child_to_parent_transform.invert(), + attachment = Attachment(self.child_object, self.parent_object, self.child_link.id, + self.parent_link.id, self.bidirectional, self.child_to_parent_transform.invert(), self.constraint_id) attachment.loose = False if self.loose else True return attachment diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 9847100ba..c6e696ca5 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -279,7 +279,7 @@ def reachable(pose: Union[Object, Pose], _apply_ik(shadow_robot, inv, joints) - diff = pose.dist(shadow_robot.get_link_pose(gripper_name)) + diff = pose.dist(shadow_robot.links[gripper_name].pose) return diff < threshold @@ -362,4 +362,4 @@ def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], l with UseProspectionWorld(): for joint, pose in joint_config.items(): shadow_object.set_joint_position(joint, pose) - return shadow_object.get_link_pose(link_name) + return shadow_object.links[link_name].pose diff --git a/test/test_action_designator.py b/test/test_action_designator.py index e5bf75c46..8a90f76ef 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -130,7 +130,7 @@ def test_grasping(self): with simulated_robot: description.resolve().perform() dist = np.linalg.norm( - np.array(self.robot.get_link_pose(robot_description.get_tool_frame("right")).position_as_list()) - + np.array(self.robot.links[robot_description.get_tool_frame("right")].position_as_list) - np.array(self.milk.get_pose().position_as_list())) self.assertTrue(dist < 0.01) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index b32256c8c..b0fea4b38 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -34,10 +34,10 @@ def test_object_movement(self): def test_robot_orientation(self): self.robot.set_pose(Pose([0, 1, 1])) - head_position = self.robot.get_link_position('head_pan_link').z + head_position = self.robot.links['head_pan_link'].position.z #self.robot.set_orientation(list(2*tf.transformations.quaternion_from_euler(0, 0, np.pi, axes="sxyz"))) self.robot.set_orientation(Pose(orientation=[0, 0, 1, 1])) - self.assertEqual(self.robot.get_link_position('head_pan_link').z, head_position) + self.assertEqual(self.robot.links['head_pan_link'].position.z, head_position) def tearDown(self): self.world.reset_world() diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index 085b15d47..2fc1055cd 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -18,13 +18,13 @@ def test_visible(self): self.milk.set_pose(Pose([1.5, 0, 1.2])) self.robot.set_pose(Pose()) time.sleep(1) - self.assertTrue(btr.visible(self.milk, self.robot.get_link_pose(robot_description.get_camera_frame()), + self.assertTrue(btr.visible(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, robot_description.front_facing_axis)) def test_occluding(self): self.milk.set_pose(Pose([3, 0, 1.2])) self.robot.set_pose(Pose()) - self.assertTrue(btr.occluding(self.milk, self.robot.get_link_pose(robot_description.get_camera_frame()), + self.assertTrue(btr.occluding(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, robot_description.front_facing_axis) != []) def test_reachable(self): From 417c17627ad0dedf048b163f649510d656bc597f Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Fri, 22 Dec 2023 11:59:04 +0100 Subject: [PATCH 022/195] [AbstractWorld] Refactoring of link related methods. Removal of redundant methods and/or properties --- src/pycram/bullet_world.py | 20 +++--- src/pycram/world.py | 115 +++++++++++++++------------------- src/pycram/world_reasoning.py | 4 +- test/test_bullet_world.py | 2 +- 4 files changed, 60 insertions(+), 81 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index af139e7ed..33bf00967 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -195,15 +195,6 @@ def get_object_number_of_joints(self, obj_id: int) -> int: """ return p.getNumJoints(obj_id, self.client_id) - def get_object_link_id(self, obj_id: int, link_name: str) -> int: - """ - Get the ID of a link in an articulated object. - - :param obj: The object - :param link_name: The name of the link - """ - return self.get_object_by_id(obj_id).link_name_to_id[link_name] - def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -242,7 +233,10 @@ def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): """ p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) - def get_object_colors(self, obj: Object) -> Dict[str, Color]: + def get_color_of_object_link(self, obj: Object, link_name: str) -> Color: + return self.get_colors_of_all_links_of_object(obj)[link_name] + + def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to color. @@ -250,9 +244,9 @@ def get_object_colors(self, obj: Object) -> Dict[str, Color]: :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. """ visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) - swap = {v: k for k, v in obj.link_name_to_id.items()} - links = list(map(lambda x: swap[x[1]] if x[1] != -1 else "base", visual_data)) - colors = Color.from_rgba(list(map(lambda x: x[7], visual_data))) + link_id_to_name = {v: k for k, v in obj.link_name_to_id.items()} + links = list(map(lambda x: link_id_to_name[x[1]] if x[1] != -1 else "base", visual_data)) + colors = list(map(lambda x: Color.from_rgba(x[7]), visual_data)) link_to_color = dict(zip(links, colors)) return link_to_color diff --git a/src/pycram/world.py b/src/pycram/world.py index 671fbfaf3..618c9d8ef 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -173,7 +173,7 @@ def remove_object(self, obj_id: int) -> None: """ pass - def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: + def _set_attached_objects_poses(self, parent, prev_object: List[Object]) -> None: """ Updates the positions of all attached objects. This is done by calculating the new pose in world coordinate frame and setting the @@ -198,7 +198,7 @@ def _set_attached_objects(self, parent, prev_object: List[Object]) -> None: world_to_object.position_as_list(), world_to_object.orientation_as_list()) child._current_pose = world_to_object - self._set_attached_objects(child, prev_object + [parent]) + self._set_attached_objects_poses(child, prev_object + [parent]) def attach_objects(self, parent_object: Object, @@ -408,15 +408,6 @@ def get_object_link_names(self, obj_id: int) -> List[str]: """ pass - def get_object_link_id(self, obj: Object, link_idx: int) -> str: - """ - Get the name of a link in an articulated object. - - :param obj: The object - :param link_idx: The index of the link (would indicate order). - """ - pass - @abstractmethod def get_object_number_of_joints(self, obj_id: int) -> int: """ @@ -492,12 +483,13 @@ def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): """ pass - def get_object_color(self, - obj: Object, - link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: + @abstractmethod + def get_color_of_object_link(self, obj: Object, link_name: str) -> Color: + pass + + def get_color_of_object(self, obj: Object) -> Union[Color, Dict[str, Color]]: """ - This method returns the color of this object or a link of this object. If no link is given then the - return is either: + This method returns the color of this object. The return is either: 1. A Color object with RGBA values, this is the case if the object only has one link (this happens for example if the object is spawned from a .obj or .stl file) @@ -505,24 +497,9 @@ def get_object_color(self, Please keep in mind that not every link may have a color. This is dependent on the URDF from which the object is spawned. - If a link is specified then the return is a list with RGBA values representing the color of this link. - It may be that this link has no color, in this case the return is None as well as an error message. - :param obj: The object for which the color should be returned. - :param link: the link name for which the color should be returned. - :return: The color of the object or link, or a dictionary containing every colored link with its color """ - link_to_color_dict = self.get_object_colors(obj) - - if link: - if link in link_to_color_dict.keys(): - return link_to_color_dict[link] - elif link not in obj.link_name_to_id.keys(): - rospy.logerr(f"The link '{link}' is not part of this obejct") - return None - else: - rospy.logerr(f"The link '{link}' has no color") - return None + link_to_color_dict = self.get_colors_of_all_links_of_object(obj) if len(link_to_color_dict) == 1: return list(link_to_color_dict.values())[0] @@ -530,7 +507,7 @@ def get_object_color(self, return link_to_color_dict @abstractmethod - def get_object_colors(self, obj: Object) -> Dict[str, Color]: + def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to color. @@ -982,7 +959,7 @@ def __init__(self, @property def is_root(self) -> bool: - return self.object.urdf_object.get_root() == self.urdf_link.name + return self.object.get_root_link_id() == self.id def update_transform(self, transform_time: Optional[rospy.Time] = None): self.local_transformer.update_transforms([self.transform], transform_time) @@ -1007,7 +984,7 @@ def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_link_aabb(self.object.id, self.id) @property - def position(self) -> Point: + def position(self) -> Pose.position: return self.pose.position @property @@ -1029,7 +1006,8 @@ def pose(self) -> Pose: """ if self.is_root: return self.object.get_pose() - return self.world.get_object_link_pose(self.object.id, self.id) + else: + return self.world.get_object_link_pose(self.object.id, self.id) @property def pose_as_list(self) -> List[List[float]]: @@ -1053,6 +1031,14 @@ def origin(self): def collision(self) -> Collision: return self.urdf_link.collision + @property + def color(self) -> Color: + return self.world.get_color_of_object_link(self.object, self.name) + + @color.setter + def color(self, color: Color) -> None: + self.world.set_object_link_color(self.object, self.id, color) + class Object: """ @@ -1188,6 +1174,8 @@ def attach(self, :param child_link: The link name of the other object. :param bidirectional: If the attachment should be a loose attachment. """ + parent_link = self.urdf_object.get_root() if parent_link is None else parent_link + child_link = child_object.urdf_object.get_root() if child_link is None else child_link self.world.attach_objects(self, child_object, self.get_link_id(parent_link), @@ -1229,6 +1217,22 @@ def get_orientation(self) -> Pose.orientation: """ return self.get_pose().orientation + def get_position_as_list(self) -> List[float]: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_pose().position_as_list() + + def get_orientation_as_list(self) -> List[float]: + """ + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw + """ + return self.get_pose().orientation_as_list() + def get_pose(self) -> Pose: """ Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. @@ -1250,25 +1254,7 @@ def set_pose(self, pose: Pose, base: bool = False) -> None: position = np.array(position) + self.base_origin_shift self.world.reset_object_base_pose(self, position, orientation) self._current_pose = pose_in_map - self.world._set_attached_objects(self, [self]) - - @property - def pose(self) -> Pose: - """ - Property that returns the current position of this Object. - - :return: The position as a list of xyz - """ - return self.get_pose() - - @pose.setter - def pose(self, value: Pose) -> None: - """ - Sets the Pose of the Object to the given value. Function for attribute use. - - :param value: New Pose of the Object - """ - self.set_pose(value) + self._set_attached_objects_poses() def move_base_to_origin_pos(self) -> None: """ @@ -1277,7 +1263,7 @@ def move_base_to_origin_pos(self) -> None: """ self.set_pose(self.get_pose(), base=True) - def _set_attached_objects(self, prev_object: List[Object]) -> None: + def _set_attached_objects_poses(self) -> None: """ Updates the positions of all attached objects. This is done by calculating the new pose in world coordinate frame and setting the @@ -1287,7 +1273,7 @@ def _set_attached_objects(self, prev_object: List[Object]) -> None: :param prev_object: A list of Objects that were already moved, these will be excluded to prevent loops in the update. """ - self.world._set_attached_objects(self, prev_object) + self.world._set_attached_objects_poses(self, [self]) def set_position(self, position: Union[Pose, Point], base=False) -> None: """ @@ -1352,17 +1338,16 @@ def get_joint_id(self, name: str) -> int: """ return self.joint_name_to_id[name] + def get_root_link_id(self) -> int: + return self.get_link_id(self.urdf_object.get_root()) + def get_link_id(self, link_name: str) -> int: """ Returns a unique id for a link name. """ - if link_name is None: - return self.get_root_link_id() + assert link_name is not None return self.link_name_to_id[link_name] - def get_root_link_id(self) -> int: - return self.get_link_id(self.urdf_object.get_root()) - def get_link_by_id(self, link_id: int) -> Link: """ Returns the link for a given unique link id @@ -1397,7 +1382,7 @@ def set_positions_of_all_joints(self, joint_poses: dict) -> None: for joint_name, joint_position in joint_poses.items(): self.world.reset_object_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position - self.world._set_attached_objects(self, [self]) + self._set_attached_objects_poses() def set_joint_position(self, joint_name: str, joint_position: float) -> None: """ @@ -1420,7 +1405,7 @@ def set_joint_position(self, joint_name: str, joint_position: float) -> None: # return self.world.reset_object_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position - self.world._set_attached_objects(self, [self]) + self._set_attached_objects_poses() def get_joint_position(self, joint_name: str) -> float: """ @@ -1498,7 +1483,7 @@ def set_color(self, color: Color, link: Optional[str] = "") -> None: self.world.set_object_color(self, color, link) def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: - return self.world.get_object_color(self, link) + return self.world.get_color_of_object(self, link) def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_aabb(self) diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index c6e696ca5..1e5f48c3e 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -100,14 +100,14 @@ def stable(object: Object, world, world_id = _world_and_id(world) shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) with UseProspectionWorld(): - coords_prev = shadow_obj.pose.position_as_list() + coords_prev = shadow_obj.get_position_as_list() state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) # one Step is approximately 1/240 seconds BulletWorld.current_world.simulate(2) # coords_past = p.getBasePositionAndOrientation(object.id, physicsClientId=world_id)[0] - coords_past = shadow_obj.pose.position_as_list() + coords_past = shadow_obj.get_position_as_list() # p.restoreState(state, physicsClientId=BulletWorld.current_bullet_world.client_id) coords_prev = list(map(lambda n: round(n, 3), coords_prev)) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index b0fea4b38..6e62cd458 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -30,7 +30,7 @@ def setUp(self): def test_object_movement(self): self.milk.set_position(Pose([0, 1, 1])) - self.assertEqual(self.milk.get_pose().position_as_list(), [0, 1, 1]) + self.assertEqual(self.milk.get_position_as_list(), [0, 1, 1]) def test_robot_orientation(self): self.robot.set_pose(Pose([0, 1, 1])) From fae2d8fdc2155ab59ba8c6dec2d7a0bc12d78bab Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sun, 24 Dec 2023 12:42:40 +0100 Subject: [PATCH 023/195] [AbstractWorld] Objects are responsible for attachments not World. Links are responsible for constraints. --- demos/pycram_bullet_world_demo/demo.py | 10 +- src/pycram/bullet_world.py | 10 +- src/pycram/world.py | 198 ++++++++++++------------- src/pycram/world_dataclasses.py | 4 +- 4 files changed, 111 insertions(+), 111 deletions(-) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 837c3a359..eabdd2ac2 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -2,7 +2,9 @@ from pycram.designators.location_designator import * from pycram.designators.object_designator import * from pycram.pose import Pose -from pycram.bullet_world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world import Object +from pycram.world_dataclasses import Color from pycram.process_module import simulated_robot, with_simulated_robot from pycram.enums import ObjectType @@ -10,11 +12,11 @@ robot = Object("pr2", ObjectType.ROBOT, "pr2.urdf", pose=Pose([1, 2, 0])) apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") -milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([2.5, 2, 1.02]), color=[1, 0, 0, 1]) +milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([2.5, 2, 1.02]), color=Color(1, 0, 0, 1)) cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([2.5, 2.3, 1.05]), color=[0, 1, 0, 1]) -spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", pose=Pose([2.4, 2.2, 0.85]), color=[0, 0, 1, 1]) -bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=Pose([2.5, 2.2, 1.02]), color=[1, 1, 0, 1]) +spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", pose=Pose([2.4, 2.2, 0.85]), color=Color(0, 0, 1, 1)) +bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=Pose([2.5, 2.2, 1.02]), color=Color(1, 1, 0, 1)) apartment.attach(spoon, 'cabinet10_drawer_top') pick_pose = Pose([2.7, 2.15, 1]) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 33bf00967..ad1cc7abe 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -73,10 +73,16 @@ def add_constraint(self, constraint: Constraint) -> int: """ Add a constraint between two objects so that attachment they become attached """ + + parent_obj = self.get_object_by_id(constraint.parent_obj_id) + parent_link_id = parent_obj.link_name_to_id[constraint.parent_link_name] + child_obj = self.get_object_by_id(constraint.child_obj_id) + child_link_id = child_obj.link_name_to_id[constraint.child_link_name] + constraint_id = p.createConstraint(constraint.parent_obj_id, - constraint.parent_link_id, + parent_link_id, constraint.child_obj_id, - constraint.child_link_id, + child_link_id, constraint.joint_type.as_int(), constraint.joint_axis_in_child_link_frame, constraint.joint_frame_position_wrt_parent_origin, diff --git a/src/pycram/world.py b/src/pycram/world.py index 618c9d8ef..6e9aec3f1 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -188,8 +188,8 @@ def _set_attached_objects_poses(self, parent, prev_object: List[Object]) -> None if child in prev_object: continue if not parent.attachments[child].bidirectional: - parent.attachments[child].update_attachment() - child.attachments[parent].update_attachment() + parent.attachments[child].update_transform_and_constraint() + child.attachments[parent].update_transform_and_constraint() else: link_to_object = parent.attachments[child].child_to_parent_transform @@ -200,37 +200,7 @@ def _set_attached_objects_poses(self, parent, prev_object: List[Object]) -> None child._current_pose = world_to_object self._set_attached_objects_poses(child, prev_object + [parent]) - def attach_objects(self, - parent_object: Object, - child_object: Object, - parent_link_id: Optional[int] = -1, - child_link_id: Optional[int] = -1, - bidirectional: Optional[bool] = True) -> None: - """ - Attaches two objects together by saving the current transformation between the links coordinate frames. - Furthermore, a constraint will be created so the attachment also works while in simulation. - - :param bidirectional: If the parent should also follow the child. - """ - - # Add the attachment to the attachment dictionary of both objects - attachment = Attachment(parent_object, child_object, parent_link_id, child_link_id, bidirectional) - self.update_objects_attachments_collection(parent_object, child_object, attachment) - self.attachment_event(parent_object, [parent_object, child_object]) - - def update_objects_attachments_collection(self, - parent_object: Object, - child_object: Object, - attachment: Attachment) -> None: - parent_object.attachments[child_object] = attachment - child_object.attachments[parent_object] = attachment.get_inverse() - - def add_fixed_constraint(self, - parent_object_id: int, - child_object_id: int, - child_to_parent_transform: Transform, - parent_link_id: Optional[int] = -1, - child_link_id: Optional[int] = -1) -> int: + def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_parent_transform: Transform) -> int: """ Creates a fixed joint constraint between the given parent and child links, the joint frame will be at the origin of the child link frame, and would have the same orientation @@ -238,11 +208,11 @@ def add_fixed_constraint(self, returns the constraint id """ - # -1 in link id means use the base link of the object - constraint = Constraint(parent_obj_id=parent_object_id, - parent_link_id=parent_link_id, - child_obj_id=child_object_id, - child_link_id=child_link_id, + + constraint = Constraint(parent_obj_id=parent_link.get_object_id(), + parent_link_name=parent_link.name, + child_obj_id=child_link.get_object_id(), + child_link_name=child_link.name, joint_type=JointType.FIXED, joint_axis_in_child_link_frame=[0, 0, 0], joint_frame_position_wrt_parent_origin=child_to_parent_transform.translation_as_list(), @@ -259,24 +229,6 @@ def add_constraint(self, constraint: Constraint) -> int: """ pass - @staticmethod - def detach_objects(obj1: Object, obj2: Object) -> None: - """ - Detaches obj2 from obj1. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of pybullet. - Afterward the detachment event of the corresponding BulletWorld will be fired. - - :param obj1: The object from which an object should be detached. - :param obj2: The object which should be detached. - """ - del obj1.attachments[obj2] - del obj2.attachments[obj1] - del obj1.cids[obj2] - del obj2.cids[obj1] - - obj1.world.detachment_event(obj1, [obj1, obj2]) - @abstractmethod def remove_constraint(self, constraint_id): pass @@ -954,8 +906,22 @@ def __init__(self, self.urdf_link = urdf_link self.object = obj self.world = obj.world - self.tf_frame = f"{obj.tf_frame}/{urdf_link.name}" if not self.is_root else obj.tf_frame self.local_transformer = LocalTransformer() + self.constraint_ids: Dict[Link, int] = {} + + def add_fixed_constraint_with_link(self, child_link: Link) -> None: + constraint_id = self.world.add_fixed_constraint(self, + child_link, + child_link.get_transform_from_link(self)) + self.constraint_ids[child_link] = constraint_id + child_link.constraint_ids[self] = constraint_id + + def get_object_id(self) -> int: + return self.object.id + + @property + def tf_frame(self) -> str: + return f"{self.object.tf_frame}/{self.urdf_link.name}" @property def is_root(self) -> bool: @@ -1004,10 +970,7 @@ def pose(self) -> Pose: """ The pose of the link relative to the world frame. """ - if self.is_root: - return self.object.get_pose() - else: - return self.world.get_object_link_pose(self.object.id, self.id) + return self.world.get_object_link_pose(self.object.id, self.id) @property def pose_as_list(self) -> List[List[float]]: @@ -1039,6 +1002,25 @@ def color(self) -> Color: def color(self, color: Color) -> None: self.world.set_object_link_color(self.object, self.id, color) + def remove_constraint_with(self, child_link: Link) -> None: + self.world.remove_constraint(self.constraint_ids[child_link]) + del self.constraint_ids[child_link] + del child_link.constraint_ids[self] + + +class RootLink(Link): + + def __init__(self, obj: Object): + super().__init__(obj.get_root_link_id(), obj.get_root_urdf_link(), obj) + + @property + def tf_frame(self) -> str: + return self.object.tf_frame + + @property + def pose(self) -> Pose: + return self.object.get_pose() + class Object: """ @@ -1110,7 +1092,10 @@ def _init_links(self): for urdf_link in self.urdf_object.links: link_name = urdf_link.name link_id = self.link_name_to_id[link_name] - links[link_name] = Link(link_id, urdf_link, self) + if link_name == self.urdf_object.get_root(): + links[link_name] = RootLink(self) + else: + links[link_name] = Link(link_id, urdf_link, self) return links def _init_current_positions_of_joint(self) -> None: @@ -1154,6 +1139,9 @@ def remove(self) -> None: if World.robot == self: World.robot = None + def remove_constraint_with(self, obj: Object) -> None: + self.world.remove_constraint(self.cids[obj]) + def attach(self, child_object: Object, parent_link: Optional[str] = None, @@ -1174,13 +1162,15 @@ def attach(self, :param child_link: The link name of the other object. :param bidirectional: If the attachment should be a loose attachment. """ - parent_link = self.urdf_object.get_root() if parent_link is None else parent_link - child_link = child_object.urdf_object.get_root() if child_link is None else child_link - self.world.attach_objects(self, - child_object, - self.get_link_id(parent_link), - child_object.get_link_id(child_link), - bidirectional) + parent_link = self.links[parent_link] if parent_link else self.get_root_link() + child_link = child_object.links[child_link] if child_link else child_object.get_root_link() + + attachment = Attachment(parent_link, child_link, bidirectional) + + self.attachments[child_object] = attachment + child_object.attachments[self] = attachment.get_inverse() + + self.world.attachment_event(self, [self, child_object]) def detach(self, child_object: Object) -> None: """ @@ -1191,7 +1181,10 @@ def detach(self, child_object: Object) -> None: :param child_object: The object which should be detached """ - self.world.detach_objects(self, child_object) + del self.attachments[child_object] + del child_object.attachments[self] + + self.world.detachment_event(self, [self, child_object]) def detach_all(self) -> None: """ @@ -1199,7 +1192,7 @@ def detach_all(self) -> None: """ attachments = self.attachments.copy() for att in attachments.keys(): - self.world.detach_objects(self, att) + self.detach(att) def get_position(self) -> Pose.position: """ @@ -1338,6 +1331,21 @@ def get_joint_id(self, name: str) -> int: """ return self.joint_name_to_id[name] + def get_root_urdf_link(self) -> urdf_parser_py.urdf.Link: + """ + Returns the root link of the URDF of this object. + """ + link_name = self.urdf_object.get_root() + for link in self.urdf_object.links: + if link.name == link_name: + return link + + def get_root_link(self) -> Link: + """ + Returns the root link of this object. + """ + return self.links[self.urdf_object.get_root()] + def get_root_link_id(self) -> int: return self.get_link_id(self.urdf_object.get_root()) @@ -1608,20 +1616,18 @@ def _get_robot_name_from_urdf(urdf_string: str) -> str: class Attachment: def __init__(self, - parent_object: Object, - child_object: Object, - parent_link_id: Optional[int] = -1, # -1 means base link - child_link_id: Optional[int] = -1, + parent_link: Link, + child_link: Link, bidirectional: Optional[bool] = False, child_to_parent_transform: Optional[Transform] = None, constraint_id: Optional[int] = None): """ Creates an attachment between the parent object and the child object. """ - self.parent_object = parent_object - self.child_object = child_object - self.parent_link = parent_object.get_link_by_id(parent_link_id) - self.child_link = child_object.get_link_by_id(child_link_id) + self.parent_link = parent_link + self.child_link = child_link + self.parent_object = parent_link.object + self.child_object = child_link.object self.bidirectional = bidirectional self._loose = False and not bidirectional @@ -1631,9 +1637,9 @@ def __init__(self, self.constraint_id = constraint_id if self.constraint_id is None: - self.add_constraint_and_update_objects_constraints_collection() + self.add_fixed_constraint() - def update_attachment(self): + def update_transform_and_constraint(self): self.update_transform() self.update_constraint() @@ -1642,35 +1648,21 @@ def update_transform(self): def update_constraint(self): self.remove_constraint_if_exists() - self.add_constraint_and_update_objects_constraints_collection() + self.add_fixed_constraint() + + def add_fixed_constraint(self): + self.parent_link.add_fixed_constraint_with_link(self.child_link) def calculate_transform(self): return self.parent_link.get_transform_to_link(self.child_link) def remove_constraint_if_exists(self): - if self.constraint_id is not None: - self.parent_object.world.remove_constraint(self.constraint_id) - - def add_constraint_and_update_objects_constraints_collection(self): - self.constraint_id = self.add_fixed_constraint() - self.update_objects_constraints_collection() - - def add_fixed_constraint(self): - constraint_id = self.parent_object.world.add_fixed_constraint(self.parent_object.id, - self.child_object.id, - self.child_to_parent_transform, - self.parent_link.id, - self.child_link.id) - return constraint_id - - def update_objects_constraints_collection(self): - self.parent_object.cids[self.child_object] = self.constraint_id - self.child_object.cids[self.parent_object] = self.constraint_id + if self.child_link in self.parent_link.constraint_ids: + self.parent_link.remove_constraint_with(self.child_link) def get_inverse(self): - attachment = Attachment(self.child_object, self.parent_object, self.child_link.id, - self.parent_link.id, self.bidirectional, self.child_to_parent_transform.invert(), - self.constraint_id) + attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, + constraint_id=self.constraint_id) attachment.loose = False if self.loose else True return attachment diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 6598c511a..3910aae73 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -37,9 +37,9 @@ class Constraint: Dataclass for storing a constraint between two objects. """ parent_obj_id: int - parent_link_id: int + parent_link_name: str child_obj_id: int - child_link_id: int + child_link_name: str joint_type: JointType joint_axis_in_child_link_frame: List[int] joint_frame_position_wrt_parent_origin: List[float] From 2099bd7410ecb26cfa3bdf368f0f72a5b4b90725 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Thu, 28 Dec 2023 14:53:27 +0100 Subject: [PATCH 024/195] [AbstractWorld] _set_attached_objects_poses implementation moved to the Object class instead of World. Cleaned World init method. Added optional argument in set_pose method of the Object class to exclude moving attached objects. --- src/pycram/world.py | 124 +++++++++++++++++++++++--------------------- 1 file changed, 64 insertions(+), 60 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 6e9aec3f1..9f5bede9a 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -82,32 +82,32 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: :param is_prospection_world: For internal usage, decides if this World should be used as a prospection world. """ - self._init_current_world_and_simulation_time_step(simulation_time_step) - # init the current world and simulation time step which are class variables. + if World.current_world is None: + World.current_world = self + World.simulation_time_step = simulation_time_step + + self.is_prospection_world: bool = is_prospection_world + self._init_and_sync_prospection_world() + + self.local_transformer = LocalTransformer() + self._update_local_transformer_worlds() self.objects: List[Object] = [] + # List of all Objects in the World + self.client_id: int = -1 + # This is used to connect to the physics server (allows multiple clients) + self.mode: str = mode + # The mode of the simulation, can be "GUI" or "DIRECT" - self._init_events() self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} - self.local_transformer = LocalTransformer() - self.is_prospection_world: bool = is_prospection_world - if is_prospection_world: # then no need to add another prospection world - self.prospection_world = None - self.world_sync = None - else: # a normal world should have a synced prospection world - self._init_and_sync_prospection_world() - self._update_local_transformer_worlds() + self._init_events() self._saved_states: Dict[int, WorldState] = {} # Different states of the world indexed by int state id. - def _init_current_world_and_simulation_time_step(self, simulation_time_step): - World.current_world = self if World.current_world is None else World.current_world - World.simulation_time_step = simulation_time_step - def _init_events(self): self.detachment_event: Event = Event() self.attachment_event: Event = Event() @@ -121,13 +121,20 @@ def _update_local_transformer_worlds(self): self.local_transformer.world = self self.local_transformer.prospection_world = self.prospection_world - @classmethod - def _init_prospection_world(cls): - cls.prospection_world: World = cls("DIRECT", True, cls.simulation_time_step) + def _init_prospection_world(self): + if self.is_prospection_world: # then no need to add another prospection world + self.prospection_world = None + else: + self.prospection_world: World = self.__class__("DIRECT", + True, + World.simulation_time_step) def _sync_prospection_world(self): - self.world_sync: WorldSync = WorldSync(self, self.prospection_world) - self.world_sync.start() + if self.is_prospection_world: # then no need to add another prospection world + self.world_sync = None + else: + self.world_sync: WorldSync = WorldSync(self, self.prospection_world) + self.world_sync.start() @property def simulation_frequency(self): @@ -155,14 +162,14 @@ def get_objects_by_type(self, obj_type: str) -> List[Object]: """ return list(filter(lambda obj: obj.obj_type == obj_type, self.objects)) - def get_object_by_id(self, id: int) -> Object: + def get_object_by_id(self, obj_id: int) -> Object: """ Returns the single Object that has the unique id. - :param id: The unique id for which the Object should be returned. + :param obj_id: The unique id for which the Object should be returned. :return: The Object with the id 'id'. """ - return list(filter(lambda obj: obj.id == id, self.objects))[0] + return list(filter(lambda obj: obj.id == obj_id, self.objects))[0] @abstractmethod def remove_object(self, obj_id: int) -> None: @@ -173,33 +180,6 @@ def remove_object(self, obj_id: int) -> None: """ pass - def _set_attached_objects_poses(self, parent, prev_object: List[Object]) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param prev_object: A list of Objects that were already moved, - these will be excluded to prevent loops in the update. - """ - for child in parent.attachments: - if child in prev_object: - continue - if not parent.attachments[child].bidirectional: - parent.attachments[child].update_transform_and_constraint() - child.attachments[parent].update_transform_and_constraint() - else: - link_to_object = parent.attachments[child].child_to_parent_transform - - world_to_object = parent.local_transformer.transform_pose_to_target_frame(link_to_object.to_pose(), "map") - self.reset_object_base_pose(child, - world_to_object.position_as_list(), - world_to_object.orientation_as_list()) - child._current_pose = world_to_object - self._set_attached_objects_poses(child, prev_object + [parent]) - def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_parent_transform: Transform) -> int: """ Creates a fixed joint constraint between the given parent and child links, @@ -697,7 +677,9 @@ def _copy(self) -> World: o.set_joint_position(joint, obj.get_joint_position(joint)) return world - def register_two_objects_collision_callbacks(self, object_a: Object, object_b: Object, + def register_two_objects_collision_callbacks(self, + object_a: Object, + object_b: Object, on_collision_callback: Callable, on_collision_removal_callback: Optional[Callable] = None) -> None: """ @@ -1194,6 +1176,9 @@ def detach_all(self) -> None: for att in attachments.keys(): self.detach(att) + def update_attachment_with_object(self, child_object: Object): + self.attachments[child_object].update_transform_and_constraint() + def get_position(self) -> Pose.position: """ Returns the position of this Object as a list of xyz. @@ -1234,12 +1219,13 @@ def get_pose(self) -> Pose: """ return self._current_pose - def set_pose(self, pose: Pose, base: bool = False) -> None: + def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Optional[bool] = True) -> None: """ Sets the Pose of the object. :param pose: New Pose for the object :param base: If True places the object base instead of origin at the specified position and orientation + :param set_attachments: Whether to set the poses of the attached objects to this object or not. """ pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") position, orientation = pose_in_map.to_list() @@ -1247,7 +1233,8 @@ def set_pose(self, pose: Pose, base: bool = False) -> None: position = np.array(position) + self.base_origin_shift self.world.reset_object_base_pose(self, position, orientation) self._current_pose = pose_in_map - self._set_attached_objects_poses() + if set_attachments: + self._set_attached_objects_poses() def move_base_to_origin_pos(self) -> None: """ @@ -1256,7 +1243,7 @@ def move_base_to_origin_pos(self) -> None: """ self.set_pose(self.get_pose(), base=True) - def _set_attached_objects_poses(self) -> None: + def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: """ Updates the positions of all attached objects. This is done by calculating the new pose in world coordinate frame and setting the @@ -1264,9 +1251,26 @@ def _set_attached_objects_poses(self) -> None: After this the _set_attached_objects method of all attached objects will be called. - :param prev_object: A list of Objects that were already moved, these will be excluded to prevent loops in the update. + :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent loops in the update. """ - self.world._set_attached_objects_poses(self, [self]) + + if already_moved_objects is None: + already_moved_objects = [] + + for child in self.attachments: + + if child in already_moved_objects: + continue + + attachment = self.attachments[child] + if not attachment.bidirectional: + self.update_attachment_with_object(child) + child.update_attachment_with_object(self) + + else: + link_to_object = attachment.parent_to_child_transform + child.set_pose(link_to_object.to_pose(), set_attachments=False) + child._set_attached_objects_poses(already_moved_objects + [self]) def set_position(self, position: Union[Pose, Point], base=False) -> None: """ @@ -1619,7 +1623,7 @@ def __init__(self, parent_link: Link, child_link: Link, bidirectional: Optional[bool] = False, - child_to_parent_transform: Optional[Transform] = None, + parent_to_child_transform: Optional[Transform] = None, constraint_id: Optional[int] = None): """ Creates an attachment between the parent object and the child object. @@ -1631,8 +1635,8 @@ def __init__(self, self.bidirectional = bidirectional self._loose = False and not bidirectional - self.child_to_parent_transform = child_to_parent_transform - if self.child_to_parent_transform is None: + self.parent_to_child_transform = parent_to_child_transform + if self.parent_to_child_transform is None: self.update_transform() self.constraint_id = constraint_id @@ -1644,7 +1648,7 @@ def update_transform_and_constraint(self): self.update_constraint() def update_transform(self): - self.child_to_parent_transform = self.calculate_transform() + self.parent_to_child_transform = self.calculate_transform() def update_constraint(self): self.remove_constraint_if_exists() From 38516ffa77f9a058cfad04870c534f8eaff263d3 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 1 Jan 2024 08:24:25 +0100 Subject: [PATCH 025/195] [AbstractWorld] Implemented a CollisionsCallbacks dataclass and used it to define the self.coll_callbacks attribute. --- src/pycram/world.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 9f5bede9a..bef1c3341 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -42,6 +42,14 @@ class WorldState: constraint_ids: Dict[Object, Dict[Object, int]] +@dataclass +class CollisionCallbacks: + obj_1: Object + obj_2: Object + on_collision_cb: Callable + no_collision_cb: Optional[Callable] = None + + class World(ABC): """ The World Class represents the physics Simulation and belief state. @@ -101,7 +109,7 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self.mode: str = mode # The mode of the simulation, can be "GUI" or "DIRECT" - self.coll_callbacks: Dict[Tuple[Object, Object], Tuple[Callable, Callable]] = {} + self.coll_callbacks: Dict[Tuple[Object, Object], CollisionCallbacks] = {} self._init_events() @@ -295,12 +303,12 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: """ for i in range(0, int(seconds * self.simulation_frequency)): self.step() - for objects, callback in self.coll_callbacks.items(): + for objects, callbacks in self.coll_callbacks.items(): contact_points = self.get_contact_points_between_two_objects(objects[0], objects[1]) if contact_points != (): - callback[0]() - elif callback[1] is not None: # Call no collision callback - callback[1]() + callbacks.on_collision_cb() + elif callbacks.no_collision_cb is not None: + callbacks.no_collision_cb() if real_time: # Simulation runs at 240 Hz time.sleep(self.simulation_time_step) From 9a9d1a63f2954dacc4a119198d172eb381d3fe39 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 1 Jan 2024 09:03:47 +0100 Subject: [PATCH 026/195] [AbstractWorld] Object Class does not manage constraints, they are managed by the Link Class instead. --- src/pycram/world.py | 57 +++++++++++---------------------------------- 1 file changed, 14 insertions(+), 43 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index bef1c3341..4b00f1f73 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -39,8 +39,6 @@ class WorldState: state_id: int attachments: Dict[Object, Dict[Object, Attachment]] - constraint_ids: Dict[Object, Dict[Object, int]] - @dataclass class CollisionCallbacks: @@ -596,9 +594,7 @@ def save_state(self) -> int: :return: A unique id of the state """ state_id = self.save_physics_simulator_state() - self._saved_states[state_id] = WorldState(state_id, - self.get_objects_attachments(), - self.get_objects_constraint_ids()) + self._saved_states[state_id] = WorldState(state_id, self.get_objects_attachments()) return state_id def restore_state(self, state_id) -> None: @@ -610,7 +606,7 @@ def restore_state(self, state_id) -> None: :param state_id: The unique id representing the state, as returned by :func:`~save_state` """ self.restore_physics_simulator_state(state_id) - self.restore_attachments_and_constraints_from_saved_world_state(state_id) + self.restore_attachments_from_saved_world_state(state_id) @abstractmethod def save_physics_simulator_state(self) -> int: @@ -628,15 +624,6 @@ def get_objects_attachments(self) -> Dict[Object, Dict[Object, Attachment]]: attachments[o] = o.attachments.copy() return attachments - def get_objects_constraint_ids(self) -> Dict[Object, Dict[Object, int]]: - """ - Get the constraint ids collection that is stored in each object. - """ - constraint_ids = {} - for o in self.objects: - constraint_ids[o] = o.cids.copy() - return constraint_ids - @abstractmethod def restore_physics_simulator_state(self, state_id): """ @@ -645,14 +632,6 @@ def restore_physics_simulator_state(self, state_id): """ pass - def restore_attachments_and_constraints_from_saved_world_state(self, state_id: int): - """ - Restores the attachments and constraints of the objects in the World. This is done by setting the attachments, - and the cids attributes of each object in the World to the given attachments and constraint_ids. - """ - self.restore_attachments_from_saved_world_state(state_id) - self.restore_constraints_from_saved_world_state(state_id) - def restore_attachments_from_saved_world_state(self, state_id: int): attachments = self._saved_states[state_id].attachments for obj in self.objects: @@ -661,14 +640,6 @@ def restore_attachments_from_saved_world_state(self, state_id: int): except KeyError: continue - def restore_constraints_from_saved_world_state(self, state_id: int): - constraint_ids = self._saved_states[state_id].constraint_ids - for obj in self.objects: - try: - obj.cids = constraint_ids[obj] - except KeyError: - continue - def _copy(self) -> World: """ Copies this World into another and returns it. The other World @@ -1038,22 +1009,27 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, :param color: The color with which the object should be spawned. :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ + if pose is None: pose = Pose() + self.world: World = world if world is not None else World.current_world - self.local_transformer = LocalTransformer() + self.name: str = name self.obj_type: Union[str, ObjectType] = obj_type self.color: Color = color - pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") - position, orientation = pose_in_map.to_list() + + self.local_transformer = LocalTransformer() + self.original_pose = self.local_transformer.transform_pose_to_target_frame(pose, "map") + position, orientation = self.original_pose.to_list() self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) + self._current_pose = self.original_pose + self.joint_name_to_id: Dict[str, int] = self._get_joint_name_to_id_map() self.link_name_to_id: Dict[str, int] = self._get_link_name_to_id_map() self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) + self.attachments: Dict[Object, Attachment] = {} - self.cids: Dict[Object, int] = {} - self.original_pose = pose_in_map self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) @@ -1065,15 +1041,13 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.urdf_object = URDF.from_xml_string(f.read()) if self.urdf_object.name == robot_description.name: self.world.set_robot_if_not_set(self) - self.link_name_to_id[self.urdf_object.get_root()] = -1 self.link_id_to_name[-1] = self.urdf_object.get_root() self.links = self._init_links() + self.update_link_transforms() - self._current_pose = pose_in_map self._current_joints_positions = {} self._init_current_positions_of_joint() - self.update_link_transforms() self.world.objects.append(self) @@ -1103,7 +1077,7 @@ def base_origin_shift(self) -> np.ndarray: return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) def __repr__(self): - skip_attr = ["links", "joints", "urdf_object", "attachments", "cids"] + skip_attr = ["links", "joints", "urdf_object", "attachments"] return self.__class__.__qualname__ + f"(" + ', \n'.join( [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" @@ -1129,9 +1103,6 @@ def remove(self) -> None: if World.robot == self: World.robot = None - def remove_constraint_with(self, obj: Object) -> None: - self.world.remove_constraint(self.cids[obj]) - def attach(self, child_object: Object, parent_link: Optional[str] = None, From 0f625b019e1e65b32ae16130889b3d5ab722738f Mon Sep 17 00:00:00 2001 From: HaSu Date: Tue, 2 Jan 2024 14:46:15 +0100 Subject: [PATCH 027/195] [intro-example] fixing typos, adding info --- examples/intro.ipynb | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/examples/intro.ipynb b/examples/intro.ipynb index aea7c14fb..0f0a1ccc0 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -88,10 +88,10 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "The BulletWorld allows to render images from arbitrary positoins. In the following example we render images with the camera at the position [0.3, 0, 1] and pointing towards [1, 0, 1], so we are looking upwards along the x-axis. \n", + "The BulletWorld allows to render images from arbitrary positions. In the following example we render images with the camera at the position [0.3, 0, 1] and pointing towards [1, 0, 1], so we are looking upwards along the x-axis. \n", "\n", - "The renderer returns 3 different kinds of images which are also shown at the left side of the BulletWorld window. These images are:\n", - "* A RGB image which shows everything like it is rendered in the BulletWorld window, just from another perspective. \n", + "The renderer returns 3 different kinds of images which are also shown on the left side of the BulletWorld window. (If these winodws are missing, click the BulletWorld window to focus it, and press \"g\") These images are:\n", + "* An RGB image which shows everything like it is rendered in the BulletWorld window, just from another perspective. \n", "* A depth image which consists of distance values from the camera towards the objects in the field of view. \n", "* A segmentation mask image which segments the image into the different objects displayed. The segmentation is done by assigning every pixel the unique id of the object that is displayed there. " ] @@ -207,7 +207,7 @@ " * Color \n", " * Ignore Cached Files\n", "\n", - "If there is only a filename and no path PyCRAM will check in the resource directory if there is a matching file. \n" + "If there is only a filename and no path, PyCRAM will check in the resource directory if there is a matching file. \n" ] }, { @@ -299,7 +299,7 @@ "metadata": {}, "source": [ "### Visibility Costmaps\n", - "Visibility costmaps determine every position, around a target position, from which the target is visible. Visibility Costmaps are able to work with cameras that are moveable in height, for example if the robot has a movable torso. " + "Visibility costmaps determine every position, around a target position, from which the target is visible. Visibility Costmaps are able to work with cameras that are movable in height for example, if the robot has a movable torso. " ] }, { @@ -432,7 +432,7 @@ "* Blocking\n", "* Supporting\n", "\n", - "To show the geometric reasoning we first a robot as well as the milk Object again." + "To show the geometric reasoning we first spawn a robot as well as the milk Object again." ] }, { @@ -540,8 +540,8 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "# Designator\n", - "Designator are symbolic descriptions of Actions, Motions, Objects or Locations. In PyCRAM the different types of designators are representet by a class which takes a description, the description then tells the designator what to do. \n", + "# Designators\n", + "Designators are symbolic descriptions of Actions, Motions, Objects or Locations. In PyCRAM the different types of designators are represented by a class which takes a description, the description then tells the designator what to do. \n", "\n", "For example, let's look at a Motion Designator to move the robot to a specific location. \n", "\n" @@ -551,11 +551,11 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "## Motion Designator\n", + "## Motion Designators\n", "\n", - "When using a Motion Designator you need to specify which Process Module needs to be used, either the Process Module for the real or the simulated robot. This can be done either with a decorator which can be added to a function and then executes every designator in this function on the specified robot. The other possibility is a \"with\" scope which wraps a code piece. \n", + "When using a Motion Designator you need to specify which Process Module needs to be used, either the Process Module for the real or the simulated robot. A Process Module is the interface between a real or simulated robot, and PyCRAM designators. By exchanging the Process Module, one can quickly change the robot the plan is executed on, allowing PyCRAM plans to be re-used across multiple robot platforms. This can be done either with a decorator which can be added to a function and then every designator executed within this function, will be executed on the specified robot. The other possibility is a \"with\" scope which wraps a code piece.\n", "\n", - "These two ways can also be combined, you could write a function which should be executed on the real robot and in the function is a \"with\" scope which executes something on the simulated robot for reasoning purposes. " + "These two ways can also be combined, you could write a function which should be executed on the real robot and the function contains a \"with\" scope which executes something on the simulated robot for reasoning purposes. " ] }, { @@ -611,9 +611,9 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "## Object Designator\n", + "## Object Designators\n", "\n", - "Object Designator represent objects, these objects could either be from the BulletWorld or the real world. Object Designator are used, for example, by the PickUpAction to know which object should be picked up." + "An Object Designator represents objects. These objects could either be from the BulletWorld or the real world. Object Designators are used, for example, by the PickUpAction to know which object should be picked up." ] }, { @@ -803,8 +803,8 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "## Location Designator\n", - "Location Designator can create a position in cartisian space from a symbolic desctiption" + "## Location Designators\n", + "Location Designators can create a position in cartesian space from a symbolic description." ] }, { @@ -835,7 +835,7 @@ "metadata": {}, "source": [ "# Action Designator\n", - "Action Designator are used to describe high-level actions. Action Designator are usually composed of other Designators to describe the high-level action in detail. " + "Action Designators are used to describe high-level actions. Action Designators are usually composed of other Designators to describe the high-level action in detail. " ] }, { @@ -856,7 +856,7 @@ "metadata": {}, "source": [ "# Making a simple plan\n", - "To get familiar with the PyCRAM Framework we will write a simple pick and place plan. This plan will let the robot grab a cereal box from the kitchen counter and place it on the kitchen island. This is a simple pick and place plan." + "To get familiar with the PyCRAM Framework we will write a simple pick and place plan. This plan will let the robot grasp a cereal box from the kitchen counter and place it on the kitchen island. This is a simple pick and place plan." ] }, { @@ -911,7 +911,7 @@ "metadata": {}, "source": [ "# Task Trees\n", - "Task trees are a hirachical representation of all Actions involved in a plan. The Task tree can later be used to inspect and restructre the execution order of Actions in the plan." + "Task trees are a hierarchical representation of all Actions involved in a plan. The Task tree can later be used to inspect and restructure the execution order of Actions in the plan." ] }, { From f3bcae767e6e1bf1792449cd766fd1fd4124f72d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 5 Jan 2024 13:08:48 +0100 Subject: [PATCH 028/195] [designator] refactored action_designator --- examples/custom_resolver.ipynb | 81 +-- examples/minimal_task_tree.ipynb | 282 +++++---- examples/orm_example.ipynb | 185 +++--- examples/orm_querying_examples.ipynb | 29 +- src/pycram/designator.py | 23 +- src/pycram/designators/action_designator.py | 610 ++------------------ src/pycram/designators/actions/actions.py | 578 +++++++++++++++++++ src/pycram/task.py | 10 +- test/test_action_designator.py | 12 +- test/test_database_resolver.py | 16 +- test/test_jpt_resolver.py | 14 +- test/test_task_tree.py | 8 +- 12 files changed, 1001 insertions(+), 847 deletions(-) create mode 100644 src/pycram/designators/actions/actions.py diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb index 0660276e4..21e1bf7cc 100644 --- a/examples/custom_resolver.ipynb +++ b/examples/custom_resolver.ipynb @@ -23,8 +23,8 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:13:58.323072599Z", - "start_time": "2023-12-13T10:13:56.448691067Z" + "end_time": "2024-01-05T11:39:35.037185202Z", + "start_time": "2024-01-05T11:39:32.842006673Z" } }, "outputs": [ @@ -32,15 +32,22 @@ "name": "stdout", "output_type": "stream", "text": [ - "Requirement already up-to-date: probabilistic_model in /home/dprueser/.local/lib/python3.8/site-packages (1.4.13)\r\n", - "Requirement already satisfied, skipping upgrade: plotly>=5.18.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (5.18.0)\r\n", + "Collecting probabilistic_model\r\n", + " Using cached probabilistic_model-1.5.18-py3-none-any.whl (30 kB)\r\n", + "Requirement already satisfied, skipping upgrade: portion>=2.4.1 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.4.1)\r\n", "Requirement already satisfied, skipping upgrade: random-events>=1.2.5 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", + "Requirement already satisfied, skipping upgrade: plotly>=5.18.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (5.18.0)\r\n", "Requirement already satisfied, skipping upgrade: anytree>=2.9.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.9.0)\r\n", - "Requirement already satisfied, skipping upgrade: portion>=2.4.1 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.4.1)\r\n", - "Requirement already satisfied, skipping upgrade: packaging in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (23.2)\r\n", + "Requirement already satisfied, skipping upgrade: sortedcontainers~=2.2 in /home/dprueser/.local/lib/python3.8/site-packages (from portion>=2.4.1->probabilistic_model) (2.4.0)\r\n", "Requirement already satisfied, skipping upgrade: tenacity>=6.2.0 in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (8.2.3)\r\n", + "Requirement already satisfied, skipping upgrade: packaging in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (23.2)\r\n", "Requirement already satisfied, skipping upgrade: six in /usr/lib/python3/dist-packages (from anytree>=2.9.0->probabilistic_model) (1.14.0)\r\n", - "Requirement already satisfied, skipping upgrade: sortedcontainers~=2.2 in /home/dprueser/.local/lib/python3.8/site-packages (from portion>=2.4.1->probabilistic_model) (2.4.0)\r\n" + "Installing collected packages: probabilistic-model\r\n", + " Attempting uninstall: probabilistic-model\r\n", + " Found existing installation: probabilistic-model 1.5.17\r\n", + " Uninstalling probabilistic-model-1.5.17:\r\n", + " Successfully uninstalled probabilistic-model-1.5.17\r\n", + "Successfully installed probabilistic-model-1.5.18\r\n" ] } ], @@ -53,8 +60,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:13:59.230429151Z", - "start_time": "2023-12-13T10:13:58.332536124Z" + "end_time": "2024-01-05T11:39:36.023993906Z", + "start_time": "2024-01-05T11:39:35.047597162Z" } }, "outputs": [ @@ -67,12 +74,13 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1702462438.857886]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1702462438.862737]: Failed to import Giskard messages\n" + "[WARN] [1704454775.649694]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1704454775.654652]: Failed to import Giskard messages\n" ] } ], "source": [ + "from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable\n", "from tf import transformations\n", "import itertools\n", "from typing import Optional, List, Tuple\n", @@ -189,13 +197,13 @@ " # try to execute a grasping plan\n", " with simulated_robot:\n", "\n", - " ParkArmsAction.Action(pycram.enums.Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform()\n", " # navigate to sampled position\n", " NavigateAction([Pose(position, orientation)]).resolve().perform()\n", "\n", " # move torso\n", " height = np.random.uniform(0., 0.33, 1)[0]\n", - " MoveTorsoAction.Action(height).perform()\n", + " MoveTorsoActionPerformable(height).perform()\n", "\n", " # try to pick it up\n", " try:\n", @@ -241,8 +249,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2023-12-13T10:15:50.758891855Z", - "start_time": "2023-12-13T10:13:59.232324147Z" + "end_time": "2024-01-05T11:41:21.098968043Z", + "start_time": "2024-01-05T11:39:36.024974459Z" } }, "outputs": [ @@ -262,9 +270,9 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - " 45%|████▍ | 430/960 [00:50<00:58, 9.02it/s, success_rate=0.0791]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/r_shoulder_lift_link (parent map) at time 1702462489.281120 according to authority default_authority\n", + " 38%|███▊ | 369/960 [00:40<01:06, 8.92it/s, success_rate=0.0867]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/l_gripper_motor_screw_link (parent map) at time 1704454816.991220 according to authority default_authority\n", " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", - "100%|██████████| 960/960 [01:51<00:00, 9.30it/s, success_rate=0.0854]" + "100%|██████████| 960/960 [01:44<00:00, 9.47it/s, success_rate=0.0854]" ] } ], @@ -290,8 +298,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:15:50.844627649Z", - "start_time": "2023-12-13T10:15:50.794715519Z" + "end_time": "2024-01-05T11:41:21.193149641Z", + "start_time": "2024-01-05T11:41:21.142076887Z" } }, "outputs": [], @@ -317,8 +325,8 @@ "metadata": { "scrolled": true, "ExecuteTime": { - "end_time": "2023-12-13T10:15:50.932190158Z", - "start_time": "2023-12-13T10:15:50.846547804Z" + "end_time": "2024-01-05T11:41:21.278910069Z", + "start_time": "2024-01-05T11:41:21.194743363Z" } }, "outputs": [], @@ -357,8 +365,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2023-12-13T10:15:50.983050833Z", - "start_time": "2023-12-13T10:15:50.939401673Z" + "end_time": "2024-01-05T11:41:21.326300043Z", + "start_time": "2024-01-05T11:41:21.284443546Z" } }, "outputs": [ @@ -437,8 +445,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:15:51.329697221Z", - "start_time": "2023-12-13T10:15:50.982828383Z" + "end_time": "2024-01-05T11:41:21.658478914Z", + "start_time": "2024-01-05T11:41:21.326092672Z" } }, "outputs": [ @@ -446,7 +454,7 @@ "name": "stderr", "output_type": "stream", "text": [ - "100%|██████████| 960/960 [01:51<00:00, 8.59it/s, success_rate=0.0854]\n" + "100%|██████████| 960/960 [01:45<00:00, 9.11it/s, success_rate=0.0854]\n" ] }, { @@ -475,10 +483,12 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 8, "metadata": { + "collapsed": false, "ExecuteTime": { - "start_time": "2023-12-13T10:15:51.329714184Z" + "end_time": "2024-01-05T11:46:59.969239637Z", + "start_time": "2024-01-05T11:41:21.659115424Z" } }, "outputs": [ @@ -489,11 +499,11 @@ "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", @@ -502,6 +512,7 @@ } ], "source": [ + "from pycram.designators.actions.actions import NavigateActionPerformable, PickUpActionPerformable\n", "from pycram.resolver import JPTCostmapLocation\n", "\n", "\n", @@ -516,13 +527,11 @@ "cml.visualize()\n", "with simulated_robot:\n", " for sample in iter(cml):\n", - " ParkArmsAction.Action(pycram.enums.Arms.BOTH).perform()\n", - " NavigateAction.Action(sample.pose).perform()\n", - " MoveTorsoAction.Action(sample.torso_height).perform()\n", + " ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform()\n", + " NavigateActionPerformable(sample.pose).perform()\n", + " MoveTorsoActionPerformable(sample.torso_height).perform()\n", " try:\n", - " PickUpAction.Action(\n", - " ObjectDesignatorDescription(types=[pycram.enums.ObjectType.MILK]).resolve(),\n", - " arm=sample.reachable_arm, grasp=sample.grasp).perform()\n", + " PickUpActionPerformable(ObjectDesignatorDescription(types=[pycram.enums.ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform()\n", " # time.sleep(5)\n", " except pycram.plan_failures.PlanFailure as p:\n", " continue\n", diff --git a/examples/minimal_task_tree.ipynb b/examples/minimal_task_tree.ipynb index 1ac203580..ff4839c44 100644 --- a/examples/minimal_task_tree.ipynb +++ b/examples/minimal_task_tree.ipynb @@ -16,11 +16,25 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:45:06.870087Z", - "start_time": "2023-04-28T09:45:06.870015Z" + "end_time": "2024-01-05T11:47:15.273850937Z", + "start_time": "2024-01-05T11:47:14.439086041Z" } }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "pybullet build time: May 20 2022 19:44:17\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1704455235.033913]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1704455235.039023]: Failed to import Giskard messages\n" + ] + } + ], "source": [ "from pycram.bullet_world import BulletWorld\n", "from pycram.robot_descriptions import robot_description\n", @@ -48,8 +62,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2023-04-27T17:32:49.441717Z", - "start_time": "2023-04-27T17:32:49.441589Z" + "end_time": "2024-01-05T11:47:21.361713709Z", + "start_time": "2024-01-05T11:47:15.370855034Z" } }, "outputs": [ @@ -57,19 +71,19 @@ "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Scalar element defined multiple times: limit\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "Scalar element defined multiple times: limit\n", "Scalar element defined multiple times: limit\n" ] } @@ -98,8 +112,8 @@ "execution_count": 3, "metadata": { "ExecuteTime": { - "end_time": "2023-04-27T17:32:58.124468Z", - "start_time": "2023-04-27T17:32:58.124325Z" + "end_time": "2024-01-05T11:47:35.217688853Z", + "start_time": "2024-01-05T11:47:21.361234790Z" } }, "outputs": [], @@ -107,7 +121,7 @@ "@pycram.task.with_tree\n", "def plan():\n", " with simulated_robot:\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", " MoveTorsoAction([0.3]).resolve().perform()\n", " pickup_pose = CostmapLocation(target=cereal_desig.resolve(), reachable_for=robot_desig).resolve()\n", " pickup_arm = pickup_pose.reachable_arms[0]\n", @@ -126,7 +140,7 @@ "\n", " ParkArmsAction([Arms.BOTH]).resolve().perform()\n", "\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", "\n", "plan()\n" ] @@ -143,8 +157,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2023-04-27T17:33:02.572319Z", - "start_time": "2023-04-27T17:33:02.572253Z" + "end_time": "2024-01-05T11:47:35.222415842Z", + "start_time": "2024-01-05T11:47:35.217889291Z" } }, "outputs": [ @@ -154,15 +168,25 @@ "text": [ "no_operation()\n", "└── plan()\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(MoveTorsoAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PickUpAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PlaceAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " └── perform(ParkArmsAction, )\n" + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(MoveTorsoActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PickUpActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PlaceActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " └── perform(ParkArmsActionPerformable)\n" ] } ], @@ -183,8 +207,8 @@ "execution_count": 5, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:45:59.592864Z", - "start_time": "2023-04-28T09:45:58.928492Z" + "end_time": "2024-01-05T11:47:49.422118950Z", + "start_time": "2024-01-05T11:47:35.221784522Z" } }, "outputs": [ @@ -194,25 +218,45 @@ "text": [ "no_operation()\n", "├── plan()\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ ├── perform(MoveTorsoAction, )\n", - "│ ├── perform(NavigateAction, )\n", - "│ ├── perform(PickUpAction, )\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ ├── perform(NavigateAction, )\n", - "│ ├── perform(PlaceAction, )\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ └── perform(ParkArmsAction, )\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ ├── perform(MoveTorsoActionPerformable)\n", + "│ ├── perform(NavigateActionPerformable)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(PickUpActionPerformable)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ ├── perform(NavigateActionPerformable)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(PlaceActionPerformable)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ └── perform(ParkArmsActionPerformable)\n", "└── plan()\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(MoveTorsoAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PickUpAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PlaceAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " └── perform(ParkArmsAction, )\n" + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(MoveTorsoActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PickUpActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PlaceActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " └── perform(ParkArmsActionPerformable)\n" ] } ], @@ -234,8 +278,8 @@ "execution_count": 6, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:37.041421Z", - "start_time": "2023-04-28T09:46:36.999813Z" + "end_time": "2024-01-05T11:47:49.434500008Z", + "start_time": "2024-01-05T11:47:49.422026208Z" } }, "outputs": [ @@ -246,25 +290,45 @@ "simulation()\n", "no_operation()\n", "├── plan()\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ ├── perform(MoveTorsoAction, )\n", - "│ ├── perform(NavigateAction, )\n", - "│ ├── perform(PickUpAction, )\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ ├── perform(NavigateAction, )\n", - "│ ├── perform(PlaceAction, )\n", - "│ ├── perform(ParkArmsAction, )\n", - "│ └── perform(ParkArmsAction, )\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ ├── perform(MoveTorsoActionPerformable)\n", + "│ ├── perform(NavigateActionPerformable)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(PickUpActionPerformable)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ ├── perform(NavigateActionPerformable)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(PlaceActionPerformable)\n", + "│ │ ├── perform(Motion)\n", + "│ │ ├── perform(Motion)\n", + "│ │ └── perform(Motion)\n", + "│ ├── perform(ParkArmsActionPerformable)\n", + "│ └── perform(ParkArmsActionPerformable)\n", "└── plan()\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(MoveTorsoAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PickUpAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(NavigateAction, )\n", - " ├── perform(PlaceAction, )\n", - " ├── perform(ParkArmsAction, )\n", - " └── perform(ParkArmsAction, )\n" + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(MoveTorsoActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PickUpActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PlaceActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " └── perform(ParkArmsActionPerformable)\n" ] } ], @@ -286,8 +350,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:45.637721Z", - "start_time": "2023-04-28T09:46:45.635535Z" + "end_time": "2024-01-05T11:47:49.438410783Z", + "start_time": "2024-01-05T11:47:49.433036544Z" } }, "outputs": [ @@ -297,15 +361,25 @@ "text": [ "no_operation()\n", "+-- plan()\n", - " |-- perform(ParkArmsAction, )\n", - " |-- perform(MoveTorsoAction, )\n", - " |-- perform(NavigateAction, )\n", - " |-- perform(PickUpAction, )\n", - " |-- perform(ParkArmsAction, )\n", - " |-- perform(NavigateAction, )\n", - " |-- perform(PlaceAction, )\n", - " |-- perform(ParkArmsAction, )\n", - " +-- perform(ParkArmsAction, )\n" + " |-- perform(ParkArmsActionPerformable)\n", + " |-- perform(MoveTorsoActionPerformable)\n", + " |-- perform(NavigateActionPerformable)\n", + " | +-- perform(Motion)\n", + " |-- perform(PickUpActionPerformable)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | +-- perform(Motion)\n", + " |-- perform(ParkArmsActionPerformable)\n", + " |-- perform(NavigateActionPerformable)\n", + " | +-- perform(Motion)\n", + " |-- perform(PlaceActionPerformable)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | +-- perform(Motion)\n", + " |-- perform(ParkArmsActionPerformable)\n", + " +-- perform(ParkArmsActionPerformable)\n" ] } ], @@ -326,8 +400,8 @@ "execution_count": 8, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:48.259716Z", - "start_time": "2023-04-28T09:46:48.233474Z" + "end_time": "2024-01-05T11:47:57.076211143Z", + "start_time": "2024-01-05T11:47:49.437672197Z" } }, "outputs": [ @@ -337,15 +411,25 @@ "text": [ "no_operation()\n", "+-- plan()\n", - " |-- perform(ParkArmsAction, )\n", - " |-- perform(MoveTorsoAction, )\n", - " |-- perform(NavigateAction, )\n", - " |-- perform(PickUpAction, )\n", - " |-- perform(ParkArmsAction, )\n", - " |-- perform(NavigateAction, )\n", - " |-- perform(PlaceAction, )\n", - " |-- perform(ParkArmsAction, )\n", - " +-- perform(ParkArmsAction, )\n" + " |-- perform(ParkArmsActionPerformable)\n", + " |-- perform(MoveTorsoActionPerformable)\n", + " |-- perform(NavigateActionPerformable)\n", + " | +-- perform(Motion)\n", + " |-- perform(PickUpActionPerformable)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | +-- perform(Motion)\n", + " |-- perform(ParkArmsActionPerformable)\n", + " |-- perform(NavigateActionPerformable)\n", + " | +-- perform(Motion)\n", + " |-- perform(PlaceActionPerformable)\n", + " | |-- perform(Motion)\n", + " | |-- perform(Motion)\n", + " | +-- perform(Motion)\n", + " |-- perform(ParkArmsActionPerformable)\n", + " +-- perform(ParkArmsActionPerformable)\n" ] } ], @@ -368,8 +452,8 @@ "execution_count": 9, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:52.656020Z", - "start_time": "2023-04-28T09:46:52.653083Z" + "end_time": "2024-01-05T11:47:57.081178616Z", + "start_time": "2024-01-05T11:47:57.077818445Z" } }, "outputs": [ @@ -378,9 +462,9 @@ "output_type": "stream", "text": [ "Code: plan() \n", - " start_time: 2023-11-08 14:01:12.716969 \n", + " start_time: 2024-01-05 12:47:21.363057 \n", " Status: TaskStatus.SUCCEEDED \n", - " end_time: 2023-11-08 14:01:24.675108 \n", + " end_time: 2024-01-05 12:47:35.214734 \n", " \n" ] } @@ -401,8 +485,8 @@ "execution_count": 10, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:55.385481Z", - "start_time": "2023-04-28T09:46:55.381316Z" + "end_time": "2024-01-05T11:47:57.090325704Z", + "start_time": "2024-01-05T11:47:57.081062518Z" } }, "outputs": [ @@ -431,8 +515,8 @@ "execution_count": 11, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:46:57.445908Z", - "start_time": "2023-04-28T09:46:57.443154Z" + "end_time": "2024-01-05T11:47:57.130889801Z", + "start_time": "2024-01-05T11:47:57.129989892Z" } }, "outputs": [ @@ -467,8 +551,8 @@ "execution_count": 12, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:47:00.292660Z", - "start_time": "2023-04-28T09:47:00.287579Z" + "end_time": "2024-01-05T11:47:57.131271385Z", + "start_time": "2024-01-05T11:47:57.130193323Z" } }, "outputs": [ @@ -479,9 +563,9 @@ "no_operation()\n", "+-- failing_plan()\n", "Code: failing_plan() \n", - " start_time: 2023-11-08 14:02:00.257042 \n", + " start_time: 2024-01-05 12:47:57.088480 \n", " Status: TaskStatus.FAILED \n", - " end_time: 2023-11-08 14:02:00.257507 \n", + " end_time: 2024-01-05 12:47:57.089024 \n", " \n" ] } @@ -496,8 +580,8 @@ "execution_count": 13, "metadata": { "ExecuteTime": { - "end_time": "2023-04-28T09:47:03.581366Z", - "start_time": "2023-04-28T09:47:03.447150Z" + "end_time": "2024-01-05T11:47:57.328473210Z", + "start_time": "2024-01-05T11:47:57.130261104Z" } }, "outputs": [], diff --git a/examples/orm_example.ipynb b/examples/orm_example.ipynb index 20a3a4532..dc0b3e711 100644 --- a/examples/orm_example.ipynb +++ b/examples/orm_example.ipynb @@ -15,14 +15,14 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:05.213398212Z", - "start_time": "2023-12-13T10:22:05.061219318Z" + "end_time": "2024-01-05T11:48:06.779230216Z", + "start_time": "2024-01-05T11:48:06.588261981Z" } }, "outputs": [ { "data": { - "text/plain": "" + "text/plain": "" }, "execution_count": 1, "metadata": {}, @@ -50,8 +50,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:05.758910570Z", - "start_time": "2023-12-13T10:22:05.211301707Z" + "end_time": "2024-01-05T11:48:07.264463765Z", + "start_time": "2024-01-05T11:48:06.770051795Z" } }, "outputs": [ @@ -64,8 +64,8 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1702462925.736253]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1702462925.741150]: Failed to import Giskard messages\n" + "[WARN] [1704455287.243634]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1704455287.248237]: Failed to import Giskard messages\n" ] } ], @@ -88,8 +88,8 @@ "execution_count": 3, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.532059166Z", - "start_time": "2023-12-13T10:22:05.759939989Z" + "end_time": "2024-01-05T11:48:27.697221588Z", + "start_time": "2024-01-05T11:48:07.267874656Z" } }, "outputs": [ @@ -119,24 +119,24 @@ "text": [ "no_operation()\n", "└── plan()\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(MoveTorsoAction, )\n", - " ├── perform(NavigateAction, )\n", - " │ └── perform(MoveMotion, )\n", - " ├── perform(PickUpAction, )\n", - " │ ├── perform(MoveTCPMotion, )\n", - " │ ├── perform(MoveGripperMotion, )\n", - " │ ├── perform(MoveTCPMotion, )\n", - " │ ├── perform(MoveGripperMotion, )\n", - " │ └── perform(MoveTCPMotion, )\n", - " ├── perform(ParkArmsAction, )\n", - " ├── perform(NavigateAction, )\n", - " │ └── perform(MoveMotion, )\n", - " ├── perform(PlaceAction, )\n", - " │ ├── perform(MoveTCPMotion, )\n", - " │ ├── perform(MoveGripperMotion, )\n", - " │ └── perform(MoveTCPMotion, )\n", - " └── perform(ParkArmsAction, )\n" + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(MoveTorsoActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PickUpActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " ├── perform(ParkArmsActionPerformable)\n", + " ├── perform(NavigateActionPerformable)\n", + " │ └── perform(Motion)\n", + " ├── perform(PlaceActionPerformable)\n", + " │ ├── perform(Motion)\n", + " │ ├── perform(Motion)\n", + " │ └── perform(Motion)\n", + " └── perform(ParkArmsActionPerformable)\n" ] } ], @@ -165,7 +165,7 @@ "@with_tree\n", "def plan():\n", " with simulated_robot:\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", " MoveTorsoAction([0.3]).resolve().perform()\n", " pickup_pose = CostmapLocation(target=cereal_desig.resolve(), reachable_for=robot_desig).resolve()\n", " pickup_arm = pickup_pose.reachable_arms[0]\n", @@ -182,7 +182,7 @@ "\n", " PlaceAction(cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform()\n", "\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", "\n", "plan()\n", "\n", @@ -204,8 +204,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.715646672Z", - "start_time": "2023-12-13T10:22:25.534065783Z" + "end_time": "2024-01-05T11:48:27.882423457Z", + "start_time": "2024-01-05T11:48:27.695892994Z" } }, "outputs": [ @@ -213,12 +213,12 @@ "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 20/20 [00:00<00:00, 114.02it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 20/20 [00:00<00:00, 112.65it/s]\n" ] }, { "data": { - "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" + "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" }, "execution_count": 4, "metadata": {}, @@ -241,8 +241,8 @@ "execution_count": 5, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.720098203Z", - "start_time": "2023-12-13T10:22:25.717086864Z" + "end_time": "2024-01-05T11:48:27.887896771Z", + "start_time": "2024-01-05T11:48:27.883057209Z" } }, "outputs": [ @@ -250,7 +250,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "ProcessMetaData(id=1, created_at=datetime.datetime(2023, 12, 13, 10, 22, 25), created_by='dprueser', description='Tutorial for getting familiar with the ORM.', pycram_version='3422aa2a9097bcb087795fccf89e5bd128ab21dd')\n" + "ProcessMetaData(id=1, created_at=datetime.datetime(2024, 1, 5, 11, 48, 27), created_by='dprueser', description='Tutorial for getting familiar with the ORM.', pycram_version='be748996363cb497af6784f6f2aaeffcb2fb1c42')\n" ] } ], @@ -271,8 +271,8 @@ "execution_count": 6, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.774954933Z", - "start_time": "2023-12-13T10:22:25.719710555Z" + "end_time": "2024-01-05T11:48:27.933255911Z", + "start_time": "2024-01-05T11:48:27.886082312Z" } }, "outputs": [ @@ -302,8 +302,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.775554799Z", - "start_time": "2023-12-13T10:22:25.774858881Z" + "end_time": "2024-01-05T11:48:27.933794333Z", + "start_time": "2024-01-05T11:48:27.930158041Z" } }, "outputs": [ @@ -339,8 +339,8 @@ "execution_count": 8, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.775915781Z", - "start_time": "2023-12-13T10:22:25.774973642Z" + "end_time": "2024-01-05T11:48:27.934174898Z", + "start_time": "2024-01-05T11:48:27.930328964Z" } }, "outputs": [ @@ -348,7 +348,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "Pose(id=7, time=datetime.datetime(2023, 12, 13, 10, 22, 12, 75413), frame='map', position_id=7, orientation_id=7, process_metadata_id=1)\n" + "Pose(id=7, time=datetime.datetime(2024, 1, 5, 11, 48, 13, 104805), frame='map', position_id=7, orientation_id=7, process_metadata_id=1)\n" ] } ], @@ -384,8 +384,8 @@ "execution_count": 9, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.776819211Z", - "start_time": "2023-12-13T10:22:25.775011202Z" + "end_time": "2024-01-05T11:48:27.992321580Z", + "start_time": "2024-01-05T11:48:27.930434353Z" } }, "outputs": [ @@ -393,25 +393,25 @@ "name": "stdout", "output_type": "stream", "text": [ - "TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=3, code_id=3, code=Code(id=3, function='perform', designator_id=1, designator=ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=, pose_id=1, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144323), end_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 650626), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=4, code_id=4, code=Code(id=4, function='perform', designator_id=2, designator=MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=, pose_id=2, process_metadata_id=1), position=0.3), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 650720), end_time=datetime.datetime(2023, 12, 13, 11, 22, 13, 154581), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 13, 704577), end_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214635), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=6, code_id=6, code=Code(id=6, function='perform', designator_id=4, designator=MoveMotion(id=4, process_metadata_id=1, dtype='MoveMotion', pose_id=5), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 13, 704616), end_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214628), status=, reason=None, parent_id=5, parent=TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 13, 704577), end_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214635), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=8, code_id=8, code=Code(id=8, function='perform', designator_id=6, designator=MoveTCPMotion(id=6, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=8), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 385460), end_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 894615), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=9, code_id=9, code=Code(id=9, function='perform', designator_id=7, designator=MoveGripperMotion(id=7, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 894706), end_time=datetime.datetime(2023, 12, 13, 11, 22, 15, 402177), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=10, code_id=10, code=Code(id=10, function='perform', designator_id=8, designator=MoveTCPMotion(id=8, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=9), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 15, 552840), end_time=datetime.datetime(2023, 12, 13, 11, 22, 16, 62542), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=11, code_id=11, code=Code(id=11, function='perform', designator_id=9, designator=MoveGripperMotion(id=9, process_metadata_id=1, dtype='MoveGripperMotion', motion='close', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 16, 62656), end_time=datetime.datetime(2023, 12, 13, 11, 22, 16, 570383), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=12, code_id=12, code=Code(id=12, function='perform', designator_id=10, designator=MoveTCPMotion(id=10, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=10), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 16, 703869), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 214127), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 14, 214734), end_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504156), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=13, code_id=13, code=Code(id=13, function='perform', designator_id=11, designator=ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=, pose_id=11, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 17, 504274), end_time=datetime.datetime(2023, 12, 13, 11, 22, 18, 13609), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 22, 957228), end_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462603), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=15, code_id=15, code=Code(id=15, function='perform', designator_id=13, designator=MoveMotion(id=13, process_metadata_id=1, dtype='MoveMotion', pose_id=14), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 22, 957259), end_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462584), status=, reason=None, parent_id=14, parent=TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 22, 957228), end_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462603), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462711), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992076), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=17, code_id=17, code=Code(id=17, function='perform', designator_id=15, designator=MoveTCPMotion(id=15, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=18), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 463717), end_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 974361), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462711), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992076), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=18, code_id=18, code=Code(id=18, function='perform', designator_id=16, designator=MoveGripperMotion(id=16, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 974450), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 482580), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462711), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992076), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=19, code_id=19, code=Code(id=19, function='perform', designator_id=17, designator=MoveTCPMotion(id=17, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=19), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 482694), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992063), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 23, 462711), end_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992076), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=20, code_id=20, code=Code(id=20, function='perform', designator_id=18, designator=ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=, pose_id=20, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 24, 992156), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498594), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 12, 144277), end_time=datetime.datetime(2023, 12, 13, 11, 22, 25, 498607), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2023, 12, 13, 11, 22, 5, 734143), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n" + "TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=3, code_id=3, code=Code(id=3, function='perform', designator_id=1, designator=ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=, pose_id=1, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167962), end_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 674674), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=4, code_id=4, code=Code(id=4, function='perform', designator_id=2, designator=MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=, pose_id=2, process_metadata_id=1), position=0.3), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 674769), end_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 177846), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742815), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288620), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=6, code_id=6, code=Code(id=6, function='perform', designator_id=4, designator=MoveMotion(id=4, process_metadata_id=1, dtype='MoveMotion', pose_id=5), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742855), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288611), status=, reason=None, parent_id=5, parent=TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742815), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288620), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=8, code_id=8, code=Code(id=8, function='perform', designator_id=6, designator=MoveTCPMotion(id=6, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=8), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 417504), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 929845), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=9, code_id=9, code=Code(id=9, function='perform', designator_id=7, designator=MoveGripperMotion(id=7, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 929939), end_time=datetime.datetime(2024, 1, 5, 12, 48, 16, 435586), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=10, code_id=10, code=Code(id=10, function='perform', designator_id=8, designator=MoveTCPMotion(id=8, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=9), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 16, 568469), end_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 76882), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=11, code_id=11, code=Code(id=11, function='perform', designator_id=9, designator=MoveGripperMotion(id=9, process_metadata_id=1, dtype='MoveGripperMotion', motion='close', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 77011), end_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 589849), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=12, code_id=12, code=Code(id=12, function='perform', designator_id=10, designator=MoveTCPMotion(id=10, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=10), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 720082), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 228417), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=13, code_id=13, code=Code(id=13, function='perform', designator_id=11, designator=ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=, pose_id=11, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 520072), end_time=datetime.datetime(2024, 1, 5, 12, 48, 19, 27331), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115462), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625686), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=15, code_id=15, code=Code(id=15, function='perform', designator_id=13, designator=MoveMotion(id=13, process_metadata_id=1, dtype='MoveMotion', pose_id=14), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115512), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625678), status=, reason=None, parent_id=14, parent=TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115462), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625686), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=17, code_id=17, code=Code(id=17, function='perform', designator_id=15, designator=MoveTCPMotion(id=15, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=18), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 626977), end_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 135284), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=18, code_id=18, code=Code(id=18, function='perform', designator_id=16, designator=MoveGripperMotion(id=16, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 135369), end_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 642910), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=19, code_id=19, code=Code(id=19, function='perform', designator_id=17, designator=MoveTCPMotion(id=17, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=19), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 643067), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153860), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=20, code_id=20, code=Code(id=20, function='perform', designator_id=18, designator=ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=, pose_id=20, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153953), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660007), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n" ] } ], @@ -434,14 +434,15 @@ "execution_count": 10, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.827781799Z", - "start_time": "2023-12-13T10:22:25.782671460Z" + "end_time": "2024-01-05T11:48:27.993029221Z", + "start_time": "2024-01-05T11:48:27.956265531Z" } }, "outputs": [], "source": [ "from sqlalchemy.orm import Mapped, mapped_column\n", "from pycram.orm.action_designator import Action\n", + "from dataclasses import dataclass\n", "\n", "\n", "# define ORM class from pattern in every pycram.orm class\n", @@ -452,32 +453,24 @@ " text: Mapped[str] \n", "\n", "# define brand new action designator\n", - "class Saying(ActionDesignatorDescription):\n", + "\n", + "@dataclass \n", + "class SayingActionPerformable(ActionDesignatorDescription.Action):\n", " \n", - " @dataclasses.dataclass \n", - " class Action(ActionDesignatorDescription.Action):\n", + " text: str\n", " \n", - " text: str\n", - " \n", - " @with_tree\n", - " def perform(self) -> Any:\n", - " print(self.text)\n", - " \n", - " def to_sql(self) -> ORMSaying:\n", - " return ORMSaying(self.text)\n", + " @with_tree\n", + " def perform(self) -> None:\n", + " print(self.text)\n", "\n", - " def insert(self, session: Session, *args, **kwargs) -> ORMSaying:\n", - " action = super().insert(session)\n", - " session.add(action)\n", - " session.commit()\n", - " return action\n", - " \n", - " def __init__(self, texts: List[str], resolver=None):\n", - " super().__init__(resolver)\n", - " self.texts = texts\n", + " def to_sql(self) -> ORMSaying:\n", + " return ORMSaying(self.text)\n", "\n", - " def ground(self) -> Action:\n", - " return self.Action(self.texts[0])" + " def insert(self, session: Session, *args, **kwargs) -> ORMSaying:\n", + " action = super().insert(session)\n", + " session.add(action)\n", + " session.commit()\n", + " return action\n" ] }, { @@ -492,8 +485,8 @@ "execution_count": 11, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:25.828275817Z", - "start_time": "2023-12-13T10:22:25.826744665Z" + "end_time": "2024-01-05T11:48:27.993997340Z", + "start_time": "2024-01-05T11:48:27.956444747Z" } }, "outputs": [], @@ -513,8 +506,8 @@ "execution_count": 12, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:26.207983261Z", - "start_time": "2023-12-13T10:22:25.826841295Z" + "end_time": "2024-01-05T11:48:28.491240632Z", + "start_time": "2024-01-05T11:48:27.965003339Z" } }, "outputs": [ @@ -529,13 +522,13 @@ "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 21/21 [00:00<00:00, 122.69it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 21/21 [00:00<00:00, 77.00it/s]\n" ] } ], "source": [ "# create a saying action and insert it\n", - "Saying.Action(\"Patchie, Patchie; Where is my Patchie?\").perform()\n", + "SayingActionPerformable(\"Patchie, Patchie; Where is my Patchie?\").perform()\n", "pycram.task.task_tree.root.insert(session)\n", "session.commit()\n", "\n", @@ -555,8 +548,8 @@ "execution_count": 13, "metadata": { "ExecuteTime": { - "end_time": "2023-12-13T10:22:26.214535062Z", - "start_time": "2023-12-13T10:22:26.209490452Z" + "end_time": "2024-01-05T11:48:28.526329436Z", + "start_time": "2024-01-05T11:48:28.478332427Z" } }, "outputs": [ diff --git a/examples/orm_querying_examples.ipynb b/examples/orm_querying_examples.ipynb index 28f52f63d..64f78edb4 100644 --- a/examples/orm_querying_examples.ipynb +++ b/examples/orm_querying_examples.ipynb @@ -36,12 +36,13 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1702467193.499071]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1702467193.504366]: Failed to import Giskard messages\n" + "[WARN] [1704455774.294953]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1704455774.300327]: Failed to import Giskard messages\n" ] } ], "source": [ + "from pycram.designators.actions.actions import MoveTorsoActionPerformable, ParkArmsActionPerformable\n", "from tf import transformations\n", "import itertools\n", "import time\n", @@ -167,13 +168,13 @@ " # try to execute a grasping plan\n", " with simulated_robot:\n", "\n", - " ParkArmsAction.Action(pycram.enums.Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform()\n", " # navigate to sampled position\n", " NavigateAction([Pose(position, orientation)]).resolve().perform()\n", "\n", " # move torso\n", " height = np.random.uniform(0., 0.33, 1)[0]\n", - " MoveTorsoAction.Action(height).perform()\n", + " MoveTorsoActionPerformable(height).perform()\n", "\n", " # try to pick it up\n", " try:\n", @@ -205,8 +206,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2023-12-13T11:33:13.874158209Z", - "start_time": "2023-12-13T11:33:12.871008643Z" + "end_time": "2024-01-05T11:56:14.747051902Z", + "start_time": "2024-01-05T11:56:13.637965477Z" } }, "id": "dc0c9e6f15f126a3" @@ -242,7 +243,9 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "100%|██████████| 960/960 [01:41<00:00, 9.87it/s, success_rate=0.0854]" + " 74%|███████▍ | 708/960 [01:31<00:29, 8.48it/s, success_rate=0.0819]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/r_gripper_palm_link (parent map) at time 1704455865.925491 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + "100%|██████████| 960/960 [02:03<00:00, 7.85it/s, success_rate=0.0854]" ] } ], @@ -258,8 +261,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2023-12-13T11:34:55.371037890Z", - "start_time": "2023-12-13T11:33:13.874635425Z" + "end_time": "2024-01-05T11:58:18.210175597Z", + "start_time": "2024-01-05T11:56:14.749214037Z" } }, "id": "f2dcacd942218899" @@ -343,8 +346,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2023-12-13T11:34:55.371818556Z", - "start_time": "2023-12-13T11:34:55.371020667Z" + "end_time": "2024-01-05T11:58:18.210316772Z", + "start_time": "2024-01-05T11:58:18.210052650Z" } }, "id": "b17c6366f317dd7" @@ -442,8 +445,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2023-12-13T11:34:55.423112328Z", - "start_time": "2023-12-13T11:34:55.371312120Z" + "end_time": "2024-01-05T11:58:18.254184939Z", + "start_time": "2024-01-05T11:58:18.210187006Z" } }, "id": "a89d1a0f2a933475" diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 20f1beb48..7a2c312ea 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -1,9 +1,8 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations -import dataclasses +from dataclasses import dataclass, field, fields from abc import ABC, abstractmethod -from copy import copy from inspect import isgenerator, isgeneratorfunction from sqlalchemy.orm.session import Session @@ -367,7 +366,7 @@ class MotionDesignatorDescription(DesignatorDescription): Parent class of motion designator descriptions. """ - @dataclasses.dataclass + @dataclass class Motion: """ Resolved motion designator which can be performed @@ -465,21 +464,21 @@ class ActionDesignatorDescription(DesignatorDescription): Descriptions hold possible parameter ranges for action designators. """ - @dataclasses.dataclass + @dataclass class Action: """ The performable designator with a single element for each list of possible parameter. """ - robot_position: Pose = dataclasses.field(init=False) + robot_position: Pose = field(init=False) """ The position of the robot at the start of the action. """ - robot_torso_height: float = dataclasses.field(init=False) + robot_torso_height: float = field(init=False) """ The torso height of the robot at the start of the action. """ - robot_type: str = dataclasses.field(init=False) + robot_type: str = field(init=False) """ The type of the robot at the start of the action. """ @@ -546,7 +545,7 @@ class LocationDesignatorDescription(DesignatorDescription): Parent class of location designator descriptions. """ - @dataclasses.dataclass + @dataclass class Location: """ Resolved location that represents a specific point in the world which satisfies the constraints of the location @@ -585,7 +584,7 @@ class ObjectDesignatorDescription(DesignatorDescription): Descriptions hold possible parameter ranges for object designators. """ - @dataclasses.dataclass + @dataclass class Object: """ A single element that fits the description. @@ -606,7 +605,7 @@ class Object: Reference to the BulletWorld object """ - _pose: Optional[Callable] = dataclasses.field(init=False) + _pose: Optional[Callable] = field(init=False) """ A callable returning the pose of this object. The _pose member is used overwritten for data copies which will not update when the original bullet_world_object is moved. @@ -645,7 +644,7 @@ def insert(self, session: Session) -> ORMObjectDesignator: session.commit() return obj - def data_copy(self) -> 'ObjectDesignatorDescription.Object': + def frozen_copy(self) -> 'ObjectDesignatorDescription.Object': """ :return: A copy containing only the fields of this class. The BulletWorldObject attached to this pycram object is not copied. The _pose gets set to a method that statically returns the pose of the object when @@ -678,7 +677,7 @@ def pose(self, value: Callable): def __repr__(self): return self.__class__.__qualname__ + f"(" + ', '.join( - [f"{f.name}={self.__getattribute__(f.name)}" for f in dataclasses.fields(self)] + [ + [f"{f.name}={self.__getattribute__(f.name)}" for f in fields(self)] + [ f"pose={self.pose}"]) + ')' def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index ddc9b24ab..f8b9d347f 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -1,31 +1,17 @@ -import dataclasses import itertools -import time -from typing import List, Optional, Any, Tuple, Union - -import sqlalchemy.orm - -from .location_designator import CostmapLocation +from typing import Union from .motion_designator import * -from .object_designator import ObjectDesignatorDescription, BelieveObject, ObjectPart -from ..local_transformer import LocalTransformer -from ..orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, - PickUpAction as ORMPickUpAction, PlaceAction as ORMPlaceAction, - MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, - Action as ORMAction, LookAtAction as ORMLookAtAction, - DetectAction as ORMDetectAction, TransportAction as ORMTransportAction, - OpenAction as ORMOpenAction, CloseAction as ORMCloseAction, - GraspingAction as ORMGraspingAction) - -from ..orm.base import Quaternion, Position, Base, RobotState, ProcessMetaData -from ..plan_failures import ObjectUnfetchable, ReachabilityFailure -from ..robot_descriptions import robot_description -from ..task import with_tree +from .object_designator import ObjectDesignatorDescription, ObjectPart from ..enums import Arms from ..designator import ActionDesignatorDescription -from ..bullet_world import BulletWorld from ..pose import Pose -from ..helper import multiply_quaternions +from pycram.designators.actions.actions import (ParkArmsActionPerformable, MoveTorsoActionPerformable, + SetGripperActionPerformable, GripActionPerformable, + PlaceActionPerformable, PickUpActionPerformable, + NavigateActionPerformable, TransportActionPerformable, + LookAtActionPerformable, DetectActionPerformable, OpenActionPerformable, + CloseActionPerformable, GraspingActionPerformable, + ReleaseActionPerformable) class MoveTorsoAction(ActionDesignatorDescription): @@ -33,30 +19,6 @@ class MoveTorsoAction(ActionDesignatorDescription): Action Designator for Moving the torso of the robot up and down """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - """ - Performable Move Torso Action designator. - """ - - position: float - """ - Target position of the torso joint - """ - - @with_tree - def perform(self) -> None: - MoveJointsMotion([robot_description.torso_joint], [self.position]).resolve().perform() - - def to_sql(self) -> ORMMoveTorsoAction: - return ORMMoveTorsoAction(self.position) - - def insert(self, session: sqlalchemy.orm.session.Session, **kwargs) -> ORMMoveTorsoAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - def __init__(self, positions: List[float], resolver=None): """ Create a designator description to move the torso of the robot up and down. @@ -67,13 +29,13 @@ def __init__(self, positions: List[float], resolver=None): super().__init__(resolver) self.positions: List[float] = positions - def ground(self) -> Action: + def ground(self) -> MoveTorsoActionPerformable: """ Creates a performable action designator with the first element from the list of possible torso heights. :return: A performable action designator """ - return self.Action(self.positions[0]) + return MoveTorsoActionPerformable(self.positions[0]) def __iter__(self): """ @@ -82,7 +44,7 @@ def __iter__(self): :return: A performable action designator """ for position in self.positions: - yield self.Action(position) + yield MoveTorsoActionPerformable(position) class SetGripperAction(ActionDesignatorDescription): @@ -90,30 +52,6 @@ class SetGripperAction(ActionDesignatorDescription): Set the gripper state of the robot """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - gripper: str - """ - The gripper that should be set - """ - motion: str - """ - The motion that should be set on the gripper - """ - - @with_tree - def perform(self) -> None: - MoveGripperMotion(gripper=self.gripper, motion=self.motion).resolve().perform() - - def to_sql(self) -> ORMSetGripperAction: - return ORMSetGripperAction(self.gripper, self.motion) - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMSetGripperAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - def __init__(self, grippers: List[str], motions: List[str], resolver=None): """ Sets the gripper state, the desired state is given with the motion. Motion can either be 'open' or 'close'. @@ -126,13 +64,13 @@ def __init__(self, grippers: List[str], motions: List[str], resolver=None): self.grippers: List[str] = grippers self.motions: List[str] = motions - def ground(self) -> Action: + def ground(self) -> SetGripperActionPerformable: """ Default resolver that returns a performable designator with the first element in the grippers and motions list. :return: A performable designator """ - return self.Action(self.grippers[0], self.motions[0]) + return SetGripperActionPerformable(self.grippers[0], self.motions[0]) def __iter__(self): """ @@ -141,7 +79,7 @@ def __iter__(self): :return: A performable designator with a combination of gripper and motion """ for parameter_combination in itertools.product(self.grippers, self.motions): - yield self.Action(*parameter_combination) + yield SetGripperActionPerformable(*parameter_combination) class ReleaseAction(ActionDesignatorDescription): @@ -151,29 +89,14 @@ class ReleaseAction(ActionDesignatorDescription): Note: This action can not be used yet. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - gripper: str - object_designator: ObjectDesignatorDescription.Object - - @with_tree - def perform(self) -> Any: - raise NotImplementedError() - - def to_sql(self) -> Base: - raise NotImplementedError() - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> Base: - raise NotImplementedError() - def __init__(self, grippers: List[str], object_designator_description: ObjectDesignatorDescription, resolver=None): super().__init__(resolver) self.grippers: List[str] = grippers self.object_designator_description = object_designator_description - def ground(self) -> Action: - return self.Action(self.grippers[0], self.object_designator_description.ground()) + def ground(self) -> ReleaseActionPerformable: + return ReleaseActionPerformable(self.grippers[0], self.object_designator_description.ground()) class GripAction(ActionDesignatorDescription): @@ -187,22 +110,6 @@ class GripAction(ActionDesignatorDescription): Note: This action can not be used yet. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - gripper: str - object_designator: ObjectDesignatorDescription.Object - effort: float - - @with_tree - def perform(self) -> Any: - raise NotImplementedError() - - def to_sql(self) -> Base: - raise NotImplementedError() - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> Base: - raise NotImplementedError() - def __init__(self, grippers: List[str], object_designator_description: ObjectDesignatorDescription, efforts: List[float], resolver=None): super().__init__(resolver) @@ -210,8 +117,8 @@ def __init__(self, grippers: List[str], object_designator_description: ObjectDes self.object_designator_description: ObjectDesignatorDescription = object_designator_description self.efforts: List[float] = efforts - def ground(self) -> Action: - return self.Action(self.grippers[0], self.object_designator_description.ground(), self.efforts[0]) + def ground(self) -> GripActionPerformable: + return GripActionPerformable(self.grippers[0], self.object_designator_description.ground(), self.efforts[0]) class ParkArmsAction(ActionDesignatorDescription): @@ -219,37 +126,6 @@ class ParkArmsAction(ActionDesignatorDescription): Park the arms of the robot. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - - arm: Arms - """ - Entry from the enum for which arm should be parked - """ - - @with_tree - def perform(self) -> None: - # create the keyword arguments - kwargs = dict() - - # add park left arm if wanted - if self.arm in [Arms.LEFT, Arms.BOTH]: - kwargs["left_arm_config"] = "park" - - # add park right arm if wanted - if self.arm in [Arms.RIGHT, Arms.BOTH]: - kwargs["right_arm_config"] = "park" - MoveArmJointsMotion(**kwargs).resolve().perform() - - def to_sql(self) -> ORMParkArmsAction: - return ORMParkArmsAction(self.arm.name) - - def insert(self, session: sqlalchemy.orm.session.Session, **kwargs) -> ORMParkArmsAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - def __init__(self, arms: List[Arms], resolver=None): """ Moves the arms in the pre-defined parking position. Arms are taken from pycram.enum.Arms @@ -260,13 +136,13 @@ def __init__(self, arms: List[Arms], resolver=None): super().__init__(resolver) self.arms: List[Arms] = arms - def ground(self) -> Action: + def ground(self) -> ParkArmsActionPerformable: """ Default resolver that returns a performable designator with the first element of the list of possible arms :return: A performable designator """ - return self.Action(self.arms[0]) + return ParkArmsActionPerformable(self.arms[0]) class PickUpAction(ActionDesignatorDescription): @@ -274,110 +150,6 @@ class PickUpAction(ActionDesignatorDescription): Designator to let the robot pick up an object. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - - object_designator: ObjectDesignatorDescription.Object - """ - Object designator describing the object that should be picked up - """ - - arm: str - """ - The arm that should be used for pick up - """ - - grasp: str - """ - The grasp that should be used. For example, 'left' or 'right' - """ - - object_at_execution: Optional[ObjectDesignatorDescription.Object] = dataclasses.field(init=False) - """ - The object at the time this Action got created. It is used to be a static, information holding entity. It is - not updated when the BulletWorld object is changed. - """ - - @with_tree - def perform(self) -> None: - # Store the object's data copy at execution - self.object_at_execution = self.object_designator.data_copy() - robot = BulletWorld.robot - # Retrieve object and robot from designators - object = self.object_designator.bullet_world_object - # Get grasp orientation and target pose - grasp = robot_description.grasps.get_orientation_for_grasp(self.grasp) - # oTm = Object Pose in Frame map - oTm = object.get_pose() - # Transform the object pose to the object frame, basically the origin of the object frame - mTo = object.local_transformer.transform_to_object_frame(oTm, object) - # Adjust the pose according to the special knowledge of the object designator - adjusted_pose = self.object_designator.special_knowledge_adjustment_pose(self.grasp, mTo) - # Transform the adjusted pose to the map frame - adjusted_oTm = object.local_transformer.transform_pose(adjusted_pose, "map") - # multiplying the orientation therefore "rotating" it, to get the correct orientation of the gripper - ori = multiply_quaternions([adjusted_oTm.orientation.x, adjusted_oTm.orientation.y, - adjusted_oTm.orientation.z, adjusted_oTm.orientation.w], - grasp) - - # Set the orientation of the object pose by grasp in MAP - adjusted_oTm.orientation.x = ori[0] - adjusted_oTm.orientation.y = ori[1] - adjusted_oTm.orientation.z = ori[2] - adjusted_oTm.orientation.w = ori[3] - - # prepose depending on the gripper (its annoying we have to put pr2_1 here tbh - # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" - gripper_frame = robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm)) - # First rotate the gripper, so the further calculations makes sense - tmp_for_rotate_pose = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) - tmp_for_rotate_pose.pose.position.x = 0 - tmp_for_rotate_pose.pose.position.y = 0 - tmp_for_rotate_pose.pose.position.z = -0.1 - gripper_rotate_pose = object.local_transformer.transform_pose(tmp_for_rotate_pose, "map") - - #Perform Gripper Rotate - # BulletWorld.current_bullet_world.add_vis_axis(gripper_rotate_pose) - # MoveTCPMotion(gripper_rotate_pose, self.arm).resolve().perform() - - oTg = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) - oTg.pose.position.x -= 0.1 # in x since this is how the gripper is oriented - prepose = object.local_transformer.transform_pose(oTg, "map") - - # Perform the motion with the prepose and open gripper - BulletWorld.current_bullet_world.add_vis_axis(prepose) - MoveTCPMotion(prepose, self.arm).resolve().perform() - MoveGripperMotion(motion="open", gripper=self.arm).resolve().perform() - - # Perform the motion with the adjusted pose -> actual grasp and close gripper - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() - adjusted_oTm.pose.position.z += 0.03 - MoveGripperMotion(motion="close", gripper=self.arm).resolve().perform() - tool_frame = robot_description.get_tool_frame(self.arm) - robot.attach(object, tool_frame) - - # Lift object - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() - - # Remove the vis axis from the world - BulletWorld.current_bullet_world.remove_vis_axis() - - def to_sql(self) -> ORMPickUpAction: - return ORMPickUpAction(self.arm, self.grasp) - - def insert(self, session: sqlalchemy.orm.session.Session, **kwargs) -> ORMPickUpAction: - action = super().insert(session) - - od = self.object_at_execution.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: Union[ObjectDesignatorDescription, ObjectDesignatorDescription.Object], arms: List[str], grasps: List[str], resolver=None): """ @@ -395,7 +167,7 @@ def __init__(self, object_designator_description: Union[ObjectDesignatorDescrip self.arms: List[str] = arms self.grasps: List[str] = grasps - def ground(self) -> Action: + def ground(self) -> PickUpActionPerformable: """ Default resolver, returns a performable designator with the first entries from the lists of possible parameter. @@ -404,7 +176,7 @@ def ground(self) -> Action: obj_desig = self.object_designator_description if isinstance(self.object_designator_description, ObjectDesignatorDescription.Object) else self.object_designator_description.resolve() - return self.Action(obj_desig, self.arms[0], self.grasps[0]) + return PickUpActionPerformable(obj_desig, self.arms[0], self.grasps[0]) class PlaceAction(ActionDesignatorDescription): @@ -412,58 +184,6 @@ class PlaceAction(ActionDesignatorDescription): Places an Object at a position using an arm. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - - object_designator: ObjectDesignatorDescription.Object - """ - Object designator describing the object that should be place - """ - arm: str - """ - Arm that is currently holding the object - """ - target_location: Pose - """ - Pose in the world at which the object should be placed - """ - - @with_tree - def perform(self) -> None: - object_pose = self.object_designator.bullet_world_object.get_pose() - local_tf = LocalTransformer() - - # Transformations such that the target position is the position of the object and not the tcp - tcp_to_object = local_tf.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame( - robot_description.get_tool_frame(self.arm))) - target_diff = self.target_location.to_transform("target").inverse_times( - tcp_to_object.to_transform("object")).to_pose() - - MoveTCPMotion(target_diff, self.arm).resolve().perform() - MoveGripperMotion("open", self.arm).resolve().perform() - BulletWorld.robot.detach(self.object_designator.bullet_world_object) - retract_pose = target_diff - retract_pose.position.x -= 0.07 - MoveTCPMotion(retract_pose, self.arm).resolve().perform() - - def to_sql(self) -> ORMPlaceAction: - return ORMPlaceAction(self.arm) - - def insert(self, session, *args, **kwargs) -> ORMPlaceAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: Union[ObjectDesignatorDescription, ObjectDesignatorDescription.Object], target_locations: List[Pose], @@ -482,7 +202,7 @@ def __init__(self, self.target_locations: List[Pose] = target_locations self.arms: List[str] = arms - def ground(self) -> Action: + def ground(self) -> PlaceActionPerformable: """ Default resolver that returns a performable designator with the first entries from the list of possible entries. @@ -491,7 +211,7 @@ def ground(self) -> Action: obj_desig = self.object_designator_description if isinstance(self.object_designator_description, ObjectDesignatorDescription.Object) else self.object_designator_description.resolve() - return self.Action(obj_desig, self.arms[0], self.target_locations[0]) + return PlaceActionPerformable(obj_desig, self.arms[0], self.target_locations[0]) class NavigateAction(ActionDesignatorDescription): @@ -499,31 +219,6 @@ class NavigateAction(ActionDesignatorDescription): Navigates the Robot to a position. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - target_location: Pose - """ - Location to which the robot should be navigated - """ - - @with_tree - def perform(self) -> None: - MoveMotion(self.target_location).resolve().perform() - - def to_sql(self) -> ORMNavigateAction: - return ORMNavigateAction() - - def insert(self, session, *args, **kwargs) -> ORMNavigateAction: - action = super().insert(session) - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - def __init__(self, target_locations: List[Pose], resolver=None): """ Navigates the robot to a location. @@ -534,13 +229,13 @@ def __init__(self, target_locations: List[Pose], resolver=None): super().__init__(resolver) self.target_locations: List[Pose] = target_locations - def ground(self) -> Action: + def ground(self) -> NavigateActionPerformable: """ Default resolver that returns a performable designator with the first entry of possible target locations. :return: A performable designator """ - return self.Action(self.target_locations[0]) + return NavigateActionPerformable(self.target_locations[0]) class TransportAction(ActionDesignatorDescription): @@ -548,67 +243,6 @@ class TransportAction(ActionDesignatorDescription): Transports an object to a position using an arm """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - object_designator: ObjectDesignatorDescription.Object - """ - Object designator describing the object that should be transported. - """ - arm: str - """ - Arm that should be used - """ - target_location: Pose - """ - Target Location to which the object should be transported - """ - - @with_tree - def perform(self) -> None: - robot_desig = BelieveObject(names=[robot_description.name]) - ParkArmsAction.Action(Arms.BOTH).perform() - pickup_loc = CostmapLocation(target=self.object_designator, reachable_for=robot_desig.resolve(), - reachable_arm=self.arm) - # Tries to find a pick-up posotion for the robot that uses the given arm - pickup_pose = None - for pose in pickup_loc: - if self.arm in pose.reachable_arms: - pickup_pose = pose - break - if not pickup_pose: - raise ObjectUnfetchable( - f"Found no pose for the robot to grasp the object: {self.object_designator} with arm: {self.arm}") - - NavigateAction([pickup_pose.pose]).resolve().perform() - PickUpAction.Action(self.object_designator, self.arm, "front").perform() - ParkArmsAction.Action(Arms.BOTH).perform() - try: - place_loc = CostmapLocation(target=self.target_location, reachable_for=robot_desig.resolve(), - reachable_arm=self.arm).resolve() - except StopIteration: - raise ReachabilityFailure( - f"No location found from where the robot can reach the target location: {self.target_location}") - NavigateAction([place_loc.pose]).resolve().perform() - PlaceAction.Action(self.object_designator, self.arm, self.target_location).perform() - ParkArmsAction.Action(Arms.BOTH).perform() - - def to_sql(self) -> ORMTransportAction: - return ORMTransportAction(self.arm) - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMTransportAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: Union[ObjectDesignatorDescription, ObjectDesignatorDescription.Object], arms: List[str], @@ -627,17 +261,17 @@ def __init__(self, self.arms: List[str] = arms self.target_locations: List[Pose] = target_locations - def ground(self) -> Action: + def ground(self) -> TransportActionPerformable: """ Default resolver that returns a performable designator with the first entries from the lists of possible parameter. :return: A performable designator """ - obj_desig = self.object_designator_description if isinstance(self.object_designator_description, - ObjectDesignatorDescription.Object) else self.object_designator_description.resolve() - return self.Action(obj_desig, - self.arms[0], - self.target_locations[0]) + obj_desig = self.object_designator_description \ + if isinstance(self.object_designator_description, ObjectDesignatorDescription.Object)\ + else self.object_designator_description.resolve() + + return TransportActionPerformable(obj_desig, self.arms[0], self.target_locations[0]) class LookAtAction(ActionDesignatorDescription): @@ -645,30 +279,6 @@ class LookAtAction(ActionDesignatorDescription): Lets the robot look at a position. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - target: Pose - """ - Position at which the robot should look, given as 6D pose - """ - - @with_tree - def perform(self) -> None: - LookingMotion(target=self.target).resolve().perform() - - def to_sql(self) -> ORMLookAtAction: - return ORMLookAtAction() - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMLookAtAction: - action = super().insert(session) - - pose = self.target.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - return action - def __init__(self, targets: List[Pose], resolver=None): """ Moves the head of the robot such that it points towards the given target location. @@ -679,13 +289,13 @@ def __init__(self, targets: List[Pose], resolver=None): super().__init__(resolver) self.targets: List[Pose] = targets - def ground(self) -> Action: + def ground(self) -> LookAtActionPerformable: """ Default resolver that returns a performable designator with the first entry in the list of possible targets :return: A performable designator """ - return self.Action(self.targets[0]) + return LookAtActionPerformable(self.targets[0]) class DetectAction(ActionDesignatorDescription): @@ -693,31 +303,6 @@ class DetectAction(ActionDesignatorDescription): Detects an object that fits the object description and returns an object designator describing the object. """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - object_designator: ObjectDesignatorDescription.Object - """ - Object designator loosely describing the object, e.g. only type. - """ - - @with_tree - def perform(self) -> Any: - return DetectingMotion(object_type=self.object_designator.type).resolve().perform() - - def to_sql(self) -> ORMDetectAction: - return ORMDetectAction() - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMDetectAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: ObjectDesignatorDescription, resolver=None): """ Tries to detect an object in the field of view (FOV) of the robot. @@ -728,13 +313,13 @@ def __init__(self, object_designator_description: ObjectDesignatorDescription, r super().__init__(resolver) self.object_designator_description: ObjectDesignatorDescription = object_designator_description - def ground(self) -> Action: + def ground(self) -> DetectActionPerformable: """ Default resolver that returns a performable designator with the resolved object description. :return: A performable designator """ - return self.Action(self.object_designator_description.resolve()) + return DetectActionPerformable(self.object_designator_description.resolve()) class OpenAction(ActionDesignatorDescription): @@ -744,38 +329,6 @@ class OpenAction(ActionDesignatorDescription): Can currently not be used """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - object_designator: ObjectPart.Object - """ - Object designator describing the object that should be opened - """ - arm: str - """ - Arm that should be used for opening the container - """ - - @with_tree - def perform(self) -> Any: - GraspingAction.Action(self.arm, self.object_designator).perform() - OpeningMotion(self.object_designator, self.arm).resolve().perform() - - MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() - - def to_sql(self) -> ORMOpenAction: - return ORMOpenAction(self.arm) - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMOpenAction: - action = super().insert(session) - - op = self.object_designator.insert(session) - action.object_id = op.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: ObjectPart, arms: List[str], resolver=None): """ Moves the arm of the robot to open a container. @@ -788,14 +341,14 @@ def __init__(self, object_designator_description: ObjectPart, arms: List[str], r self.object_designator_description: ObjectPart = object_designator_description self.arms: List[str] = arms - def ground(self) -> Action: + def ground(self) -> OpenActionPerformable: """ Default resolver that returns a performable designator with the resolved object description and the first entries from the lists of possible parameter. :return: A performable designator """ - return self.Action(self.object_designator_description.resolve(), self.arms[0]) + return OpenActionPerformable(self.object_designator_description.resolve(), self.arms[0]) class CloseAction(ActionDesignatorDescription): @@ -805,38 +358,6 @@ class CloseAction(ActionDesignatorDescription): Can currently not be used """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - object_designator: ObjectPart.Object - """ - Object designator describing the object that should be closed - """ - arm: str - """ - Arm that should be used for closing - """ - - @with_tree - def perform(self) -> Any: - GraspingAction.Action(self.arm, self.object_designator).perform() - ClosingMotion(self.object_designator, self.arm).resolve().perform() - - MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() - - def to_sql(self) -> ORMCloseAction: - return ORMCloseAction(self.arm) - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMCloseAction: - action = super().insert(session) - - op = self.object_designator.insert(session) - action.object_id = op.id - - session.add(action) - session.commit() - - return action - def __init__(self, object_designator_description: ObjectPart, arms: List[str], resolver=None): """ @@ -850,14 +371,14 @@ def __init__(self, object_designator_description: ObjectPart, arms: List[str], self.object_designator_description: ObjectPart = object_designator_description self.arms: List[str] = arms - def ground(self) -> Action: + def ground(self) -> CloseActionPerformable: """ Default resolver that returns a performable designator with the resolved object designator and the first entry from the list of possible arms. :return: A performable designator """ - return self.Action(self.object_designator_description.resolve(), self.arms[0]) + return CloseActionPerformable(self.object_designator_description.resolve(), self.arms[0]) class GraspingAction(ActionDesignatorDescription): @@ -865,51 +386,6 @@ class GraspingAction(ActionDesignatorDescription): Grasps an object described by the given Object Designator description """ - @dataclasses.dataclass - class Action(ActionDesignatorDescription.Action): - arm: str - """ - The arm that should be used to grasp - """ - object_desig: Union[ObjectDesignatorDescription.Object, ObjectPart.Object] - """ - Object Designator for the object that should be grasped - """ - - def perform(self) -> Any: - if isinstance(self.object_desig, ObjectPart.Object): - object_pose = self.object_desig.part_pose - else: - object_pose = self.object_desig.bullet_world_object.get_pose() - lt = LocalTransformer() - gripper_name = robot_description.get_tool_frame(self.arm) - - object_pose_in_gripper = lt.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame(gripper_name)) - - pre_grasp = object_pose_in_gripper.copy() - pre_grasp.pose.position.x -= 0.1 - - MoveTCPMotion(pre_grasp, self.arm).resolve().perform() - MoveGripperMotion("open", self.arm).resolve().perform() - - MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).resolve().perform() - MoveGripperMotion("close", self.arm, allow_gripper_collision=True).resolve().perform() - - def to_sql(self) -> ORMGraspingAction: - return ORMGraspingAction(self.arm) - - def insert(self, session: sqlalchemy.orm.session.Session, *args, **kwargs) -> ORMGraspingAction: - action = super().insert(session) - - od = self.object_desig.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action - def __init__(self, arms: List[str], object_description: Union[ObjectDesignatorDescription, ObjectPart], resolver: Callable = None): """ @@ -924,11 +400,11 @@ def __init__(self, arms: List[str], object_description: Union[ObjectDesignatorDe self.arms: List[str] = arms self.object_description: ObjectDesignatorDescription = object_description - def ground(self) -> Action: + def ground(self) -> GraspingActionPerformable: """ Default resolver that takes the first element from the list of arms and the first solution for the object designator description ond returns it. :return: A performable action designator that contains specific arguments """ - return self.Action(self.arms[0], self.object_description.resolve()) + return GraspingActionPerformable(self.arms[0], self.object_description.resolve()) diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py new file mode 100644 index 000000000..add4bc650 --- /dev/null +++ b/src/pycram/designators/actions/actions.py @@ -0,0 +1,578 @@ +import abc +from typing import Union +from pycram.designator import ActionDesignatorDescription +from pycram.designators.motion_designator import * +from pycram.enums import Arms +from pycram.task import with_tree +from dataclasses import dataclass +from ..location_designator import CostmapLocation +from ..object_designator import BelieveObject +from ...helper import multiply_quaternions +from ...local_transformer import LocalTransformer +from ...orm.base import Base +from ...plan_failures import ObjectUnfetchable, ReachabilityFailure +from ...robot_descriptions import robot_description +from ...orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, + PickUpAction as ORMPickUpAction, PlaceAction as ORMPlaceAction, + MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, + LookAtAction as ORMLookAtAction, DetectAction as ORMDetectAction, + TransportAction as ORMTransportAction, OpenAction as ORMOpenAction, + CloseAction as ORMCloseAction, GraspingAction as ORMGraspingAction, Action) + + +@dataclass +class ActionAbstract(ActionDesignatorDescription.Action, abc.ABC): + """Base class for performable actions.""" + + @abc.abstractmethod + def perform(self) -> None: + """Perform the action.""" + pass + + @abc.abstractmethod + def to_sql(self) -> Action: + """Convert this action to its ORM equivalent.""" + pass + + @abc.abstractmethod + def insert(self, session: Session, **kwargs) -> Action: + """Insert this action into the database.""" + action = super().insert(session) + return action + + +@dataclass +class ParkArmsActionPerformable(ActionAbstract): + + arm: Arms + """ + Entry from the enum for which arm should be parked + """ + + @with_tree + def perform(self) -> None: + # create the keyword arguments + kwargs = dict() + + # add park left arm if wanted + if self.arm in [Arms.LEFT, Arms.BOTH]: + kwargs["left_arm_config"] = "park" + + # add park right arm if wanted + if self.arm in [Arms.RIGHT, Arms.BOTH]: + kwargs["right_arm_config"] = "park" + MoveArmJointsMotion(**kwargs).resolve().perform() + + def to_sql(self) -> ORMParkArmsAction: + return ORMParkArmsAction(self.arm.name) + + def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: + action = super().insert(session) + session.add(action) + session.commit() + return action + + +@dataclass +class MoveTorsoActionPerformable(ActionAbstract): + """ + Performable Move Torso Action designator. + """ + + position: float + """ + Target position of the torso joint + """ + + @with_tree + def perform(self) -> None: + MoveJointsMotion([robot_description.torso_joint], [self.position]).resolve().perform() + + def to_sql(self) -> ORMMoveTorsoAction: + return ORMMoveTorsoAction(self.position) + + def insert(self, session: Session, **kwargs) -> ORMMoveTorsoAction: + action = super().insert(session) + session.add(action) + session.commit() + return action + + +@dataclass +class SetGripperActionPerformable(ActionAbstract): + + gripper: str + """ + The gripper that should be set + """ + motion: str + """ + The motion that should be set on the gripper + """ + + @with_tree + def perform(self) -> None: + MoveGripperMotion(gripper=self.gripper, motion=self.motion).resolve().perform() + + def to_sql(self) -> ORMSetGripperAction: + return ORMSetGripperAction(self.gripper, self.motion) + + def insert(self, session: Session, *args, **kwargs) -> ORMSetGripperAction: + action = super().insert(session) + session.add(action) + session.commit() + return action + + +@dataclass +class ReleaseActionPerformable(ActionAbstract): + + gripper: str + + object_designator: ObjectDesignatorDescription.Object + + def perform(self) -> None: + raise NotImplementedError + + def to_sql(self) -> ORMParkArmsAction: + raise NotImplementedError + + def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: + raise NotImplementedError + + +@dataclass +class GripActionPerformable(ActionAbstract): + + gripper: str + object_designator: ObjectDesignatorDescription.Object + effort: float + + @with_tree + def perform(self) -> None: + raise NotImplementedError() + + def to_sql(self) -> Base: + raise NotImplementedError() + + def insert(self, session: Session, *args, **kwargs) -> Base: + raise NotImplementedError() + + +@dataclass +class PickUpActionPerformable(ActionAbstract): + + object_designator: ObjectDesignatorDescription.Object + """ + Object designator describing the object that should be picked up + """ + + arm: str + """ + The arm that should be used for pick up + """ + + grasp: str + """ + The grasp that should be used. For example, 'left' or 'right' + """ + + object_at_execution: Optional[ObjectDesignatorDescription.Object] = dataclasses.field(init=False) + """ + The object at the time this Action got created. It is used to be a static, information holding entity. It is + not updated when the BulletWorld object is changed. + """ + + @with_tree + def perform(self) -> None: + # Store the object's data copy at execution + self.object_at_execution = self.object_designator.frozen_copy() + robot = BulletWorld.robot + # Retrieve object and robot from designators + object = self.object_designator.bullet_world_object + # Get grasp orientation and target pose + grasp = robot_description.grasps.get_orientation_for_grasp(self.grasp) + # oTm = Object Pose in Frame map + oTm = object.get_pose() + # Transform the object pose to the object frame, basically the origin of the object frame + mTo = object.local_transformer.transform_to_object_frame(oTm, object) + # Adjust the pose according to the special knowledge of the object designator + adjusted_pose = self.object_designator.special_knowledge_adjustment_pose(self.grasp, mTo) + # Transform the adjusted pose to the map frame + adjusted_oTm = object.local_transformer.transform_pose(adjusted_pose, "map") + # multiplying the orientation therefore "rotating" it, to get the correct orientation of the gripper + ori = multiply_quaternions([adjusted_oTm.orientation.x, adjusted_oTm.orientation.y, + adjusted_oTm.orientation.z, adjusted_oTm.orientation.w], + grasp) + + # Set the orientation of the object pose by grasp in MAP + adjusted_oTm.orientation.x = ori[0] + adjusted_oTm.orientation.y = ori[1] + adjusted_oTm.orientation.z = ori[2] + adjusted_oTm.orientation.w = ori[3] + + # prepose depending on the gripper (its annoying we have to put pr2_1 here tbh + # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" + gripper_frame = robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm)) + # First rotate the gripper, so the further calculations makes sense + tmp_for_rotate_pose = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) + tmp_for_rotate_pose.pose.position.x = 0 + tmp_for_rotate_pose.pose.position.y = 0 + tmp_for_rotate_pose.pose.position.z = -0.1 + gripper_rotate_pose = object.local_transformer.transform_pose(tmp_for_rotate_pose, "map") + + #Perform Gripper Rotate + # BulletWorld.current_bullet_world.add_vis_axis(gripper_rotate_pose) + # MoveTCPMotion(gripper_rotate_pose, self.arm).resolve().perform() + + oTg = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) + oTg.pose.position.x -= 0.1 # in x since this is how the gripper is oriented + prepose = object.local_transformer.transform_pose(oTg, "map") + + # Perform the motion with the prepose and open gripper + BulletWorld.current_bullet_world.add_vis_axis(prepose) + MoveTCPMotion(prepose, self.arm).resolve().perform() + MoveGripperMotion(motion="open", gripper=self.arm).resolve().perform() + + # Perform the motion with the adjusted pose -> actual grasp and close gripper + BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() + adjusted_oTm.pose.position.z += 0.03 + MoveGripperMotion(motion="close", gripper=self.arm).resolve().perform() + tool_frame = robot_description.get_tool_frame(self.arm) + robot.attach(object, tool_frame) + + # Lift object + BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() + + # Remove the vis axis from the world + BulletWorld.current_bullet_world.remove_vis_axis() + + def to_sql(self) -> ORMPickUpAction: + return ORMPickUpAction(self.arm, self.grasp) + + def insert(self, session: Session, **kwargs) -> ORMPickUpAction: + action = super().insert(session) + + od = self.object_at_execution.insert(session) + action.object_id = od.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class PlaceActionPerformable(ActionAbstract): + + object_designator: ObjectDesignatorDescription.Object + """ + Object designator describing the object that should be place + """ + arm: str + """ + Arm that is currently holding the object + """ + target_location: Pose + """ + Pose in the world at which the object should be placed + """ + + @with_tree + def perform(self) -> None: + object_pose = self.object_designator.bullet_world_object.get_pose() + local_tf = LocalTransformer() + + # Transformations such that the target position is the position of the object and not the tcp + tcp_to_object = local_tf.transform_pose(object_pose, + BulletWorld.robot.get_link_tf_frame( + robot_description.get_tool_frame(self.arm))) + target_diff = self.target_location.to_transform("target").inverse_times( + tcp_to_object.to_transform("object")).to_pose() + + MoveTCPMotion(target_diff, self.arm).resolve().perform() + MoveGripperMotion("open", self.arm).resolve().perform() + BulletWorld.robot.detach(self.object_designator.bullet_world_object) + retract_pose = target_diff + retract_pose.position.x -= 0.07 + MoveTCPMotion(retract_pose, self.arm).resolve().perform() + + def to_sql(self) -> ORMPlaceAction: + return ORMPlaceAction(self.arm) + + def insert(self, session: Session, *args, **kwargs) -> ORMPlaceAction: + action = super().insert(session) + + od = self.object_designator.insert(session) + action.object_id = od.id + + pose = self.target_location.insert(session) + action.pose_id = pose.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class NavigateActionPerformable(ActionAbstract): + + target_location: Pose + """ + Location to which the robot should be navigated + """ + + @with_tree + def perform(self) -> None: + MoveMotion(self.target_location).resolve().perform() + + def to_sql(self) -> ORMNavigateAction: + return ORMNavigateAction() + + def insert(self, session: Session, *args, **kwargs) -> ORMNavigateAction: + action = super().insert(session) + + pose = self.target_location.insert(session) + action.pose_id = pose.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class TransportActionPerformable(ActionAbstract): + + object_designator: ObjectDesignatorDescription.Object + """ + Object designator describing the object that should be transported. + """ + arm: str + """ + Arm that should be used + """ + target_location: Pose + """ + Target Location to which the object should be transported + """ + + @with_tree + def perform(self) -> None: + robot_desig = BelieveObject(names=[robot_description.name]) + # ParkArmsAction.Action(Arms.BOTH).perform() + ParkArmsActionPerformable(Arms.BOTH).perform() + pickup_loc = CostmapLocation(target=self.object_designator, reachable_for=robot_desig.resolve(), + reachable_arm=self.arm) + # Tries to find a pick-up posotion for the robot that uses the given arm + pickup_pose = None + for pose in pickup_loc: + if self.arm in pose.reachable_arms: + pickup_pose = pose + break + if not pickup_pose: + raise ObjectUnfetchable( + f"Found no pose for the robot to grasp the object: {self.object_designator} with arm: {self.arm}") + + NavigateActionPerformable(pickup_pose.pose).perform() + PickUpActionPerformable(self.object_designator, self.arm, "front").perform() + # ParkArmsAction.Action(Arms.BOTH).perform() + ParkArmsActionPerformable(Arms.BOTH).perform() + try: + place_loc = CostmapLocation(target=self.target_location, reachable_for=robot_desig.resolve(), + reachable_arm=self.arm).resolve() + except StopIteration: + raise ReachabilityFailure( + f"No location found from where the robot can reach the target location: {self.target_location}") + NavigateActionPerformable(place_loc.pose).perform() + PlaceActionPerformable(self.object_designator, self.arm, self.target_location).perform() + ParkArmsActionPerformable(Arms.BOTH).perform() + + def to_sql(self) -> ORMTransportAction: + return ORMTransportAction(self.arm) + + def insert(self, session: Session, *args, **kwargs) -> ORMTransportAction: + action = super().insert(session) + + od = self.object_designator.insert(session) + action.object_id = od.id + + pose = self.target_location.insert(session) + action.pose_id = pose.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class LookAtActionPerformable(ActionAbstract): + + target: Pose + """ + Position at which the robot should look, given as 6D pose + """ + + @with_tree + def perform(self) -> None: + LookingMotion(target=self.target).resolve().perform() + + def to_sql(self) -> ORMLookAtAction: + return ORMLookAtAction() + + def insert(self, session: Session, *args, **kwargs) -> ORMLookAtAction: + action = super().insert(session) + + pose = self.target.insert(session) + action.pose_id = pose.id + + session.add(action) + session.commit() + return action + + +@dataclass +class DetectActionPerformable(ActionAbstract): + + object_designator: ObjectDesignatorDescription.Object + """ + Object designator loosely describing the object, e.g. only type. + """ + + @with_tree + def perform(self) -> None: + return DetectingMotion(object_type=self.object_designator.type).resolve().perform() + + def to_sql(self) -> ORMDetectAction: + return ORMDetectAction() + + def insert(self, session: Session, *args, **kwargs) -> ORMDetectAction: + action = super().insert(session) + + od = self.object_designator.insert(session) + action.object_id = od.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class OpenActionPerformable(ActionAbstract): + + object_designator: ObjectPart.Object + """ + Object designator describing the object that should be opened + """ + arm: str + """ + Arm that should be used for opening the container + """ + + @with_tree + def perform(self) -> None: + GraspingActionPerformable(self.arm, self.object_designator).perform() + OpeningMotion(self.object_designator, self.arm).resolve().perform() + + MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() + + def to_sql(self) -> ORMOpenAction: + return ORMOpenAction(self.arm) + + def insert(self, session: Session, *args, **kwargs) -> ORMOpenAction: + action = super().insert(session) + + op = self.object_designator.insert(session) + action.object_id = op.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class CloseActionPerformable(ActionAbstract): + + object_designator: ObjectPart.Object + """ + Object designator describing the object that should be closed + """ + arm: str + """ + Arm that should be used for closing + """ + + @with_tree + def perform(self) -> None: + GraspingActionPerformable(self.arm, self.object_designator).perform() + ClosingMotion(self.object_designator, self.arm).resolve().perform() + + MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() + + def to_sql(self) -> ORMCloseAction: + return ORMCloseAction(self.arm) + + def insert(self, session: Session, *args, **kwargs) -> ORMCloseAction: + action = super().insert(session) + + op = self.object_designator.insert(session) + action.object_id = op.id + + session.add(action) + session.commit() + + return action + + +@dataclass +class GraspingActionPerformable(ActionAbstract): + + arm: str + """ + The arm that should be used to grasp + """ + object_desig: Union[ObjectDesignatorDescription.Object, ObjectPart.Object] + """ + Object Designator for the object that should be grasped + """ + + @with_tree + def perform(self) -> None: + if isinstance(self.object_desig, ObjectPart.Object): + object_pose = self.object_desig.part_pose + else: + object_pose = self.object_desig.bullet_world_object.get_pose() + lt = LocalTransformer() + gripper_name = robot_description.get_tool_frame(self.arm) + + object_pose_in_gripper = lt.transform_pose(object_pose, + BulletWorld.robot.get_link_tf_frame(gripper_name)) + + pre_grasp = object_pose_in_gripper.copy() + pre_grasp.pose.position.x -= 0.1 + + MoveTCPMotion(pre_grasp, self.arm).resolve().perform() + MoveGripperMotion("open", self.arm).resolve().perform() + + MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).resolve().perform() + MoveGripperMotion("close", self.arm, allow_gripper_collision=True).resolve().perform() + + def to_sql(self) -> ORMGraspingAction: + return ORMGraspingAction(self.arm) + + def insert(self, session: Session, *args, **kwargs) -> ORMGraspingAction: + action = super().insert(session) + + od = self.object_desig.insert(session) + action.object_id = od.id + + session.add(action) + session.commit() + + return action diff --git a/src/pycram/task.py b/src/pycram/task.py index f17e2b7e1..1c404577f 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -56,9 +56,13 @@ def execute(self) -> Any: # self.kwargs.items()])) def __str__(self) -> str: - return "%s(%s)" % ( - self.function.__name__, ", ".join(["%s, " % (str(value.__class__).split(".")[-2]) for value in - self.kwargs.values()])) + if "self" in self.kwargs: + class_name = self.kwargs["self"].__class__.__name__ + else: + class_name = "" + function_name = self.function.__name__ + + return f"{function_name}({class_name})" def __eq__(self, other): return isinstance(other, Code) and other.function.__name__ == self.function.__name__ \ diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 49c58c436..8711b3f8b 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -1,6 +1,8 @@ import time import unittest from pycram.designators import action_designator, object_designator +from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ + NavigateActionPerformable from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot from pycram.pose import Pose @@ -61,8 +63,8 @@ def test_pick_up(self): description = action_designator.PickUpAction(object_description, ["left"], ["front"]) self.assertEqual(description.ground().object_designator.name, "milk") with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() description.resolve().perform() self.assertTrue(object_description.resolve().bullet_world_object in self.robot.attachments.keys()) @@ -71,9 +73,9 @@ def test_place(self): description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) self.assertEqual(description.ground().object_designator.name, "milk") with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() description.resolve().perform() self.assertFalse(object_description.resolve().bullet_world_object in self.robot.attachments.keys()) diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index a9103bd0a..4c7d10822 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -6,6 +6,8 @@ from pycram import task from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator, object_designator +from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ + NavigateActionPerformable from pycram.orm.base import Base from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot @@ -68,9 +70,9 @@ def plan(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() description.resolve().perform() def test_costmap_no_obstacles(self): @@ -85,7 +87,7 @@ def test_costmap_no_obstacles(self): with simulated_robot: # action_designator.NavigateAction.Action(sample.pose).perform() action_designator.MoveTorsoAction.Action(sample.torso_height).perform() - action_designator.PickUpAction.Action( + PickUpActionPerformable( object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() @@ -98,10 +100,10 @@ def test_costmap_with_obstacles(self): for i in range(20): sample = next(iter(cml)) with simulated_robot: - action_designator.NavigateAction.Action(sample.pose).perform() - action_designator.MoveTorsoAction.Action(sample.torso_height).perform() + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() try: - action_designator.PickUpAction.Action( + PickUpActionPerformable( object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure: diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 98884a0d7..9979d4a62 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -7,6 +7,8 @@ import pycram.plan_failures from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator, object_designator +from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ + NavigateActionPerformable from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description @@ -63,9 +65,9 @@ def test_costmap_no_obstacles(self): sample = next(iter(cml)) with simulated_robot: - action_designator.NavigateAction.Action(sample.pose).perform() - action_designator.MoveTorsoAction.Action(sample.torso_height).perform() - action_designator.PickUpAction.Action( + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() + PickUpActionPerformable( object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() @@ -77,10 +79,10 @@ def test_costmap_with_obstacles(self): for i in range(20): sample = next(iter(cml)) with simulated_robot: - action_designator.NavigateAction.Action(sample.pose).perform() - action_designator.MoveTorsoAction.Action(sample.torso_height).perform() + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() try: - action_designator.PickUpAction.Action( + PickUpActionPerformable( object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure: diff --git a/test/test_task_tree.py b/test/test_task_tree.py index abe3f3ab8..f343d7b9a 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -1,3 +1,5 @@ +from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ + NavigateActionPerformable from pycram.pose import Pose from pycram.process_module import simulated_robot import pycram.task @@ -17,9 +19,9 @@ def plan(self): description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) self.assertEqual(description.ground().object_designator.name, "milk") with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() description.resolve().perform() def setUp(self): From 8d11a5d693a6f44524e27a88acdb646bc586cc6c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 5 Jan 2024 13:09:42 +0100 Subject: [PATCH 029/195] [orm] fixed orm querying --- examples/intro.ipynb | 8521 ++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 8167 insertions(+), 354 deletions(-) diff --git a/examples/intro.ipynb b/examples/intro.ipynb index aea7c14fb..74a7d5342 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -12,11 +12,25 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2023-04-05T16:37:51.973404Z", - "start_time": "2023-04-05T16:37:51.483749Z" + "end_time": "2024-01-05T11:38:17.693331699Z", + "start_time": "2024-01-05T11:38:17.084580161Z" } }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "pybullet build time: May 20 2022 19:44:17\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1704454697.683303]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "[WARN] [1704454697.688683]: Failed to import Giskard messages\n" + ] + } + ], "source": [ "import pycram" ] @@ -39,8 +53,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2023-04-05T16:37:59.788099Z", - "start_time": "2023-04-05T16:37:57.586879Z" + "end_time": "2024-01-05T11:38:18.005042043Z", + "start_time": "2024-01-05T11:38:17.754902302Z" } }, "outputs": [ @@ -48,8 +62,6 @@ "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" ] @@ -63,27 +75,6 @@ "world = BulletWorld()" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The world can also be closed with the 'exit' method" - ] - }, - { - "cell_type": "code", - "execution_count": 37, - "metadata": { - "ExecuteTime": { - "end_time": "2023-04-05T16:38:04.800655Z", - "start_time": "2023-04-05T16:38:03.943911Z" - } - }, - "outputs": [], - "source": [ - "world.exit()" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -98,86 +89,29 @@ }, { "cell_type": "code", - "execution_count": 4, - "metadata": {}, + "execution_count": 3, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:18.052419130Z", + "start_time": "2024-01-05T11:38:18.021916002Z" + } + }, "outputs": [ { "data": { - "text/plain": [ - "[array([[[255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " ...,\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255]],\n", - " \n", - " [[255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " ...,\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255]],\n", - " \n", - " [[255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " ...,\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255],\n", - " [255, 255, 255, 255]],\n", - " \n", - " ...,\n", - " \n", - " [[239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " ...,\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255]],\n", - " \n", - " [[239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " ...,\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255]],\n", - " \n", - " [[239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " ...,\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255],\n", - " [239, 239, 239, 255]]], dtype=uint8),\n", - " array([[0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", - " 0.99999994],\n", - " [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", - " 0.99999994],\n", - " [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n", - " 0.99999994],\n", - " ...,\n", - " [0.80473447, 0.80473447, 0.80473447, ..., 0.80473447, 0.80473447,\n", - " 0.80473447],\n", - " [0.8031688 , 0.8031688 , 0.8031688 , ..., 0.8031688 , 0.8031688 ,\n", - " 0.8031688 ],\n", - " [0.80160314, 0.80160314, 0.80160314, ..., 0.80160314, 0.80160314,\n", - " 0.80160314]], dtype=float32),\n", - " array([[-1, -1, -1, ..., -1, -1, -1],\n", - " [-1, -1, -1, ..., -1, -1, -1],\n", - " [-1, -1, -1, ..., -1, -1, -1],\n", - " ...,\n", - " [ 1, 1, 1, ..., 1, 1, 1],\n", - " [ 1, 1, 1, ..., 1, 1, 1],\n", - " [ 1, 1, 1, ..., 1, 1, 1]], dtype=int32)]" - ] + "text/plain": "[array([[[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n ...,\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]]], dtype=uint8),\n array([[0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n ...,\n [0.80473447, 0.80473447, 0.80473447, ..., 0.80473447, 0.80473447,\n 0.80473447],\n [0.8031688 , 0.8031688 , 0.8031688 , ..., 0.8031688 , 0.8031688 ,\n 0.8031688 ],\n [0.80160314, 0.80160314, 0.80160314, ..., 0.80160314, 0.80160314,\n 0.80160314]], dtype=float32),\n array([[-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n ...,\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1]], dtype=int32)]" }, - "execution_count": 4, + "execution_count": 3, "metadata": {}, "output_type": "execute_result" + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" + ] } ], "source": [ @@ -212,8 +146,13 @@ }, { "cell_type": "code", - "execution_count": 5, - "metadata": {}, + "execution_count": 4, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:18.094930935Z", + "start_time": "2024-01-05T11:38:18.028522514Z" + } + }, "outputs": [], "source": [ "milk = Object(\"Milk\", ObjectType.MILK, \"milk.stl\")" @@ -230,8 +169,13 @@ }, { "cell_type": "code", - "execution_count": 6, - "metadata": {}, + "execution_count": 5, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:18.097339564Z", + "start_time": "2024-01-05T11:38:18.096109982Z" + } + }, "outputs": [], "source": [ "milk.set_position(Pose([1, 0, 0]))" @@ -246,8 +190,13 @@ }, { "cell_type": "code", - "execution_count": 7, - "metadata": {}, + "execution_count": 6, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:18.142227637Z", + "start_time": "2024-01-05T11:38:18.099015288Z" + } + }, "outputs": [], "source": [ "milk.remove()" @@ -262,8 +211,13 @@ }, { "cell_type": "code", - "execution_count": 8, - "metadata": {}, + "execution_count": 7, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:21.716481380Z", + "start_time": "2024-01-05T11:38:18.142151725Z" + } + }, "outputs": [ { "name": "stderr", @@ -304,8 +258,13 @@ }, { "cell_type": "code", - "execution_count": 9, - "metadata": {}, + "execution_count": 8, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:22.274205765Z", + "start_time": "2024-01-05T11:38:21.717433092Z" + } + }, "outputs": [], "source": [ "import pycram.costmaps as cm\n", @@ -314,8 +273,13 @@ }, { "cell_type": "code", - "execution_count": 10, - "metadata": {}, + "execution_count": 9, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:30.651191441Z", + "start_time": "2024-01-05T11:38:30.646880498Z" + } + }, "outputs": [], "source": [ "v.visualize()" @@ -323,8 +287,13 @@ }, { "cell_type": "code", - "execution_count": 11, - "metadata": {}, + "execution_count": 10, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:33.983967866Z", + "start_time": "2024-01-05T11:38:30.649221674Z" + } + }, "outputs": [], "source": [ "v.close_visualization()" @@ -340,8 +309,13 @@ }, { "cell_type": "code", - "execution_count": 12, - "metadata": {}, + "execution_count": 11, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:34.747939331Z", + "start_time": "2024-01-05T11:38:33.985076157Z" + } + }, "outputs": [], "source": [ "o = cm.OccupancyCostmap(0.2, from_ros=False, size=300, resolution=0.02, origin=Pose([0, 0, 0.1], [0, 0, 0, 1]))" @@ -349,8 +323,13 @@ }, { "cell_type": "code", - "execution_count": 13, - "metadata": {}, + "execution_count": 12, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:34.845540496Z", + "start_time": "2024-01-05T11:38:34.749095455Z" + } + }, "outputs": [], "source": [ "s = cm.SemanticCostmap(kitchen, \"kitchen_island_surface\", size=100, resolution=0.02)\n", @@ -368,8 +347,13 @@ }, { "cell_type": "code", - "execution_count": 14, - "metadata": {}, + "execution_count": 13, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:35.719367991Z", + "start_time": "2024-01-05T11:38:34.846943933Z" + } + }, "outputs": [], "source": [ "o.visualize()" @@ -377,8 +361,13 @@ }, { "cell_type": "code", - "execution_count": 15, - "metadata": {}, + "execution_count": 14, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:36.074271101Z", + "start_time": "2024-01-05T11:38:36.067925005Z" + } + }, "outputs": [], "source": [ "o.close_visualization()" @@ -393,8 +382,13 @@ }, { "cell_type": "code", - "execution_count": 16, - "metadata": {}, + "execution_count": 15, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:36.075213164Z", + "start_time": "2024-01-05T11:38:36.070266632Z" + } + }, "outputs": [], "source": [ "ov = o + v" @@ -402,8 +396,13 @@ }, { "cell_type": "code", - "execution_count": 17, - "metadata": {}, + "execution_count": 16, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:38.237916925Z", + "start_time": "2024-01-05T11:38:36.073992561Z" + } + }, "outputs": [], "source": [ "ov.visualize()" @@ -411,8 +410,13 @@ }, { "cell_type": "code", - "execution_count": 18, - "metadata": {}, + "execution_count": 17, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:39.305574111Z", + "start_time": "2024-01-05T11:38:38.238541874Z" + } + }, "outputs": [], "source": [ "ov.close_visualization()" @@ -437,8 +441,13 @@ }, { "cell_type": "code", - "execution_count": 19, - "metadata": {}, + "execution_count": 18, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:41.970422232Z", + "start_time": "2024-01-05T11:38:39.305851886Z" + } + }, "outputs": [ { "name": "stderr", @@ -466,9 +475,13 @@ }, { "cell_type": "code", - "execution_count": 20, + "execution_count": 19, "metadata": { - "scrolled": true + "scrolled": true, + "ExecuteTime": { + "end_time": "2024-01-05T11:38:42.271284276Z", + "start_time": "2024-01-05T11:38:41.989603716Z" + } }, "outputs": [ { @@ -497,8 +510,13 @@ }, { "cell_type": "code", - "execution_count": 21, - "metadata": {}, + "execution_count": 20, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:42.355865055Z", + "start_time": "2024-01-05T11:38:42.270253375Z" + } + }, "outputs": [ { "name": "stdout", @@ -518,8 +536,13 @@ }, { "cell_type": "code", - "execution_count": 22, - "metadata": {}, + "execution_count": 21, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:42.450970248Z", + "start_time": "2024-01-05T11:38:42.358883797Z" + } + }, "outputs": [ { "name": "stdout", @@ -560,8 +583,13 @@ }, { "cell_type": "code", - "execution_count": 23, - "metadata": {}, + "execution_count": 22, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:42.957994018Z", + "start_time": "2024-01-05T11:38:42.494000112Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import *\n", @@ -576,9 +604,13 @@ }, { "cell_type": "code", - "execution_count": 24, + "execution_count": 23, "metadata": { - "scrolled": true + "scrolled": true, + "ExecuteTime": { + "end_time": "2024-01-05T11:38:43.465280115Z", + "start_time": "2024-01-05T11:38:42.966741953Z" + } }, "outputs": [], "source": [ @@ -618,176 +650,19 @@ }, { "cell_type": "code", - "execution_count": 25, - "metadata": {}, + "execution_count": 24, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:43.472245439Z", + "start_time": "2024-01-05T11:38:43.467689247Z" + } + }, "outputs": [ { "data": { - "text/plain": [ - "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \n", - "local_transformer=, \n", - "name=Milk, \n", - "type=ObjectType.MILK, \n", - "color=[1, 1, 1, 1], \n", - "id=4, \n", - "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", - "joints: ..., \n", - "links: ..., \n", - "attachments: ..., \n", - "cids: ..., \n", - "original_pose=header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448180\n", - " nsecs: 830921888\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 1.0\n", - " y: 0.0\n", - " z: 1.0\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0, \n", - "tf_frame=Milk_4, \n", - "urdf_object: ..., \n", - "_current_pose=header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448184\n", - " nsecs: 735546827\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0, \n", - "_current_link_poses={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448184\n", - " nsecs: 735546827\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_link_transforms={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448185\n", - " nsecs: 354960680\n", - " frame_id: \"map\"\n", - "child_frame_id: \"Milk_4\"\n", - "transform: \n", - " translation: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " rotation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_joint_states={}, \n", - "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", - "link_to_geometry={'milk_main': }), _pose=, \n", - "local_transformer=, \n", - "name=Milk, \n", - "type=ObjectType.MILK, \n", - "color=[1, 1, 1, 1], \n", - "id=4, \n", - "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", - "joints: ..., \n", - "links: ..., \n", - "attachments: ..., \n", - "cids: ..., \n", - "original_pose=header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448180\n", - " nsecs: 830921888\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 1.0\n", - " y: 0.0\n", - " z: 1.0\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0, \n", - "tf_frame=Milk_4, \n", - "urdf_object: ..., \n", - "_current_pose=header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448184\n", - " nsecs: 735546827\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0, \n", - "_current_link_poses={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448184\n", - " nsecs: 735546827\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_link_transforms={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448185\n", - " nsecs: 354960680\n", - " frame_id: \"map\"\n", - "child_frame_id: \"Milk_4\"\n", - "transform: \n", - " translation: \n", - " x: 0.6\n", - " y: -0.5\n", - " z: 0.7\n", - " rotation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_joint_states={}, \n", - "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", - "link_to_geometry={'milk_main': })>)" - ] + "text/plain": "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1704454719\n nsecs: 314873933\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1704454722\n nsecs: 356852293\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...), _pose=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1704454719\n nsecs: 314873933\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1704454722\n nsecs: 356852293\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...)>)" }, - "execution_count": 25, + "execution_count": 24, "metadata": {}, "output_type": "execute_result" } @@ -809,11 +684,7878 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 25, "metadata": { - "scrolled": false + "scrolled": false, + "ExecuteTime": { + "end_time": "2024-01-05T11:38:50.957195391Z", + "start_time": "2024-01-05T11:38:43.471315489Z" + } }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Resolved: CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 189191341\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -1.26\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.443467406158451\n", + " w: 0.8962904996010476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 901956796\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -1.26\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.443467406158451\n", + " w: 0.8962904996010476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 911677598\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.08868143268496492\n", + " w: -0.9960600401064899, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 921111106\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.1341778331057823\n", + " w: -0.9909572690600926, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 930423736\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.1018321670517163\n", + " w: -0.9948015931599383, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 939850091\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.1181477706660459\n", + " w: -0.9929960243055576, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 949112415\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7414525335518785\n", + " w: -0.6710053207609464, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 958681583\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7421299374143975\n", + " w: -0.6702560376403205, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 968044519\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.07625058147116927\n", + " w: -0.997088686539622, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 977337121\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.0637115975084186\n", + " w: -0.9979683523754275, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454724\n", + " nsecs: 986764192\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.08526395561915938\n", + " w: -0.9963583983046332, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 5548715\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.025615781497071395\n", + " w: -0.9996718620318842, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 24160146\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.44000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7435677691352427\n", + " w: -0.6686605810897175, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 33551692\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.42000000000000004\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7443316400531483\n", + " w: -0.6678101598626592, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 43041944\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7451280178851306\n", + " w: -0.6669214623646299, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 52456855\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.0684794522339555\n", + " w: -0.9976525269961167, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 61823606\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.44\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.051517987991811\n", + " w: -0.9986720667532839, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 71311473\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.03442144373073932\n", + " w: -0.9994074065222308, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 80672740\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.051081118766858044\n", + " w: -0.9986945074974259, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 90170145\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 118748664\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 128309965\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.012817353286048666\n", + " w: 0.9999178543534167, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 137932062\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.54\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.025615781497071274\n", + " w: 0.9996718620318842, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 147601604\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.56\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.03837651950358723\n", + " w: 0.9992633500488202, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 157281398\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.58\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.051081118766857926\n", + " w: 0.9986945074974259, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 166773319\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.6\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.06371159750841848\n", + " w: 0.9979683523754275, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 176612615\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.18000000000000005\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.07625058147116914\n", + " w: 0.997088686539622, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 186205387\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6400579972438699\n", + " w: -0.7683265973296552, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 196010589\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.45999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6386358371363977\n", + " w: -0.7695091081495349, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 205993652\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.44000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.637152936590636\n", + " w: -0.7707373971684058, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 215711593\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.42000000000000004\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6356053782081866\n", + " w: -0.7720141211097294, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 225684404\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6339889056055383\n", + " w: -0.7733421413379021, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 235526561\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6322988865446836\n", + " w: -0.7747245433535415, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 255168437\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.21999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6154122094026357\n", + " w: -0.7882054380161091, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 264625310\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.20000000000000007\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6127638044913316\n", + " w: -0.7902661070204827, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 274528026\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.017233697316775633\n", + " w: -0.9998514888106103, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 293281793\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.01723369731677551\n", + " w: 0.9998514888106103, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 302706003\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3745654411331824\n", + " w: 0.9272004801059501, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 321676969\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.21999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7541778209662121\n", + " w: -0.6566702478129005, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 331218719\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.20000000000000007\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7554539549957066\n", + " w: -0.6552017413601289, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 341029405\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.18000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7568004989740795\n", + " w: -0.6536459322542933, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 350405693\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.16000000000000003\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7582233771877503\n", + " w: -0.6519948698310459, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 360239028\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.14\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7597291886829179\n", + " w: -0.6502396172667391, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 369774341\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.12\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7613253045921371\n", + " w: -0.6483700953835624, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 379291534\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.09999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7630199824727258\n", + " w: -0.6463748961301956, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 408546209\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.040000000000000036\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7687942703292956\n", + " w: -0.6394961844365031, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 418382167\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7785979849482799\n", + " w: -0.6275230496439776, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 428440093\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.54\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.034421443730739416\n", + " w: 0.9994074065222308, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 448060989\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.58\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.06847945223395538\n", + " w: 0.9976525269961167, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 458268404\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.6\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.08526395561915948\n", + " w: 0.9963583983046332, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 468119144\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.10183216705171617\n", + " w: 0.9948015931599383, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 477586746\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.118147770666046\n", + " w: 0.9929960243055576, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 487447023\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.13417783310578218\n", + " w: 0.9909572690600926, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 496778726\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.6799999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1498930671991917\n", + " w: 0.9887022142210559, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 515697717\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.18028099412059023\n", + " w: 0.98361514992343, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 535202741\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.76\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.20915386140954798\n", + " w: 0.9778827446363269, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 562966585\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.8400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2620133869693895\n", + " w: 0.9650642388197943, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 603397607\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.30826764220152825\n", + " w: 0.9512996692796181, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 613683938\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.318832815984807\n", + " w: 0.947810970315916, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 623685836\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.32901544105897695\n", + " w: 0.9443245414288284, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 635320425\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3388256770636711\n", + " w: 0.9408491699323249, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 645336151\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.34827434473373386\n", + " w: 0.9373926502807073, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 665030956\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.36613250713959444\n", + " w: 0.9305627261048418, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 684486150\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: 0.09999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8022929282893952\n", + " w: -0.5969305296404493, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 694182634\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.636848728643575\n", + " w: 0.7709887786635173, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 703764915\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6394961844365034\n", + " w: 0.7687942703292954, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 722873687\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6275230496439778\n", + " w: 0.7785979849482799, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 732309579\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6238505014869475\n", + " w: 0.7815436979430415, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 742166519\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6198304093435398\n", + " w: 0.7847357922594203, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 752015113\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6419537995511603\n", + " w: 0.7667433203111904, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 762117147\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.26\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4586899104028806\n", + " w: 0.8885964022516619, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 772179365\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4068385849311433\n", + " w: 0.9135000633887361, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 781810283\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.08\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.39911243533693425\n", + " w: 0.9169019925594128, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 792211532\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.39106548646982875\n", + " w: 0.9203628552327153, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 802207708\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3826834323650898\n", + " w: 0.9238795325112867, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 811917543\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3739517258340434\n", + " w: 0.9274481693042154, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 822474241\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: 0.07999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5435734062236173\n", + " w: -0.8393616336517022, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 832451105\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.36485567419311876\n", + " w: 0.9310640885616225, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 842451095\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7398679249122764\n", + " w: 0.6727521487784355, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 864063024\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6908662457673519\n", + " w: -0.7229825934691131, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 874287605\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7370989134318549\n", + " w: 0.6757848709593749, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 884132862\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5039557239143624\n", + " w: -0.8637294879381802, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 893823862\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.49561612558176465\n", + " w: -0.8685416835496846, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 913730621\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6928318560989847\n", + " w: -0.7210991742988171, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 923520088\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6933854908702646\n", + " w: -0.7205668331602574, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 932972908\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3553805575128866\n", + " w: 0.9347217015464174, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 942650079\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.10682611122099109\n", + " w: -0.9942777187292293, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 952360153\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4866443184625216\n", + " w: 0.8736001987798239, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 962044715\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.0859890841337593\n", + " w: -0.9962960791902362, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454725\n", + " nsecs: 972100019\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5039557239143623\n", + " w: 0.8637294879381803, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 10155916\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6908662457673519\n", + " w: 0.7229825934691132, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 19874572\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6915789093529722\n", + " w: 0.7223009152272711, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 39346933\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.44\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.06480582077938048\n", + " w: -0.9978978933704143, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 48823833\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.043355575214250826\n", + " w: -0.9990597049715505, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 58706760\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6938978092954753\n", + " w: 0.7200734894821085, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 68709850\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.58\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6943732675901296\n", + " w: 0.7196150118335541, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 87986469\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 97659826\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.02172373868536963\n", + " w: 0.9997640117435364, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 107616424\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.33999999999999997\n", + " y: -1.12\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5537478323882296\n", + " w: 0.8326844168863359, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 117786407\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7967527613758144\n", + " w: -0.6043054171857262, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 127777814\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8000000000000002\n", + " w: -0.5999999999999999, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 138854026\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.54\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.04335557521425048\n", + " w: 0.9990597049715505, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 149201869\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.56\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.06480582077938013\n", + " w: 0.9978978933704143, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 159495592\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8112421851755609\n", + " w: 0.584710284663765, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 169792652\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8072185755038553\n", + " w: 0.5902526335066423, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 179657697\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8034804340438839\n", + " w: 0.5953311617147653, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 189663410\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.58\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.08598908413375941\n", + " w: 0.9962960791902362, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 199556350\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.6\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.10682611122099096\n", + " w: 0.9942777187292293, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 209797859\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6043054171857263\n", + " w: -0.7967527613758143, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 219633102\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6\n", + " w: -0.8, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 229408979\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7384225572267273\n", + " w: -0.6743382882342812, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 239880800\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7937170381968226\n", + " w: 0.6082871552778866, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 250423669\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.74\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.790873617837808\n", + " w: 0.6119795099577574, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 260511398\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7347602405829027\n", + " w: -0.6783269041240771, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 280463457\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.12724528989938316\n", + " w: 0.9918712800552408, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 291324138\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1471837619629651\n", + " w: 0.9891091649633165, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 313117504\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7327590618734483\n", + " w: 0.680488175681506, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 323770761\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.64\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7318630507095947\n", + " w: 0.6814517407755631, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 334040164\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.33523500300737585\n", + " w: 0.9421345406886665, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 344825744\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.74\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.23813352749512762\n", + " w: 0.9712324248513985, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 355269432\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.76\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2543984682342504\n", + " w: 0.9670994878294927, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 365238666\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.78\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2700013373907261\n", + " w: 0.9628599471404028, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 376126766\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.8\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.28494683992052433\n", + " w: 0.9585433210968125, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 387210607\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.13999999999999996\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2992447144182441\n", + " w: 0.9541763992536934, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 408796787\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.9\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.31340294084074444\n", + " w: 0.9496202381333145, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 419713258\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.88\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3018224483858295\n", + " w: 0.9533641537473408, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 439749002\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.8400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.27727888479854484\n", + " w: 0.9607894774844672, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 449327468\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.26429951415565045\n", + " w: 0.9644406497120946, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 470635890\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.8\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2508413082792208\n", + " w: 0.9680282217274292, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 480293035\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6308905395898716\n", + " w: -0.7758718496349771, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 500214099\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6368487286435749\n", + " w: -0.7709887786635174, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 520314931\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.45999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6308905395898716\n", + " w: -0.7758718496349771, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 530125856\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.44000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6292425428779993\n", + " w: -0.7772089952081288, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 540076732\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.8400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.323044113557137\n", + " w: 0.9463839076696536, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 549759149\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.30924417189076625\n", + " w: 0.9509826718461247, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 569632768\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.78\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.27958765375807687\n", + " w: 0.9601201715754407, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 589303016\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6257273935913882\n", + " w: -0.7800418122827314, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 599044799\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6238505014869477\n", + " w: -0.7815436979430415, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 609395503\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.7\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2116996959579716\n", + " w: 0.9773347628787704, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 619220018\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.6799999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.19294175778498965\n", + " w: 0.9812102109654376, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 629041433\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.17350299206578976\n", + " w: 0.9848333421164307, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 639055252\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.15341808887275654\n", + " w: 0.988161368404286, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 648601055\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.78\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.23690237287865074\n", + " w: 0.9715334609391818, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 668470382\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.58\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.08980559531591699\n", + " w: 0.9959593139531121, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 678457498\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.56\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.06771200763417459\n", + " w: 0.9977049082880918, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 688319921\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.54\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.0453144211719414\n", + " w: 0.9989727740203193, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 697925806\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.022709687246860417\n", + " w: 0.9997421017968333, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 708099126\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 717890977\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.022709687246860538\n", + " w: -0.9997421017968333, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 727897167\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.045314421171941524\n", + " w: -0.9989727740203193, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 737935304\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.44\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.06771200763417472\n", + " w: -0.9977049082880918, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 747606992\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.08980559531591711\n", + " w: -0.9959593139531121, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 761164903\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.11150592856108661\n", + " w: -0.9937637686571844, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 772180557\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.1327331510254085\n", + " w: -0.9911518100769762, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 786565303\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.15341808887275665\n", + " w: -0.9881613684042859, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 800817966\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.17350299206579006\n", + " w: -0.9848333421164306, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 811119318\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.76\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.22248407835269934\n", + " w: 0.9749363234999248, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 821317911\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.74\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.20759148751784465\n", + " w: 0.978215607271796, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 831474781\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.19223376424350164\n", + " w: 0.9813491630835448, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 851423263\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.6799999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1601822430069672\n", + " w: 0.9870874576374967, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 861536979\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.24\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6079025311911547\n", + " w: -0.7940116577049655, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 871807813\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.21999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6051264893449574\n", + " w: -0.7961293436955124, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 891721963\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.18000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5990966850218961\n", + " w: -0.8006766900539662, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 901814699\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.16000000000000003\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.595815661390807\n", + " w: -0.8031212222581565, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 915273189\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.14\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5923364782216495\n", + " w: -0.805690695346529, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 926554679\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.12\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5886413254594184\n", + " w: -0.8083943282590367, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 940182209\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.09999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5847102846637651\n", + " w: -0.8112421851755608, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 965167760\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.06000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5760484367663208\n", + " w: -0.8174155604703632, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 975308895\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.040000000000000036\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5712642314097769\n", + " w: -0.8207662139195283, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454726\n", + " nsecs: 985270500\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5661364326251805\n", + " w: -0.8243115549684078, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 14838933\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5483036971357891\n", + " w: -0.8362792928843958, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 24997949\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.541385747733913\n", + " w: -0.840774328907937, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 34455060\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.14353028825236291\n", + " w: 0.9896459247398505, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 44534921\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.12649723679630143\n", + " w: 0.9919669596730026, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 54246187\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.10911677189150902\n", + " w: 0.9940289382568178, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 83569049\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.31999999999999995\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.4812091581666131\n", + " w: -0.8766058099833582, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 93582630\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.56\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.05530038574178813\n", + " w: 0.9984697628555457, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 112976551\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.01850900096213863\n", + " w: 0.9998286937687794, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 123248338\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 132923603\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.36\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.532573437384568\n", + " w: 0.8463837981627399, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 142979860\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.36\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5257311121191336\n", + " w: 0.85065080835204, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 152651309\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.018509000962138755\n", + " w: -0.9998286937687794, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 163275718\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.036961098084952626\n", + " w: -0.9993167051682638, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 173099279\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.36\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5019268181932334\n", + " w: 0.8649100931185952, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 199396848\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.31999999999999995\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.49806072645607874\n", + " w: 0.8671421525690256, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 220230817\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: -0.020000000000000018\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.16966474960750313\n", + " w: 0.9855018380199112, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 230001449\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.07347291217220556\n", + " w: -0.9972972130598458, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 240165948\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.36\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5104644303570166\n", + " w: -0.8598988692516618, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 249710559\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.36\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5183792016009997\n", + " w: -0.8551508658403557, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 260489702\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.09142755332923423\n", + " w: -0.9958117304451831, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 270841121\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.10911677189150912\n", + " w: -0.9940289382568177, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 280830144\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.12649723679630132\n", + " w: -0.9919669596730026, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 290997505\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.14353028825236303\n", + " w: -0.9896459247398504, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 300702810\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: -0.32\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.16018224300696732\n", + " w: -0.9870874576374967, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 310925006\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.05999999999999994\n", + " y: 0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.47918806782228074\n", + " w: -0.8777122510576854, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 320628404\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.46\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7630199824727257\n", + " w: 0.6463748961301957, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 330796957\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.44\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.764133282892573\n", + " w: 0.6450583895864149, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 350512981\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.3\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7733421413379024\n", + " w: 0.6339889056055382, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 360772371\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.28\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7749013304032105\n", + " w: 0.6320822162815011, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 370627880\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.26\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7765341206443674\n", + " w: 0.6300752014443031, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 380810976\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.24\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7782457171509326\n", + " w: 0.6279598743042668, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 390733242\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.22\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7800418122827314\n", + " w: 0.6257273935913882, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 401291370\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.2000000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7819286417257463\n", + " w: 0.6233679485255313, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 411706209\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.1800000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.783913048024316\n", + " w: 0.6208706251202633, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 421663045\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.1600000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7860025526744504\n", + " w: 0.6182232502820061, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 431575298\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.1400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7882054380161092\n", + " w: 0.6154122094026356, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 442079544\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.12\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7905308403287533\n", + " w: 0.6124222321969667, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 451843976\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7929888557099438\n", + " w: 0.6092361403592484, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 471526861\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7983486481160277\n", + " w: 0.602195513144453, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 481531858\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8012765844860855\n", + " w: 0.5982941042282742, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 510531187\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7882054380161092\n", + " w: -0.6154122094026356, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 520304441\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8043897838851272\n", + " w: 0.5941019067308558, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 529991149\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7947066772690753\n", + " w: -0.6069936549124264, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 539878845\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8077053073689017\n", + " w: 0.5895864113496071, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 549521207\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.584710284663765\n", + " w: 0.8112421851755609, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 559333324\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4310817166804798\n", + " w: 0.9023128911546209, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 568988084\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6794495938313833\n", + " w: -0.7337221881900318, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 588930606\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5800385487693184\n", + " w: 0.8145890264063119, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 598807811\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5750132745107971\n", + " w: 0.818144079081656, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 619289398\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8112421851755609\n", + " w: 0.584710284663765, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 629359006\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5637378164623551\n", + " w: 0.8259537967043049, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 639499425\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5847102846637648\n", + " w: 0.8112421851755609, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 649319171\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5902526335066423\n", + " w: 0.8072185755038553, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 659330844\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.88\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.35948867915153393\n", + " w: 0.9331494465314146, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 669612884\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.86\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3469462477349362\n", + " w: 0.9378850149046248, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 679676771\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.8400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.333732774306416\n", + " w: 0.9426677226646422, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 689470529\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3198189174888669\n", + " w: 0.9474786857846721, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 699056148\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5953311617147652\n", + " w: 0.8034804340438839, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 708853006\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5573899686393252\n", + " w: 0.8302508192469624, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 718634128\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5504910087462066\n", + " w: 0.8348410922382677, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 728414297\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.74\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2566679351570243\n", + " w: 0.9664996487646695, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 749159097\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.7\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2203854364245398\n", + " w: 0.9754128661300122, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 759160280\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.6799999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.20106587226819733\n", + " w: 0.9795777228015289, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 769248008\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1809865534660407\n", + " w: 0.9834855705420817, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 779141187\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1601822430069672\n", + " w: 0.9870874576374967, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 789060115\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.13870121188940068\n", + " w: 0.9903342737785114, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 818681716\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.56\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.07088902009067935\n", + " w: 0.9974842088126424, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 829430341\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.54\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.04745802042883704\n", + " w: 0.9988732333469429, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 839163064\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.023789307215243066\n", + " w: 0.9997169943850204, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 848954200\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.5\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 1.2246467991473532e-16\n", + " w: -1.0, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 859354734\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.02378930721524297\n", + " w: -0.9997169943850204, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 879795551\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.44\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.07088902009067946\n", + " w: -0.9974842088126424, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 899379730\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.11660571451398305\n", + " w: -0.9931782857788845, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 909643888\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.13870121188940082\n", + " w: -0.9903342737785114, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 929649591\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.1809865534660408\n", + " w: -0.9834855705420817, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 939815521\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.18\n", + " y: -0.32\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.20106587226819744\n", + " w: -0.9795777228015289, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 959586143\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6082871552778866\n", + " w: 0.7937170381968226, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 969409227\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.45999999999999996\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6119795099577574\n", + " w: 0.790873617837808, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 979031085\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8150216638044884\n", + " w: 0.5794304855022417, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 988930702\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.12\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.16018224300696732\n", + " w: -0.9870874576374967, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454727\n", + " nsecs: 999084234\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8190674767950149\n", + " w: 0.5736971923032635, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 8918762\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8234061353888457\n", + " w: 0.5674524968700076, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 28315067\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5413857477339129\n", + " w: 0.8407743289079371, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 37947177\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6727521487784355\n", + " w: 0.7398679249122764, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 47890901\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6743382882342814\n", + " w: 0.7384225572267273, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 57522058\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6757848709593749\n", + " w: 0.7370989134318549, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 67149162\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6771094889847062\n", + " w: 0.7358822867326472, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 76910734\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5483036971357889\n", + " w: 0.8362792928843958, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 87213277\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.554700196225229\n", + " w: 0.8320502943378437, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 97060918\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6804881756815059\n", + " w: 0.7327590618734483, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 108145713\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.5599999999999999\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6814517407755631\n", + " w: 0.7318630507095948, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 118573904\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5606288093051838\n", + " w: 0.8280672304692729, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 128924608\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5661364326251803\n", + " w: 0.8243115549684079, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 139441013\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5712642314097768\n", + " w: 0.8207662139195284, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 149400472\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5760484367663208\n", + " w: 0.8174155604703632, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 159833192\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.08\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5805210231682381\n", + " w: 0.8142452589114058, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 169833660\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.584710284663765\n", + " w: 0.8112421851755609, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 179687261\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.12\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5886413254594183\n", + " w: 0.8083943282590367, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 189734935\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.1400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5923364782216495\n", + " w: 0.805690695346529, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 199295997\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.1600000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5958156613908069\n", + " w: 0.8031212222581566, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 209303140\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.1800000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5990966850218961\n", + " w: 0.8006766900539662, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 219341278\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.3\n", + " y: 0.06000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5137015609692951\n", + " w: -0.8579689424785198, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 229027032\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.2000000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.602195513144453\n", + " w: 0.7983486481160277, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 238579750\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.12\n", + " y: -0.7\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.19611613513818393\n", + " w: 0.9805806756909202, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 248189449\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.12\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2132313029385177\n", + " w: 0.9770017458772231, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 258103370\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.12\n", + " y: -0.74\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2297529205473612\n", + " w: 0.9732489894677302, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 268151521\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7983486481160277\n", + " w: 0.602195513144453, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 278077602\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.3\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.4672596576628944\n", + " w: -0.8841201345522873, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 288434267\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7947066772690754\n", + " w: 0.6069936549124263, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 298222303\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7913349155531438\n", + " w: 0.6113829008293401, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 308148384\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7882054380161092\n", + " w: 0.6154122094026356, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 329452991\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7825789118992277\n", + " w: 0.6225514008101024, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 339732646\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7800418122827314\n", + " w: 0.6257273935913882, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 349679470\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.72\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.77766608796156\n", + " w: 0.6286775450376476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 372056722\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.22\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6051264893449573\n", + " w: 0.7961293436955124, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 382091522\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.24\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6079025311911546\n", + " w: 0.7940116577049655, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 412238359\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.3\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.47630463962314995\n", + " w: 0.8792803251941108, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 422187566\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.3\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4847685323929452\n", + " w: 0.8746424812468178, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 431981563\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.28\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6130353373714668\n", + " w: 0.790055488642318, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 441920280\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.42\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6275230496439778\n", + " w: 0.7785979849482799, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 451804637\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.44\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6292425428779992\n", + " w: 0.7772089952081289, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 475440740\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.48\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6324713384826219\n", + " w: 0.7745837630611687, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 485437870\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.3\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5257311121191336\n", + " w: 0.85065080835204, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 495399475\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.5\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6339889056055381\n", + " w: 0.7733421413379024, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 505185365\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7438189039121905\n", + " w: 0.6683812072334675, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 515660047\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7451280178851304\n", + " w: 0.6669214623646302, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 525471210\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.39999999999999997\n", + " y: -1.52\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6354469054448959\n", + " w: 0.7721445657132514, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 536112785\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.819067476795015\n", + " w: -0.5736971923032633, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 570803880\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7533635260394922\n", + " w: 0.6576042865077321, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 580623388\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7554539549957063\n", + " w: 0.655201741360129, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 590690374\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8150216638044883\n", + " w: -0.5794304855022419, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 600275516\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8112421851755609\n", + " w: -0.5847102846637648, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 620325326\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5637378164623552\n", + " w: -0.8259537967043047, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 639937162\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.42\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5750132745107973\n", + " w: -0.8181440790816558, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 649961471\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8043897838851272\n", + " w: -0.5941019067308557, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 669656515\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.06000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7983486481160278\n", + " w: -0.6021955131444529, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 679559946\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.07999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7955906604925091\n", + " w: -0.6058345491444782, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 689200401\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.09999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7929888557099438\n", + " w: -0.6092361403592484, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 699025630\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7071067811865475\n", + " w: 0.7071067811865476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 718453407\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.12\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7905308403287534\n", + " w: -0.6124222321969663, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 728411674\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.14\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7882054380161092\n", + " w: -0.6154122094026356, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 747882127\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7071067811865475\n", + " w: 0.7071067811865476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 767148971\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7071067811865475\n", + " w: 0.7071067811865476, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 777645587\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.16000000000000003\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7860025526744504\n", + " w: -0.618223250282006, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 788507223\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.18000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.783913048024316\n", + " w: -0.6208706251202633, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 798871278\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.20000000000000007\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7819286417257465\n", + " w: -0.623367948525531, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 823041200\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.24\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7782457171509329\n", + " w: -0.6279598743042666, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 833983421\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.26\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7765341206443676\n", + " w: -0.6300752014443028, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 853881120\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7664963583466964\n", + " w: -0.6422486532809958, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 863618850\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.42000000000000004\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7652911781639873\n", + " w: -0.6436842491659838, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 873755455\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6552017413601289\n", + " w: 0.7554539549957063, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 883673667\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6532424277825721\n", + " w: 0.7571488166435519, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 893738508\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.44000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.764133282892573\n", + " w: -0.6450583895864149, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 903726816\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.45999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7630199824727258\n", + " w: -0.6463748961301956, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 914144754\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6463748961301958\n", + " w: 0.7630199824727257, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 924309968\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6436842491659837\n", + " w: 0.7652911781639874, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 934568881\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6407474392457675\n", + " w: 0.767751730118527, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 944923162\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6375295648477821\n", + " w: 0.7704258912737796, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 954938173\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.76\n", + " y: 0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7619487840078729\n", + " w: -0.647637283167765, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 964920282\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.4\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4998611817921905\n", + " w: 0.8661055356810247, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 974496364\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.38\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4956161255817646\n", + " w: 0.8685416835496848, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454728\n", + " nsecs: 994848012\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.3399999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4866443184625216\n", + " w: 0.8736001987798239, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 5209684\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.32\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.48190142905041683\n", + " w: 0.8762254348506247, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 15120983\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: 0.09999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8112421851755609\n", + " w: -0.5847102846637648, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 34841537\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.28\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4718579255320242\n", + " w: 0.8816745987679439, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 54306030\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4153730020007066\n", + " w: 0.9096511799634632, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 63890218\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.08\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4077100588947825\n", + " w: 0.9131114432948549, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 73581933\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7533635260394923\n", + " w: -0.657604286507732, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 83770036\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8320502943378438\n", + " w: -0.5547001962252289, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 114562034\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6599999999999999\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7465333575886381\n", + " w: -0.6653479886551357, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 128451824\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.39971796346469235\n", + " w: 0.9166381781726305, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 140075445\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.39138108854039505\n", + " w: 0.9202286908877246, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 149988651\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3826834323650898\n", + " w: 0.9238795325112867, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 160300254\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3736087091451055\n", + " w: 0.9275864016095363, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 170534372\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3641404642253537\n", + " w: 0.9313440407893014, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 180233716\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.3542622175095866\n", + " w: 0.9351461282843395, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 190173625\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.34395763883862607\n", + " w: 0.9389851663815341, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 199840784\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.33321075897716623\n", + " w: 0.9428523691977768, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 209982872\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.9\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.32200621957921877\n", + " w: 0.9467375531541463, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 220086812\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7205668331602575\n", + " w: -0.6933854908702645, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 230565071\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7210991742988173\n", + " w: -0.6928318560989846, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 262809038\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.15423335048016681\n", + " w: -0.9880344496016634, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 274945259\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.13608082209815303\n", + " w: -0.9906977388977382, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 284489154\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.11750042131729284\n", + " w: -0.993072832671531, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 294175386\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.27999999999999997\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.44382247843994094\n", + " w: 0.8961147290561785, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 303731441\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.27999999999999997\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.453777645066917\n", + " w: 0.8911149470396753, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 313288927\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.27999999999999997\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.46310663556107695\n", + " w: 0.8863025691598214, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 322869777\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.09853761796664212\n", + " w: -0.9951333266680702, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 332524299\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7071067811865476\n", + " w: -0.7071067811865475, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 342247724\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7229825934691132\n", + " w: -0.6908662457673518, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 351795196\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8455570886676865\n", + " w: 0.5338850155265888, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 361424207\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7071067811865476\n", + " w: -0.7071067811865475, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 371025085\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7071067811865476\n", + " w: -0.7071067811865475, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 380615949\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7709887786635176\n", + " w: -0.6368487286435748, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 399971723\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7758718496349772\n", + " w: -0.6308905395898715, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 410209894\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8407743289079371\n", + " w: 0.5413857477339129, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 420065879\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7815436979430416\n", + " w: -0.6238505014869474, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 429817914\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.8400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2855086566344833\n", + " w: 0.9583761302259008, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 439763307\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2723432423390162\n", + " w: 0.9622001654293517, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 449737310\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8280672304692729\n", + " w: 0.5606288093051838, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 459516048\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8243115549684079\n", + " w: 0.5661364326251804, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 469855308\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.8\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2586642746412806\n", + " w: 0.9659672836200511, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 480250120\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.78\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.24446768710590863\n", + " w: 0.9696574394914359, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 489985704\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.76\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2297529205473612\n", + " w: 0.9732489894677302, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 514060497\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.198787259314375\n", + " w: 0.9800426651601856, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 524521827\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.8\n", + " y: -1.1400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.805690695346529\n", + " w: 0.5923364782216496, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 534343481\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.7\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.18255737974256264\n", + " w: 0.9831952009146149, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 553424119\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.14869598393710892\n", + " w: 0.9888829578676007, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 563100337\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.13111872764660712\n", + " w: 0.9913666724579432, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 572806596\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.020000000000000018\n", + " y: -0.8200000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.24942164698879468\n", + " w: 0.968394982439189, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 592219591\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6653479886551358\n", + " w: -0.746533357588638, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 602131605\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6636470369788332\n", + " w: -0.7480458611002506, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 612154722\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.6\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.09485133899780393\n", + " w: 0.9954914482256106, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 621884822\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.58\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.07625058147116914\n", + " w: 0.997088686539622, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 631433486\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6576042865077321\n", + " w: -0.7533635260394922, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 640997409\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.07924445748219482\n", + " w: -0.9968552131369695, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 689654350\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.01922011145500681\n", + " w: -0.9998152765964606, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 699763059\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.46\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.03837651950358736\n", + " w: -0.9992633500488202, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 709666728\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.44\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.057406724906011355\n", + " w: -0.9983508741597643, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 719478130\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.42\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.07625058147116927\n", + " w: -0.997088686539622, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 729162454\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.09485133899780428\n", + " w: -0.9954914482256106, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 739078283\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.11315653826752582\n", + " w: -0.9935771725675414, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 748747825\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.13111872764660726\n", + " w: -0.9913666724579432, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 758508443\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.21999999999999997\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4056394187149922\n", + " w: 0.9140331842906817, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 768118619\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: -0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.14869598393710906\n", + " w: -0.9888829578676007, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 778162002\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.46\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.769509108149535\n", + " w: 0.6386358371363977, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 788316965\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.44\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7707373971684058\n", + " w: 0.6371529365906361, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 798148393\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.42\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7720141211097296\n", + " w: 0.6356053782081865, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 808482408\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7847357922594201\n", + " w: 0.6198304093435398, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 818536281\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7815436979430415\n", + " w: 0.6238505014869475, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 828765153\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7785979849482798\n", + " w: 0.6275230496439778, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 848044395\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: 0.30000000000000004\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.476975706616483\n", + " w: -0.8789164779987384, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 858117818\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7709887786635173\n", + " w: 0.636848728643575, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 867625951\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7687942703292954\n", + " w: 0.6394961844365034, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 877413272\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.7\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7667433203111904\n", + " w: 0.6419537995511603, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 887440681\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: 0.32000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.48190142905041666\n", + " w: -0.8762254348506247, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 897084951\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.28\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7825789118992277\n", + " w: 0.6225514008101024, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 907503843\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.26\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7843680207272645\n", + " w: 0.6202957424167875, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 917495489\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.24\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.78624155930207\n", + " w: 0.6179192588245245, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 927219152\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5524309953122208\n", + " w: 0.8335586334615874, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 937005519\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5464711272034338\n", + " w: 0.8374779442665988, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 946638345\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5400672594718117\n", + " w: 0.8416218600099494, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 975183248\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5257311121191336\n", + " w: 0.85065080835204, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 984693288\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5176837863645347\n", + " w: 0.8555720293086252, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454729\n", + " nsecs: 994870901\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6488487878132037\n", + " w: -0.7609173743274208, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 4707336\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.52\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6511308684688737\n", + " w: -0.7589654749242356, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 34533977\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6225514008101024\n", + " w: 0.7825789118992277, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 44676065\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.2000000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7902661070204828\n", + " w: 0.6127638044913315, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 54926156\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6552017413601289\n", + " w: 0.7554539549957063, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 64422369\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.657604286507732\n", + " w: 0.7533635260394923, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 74395179\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6597957320005307\n", + " w: 0.7514450026674501, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 83957433\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6618025632357402\n", + " w: 0.7496781758158658, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 93839406\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.11750042131729249\n", + " w: 0.9930728326715311, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 103564739\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.64\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1360808220981529\n", + " w: 0.9906977388977382, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 113248825\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6669214623646302\n", + " w: 0.7451280178851305, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 123576402\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.54\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6683812072334675\n", + " w: 0.7438189039121905, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 133637905\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.66\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.15423335048016673\n", + " w: 0.9880344496016635, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 143495321\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.6799999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.1719194406273956\n", + " w: 0.9851110119851283, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 153331756\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.7\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.18910752115495127\n", + " w: 0.9819563867314218, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 163374900\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.72\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.205772893716877\n", + " w: 0.9785997732532861, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 174808502\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.09999999999999998\n", + " y: -0.74\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.22189743411284238\n", + " w: 0.9750700122217567, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 185347795\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6154122094026356\n", + " w: 0.7882054380161092, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 196193218\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.61138290082934\n", + " w: 0.791334915553144, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 206784486\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6069936549124263\n", + " w: 0.7947066772690754, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 217048168\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7237282464487099\n", + " w: 0.6900850855454531, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 227622985\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7229825934691132\n", + " w: 0.6908662457673519, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 237950801\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7223009152272711\n", + " w: 0.6915789093529722, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 248067378\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7216753233664641\n", + " w: 0.6922317008371615, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 258363723\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.1800000000000002\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7924306153589356\n", + " w: 0.6099620642645399, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 268745660\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.1600000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7947066772690754\n", + " w: 0.6069936549124263, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 278952360\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.43999999999999995\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5982941042282742\n", + " w: 0.8012765844860855, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 289012908\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.25999999999999995\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.4305820312855818\n", + " w: 0.9025514469181146, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 299065113\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.25999999999999995\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.44076779540038685\n", + " w: 0.8976211620376843, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 339966058\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.43999999999999995\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5794304855022417\n", + " w: 0.8150216638044885, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 351265430\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.43999999999999995\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.5736971923032635\n", + " w: 0.8190674767950149, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 383670091\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.62\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7196150118335541\n", + " w: 0.6943732675901296, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 401098966\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.1400000000000001\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7971027464882692\n", + " w: 0.6038436979391754, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 414599180\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.12\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7996280994512247\n", + " w: 0.6004955475005809, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 425669193\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.1\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8022929282893952\n", + " w: 0.5969305296404492, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 436941385\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.08\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8051084445192626\n", + " w: 0.5931276359804638, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 447655439\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8080869942070349\n", + " w: 0.5890631628216448, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 470032453\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.02\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8145890264063119\n", + " w: 0.5800385487693183, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 480431079\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -1.0\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.818144079081656\n", + " w: 0.575013274510797, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 490664720\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8219256175556252\n", + " w: 0.5695948377626013, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 501055717\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6225514008101027\n", + " w: -0.7825789118992276, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 511538267\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6191231894884393\n", + " w: -0.7852938788999072, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 521835565\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6154122094026357\n", + " w: -0.7882054380161091, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 531538486\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -0.96\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8259537967043049\n", + " w: 0.563737816462355, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 540988683\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6069936549124266\n", + " w: -0.7947066772690753, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 559922933\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.8348410922382677\n", + " w: 0.5504910087462066, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 569701671\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5257311121191337\n", + " w: -0.8506508083520399, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 579053401\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.0\n", + " y: -0.78\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.2165835404696473\n", + " w: 0.9762640882454054, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 588583230\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7589654749242356\n", + " w: -0.6511308684688735, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 598399162\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.7609173743274209\n", + " w: -0.6488487878132035, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 608730077\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.03999999999999998\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5331718778667884\n", + " w: -0.8460069436192604, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 618813991\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5400672594718116\n", + " w: -0.8416218600099494, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 628623723\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: -0.06\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.767751730118527\n", + " w: -0.6407474392457674, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 638496398\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: 0.33999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.4866443184625217\n", + " w: -0.8736001987798239, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 648101329\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.07999999999999996\n", + " y: 0.36\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.49121312130825956\n", + " w: -0.8710394190015727, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 657718896\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.48\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6248846524332634\n", + " w: -0.780717087781073, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 667537689\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.45999999999999996\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6231467899582747\n", + " w: -0.7821049022763493, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 677129745\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.44000000000000006\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6213354700248949\n", + " w: -0.7835446596646187, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 686960220\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.42000000000000004\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6194460375118611\n", + " w: -0.7850392388988298, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 696655988\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.4\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6174734445800121\n", + " w: -0.7865917271612352, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 706870079\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.38\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.6154122094026357\n", + " w: -0.7882054380161091, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 716971874\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.48\n", + " y: -0.9199999999999999\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6021955131444529\n", + " w: 0.7983486481160278, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 746616125\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.24\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5979254685648697\n", + " w: -0.8015517039102849, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 756603956\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.21999999999999997\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5948871592163426\n", + " w: -0.8038092235098512, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 766701936\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.20000000000000007\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5916812500238643\n", + " w: -0.8061720029684716, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 776644468\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.18000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5882940228258898\n", + " w: -0.8086471064112771, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 786627054\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.38\n", + " y: 0.16000000000000003\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5847102846637651\n", + " w: -0.8112421851755608, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 806035041\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: -1.06\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7554539549957063\n", + " w: 0.655201741360129, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 815665483\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: -1.04\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7571488166435519\n", + " w: 0.6532424277825721, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 845581769\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: -0.98\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7630199824727256\n", + " w: 0.6463748961301958, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 865120410\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.6799999999999999\n", + " y: -0.94\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.7677517301185269\n", + " w: 0.6407474392457675, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 884716749\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.43999999999999995\n", + " y: -0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5847102846637651\n", + " w: -0.8112421851755608, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 894847631\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.43999999999999995\n", + " y: 0.0\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.5895864113496071\n", + " w: -0.8077053073689017, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 914685487\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: 0.020000000000000018\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.814589026406312\n", + " w: -0.5800385487693182, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 924642562\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: 0.040000000000000036\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8112421851755609\n", + " w: -0.5847102846637648, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 934620380\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.78\n", + " y: 0.06000000000000005\n", + " z: 0.0\n", + " orientation: \n", + " x: -0.0\n", + " y: 0.0\n", + " z: 0.8080869942070349\n", + " w: -0.5890631628216447, reachable_arms=None)\n", + "CostmapLocation.Location(pose=header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1704454730\n", + " nsecs: 944352626\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 0.15999999999999998\n", + " y: -0.62\n", + " z: 0.0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.13273315102540856\n", + " w: 0.9911518100769761, reachable_arms=None)\n" + ] + } + ], "source": [ "from pycram.designators.location_designator import *\n", "from pycram.designators.object_designator import *\n", @@ -840,8 +8582,13 @@ }, { "cell_type": "code", - "execution_count": 29, - "metadata": {}, + "execution_count": 26, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:51.471552922Z", + "start_time": "2024-01-05T11:38:50.957762794Z" + } + }, "outputs": [], "source": [ "from pycram.designators.action_designator import *\n", @@ -861,8 +8608,13 @@ }, { "cell_type": "code", - "execution_count": 30, - "metadata": {}, + "execution_count": 27, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:38:51.532465685Z", + "start_time": "2024-01-05T11:38:51.473570735Z" + } + }, "outputs": [], "source": [ "from pycram.designators.object_designator import *\n", @@ -871,8 +8623,13 @@ }, { "cell_type": "code", - "execution_count": 31, - "metadata": {}, + "execution_count": 28, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.490830292Z", + "start_time": "2024-01-05T11:38:51.542100060Z" + } + }, "outputs": [], "source": [ "cereal_desig = ObjectDesignatorDescription(names=[\"cereal\"])\n", @@ -916,23 +8673,40 @@ }, { "cell_type": "code", - "execution_count": 32, - "metadata": {}, + "execution_count": 29, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.494121167Z", + "start_time": "2024-01-05T11:39:03.491538560Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "no_operation()\n", - "├── perform(ParkArmsAction, )\n", - "├── perform(ParkArmsAction, )\n", - "├── perform(MoveTorsoAction, )\n", - "├── perform(NavigateAction, )\n", - "├── perform(PickUpAction, )\n", - "├── perform(ParkArmsAction, )\n", - "├── perform(NavigateAction, )\n", - "├── perform(PlaceAction, )\n", - "└── perform(ParkArmsAction, )\n" + "├── perform(Motion)\n", + "├── perform(Motion)\n", + "├── perform(ParkArmsActionPerformable)\n", + "├── perform(ParkArmsActionPerformable)\n", + "├── perform(MoveTorsoActionPerformable)\n", + "├── perform(NavigateActionPerformable)\n", + "│ └── perform(Motion)\n", + "├── perform(PickUpActionPerformable)\n", + "│ ├── perform(Motion)\n", + "│ ├── perform(Motion)\n", + "│ ├── perform(Motion)\n", + "│ ├── perform(Motion)\n", + "│ └── perform(Motion)\n", + "├── perform(ParkArmsActionPerformable)\n", + "├── perform(NavigateActionPerformable)\n", + "│ └── perform(Motion)\n", + "├── perform(PlaceActionPerformable)\n", + "│ ├── perform(Motion)\n", + "│ ├── perform(Motion)\n", + "│ └── perform(Motion)\n", + "└── perform(ParkArmsActionPerformable)\n" ] } ], @@ -945,8 +8719,13 @@ }, { "cell_type": "code", - "execution_count": 33, - "metadata": {}, + "execution_count": 30, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.669289460Z", + "start_time": "2024-01-05T11:39:03.494369670Z" + } + }, "outputs": [], "source": [ "from anytree.dotexport import RenderTreeGraph, DotExporter\n", @@ -962,38 +8741,37 @@ }, { "cell_type": "code", - "execution_count": 34, - "metadata": {}, + "execution_count": 31, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.922190909Z", + "start_time": "2024-01-05T11:39:03.675069105Z" + } + }, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 10/10 [00:00<00:00, 143.50it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 22/22 [00:00<00:00, 116.49it/s]\n" ] }, { "data": { - "text/plain": [ - "pycram.orm.task.TaskTreeNode(1, 2023-11-08 13:55:09.816577, None, TaskStatus.RUNNING, None, None, 1, 1)" - ] + "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 38, 17, 681423), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" }, - "execution_count": 34, + "execution_count": 31, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "import sqlalchemy\n", "import sqlalchemy.orm\n", "import pycram.orm.base\n", - "import pycram.orm.task\n", - "import pycram.orm.object_designator\n", - "import pycram.orm.motion_designator\n", "import pycram.orm.action_designator\n", "\n", "# set description of what we are doing\n", - "pycram.orm.base.MetaData().description = \"Tutorial for getting familiar with the ORM.\"\n", + "pycram.orm.base.ProcessMetaData().description = \"Tutorial for getting familiar with the ORM.\"\n", "\n", "engine = sqlalchemy.create_engine(\"sqlite+pysqlite:///:memory:\", echo=False)\n", "session = sqlalchemy.orm.Session(bind=engine)\n", @@ -1006,15 +8784,20 @@ }, { "cell_type": "code", - "execution_count": 35, - "metadata": {}, + "execution_count": 32, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.966372243Z", + "start_time": "2024-01-05T11:39:03.922350989Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "pycram.orm.action_designator.NavigateAction(Navigate, 4, 4, 1, 4, 4)\n", - "pycram.orm.action_designator.NavigateAction(Navigate, 7, 7, 1, 9, 9)\n" + "NavigateAction(id=6, process_metadata_id=1, dtype='NavigateAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), pose_id=7)\n", + "NavigateAction(id=15, process_metadata_id=1, dtype='NavigateAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), pose_id=16)\n" ] } ], @@ -1025,26 +8808,56 @@ }, { "cell_type": "code", - "execution_count": 36, - "metadata": {}, + "execution_count": 33, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-05T11:39:03.967890749Z", + "start_time": "2024-01-05T11:39:03.966131716Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "(pycram.orm.action_designator.NavigateAction(Navigate, 4, 4, 1, 4, 4), pycram.orm.base.Position(0.5799999999999998, 1.28, 0.0, 4, None), pycram.orm.base.Quaternion(0.0, 0.0, 0.16378361324016077, -0.9864962889104031, 4, None))\n", - "(pycram.orm.action_designator.NavigateAction(Navigate, 7, 7, 1, 9, 9), pycram.orm.base.Position(-1.9074999952316287, 0.779200015068054, 0.0, 9, None), pycram.orm.base.Quaternion(0.0, 0.0, 0.16439898730535735, 0.9863939238321437, 9, None))\n" + "(NavigateAction(id=6, process_metadata_id=1, dtype='NavigateAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), pose_id=7), Position(id=7, x=0.5799999999999998, y=1.28, z=0.0, process_metadata_id=1), Quaternion(id=7, x=0.0, y=0.0, z=0.16378361324016077, w=-0.9864962889104031, process_metadata_id=1))\n", + "(NavigateAction(id=15, process_metadata_id=1, dtype='NavigateAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), pose_id=16), Position(id=16, x=-1.9074999952316287, y=0.779200015068054, z=0.0, process_metadata_id=1), Quaternion(id=16, x=0.0, y=0.0, z=0.16439898730535735, w=0.9863939238321437, process_metadata_id=1))\n" ] } ], "source": [ - "navigations = session.query(pycram.orm.action_designator.NavigateAction, \n", + "navigations = (session.query(pycram.orm.action_designator.NavigateAction, \n", " pycram.orm.base.Position, \n", - " pycram.orm.base.Quaternion).\\\n", - " join(pycram.orm.base.Position).\\\n", - " join(pycram.orm.base.Quaternion).all()\n", + " pycram.orm.base.Quaternion).\n", + " join(pycram.orm.action_designator.NavigateAction.pose).\n", + " join(pycram.orm.base.Pose.position).\n", + " join(pycram.orm.base.Pose.orientation).all())\n", "print(*navigations, sep=\"\\n\")" ] + }, + { + "cell_type": "markdown", + "source": [ + "The world can also be closed with the 'exit' method" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "code", + "execution_count": 34, + "outputs": [], + "source": [ + "world.exit()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-01-05T11:39:04.199668442Z", + "start_time": "2024-01-05T11:39:03.966287501Z" + } + } } ], "metadata": { From 6f90a4708394c35a2bcd72fdc28404827d3f9b65 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 5 Jan 2024 13:16:29 +0100 Subject: [PATCH 030/195] [tests] updated orm tests --- src/pycram/orm/object_designator.py | 6 +- test/test_orm.py | 201 +++++++++++++++++----------- 2 files changed, 130 insertions(+), 77 deletions(-) diff --git a/src/pycram/orm/object_designator.py b/src/pycram/orm/object_designator.py index 78a584282..3f2d64205 100644 --- a/src/pycram/orm/object_designator.py +++ b/src/pycram/orm/object_designator.py @@ -1,9 +1,11 @@ +from typing import Optional -from pycram.orm.base import Base, MapperArgsMixin, PoseMixin +from pycram.orm.base import Base, MapperArgsMixin, PoseMixin, Pose from sqlalchemy.orm import Mapped, mapped_column, declared_attr, relationship from sqlalchemy import ForeignKey from ..enums import ObjectType + class ObjectMixin: """ ObjectMixin holds a foreign key column and its relationship to the referenced table. @@ -26,7 +28,7 @@ class Object(PoseMixin, Base): """ORM class of pycram.designators.object_designator.ObjectDesignator""" dtype: Mapped[str] = mapped_column(init=False) - type: Mapped[ObjectType] + type: Mapped[Optional[ObjectType]] name: Mapped[str] __mapper_args__ = { diff --git a/test/test_orm.py b/test/test_orm.py index 0f4e6cf63..34eea942a 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -13,7 +13,13 @@ import pycram.task import test_bullet_world import test_task_tree -from pycram.designators import action_designator, object_designator +from pycram.bullet_world import Object +from pycram.designators import action_designator, object_designator, motion_designator +from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable, \ + SetGripperActionPerformable, PickUpActionPerformable, NavigateActionPerformable, TransportActionPerformable, \ + OpenActionPerformable, CloseActionPerformable, DetectActionPerformable, LookAtActionPerformable +from pycram.designators.object_designator import BelieveObject +from pycram.enums import ObjectType from pycram.pose import Pose from pycram.process_module import simulated_robot from pycram.task import with_tree @@ -30,11 +36,14 @@ def setUpClass(cls): def setUp(self): super().setUp() + pycram.orm.base.Base.metadata.create_all(self.engine) self.session = sqlalchemy.orm.Session(bind=self.engine) self.session.commit() def tearDown(self): super().tearDown() + pycram.task.reset_tree() + pycram.orm.base.ProcessMetaData.reset() pycram.orm.base.Base.metadata.drop_all(self.engine) self.session.close() @@ -123,6 +132,21 @@ def test_node(self): action_results = self.session.query(pycram.orm.action_designator.Action).all() self.assertEqual(4, len(action_results)) + def test_metadata_existence(self): + pycram.orm.base.ProcessMetaData().description = "metadata_existence_test" + self.plan() + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.base.Pose).all() + self.assertTrue(all([r.process_metadata is not None for r in result])) + + def test_task_tree_node_parents(self): + self.plan() + pycram.orm.base.ProcessMetaData().description = "task_tree_node_parents_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.task.TaskTreeNode).all() + self.assertTrue([result[i].parent == result[result[i].parent_id - 1] for i in range(len(result)) + if result[i].parent_id is not None]) + def test_meta_data(self): self.plan() pycram.orm.base.ProcessMetaData().description = "Unittest" @@ -140,12 +164,38 @@ def test_meta_data(self): self.assertTrue(all([o.process_metadata_id for o in object_results])) def test_meta_data_alternation(self): - meta_data = pycram.orm.base.ProcessMetaData() - meta_data.description = "Test" self.plan() + pycram.orm.base.ProcessMetaData().description = "meta_data_alternation_test" pycram.task.task_tree.root.insert(self.session, ) metadata_result = self.session.query(pycram.orm.base.ProcessMetaData).first() - self.assertEqual(metadata_result.description, "Test") + self.assertEqual(metadata_result.description, "meta_data_alternation_test") + + +class MixinTestCase(ORMTestSchema, test_bullet_world.BulletWorldTest): + @with_tree + def plan(self): + object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) + self.assertEqual(description.ground().object_designator.name, "milk") + with simulated_robot: + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + description.resolve().perform() + + def test_pose(self): + self.plan() + pycram.orm.base.ProcessMetaData().description = "pose_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.base.Pose).all() + self.assertTrue(all([r.position is not None and r.orientation is not None for r in result])) + + def test_pose_mixin(self): + self.plan() + pycram.orm.base.ProcessMetaData().description = "pose_mixin_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.base.RobotState).all() + self.assertTrue(all([r.pose is not None and r.pose_id == r.pose.id for r in result])) class ORMObjectDesignatorTestCase(test_bullet_world.BulletWorldTest): @@ -160,9 +210,9 @@ def plan(self): description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) self.assertEqual(description.ground().object_designator.name, "milk") with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() description.resolve().perform() @classmethod @@ -197,21 +247,11 @@ def test_plan_serialization(self): self.assertEqual(len(tt) - 2, len(action_results) + len(motion_results)) -class RelationshipTestCase(test_task_tree.TaskTreeTestCase): +class ORMActionDesignatorTestCase(test_bullet_world.BulletWorldTest): + engine: sqlalchemy.engine.Engine session: sqlalchemy.orm.Session - @with_tree - def plan(self): - object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) - description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) - self.assertEqual(description.ground().object_designator.name, "milk") - with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() - description.resolve().perform() - @classmethod def setUpClass(cls): super().setUpClass() @@ -236,74 +276,85 @@ def TearDownClass(cls): cls.session.commit() cls.session.close() - def test_metadata(self): - pycram.orm.base.ProcessMetaData().description = "MetaDataRelationshipTest" - self.plan() + def test_code_designator_type(self): + action = NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])) + with simulated_robot: + action.perform() + pycram.orm.base.ProcessMetaData().description = "code_designator_type_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.base.Position).all() - self.assertTrue(all([r.process_metadata is not None for r in result])) + result = self.session.query(pycram.orm.task.Code).filter(pycram.orm.task.Code.function == "perform").all() + self.assertEqual(result[0].designator.dtype, action_designator.NavigateAction.__name__) + self.assertEqual(result[1].designator.dtype, motion_designator.MoveMotion.__name__) - def test_task_tree_node_parents(self): - self.plan() - pycram.orm.base.ProcessMetaData().description = "taskTest" + def test_parkArmsAction(self): + action = ParkArmsActionPerformable(pycram.enums.Arms.BOTH) + with simulated_robot: + action.perform() + pycram.orm.base.ProcessMetaData().description = "parkArmsAction_test" pycram.task.task_tree.root.insert(self.session) - r = self.session.query(pycram.orm.task.TaskTreeNode).all() - self.assertTrue([r[i].parent == r[r[i].parent_id - 1] for i in range(len(r)) if r[i].parent_id is not None]) + result = self.session.query(pycram.orm.action_designator.ParkArmsAction).all() + self.assertTrue(all([result[i+1].dtype is not pycram.orm.action_designator.Action.dtype + if result[i].dtype is pycram.orm.action_designator.ParkArmsAction.dtype else None + for i in range(len(result)-1)])) - -class MotionDesigTest(test_bullet_world.BulletWorldTest): - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - - @with_tree - def plan(self): + def test_transportAction(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) - description = action_designator.PlaceAction(object_description, [Pose([1.3, 0.9, 0.9], [0, 0, 0, 1])], ["left"]) - self.assertEqual(description.ground().object_designator.name, "milk") + action = TransportActionPerformable(object_description.resolve(), "left", + Pose([1.3, 0.9, 0.9], [0, 0, 0, 1])) with simulated_robot: - action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.MoveTorsoAction.Action(0.3).perform() - action_designator.LookAtAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() - action_designator.SetGripperAction.Action("right", "open").perform() - description.resolve().perform() + action.perform() + pycram.orm.base.ProcessMetaData().description = "transportAction_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.action_designator.TransportAction).all() + milk_object = self.session.query(pycram.orm.object_designator.Object).first() + self.assertEqual(milk_object.pose, result[0].object.pose) - @classmethod - def setUpClass(cls): - super().setUpClass() - cls.engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False) + def test_lookAt_and_detectAction(self): + object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + action = DetectActionPerformable(object_description.resolve()) + with simulated_robot: + ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform() + NavigateActionPerformable(Pose([0, 1, 0], [0, 0, 0, 1])).perform() + LookAtActionPerformable(object_description.resolve().pose).perform() + action.perform() + pycram.orm.base.ProcessMetaData().description = "detectAction_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.action_designator.DetectAction).all() + self.assertEqual(result[0].object.name, "milk") - def setUp(self): - super().setUp() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() + def test_setGripperAction(self): + action = SetGripperActionPerformable("left", "open") + with simulated_robot: + action.perform() + pycram.orm.base.ProcessMetaData().description = "setGripperAction_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.query(pycram.orm.action_designator.SetGripperAction).all() + self.assertEqual(result[0].gripper, "left") + self.assertEqual(result[0].motion, "open") - def tearDown(self): - super().tearDown() - pycram.task.reset_tree() - pycram.orm.base.ProcessMetaData.reset() - pycram.orm.base.Base.metadata.drop_all(self.engine) - self.session.close() + def test_open_and_closeAction(self): + apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") + apartment_desig = BelieveObject(names=["apartment"]).resolve() + handle_desig = object_designator.ObjectPart(names=["handle_cab10_t"], part_of=apartment_desig).resolve() - @classmethod - def TearDownClass(cls): - super().tearDownClass() - cls.session.commit() - cls.session.close() + self.kitchen.set_pose(Pose([20, 20, 0], [0, 0, 0, 1])) - def testTest(self): - self.plan() - pycram.orm.base.ProcessMetaData().description = "Unittest" - tt = pycram.task.task_tree - tt.insert(self.session) + with simulated_robot: + ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform() + NavigateActionPerformable(Pose([1.81, 1.73, 0.0], + [0.0, 0.0, 0.594, 0.804])).perform() + OpenActionPerformable(handle_desig, arm="left").perform() + CloseActionPerformable(handle_desig, arm="left").perform() - def test_insert_base_motion(self): - motion = pycram.orm.motion_designator.Motion() - self.assertIsNone(motion.id) - self.session.add(motion) - self.session.commit() - self.assertIsNotNone(motion.id) + pycram.orm.base.ProcessMetaData().description = "open_and_closeAction_test" + pycram.task.task_tree.root.insert(self.session) + open_result = self.session.query(pycram.orm.action_designator.OpenAction).all() + close_result = self.session.query(pycram.orm.action_designator.CloseAction).all() + self.assertTrue(open_result is not None) + self.assertEqual(open_result[0].object.name, "handle_cab10_t") + self.assertTrue(close_result is not None) + self.assertEqual(close_result[0].object.name, "handle_cab10_t") + apartment.remove() if __name__ == '__main__': From af9e3e64374ca627e3dae857167f859c1a1786af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 5 Jan 2024 14:03:51 +0100 Subject: [PATCH 031/195] [tests] fixed object designator test --- test/test_object_designator.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test/test_object_designator.py b/test/test_object_designator.py index 625e107a2..3cdcdce0c 100644 --- a/test/test_object_designator.py +++ b/test/test_object_designator.py @@ -13,12 +13,12 @@ def test_object_grounding(self): self.assertEqual(obj.name, "milk") self.assertEqual(obj.type, ObjectType.MILK) - def test_data_copy(self): + def test_frozen_copy(self): description = ObjectDesignatorDescription(["milk"], [ObjectType.MILK]) obj = description.ground() - data_copy = obj.data_copy() - self.assertEqual(obj.pose, data_copy.pose) + frozen_copy = obj.frozen_copy() + self.assertEqual(obj.pose, frozen_copy.pose) if __name__ == '__main__': From dce2b77d6b378c5e199a3076617ffc736c4fa824 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Sat, 13 Jan 2024 18:54:20 +0100 Subject: [PATCH 032/195] [doc] added language example to doc --- doc/source/examples.rst | 1 + doc/source/notebooks/language.ipynb | 1 + 2 files changed, 2 insertions(+) create mode 120000 doc/source/notebooks/language.ipynb diff --git a/doc/source/examples.rst b/doc/source/examples.rst index 9cd424b2f..ac52e9ac0 100644 --- a/doc/source/examples.rst +++ b/doc/source/examples.rst @@ -28,6 +28,7 @@ Misc notebooks/minimal_task_tree notebooks/pose notebooks/custom_resolver + notebooks/language Interface Examples ================== diff --git a/doc/source/notebooks/language.ipynb b/doc/source/notebooks/language.ipynb new file mode 120000 index 000000000..ae22ff1e9 --- /dev/null +++ b/doc/source/notebooks/language.ipynb @@ -0,0 +1 @@ +../../../examples/language.ipynb \ No newline at end of file From bd41a55efc17c8dd50f05ff8edf4703932153285 Mon Sep 17 00:00:00 2001 From: HaSu Date: Wed, 17 Jan 2024 12:38:51 +0100 Subject: [PATCH 033/195] [examples] fixing typos --- examples/action_designator.ipynb | 18 +++++----- examples/bullet_world.ipynb | 20 ++++++------ examples/cram_plan_tutorial.ipynb | 12 +++---- examples/interface_examples/giskard.ipynb | 38 +++++++++++----------- examples/interface_examples/robokudo.ipynb | 12 +++---- examples/location_designator.ipynb | 16 ++++----- examples/motion_designator.ipynb | 10 +++--- examples/object_designator.ipynb | 17 +++++----- examples/pose.ipynb | 15 ++++----- 9 files changed, 78 insertions(+), 80 deletions(-) diff --git a/examples/action_designator.ipynb b/examples/action_designator.ipynb index 69cfa4ef3..9ee38d1f1 100644 --- a/examples/action_designator.ipynb +++ b/examples/action_designator.ipynb @@ -6,12 +6,12 @@ "metadata": {}, "source": [ "# Action Designator\n", - "This example will show the different kinds of Action Designator that are available. We will see how to create Action Designators and what they do.\n", + "This example will show the different kinds of Action Designators that are available. We will see how to create Action Designators and what they do.\n", "\n", "\n", - "Action Designator are high-level descriptions of actions which the robot should execute. \n", + "Action Designators are high-level descriptions of actions which the robot should execute. \n", "\n", - "Action Deisgnators are created from a Action Designator Descritpion, which describes the type of action as well as the parameter for this action. Parameter are given as a list of possible parameters.\n", + "Action Designators are created from an Action Designator Description, which describes the type of action as well as the parameter for this action. Parameter are given as a list of possible parameters.\n", "For example, if you want to describe the robot moving to a table you would need a ```NavigateAction``` and a list of poses that are near the table. The Action Designator Description will then pick one of the poses and return a performable Action Designator which contains the picked pose. \n", "\n" ] @@ -103,7 +103,7 @@ "id": "30bd6765", "metadata": {}, "source": [ - "What we now did was create the pose were we want to move the robot, create a description describing a navigation with a list of possible poses (in this case the list contains only one pose) and create an action designator from the description. The action designator contains the pose picked from the list of possible poses and can be performed." + "What we now did was: create the pose where we want to move the robot, create a description describing a navigation with a list of possible poses (in this case the list contains only one pose) and create an action designator from the description. The action designator contains the pose picked from the list of possible poses and can be performed." ] }, { @@ -126,7 +126,7 @@ "source": [ "Every designator that is performed needs to be in an environment that specifies where to perform the designator either on the real robot or the simulated one. This environment is called ```simulated_robot``` similar there is also a ```real_robot``` environment. \n", "\n", - "There are also decorators which do the same thing but for whole methods, they are called ```with_real_robot``` and ```with_simulated_robor```" + "There are also decorators which do the same thing but for whole methods, they are called ```with_real_robot``` and ```with_simulated_robot```." ] }, { @@ -137,7 +137,7 @@ "## Move Torso\n", "This action designator moves the torso up or down, specifically it sets the torso joint to a given value.\n", "\n", - "We start again by creating a description and resolving it to a designator. Afterwards, the designator is perfomed in a ```simulated_robot``` environment. " + "We start again by creating a description and resolving it to a designator. Afterwards, the designator is performed in a ```simulated_robot``` environment. " ] }, { @@ -216,9 +216,9 @@ "metadata": {}, "source": [ "## Pick Up and Place\n", - "Since these are depending on each other, meaning you can only place something when you picked it up beforehand, they will be shown together. \n", + "Since these two are dependent on each other, meaning you can only place something when you picked it up beforehand, they will be shown together. \n", "\n", - "These action designators use object designators, which will not be further explained so please check the example on object designators for more details. \n", + "These action designators use object designators, which will not be further explained in this tutorial so please check the example on object designators for more details. \n", "\n", "To start we need an environment in which we can pick up and place things as well as an object to pick up." ] @@ -552,7 +552,7 @@ "metadata": {}, "source": [ "## Transporting\n", - "Transporting can transport an object from its current position to another target position. It is similar to the Pick and Place plan used in the Pick-up and Place example. Since we need an Object which we can transport we spawn a milk, you don't need to do this if you alredy spawned it in a previous example." + "Transporting can transport an object from its current position to another target position. It is similar to the Pick and Place plan used in the Pick-up and Place example. Since we need an Object which we can transport we spawn a milk, you don't need to do this if you already have spawned it in a previous example." ] }, { diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index 67016f4d2..05d506f68 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -96,15 +96,15 @@ "source": [ "As you can see this spawns a milk floating in the air. What we did here was create a new Object which has the name \"milk\" as well as the type ```ObjectType.MILK ``` , is spawned from the file \"milk.stl\" and is at the position [0, 0, 1]. \n", "\n", - "The type of an Object can either be from the enum ObjectType or a string. However, it is recommended to use the enum since this would make for a more consistent naming of types which makes it easiert to work with types. But since the types of the enum might not fit your case you can also use strings. \n", + "The type of an Object can either be from the enum ObjectType or a string. However, it is recommended to use the enum since this would make for a more consistent naming of types which makes it easier to work with types. But since the types of the enum might not fit your case you can also use strings. \n", "\n", - "The first three of these parameters are required while the position is optional. As you can see it was sufficent to only specify the filename for PyCRAM to spawn the milk mesh. When only providing a filename PyCRAM will search in its resource directory for a matching file and use it. \n", + "The first three of these parameters are required while the position is optional. As you can see it was sufficient to only specify the filename for PyCRAM to spawn the milk mesh. When only providing a filename, PyCRAM will search in its resource directory for a matching file and use it. \n", "\n", "For a complete list of all parameters that can be used to crate an Object please check the documentation. \n", "\n", "\n", "\n", - "Since the Object is spawned we can now interact with it. First we want to move it around and change it's orientation" + "Since the Object is spawned, we can now interact with it. First we want to move it around and change its orientation" ] }, { @@ -142,7 +142,7 @@ "id": "5805be38", "metadata": {}, "source": [ - "In the same sense as setting the position or orientation you can also get the position and orientation." + "In the same sense as setting the position or orientation, you can also get the position and orientation." ] }, { @@ -200,7 +200,7 @@ "## Attachments\n", "You can attach Objects to each other simply by calling the attach method on one of them and providing the other as parameter. Since attachments are bi-directional it doesn't matter on which Object you call the method. \n", "\n", - "First we neeed another Object" + "First we need another Object" ] }, { @@ -265,9 +265,9 @@ "metadata": {}, "source": [ "## Links and Joints\n", - "Objects spawned from mesh files do not have links or joints, but if you spawn things from a URDF like a robot they will have a lot of links and joints. Every Object has two dictionaries as attributes namley ```links``` and ```joints``` which contain every link or joint as key and a unique id, used by PyBullet, as value. \n", + "Objects spawned from mesh files do not have links or joints, but if you spawn things from a URDF like a robot they will have a lot of links and joints. Every Object has two dictionaries as attributes, namely ```links``` and ```joints``` which contain every link or joint as key and a unique id, used by PyBullet, as value. \n", "\n", - "We will see this at the example of the PR2" + "We will see this at the example of the PR2:" ] }, { @@ -369,7 +369,7 @@ " * ```set_joint_state```\n", " * ```get_joint_limits```\n", " \n", - "We will see how these methods work at the example of the torso_lift_joint" + "We will see how these methods work at the example of the torso_lift_joint:" ] }, { @@ -404,7 +404,7 @@ "metadata": {}, "source": [ "## Misc Methods\n", - "There are a few methods that don't fit any category but could be helpful anyways. The first two are ```get_color``` and ```set_color```, as the name implies they can be used to get or set the color for specific links or the whole Object. " + "There are a few methods that don't fit any category but could be helpful anyway. The first two are ```get_color``` and ```set_color```, as the name implies they can be used to get or set the color for specific links or the whole Object. " ] }, { @@ -440,7 +440,7 @@ "id": "ce5d910b", "metadata": {}, "source": [ - "Lastly, there is ```get_AABB``` AABB stands for axis aligned bounding box. This method returns two points in world coordinates which span a rectangle representing the AABB." + "Lastly, there is ```get_AABB```, AABB stands for *A*xis *A*ligned *B*ounding *B*ox. This method returns two points in world coordinates which span a rectangle representing the AABB." ] }, { diff --git a/examples/cram_plan_tutorial.ipynb b/examples/cram_plan_tutorial.ipynb index d322d7be3..a7fd04383 100644 --- a/examples/cram_plan_tutorial.ipynb +++ b/examples/cram_plan_tutorial.ipynb @@ -489,7 +489,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "Task tree can be manipulated with ordinary anytree manipulation. If we for example want to discard the second plan, we would write" + "Task tree can be manipulated with ordinary anytree manipulation. If we for example want to discard the second plan, we would write:" ] }, { @@ -613,7 +613,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "The task tree can also be reset to an empty one by invoking" + "The task tree can also be reset to an empty one by invoking:" ] }, { @@ -720,10 +720,10 @@ "evalue": "name 'world' is not defined", "output_type": "error", "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", - "Cell \u001b[0;32mIn[1], line 1\u001b[0m\n\u001b[0;32m----> 1\u001b[0m \u001b[43mworld\u001b[49m\u001b[38;5;241m.\u001b[39mexit()\n", - "\u001b[0;31mNameError\u001b[0m: name 'world' is not defined" + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mNameError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[1], line 1\u001B[0m\n\u001B[0;32m----> 1\u001B[0m \u001B[43mworld\u001B[49m\u001B[38;5;241m.\u001B[39mexit()\n", + "\u001B[0;31mNameError\u001B[0m: name 'world' is not defined" ] } ], diff --git a/examples/interface_examples/giskard.ipynb b/examples/interface_examples/giskard.ipynb index 91c6b957b..54f81f4bc 100644 --- a/examples/interface_examples/giskard.ipynb +++ b/examples/interface_examples/giskard.ipynb @@ -8,17 +8,17 @@ "# Giskard interface in PyCRAM\n", "This notebook should provide you with an example on how to use the Giskard interface. This includes how to use the interface, how it actually works and how to extend it. \n", "\n", - "We start installing and starting Giskard. For the installation please follow the instructions [here](https://github.com/SemRoCo/giskardpy).\n", - "After you finish the installation you should be able to start giskard by calling \n", + "We start by installing and launching Giskard. For the installation please follow the instructions [here](https://github.com/SemRoCo/giskardpy).\n", + "After you finish the installation you should be able to launch Giskard by calling: \n", "```\n", "roslaunch giskardpy giskardpy_pr2_standalone.launch\n", "```\n", "\n", - "In this way you can start Giskard for any robot that is supported.\n", + "This way you can launch Giskard for any robot that is supported:\n", "```\n", "roslaunch giskardpy giskardpy_hsr_standalone.launch\n", "```\n", - "\"Standalone\" means that Giskard only uses a simulated robot and does not look for a real robot. If you want to use Giskard with a real robot you have to switch \"standalone\" with \"iai\". \n", + "\"Standalone\" means that Giskard only uses a simulated robot and does not look for a real robot. If you want to use Giskard with a real robot you have to switch out \"standalone\" with \"iai\", e.g:\n", "```\n", "roslaunch giskardpy giskardpy_hsr_iai.launch\n", "```\n", @@ -33,9 +33,9 @@ "source": [ "## How to use the Giskard interface \n", "Everything related to the Giskard interface is located in ```pycram.external_interfaces.giskard```. \n", - "The content of the file can be roughtly divided into three parts:\n", - " 1. Methods to manage the beliefe states between PyCRAM and Giskard\n", - " 2. Motion goals that should be send to Giskard for execution \n", + "The content of the file can be roughly divided into three parts:\n", + " 1. Methods to manage the belief states between PyCRAM and Giskard\n", + " 2. Motion goals that should be sent to Giskard for execution \n", " 3. Helper methods to construct ROS messages\n", " \n", "The most useful methods are the ones for sending and executing Motion goals. These are the ones we will mostly look at.\n", @@ -84,11 +84,11 @@ "id": "f4c4f85d", "metadata": {}, "source": [ - "Now we have a PyCRAM belief state set up, belief state in this case just refeers to the BulletWorld since the BulletWorld represents what we belief the world to look like. \n", + "Now we have a PyCRAM belief state set up, belief state in this case just refers to the BulletWorld since the BulletWorld represents what we believe the world to look like. \n", "\n", - "The next step will be to send a simple motion goal. The motion goal we will be sending is moving the torso up. For this we just need to move one joint so we use the ```achive_joint_goal```. This method takes a dictionary with the joints that should be moved and the target value for the joint. \n", + "The next step will be to send a simple motion goal. The motion goal we will be sending is moving the torso up. For this we just need to move one joint, so we can use the ```achive_joint_goal```. This method takes a dictionary with the joints that should be moved and the target value for the joints. \n", "\n", - "Look at Rviz to see the robot move, since we call Giskard for movement the robot in the BulletWorld will not move." + "Look at RViz to see the robot move, since we call Giskard for movement the robot in the BulletWorld will not move." ] }, { @@ -110,11 +110,11 @@ "id": "77dbded9", "metadata": {}, "source": [ - "For Giskard everything is connected by joints (this is called [World Tree](https://github.com/SemRoCo/giskardpy/wiki/World-Tree) by Giskard) therefore we can move the robot by using a motion goal between the map origin and the robot base. \n", + "For Giskard everything is connected by joints (this is called a [World Tree](https://github.com/SemRoCo/giskardpy/wiki/World-Tree) by Giskard) therefore we can move the robot's base by using motion goals between the map origin and the robot base. (e.g. by sending a \"base_link\" goal in the \"map\" frame).\n", "\n", "In the example below we use a cartesian goal, meaning we give Giskard a goal pose, a root link and a tip link and Giskard tries to move all joints between root link and tip link such that the tip link is at the goal pose.\n", "\n", - "This sort of movement is fine for short distance but keep in mind that Giskard has no collision avoidance for longer journeys. So using MoveBase for longer distances is a better idea." + "This sort of movement is fine for short distances, but keep in mind that Giskard has no collision avoidance for longer journeys. So using MoveBase for longer distances is a better idea." ] }, { @@ -135,9 +135,9 @@ "id": "98af5723", "metadata": {}, "source": [ - "Now for the last example: we will move the gripper using full body motion controll. \n", + "Now for the last example: we will move the gripper using full body motion control. \n", "\n", - "We will again use the cartesian goal, but now between \"map\" and \"r_gripper_tool_frame\". This will not only move the robot (because the chain between \"map\" and \"base_link\" as used in the previous example is also part of this chain) but also move the arm of the robot such that it reaches the goal pose." + "We will again use the cartesian goal, but now between \"map\" and \"r_gripper_tool_frame\" frames. This will not only move the robot (because the kinematic chain between \"map\" and \"base_link\" as used in the previous example is also part of this chain) but also move the arm of the robot such that it reaches the goal pose." ] }, { @@ -158,7 +158,7 @@ "id": "7dfe78ba", "metadata": {}, "source": [ - "That conludes this example you can now close the BulletWorld by using the \"exit\" method." + "That concludes this example you can now close the BulletWorld by using the \"exit\" method." ] }, { @@ -177,15 +177,15 @@ "metadata": {}, "source": [ "## How the Giskard interface works \n", - "The PyCRAM interface to Giskard mostly relies on the Python interface that Giskard already proviedes ([tutorial](https://github.com/SemRoCo/giskardpy/wiki/Python-Interface) and the [source code](https://github.com/SemRoCo/giskardpy/blob/master/src/giskardpy/python_interface.py)). This inteface provides methods to achive motion goals and load things into the Giskard believe state. \n", + "The PyCRAM interface to Giskard mostly relies on the Python interface that Giskard already provides ([tutorial](https://github.com/SemRoCo/giskardpy/wiki/Python-Interface) and the [source code](https://github.com/SemRoCo/giskardpy/blob/master/src/giskardpy/python_interface.py)). This interface provides methods to achieve motion goals and load things into the Giskard believe state. \n", "\n", - "What PyCRAM with this does is: Synchronize the believe state of Giskard with the one of PyCRAM by loading the environment URDF in Giskard, this is done before any motion goal is send. Furthermore, the motion goals are wrapped in methods that use PyCRAM data types. \n", + "What PyCRAM does with this, is: Synchronize the belief state of Giskard with the one of PyCRAM by loading the environment URDF in Giskard, this is done before any motion goal is sent. Furthermore, the motion goals are wrapped in methods that use PyCRAM data types. \n", "\n", - "You can also set collisions between different groups of links. By default Giskard avoids all collisions but for things like grasping an object you want to allow collisions of the gripper. The interface also the following colliion modes:\n", + "You can also set collisions between different groups of links. By default, Giskard avoids all collisions but for things like grasping an object you want to allow collisions of the gripper. The interface also supports the following collision modes:\n", " * avoid_all_collisions\n", " * allow_self_collision\n", " * allow_gripper_collision\n", - "The collision mode can be set by calling the respective method, after calling the method the collision mode is valid for the next motion goal afterwards it default back to avoid_all_collisions.\n", + "The collision mode can be set by calling the respective method, after calling the method the collision mode is valid for the next motion goal. Afterwards, it defaults back to avoid_all_collisions.\n", "\n", "There is a ```init_giskard_interface``` method which can be used as a decorator. This decorator should be used on all methods that access the giskard_wrapper, since it assures that the interface is working and checks if Giskard died or the imports for the giskard_msgs failed. " ] diff --git a/examples/interface_examples/robokudo.ipynb b/examples/interface_examples/robokudo.ipynb index 7f7f0f33d..04268950b 100644 --- a/examples/interface_examples/robokudo.ipynb +++ b/examples/interface_examples/robokudo.ipynb @@ -6,7 +6,7 @@ "metadata": {}, "source": [ "# Robokudo interface in PyCRAM\n", - "This notebook should give you an example on how the robokudo interface in PyCRAM works. We will go over how to use the interface, how it is implemented and what can be extended. \n", + "This notebook should give you an example on how the RoboKudo interface in PyCRAM works. We will go over how to use the interface, how it is implemented and what can be extended. \n", "\n", "First, you need to install RoboKudo by following the installation instructions [here](https://robokudo.ai.uni-bremen.de/installation.html). \n", "\n", @@ -61,7 +61,7 @@ "id": "da0dbc43", "metadata": {}, "source": [ - "There was no object detected since the pipline we are using for this example only returns an empty message. However this should give you an impression on how the interface works." + "There was no object detected since the pipline we are using for this example only returns an empty message. However, this should give you an impression on how the interface works." ] }, { @@ -70,12 +70,12 @@ "metadata": {}, "source": [ "## How the RoboKudo interface in PyCRAM works\n", - "The interface to RoboKudo is designed around the ROS service that RoboKudo proviedes. The interface takes a ObjectDesignatorDescription which is PyCRAMs symbolic representation of objects and converts it to a RoboKudo ObjectDesignator, the RoboKudo ObjectDesignator is then send to RoboKudo. \n", + "The interface to RoboKudo is designed around the ROS service that RoboKudo provides. The interface takes an ObjectDesignatorDescription which is PyCRAMs symbolic representation of objects and converts it to a RoboKudo ObjectDesignator, the RoboKudo ObjectDesignator is then send to RoboKudo. \n", "\n", - "The result from this is a list of RoboKudo ObjectDesignators which are possbile matches that were found in the camera FOV. Each of these ObjectDesignators has a list of possible poses that are the result of different pose estimators (currently PyCRAM picks the pose from 'ClusterPoseBBAnnotator' from the list of possible poses).\n", + "The result from this is a list of RoboKudo ObjectDesignators which are possible matches that were found in the camera FOV. Each of these ObjectDesignators has a list of possible poses that are the result of different pose estimators (currently PyCRAM picks the pose from 'ClusterPoseBBAnnotator' from the list of possible poses).\n", "PyCRAM then transforms all possible poses for the found Objects to 'map' frame and returns them as a dictionary.\n", "\n", - "When using the interface the decorator ```init_robokudo_interface``` should be added to all methods that want to send queries to RoboKudo. This decorator makes sure that RoboKudo is running and creates an action client which can be used via the gloabl variable ```robokudo_action_client```." + "When using the interface the decorator ```init_robokudo_interface``` should be added to all methods that want to send queries to RoboKudo. This decorator makes sure that RoboKudo is running and creates an action client which can be used via the global variable ```robokudo_action_client```." ] }, { @@ -84,7 +84,7 @@ "metadata": {}, "source": [ "## How to extend the RoboKudo interface in PyCRAM\n", - "At the moment the RoboKudo interface is tailored toward a specific scenarion in which only two types of objects need to be detected. The distiction is mainly made by the difference in color, which is written to the RoboKudo ObjectDesignator depending on the ObjectType of the PyCRAM ObjectDesignator. \n", + "At the moment the RoboKudo interface is tailored towards a specific scenario, in which only two types of objects need to be detected. The distinction is mainly made by the difference in color, which is written in the RoboKudo ObjectDesignator depending on the ObjectType of the PyCRAM ObjectDesignator. \n", "\n", "The main point for extension would be to make the interface more universal and extend it to work with other pipelines for example for human detection." ] diff --git a/examples/location_designator.ipynb b/examples/location_designator.ipynb index 9865e46f7..a6c368aec 100644 --- a/examples/location_designator.ipynb +++ b/examples/location_designator.ipynb @@ -6,18 +6,18 @@ "metadata": {}, "source": [ "# Location Designator\n", - "This example will show you waht location designator are, how to use them and what they are capable of. \n", + "This example will show you what location designators are, how to use them and what they are capable of. \n", "\n", - "Location Deisgnator are used to semantically describe locations in the world. You could, for example, create a location designator that describes every position where a robot can be placed without colliding with the environment. Location designator can describe locations for:\n", + "Location Designators are used to semantically describe locations in the world. You could, for example, create a location designator that describes every position where a robot can be placed without colliding with the environment. Location designator can describe locations for:\n", "\n", " * Visibility \n", " * Reachability\n", - " * Occupany \n", + " * Occupancy \n", " * URDF Links (for example a table)\n", "\n", "To find locations that fit the given constrains, location designator create Costmaps. Costmaps are a 2D distribution that have a value greater than 0 for every position that fits the costmap criteria.\n", "\n", - "Location designator work similar to other designator, meaning you have to create a location designator description which describes the location. This description can then be resolved to the actual 6D pose on runtime.\n", + "Location designators work similar to other designators, meaning you have to create a location designator description which describes the location. This description can then be resolved to the actual 6D pose on runtime.\n", "\n", "## Occupancy\n", "\n", @@ -63,7 +63,7 @@ "id": "8c09672d", "metadata": {}, "source": [ - "Next up we will create the location designator description, the ```CostmapLocation``` that we will be using needs a target as parameter. This target describes what the location designator is for, this could either be a pose or object that the robot should be able to see or reach.\n", + "Next up we will create the location designator description, the ```CostmapLocation``` that we will be using needs a target as a parameter. This target describes what the location designator is for, this could either be a pose or object that the robot should be able to see or reach.\n", "\n", "In this case we only want poses where the robot can be placed, this is the default behaviour of the location designator which we will be extending later. " ] @@ -187,7 +187,7 @@ "metadata": {}, "source": [ "## Visibile\n", - "The ```CostmapLocation``` can also find position from which the robot can see a given object or location. This is very similar to how rechable locations are described, meaning we provide a object designator or a pose and a robot designator but this time we use the ```visible_for``` parameter. \n", + "The ```CostmapLocation``` can also find position from which the robot can see a given object or location. This is very similar to how reachable locations are described, meaning we provide a object designator or a pose and a robot designator but this time we use the ```visible_for``` parameter. \n", "\n", "For this example we need the milk as well as the PR2, so if you did not spawn them during the previous location designator you can spawn them with the following cell. " ] @@ -252,7 +252,7 @@ "## Semantic \n", "Semantic location designator are used to create location descriptions for semantic entities, like a table. An example of this is: You have a robot that picked up an object and should place it on a table. Semantic location designator then allows to find poses that are on this table.\n", "\n", - "Semantic location designator need an object from which the target entity is a part and the urdf link representing the entity. In this case we want a position on the kitchen island, so we have to provide the kitchen object designator since the island is a part of the kitchen and the link name of the island surface. \n", + "Semantic location designator need an object from which the target entity is a part and the URDF link representing the entity. In this case we want a position on the kitchen island, so we have to provide the kitchen object designator since the island is a part of the kitchen and the link name of the island surface. \n", "\n", "For this example we need the kitchen as well as the milk. If you spawned them in one of the previous examples you don't need to execute the following cell." ] @@ -359,7 +359,7 @@ "## Accessing Locations\n", "Accessing describes a location from which the robot can open a drawer. The drawer is specified by a ObjetcPart designator which describes the handle of the drawer.\n", "\n", - "At the moment this location designator only works in the apartment environment, so please remove the kitchen if you spawned it in a previous example. Furthermore, we need a robot so we also spawn the pr2 if it isn't spawned already." + "At the moment this location designator only works in the apartment environment, so please remove the kitchen if you spawned it in a previous example. Furthermore, we need a robot, so we also spawn the PR2 if it isn't spawned already." ] }, { diff --git a/examples/motion_designator.ipynb b/examples/motion_designator.ipynb index 9dd9b5c66..9b0dbb8b6 100644 --- a/examples/motion_designator.ipynb +++ b/examples/motion_designator.ipynb @@ -6,9 +6,9 @@ "metadata": {}, "source": [ "# Motion Designator\n", - "Motion designator are similar to action designator, but unlike action designator, motion designator represent atomar low-level motions. Motion designator only take the parameter that they should execute and not a list of possible parameter, like the other designator. Like action designator motion designator can be performed, performing motion designator verifies the parameter and passes the designator to the respective process module. \n", + "Motion designators are similar to action designators, but unlike action designators, motion designators represent atomic low-level motions. Motion designators only take the parameter that they should execute and not a list of possible parameters, like the other designators. Like action designators, motion designators can be performed, performing motion designator verifies the parameter and passes the designator to the respective process module. \n", "\n", - "Since motion designaotr perform motion on the robot, we need a robot which we can use. Therefore, we will create a BulletWorld as well as a PR2 robot." + "Since motion designators perform a motion on the robot, we need a robot which we can use. Therefore, we will create a BulletWorld as well as a PR2 robot." ] }, { @@ -155,7 +155,7 @@ "metadata": {}, "source": [ "## Move Gripper\n", - "Move gripper moves the gripper of an arm to one of two states. The states can be ```open``` and ```close```, which open and close the gripper respectivly." + "Move gripper moves the gripper of an arm to one of two states. The states can be ```open``` and ```close```, which open and close the gripper respectively." ] }, { @@ -429,9 +429,9 @@ "metadata": {}, "source": [ "## World State Detecting\n", - "World state detecting is also used to detect objects, however, the object is not required to be in the FOV of the robot. As long as the object is somewhere in the beliefe state (BulletWorld) a resolved object designator will be returned.\n", + "World state detecting is also used to detect objects, however, the object is not required to be in the FOV of the robot. As long as the object is somewhere in the belief state (BulletWorld) a resolved object designator will be returned.\n", "\n", - "Sine we want to detect something we will spawn an object that we can detect. If you already spawned the milk the the previous example you can skip this step." + "Sine we want to detect something we will spawn an object that we can detect. If you already spawned the milk from the previous example, you can skip this step." ] }, { diff --git a/examples/object_designator.ipynb b/examples/object_designator.ipynb index bd03c2d3c..b5c09ca0b 100644 --- a/examples/object_designator.ipynb +++ b/examples/object_designator.ipynb @@ -6,11 +6,11 @@ "metadata": {}, "source": [ "# Object Designator\n", - "Object designator are used to describe objects located in the BulletWorld or the real environment and then resolve them during runtime to concrete objects.\n", + "Object designators are used to describe objects located in the BulletWorld or the real environment and then resolve them during runtime to concrete objects.\n", "\n", - "Object designator are different from the Object class in bullet_world.py in the way that they just describe an object and do not create objects or provide methods to manipulate them. Nethertheless, object designator contain a reference to the BulletWorld object.\n", + "Object designators are different from the Object class in bullet_world.py in the way that they just describe an object and do not create objects or provide methods to manipulate them. Nevertheless, object designators contain a reference to the BulletWorld object.\n", "\n", - "Object designator take two parameter, of which at least one has to be provided. These parameter are:\n", + "An Object designator takes two parameters, of which at least one has to be provided. These parameters are:\n", "\n", " * A list of names \n", " * A list of types \n", @@ -61,9 +61,9 @@ "metadata": {}, "source": [ "## Believe Object\n", - "This object designator is used to describe object that are located in the BulletWorld. So objects that are in the believe state, hence the name. In the futre when there is a perception interface there will be a ```RealObject``` description which will be used to describe objects in the real world. \n", + "This object designator is used to describe objects that are located in the BulletWorld. So objects that are in the belief state, hence the name. In the future when there is a perception interface, there will be a ```RealObject``` description which will be used to describe objects in the real world. \n", "\n", - "Since ```BelieveObject``` decribes Objects in the BulletWorld we create a few." + "Since ```BelieveObject``` describes Objects in the BulletWorld we create a few." ] }, { @@ -474,7 +474,7 @@ "metadata": {}, "source": [ "## Object Part \n", - "Part of object designators can be used to describe describe something as part of another obeject. For example, you could describe a specific drawer as part of the kitchen. This is necessary since the drawer is no single BulletWorld Object but rather a link of the kitchen which is a BulletWorld Object.\n", + "Part of object designators can be used to describe something as part of another object. For example, you could describe a specific drawer as part of the kitchen. This is necessary since the drawer is no single BulletWorld Object but rather a link of the kitchen which is a BulletWorld Object.\n", "\n", "For this example we need just need the kitchen, if you didn't spawn it in the previous example you can spawn it with the following cell." ] @@ -513,7 +513,7 @@ "## Object Designators as Generators \n", "Similar to location designators object designators can be used as generators to iterate through every object that they are describing. We will see this at the example of an object designator describing every type of food. \n", "\n", - "For this we need some obejcts, so if you didn't already spawn them you can use the next cell for this." + "For this we need some objects, so if you didn't already spawn them you can use the next cell for this." ] }, { @@ -861,8 +861,7 @@ " w: 1.0}, \n", "_current_joint_states={}, \n", "base_origin_shift=[0.00124406 0.00101732 0.1038567 ], \n", - "link_to_geometry={'cereal_main': })>) \n", - "\n" + "link_to_geometry={'cereal_main': })>) \n" ] } ], diff --git a/examples/pose.ipynb b/examples/pose.ipynb index f3f94093f..91443c79b 100644 --- a/examples/pose.ipynb +++ b/examples/pose.ipynb @@ -18,8 +18,8 @@ "source": [ "Before we start a few words about naming convention of Poses in PyCRAM. Naming convention is similar to the PoseStamped message so if you are familiar with that this should be easy. \n", "\n", - "* **Position:** A position means the position in cartisian space, so the x, y, and z coordinates. \n", - "* **Orientation:** An orientation is the rotation in all thre axes represented as a quaternion with x, y, z, w.\n", + "* **Position:** A position means the position in cartesian space, so the x, y, and z coordinates. \n", + "* **Orientation:** An orientation is the rotation in all three axes represented as a quaternion with x, y, z, w.\n", "* **Pose:** A pose is the combination of a position and an orientation. Poses in PyCRAM also contain a frame of reference to which the position and orientation are relative." ] }, @@ -192,8 +192,7 @@ "Set the position via method:\n", "x: 3\n", "y: 2\n", - "z: 1 \n", - "\n" + "z: 1 \n" ] } ], @@ -340,7 +339,7 @@ "metadata": {}, "source": [ "# Transforms\n", - "Transforms are similar to Poses but instead of representing a Pose in a frame of reference they represent a transformation from one frame of reference to another. For this purpose Transforms have an additioinal parameter called ```child_frame_id``` which is the frame of reference to which the Transform is pointing. \n", + "Transforms are similar to Poses but instead of representing a Pose in a frame of reference they represent a transformation from one frame of reference to another. For this purpose Transforms have an additional parameter called ```child_frame_id``` which is the frame of reference to which the Transform is pointing. \n", "\n", "Transforms in PyCRAM inherit from the TransformStamped message of ROS which makes them, like Poses, compatible to ROS services and topics that expect a TransformStamped message. Therefore, the naming conventions of Transforms are the same as of TransformStamped which. \n", "\n", @@ -392,7 +391,7 @@ "id": "acfe3d8c", "metadata": {}, "source": [ - "Transforms have the same methods to get and set values as Poses have, theresfore only a short showcase will be given. For more details please look at the Pose example or the API documentation." + "Transforms have the same methods to get and set values as Poses have, therefore only a short showcase will be given. For more details please look at the Pose example or the API documentation." ] }, { @@ -524,7 +523,7 @@ "* InverseTimes\n", "\n", "### Multiplication\n", - "We will first take a look at the multiplication of Transforms. We will use an example were we have two Transforms, the first from ```map``` to a ```hand``` frame and the second from the ```hand``` to a ```milk``` frame. By multiplicating these two we get the Transform from ```map``` to ```milk``` frame." + "We will first take a look at the multiplication of Transforms. We will use an example were we have two Transforms, the first from ```map``` to a ```hand``` frame and the second from the ```hand``` to a ```milk``` frame. By multiplying these two we get the Transform from ```map``` to ```milk``` frame." ] }, { @@ -624,7 +623,7 @@ "metadata": {}, "source": [ "### Inverse Times\n", - "Inverse times combines the inverting and multiplication of Transforms, this results in a 'minus' for Transforms. We will again use the examle of a hand holding a milk, but this time we have the Transforms from ```map``` to ```milk``` and ```hand``` to ```milk```. " + "Inverse times combines the inverting and multiplication of Transforms, this results in a 'minus' for Transforms. We will again use the example of a hand holding a milk, but this time we have the Transforms from ```map``` to ```milk``` and ```hand``` to ```milk```. " ] }, { From b2c2f5d3c3f435b6b7fb23dbc329809cd156719c Mon Sep 17 00:00:00 2001 From: Arthur Niedzwiecki Date: Wed, 17 Jan 2024 14:48:04 +0100 Subject: [PATCH 034/195] Add explanation to virtualenv and pycharm setup --- doc/source/installation.rst | 65 ++++++++++++++++++++++++++++++++----- 1 file changed, 57 insertions(+), 8 deletions(-) diff --git a/doc/source/installation.rst b/doc/source/installation.rst index 32625f5b1..dda84a2a1 100644 --- a/doc/source/installation.rst +++ b/doc/source/installation.rst @@ -112,6 +112,7 @@ Then install the Python packages in the requirements.txt file Building your ROS workspace =========================== +.. _build-ws: Building and sourcing your ROS workspace using catkin compiles all ROS packages and manages the appending to the respective PATH variables. This is necessary to be able to import PyCRAM via the Python import system and to find the @@ -160,6 +161,12 @@ After installing pandoc, install sphinx on your device. sudo apt install python3-sphinx +Install IPython + +.. code-block:: shell + + sudo pip3 install ipython + Install the requirements in your python interpreter. .. code-block:: shell @@ -180,27 +187,67 @@ Show the index. firefox build/html/index.html + Setting up PyCRAM with PyCharm ============================== -Setting up PyCharm with packages that rely on rospy is non trivial. Follow this guide to get correct syntax highlighting -for the PyCRAM project. +Setting up PyCharm with packages that rely on rospy is non trivial. Follow this guide to get correct syntax highlighting for the PyCRAM project. + +Install PyCharm Professional +---------------------------- First, `install PyCharm Professional `_. -Next, if you have virtual environments that you want to use, you need to make sure that they have rospy available. -If you create a new environment, make sure to include `--system-site-packages` in your creation command. -You can check by activating your environment and calling the import +Create a JetBrains account and verify it for educational purpose. Now you can unlock the PyCharm Professional features in PyCharm. + +The next step will set up the virtual Python environment, so it can be used as a project interpreter in PyCharm. + + +Set up virtualenv +----------------- +.. _virtualenv: + +The virtualenvwrapper allows to manage virtual Python environments, where additional packages can be installed without the risk of breaking the system-wide Python configuration. Install `virtualenvwrapper `_ via pip and set it up. + +.. code-block:: shell + + sudo pip3 install virtualenvwrapper + echo "export WORKON_HOME=~/envs" >> ~/.bashrc + echo "source /usr/local/bin/virtualenvwrapper.sh" >> ~/.bashrc + mkdir -p $WORKON_HOME + source ~/.bashrc + +Create a virtual env based on the workspaces libraries (see build-ws_) and add the `--system-site-packages` to get them properly. The env will be registered in `$WORKON_HOME`. .. code-block:: shell - workon your_env + source ~/workspace/ros/devel/setup.bash + mkvirtualenv pycram --system-site-packages + ls $WORKON_HOME + + +Check if the ROS libraries are available in the virtual env. + +.. code-block:: shell + + workon pycram python -c "import rospy" +If it complains about `python`, install the following, to set `python` to Python 3 by default. + +.. code-block:: shell + + sudo apt install python-is-python3 + +If it finds `python` but complains about missing packages, make sure that the workspace is sourced before creating the virtual env. Also remember to create the virtual env with the `--system-site-packages` flag. + If this returns no errors, you can be sure that rospy is usable in your virtual environment. Next you have to build the -ros workspace including pycram and source it as described in install-pycram_. +ros workspace including pycram and source it as described in build-ws_. -After that you have to start PyCharm from the terminal via +Configure PyCharm +----------------- + +Always start PyCharm from the terminal via .. code-block:: shell @@ -212,6 +259,7 @@ or ~/pycharm/bin/pycharm.sh + Select **File | Open** and select the root folder of the PyCRAM package. Next go to **File | Settings | Project: pycram | Python Interpreter** and set up your virtual environment with rospy and the sourced workspace available as the python interpreter. @@ -221,6 +269,7 @@ folder as Tests and the resources as Resources. To verify that it works, you can execute any Testcase. + Using IPython as REPL ===================== From ae10d6f2da43613f94c350ce72edba19f7ecd02d Mon Sep 17 00:00:00 2001 From: Nils Leusmann Date: Thu, 18 Jan 2024 14:29:40 +0100 Subject: [PATCH 035/195] Updates the reachability_validator to check all tool_frames for reachabilty, keeps the retrace pose in mind --- src/pycram/pose_generator_and_validator.py | 112 +++++++++------------ 1 file changed, 48 insertions(+), 64 deletions(-) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index f959fd126..0b39af7ee 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -6,7 +6,9 @@ from .bullet_world import Object, BulletWorld, Use_shadow_world from .bullet_world_reasoning import contact from .costmaps import Costmap +from .local_transformer import LocalTransformer from .pose import Pose, Transform +from .robot_description import ManipulatorDescription from .robot_descriptions import robot_description from .external_interfaces.ik import request_ik from .plan_failures import IKError @@ -70,7 +72,7 @@ def generate_orientation(position: List[float], origin: Pose) -> List[float]: robot should face. :return: A quaternion of the calculated orientation """ - angle = np.arctan2(position[1]-origin.position.y, position[0]-origin.position.x) + np.pi + angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi quaternion = list(tf.transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) return quaternion @@ -134,74 +136,56 @@ def reachability_validator(pose: Pose, target = target.get_pose() robot.set_pose(pose) - - left_gripper = robot_description.get_tool_frame('left') - right_gripper = robot_description.get_tool_frame('right') - - # left_joints = robot_description._safely_access_chains('left').joints - left_joints = robot_description.chains['left'].joints - # right_joints = robot_description._safely_access_chains('right').joints - right_joints = robot_description.chains['right'].joints - # TODO Make orientation adhere to grasping orientation - res = False - arms = [] + for name, chain in robot_description.chains.items(): + if isinstance(chain, ManipulatorDescription): + retract_traget_pose = LocalTransformer().transform_pose(target,robot.get_link_tf_frame(chain.tool_frame)) + #BulletWorld.robot.get_link_tf_frame(robot_description.get_tool_frame(chain.tool_frame))) + retract_traget_pose.position.x -= 0.07 # Care hard coded value copied from PlaceAction class + + joints = robot_description.chains[chain.name].joints + # TODO Make orientation adhere to grasping orientation + res = False + arms = [] + in_contact = False + + joint_state_before_ik = robot._current_joint_states + try: + # test the possible solution and apply it to the robot + resp = request_ik(target, robot, chain.joints, chain.tool_frame) + _apply_ik(robot, resp, joints) + + in_contact = collision_check(robot, allowed_collision) + if not in_contact: # only check for retract pose if pose worked + resp = request_ik(retract_traget_pose, robot, chain.joints, chain.tool_frame) + _apply_ik(robot, resp, joints) + in_contact = collision_check(robot, allowed_collision) + if not in_contact: + arms.append(chain.name) + res = True + except IKError: + pass + finally: + robot.set_joint_states(joint_state_before_ik) + + return res, arms + + +def collision_check(robot, allowed_collision): in_contact = False - allowed_robot_links = [] if robot in allowed_collision.keys(): allowed_robot_links = allowed_collision[robot] - joint_state_before_ik=robot._current_joint_states - try: - # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) - resp = request_ik(target, robot, left_joints, left_gripper) - - _apply_ik(robot, resp, left_joints) - - for obj in BulletWorld.current_bullet_world.objects: - if obj.name == "floor": - continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - - if in_contact: - for link in contact_links: - - if link[0] in allowed_robot_links or link[1] in allowed_links: - in_contact = False - - if not in_contact: - arms.append("left") - res = True - except IKError: - pass - finally: - robot.set_joint_states(joint_state_before_ik) - - try: - # resp = request_ik(base_link, end_effector, target_diff, robot, right_joints) - resp = request_ik(target, robot, right_joints, right_gripper) - - _apply_ik(robot, resp, right_joints) - - for obj in BulletWorld.current_bullet_world.objects: - if obj.name == "floor": - continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - - if in_contact: - for link in contact_links: + for obj in BulletWorld.current_bullet_world.objects: + if obj.name == "floor": + continue + in_contact, contact_links = contact(robot, obj, return_links=True) + allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - if link[0] in allowed_robot_links or link[1] in allowed_links: - in_contact = False + if in_contact: + for link in contact_links: - if not in_contact: - arms.append("right") - res = True - except IKError: - pass - finally: - robot.set_joint_states(joint_state_before_ik) + if link[0] in allowed_robot_links or link[1] in allowed_links: + in_contact = False - return res, arms + return in_contact From 04d2105f2fdd80385e7eb26944c1ae121d2ad2e3 Mon Sep 17 00:00:00 2001 From: Nils Leusmann Date: Thu, 18 Jan 2024 14:39:52 +0100 Subject: [PATCH 036/195] Fixes an error where only the first test would be sucessful --- test/test_database_merger.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/test/test_database_merger.py b/test/test_database_merger.py index f3e8b0472..56bd90bce 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -92,19 +92,17 @@ def setUpClass(cls) -> None: cls.source_engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False) cls.source_session_maker = sqlalchemy.orm.sessionmaker(bind=cls.source_engine) cls.destination_session_maker = sqlalchemy.orm.sessionmaker(bind=cls.destination_engine) - source_session = cls.source_session_maker() destination_session = cls.destination_session_maker() - pycram.orm.base.Base.metadata.create_all(cls.source_engine) pycram.orm.base.Base.metadata.create_all(cls.destination_engine) - source_session.commit() destination_session.commit() - source_session.close() destination_session.close() cls.numbers_of_example_runs = 3 def setUp(self) -> None: super().setUp() source_session = self.source_session_maker() + # If there is no session (connection to the memory database) it resets thus we need to define this here + pycram.orm.base.Base.metadata.create_all(self.source_engine) example_plans = ExamplePlans() for i in range(self.numbers_of_example_runs): try: @@ -151,7 +149,7 @@ def test_merge_databases(self): self.assertEqual(destination_content[key], destination_content[key].union(source_content[key])) def test_migrate_neems(self): - pycram.orm.utils.migrate_neems(self.source_session_maker,self.destination_session_maker) + pycram.orm.utils.migrate_neems(self.source_session_maker, self.destination_session_maker) destination_content = dict() source_content = dict() with self.destination_session_maker() as session: From 58a612176cadec5090071cd6bf53805ca304a495 Mon Sep 17 00:00:00 2001 From: Vanessa Hassouna Date: Thu, 18 Jan 2024 15:57:47 +0100 Subject: [PATCH 037/195] [submodule] deleted submodule macropy, since it is no longer used due the new pycram language --- .gitmodules | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.gitmodules b/.gitmodules index 63abede05..a87f5a181 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,6 +1,4 @@ [submodule "src/neem_interface_python"] path = src/neem_interface_python url = https://github.com/Tigul/neem_interface_python -[submodule "src/macropy"] - path = src/macropy - url = https://github.com/Tigul/macropy.git + From 34fd070f39f2e2ad3bd0539ae05868fb4b79daf0 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Thu, 18 Jan 2024 17:06:34 +0100 Subject: [PATCH 038/195] [AbstractWorld] Implemented save and restore state for World, Object, and Link classes. Added tests for Object, Attachment, and Link Classes. --- src/pycram/pose.py | 8 +-- src/pycram/world.py | 110 ++++++++++++++++++++++++++++---------- test/test_attachment.py | 42 +++++++++++++++ test/test_bullet_world.py | 14 +++++ test/test_links.py | 27 ++++++++++ test/test_object.py | 42 +++++++++++++++ 6 files changed, 212 insertions(+), 31 deletions(-) create mode 100644 test/test_attachment.py create mode 100644 test/test_links.py create mode 100644 test/test_object.py diff --git a/src/pycram/pose.py b/src/pycram/pose.py index e707aaa61..cd30c2d4b 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -9,7 +9,7 @@ import numpy as np import rospy import sqlalchemy.orm -from geometry_msgs.msg import PoseStamped, TransformStamped, Vector3 +from geometry_msgs.msg import PoseStamped, TransformStamped, Vector3, Point from geometry_msgs.msg import (Pose as GeoPose, Quaternion as GeoQuaternion) from std_msgs.msg import Header from tf import transformations @@ -87,7 +87,7 @@ def frame(self, value: str) -> None: self.header.frame_id = value @property - def position(self) -> GeoPose: + def position(self) -> Point: """ Property that points to the position of this pose """ @@ -168,6 +168,8 @@ def copy(self) -> Pose: :return: A copy of this pose """ + if isinstance(self.position, list): + print("Position is list") p = Pose(self.position_as_list(), self.orientation_as_list(), self.frame, self.header.stamp) p.header.frame_id = self.header.frame_id # p.header.stamp = self.header.stamp @@ -179,7 +181,7 @@ def position_as_list(self) -> List[float]: :return: The position as a list """ - return [self.pose.position.x, self.pose.position.y, self.pose.position.z] + return [self.position.x, self.position.y, self.position.z] def orientation_as_list(self) -> List[float]: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index 4b00f1f73..e3eb38116 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -13,6 +13,7 @@ from tf.transformations import quaternion_from_euler from typing import List, Optional, Dict, Tuple, Callable from typing import Union +from copy import deepcopy import numpy as np import rospkg @@ -40,6 +41,7 @@ class WorldState: state_id: int attachments: Dict[Object, Dict[Object, Attachment]] + @dataclass class CollisionCallbacks: obj_1: Object @@ -594,9 +596,13 @@ def save_state(self) -> int: :return: A unique id of the state """ state_id = self.save_physics_simulator_state() - self._saved_states[state_id] = WorldState(state_id, self.get_objects_attachments()) + self.save_objects_state(state_id) return state_id + def save_objects_state(self, state_id: int): + for obj in self.objects: + obj.save_state(state_id) + def restore_state(self, state_id) -> None: """ Restores the state of the World according to the given state using the unique state id. This includes position, @@ -606,7 +612,7 @@ def restore_state(self, state_id) -> None: :param state_id: The unique id representing the state, as returned by :func:`~save_state` """ self.restore_physics_simulator_state(state_id) - self.restore_attachments_from_saved_world_state(state_id) + self.restore_objects_states(state_id) @abstractmethod def save_physics_simulator_state(self) -> int: @@ -615,30 +621,17 @@ def save_physics_simulator_state(self) -> int: """ pass - def get_objects_attachments(self) -> Dict[Object, Dict[Object, Attachment]]: - """ - Get The attachments collections that is stored in each object. - """ - attachments = {} - for o in self.objects: - attachments[o] = o.attachments.copy() - return attachments - @abstractmethod - def restore_physics_simulator_state(self, state_id): + def restore_physics_simulator_state(self, state_id: int): """ Restores the objects and environment state in the physics simulator according to the given state using the unique state id. """ pass - def restore_attachments_from_saved_world_state(self, state_id: int): - attachments = self._saved_states[state_id].attachments + def restore_objects_states(self, state_id: int): for obj in self.objects: - try: - obj.attachments = attachments[obj] - except KeyError: - continue + obj.restore_state(state_id) def _copy(self) -> World: """ @@ -857,6 +850,11 @@ def check_for_equal(self) -> None: self.equal_states = eql +@dataclass +class LinkState: + constraint_ids: Dict[Link, int] + + class Link: def __init__(self, @@ -869,13 +867,35 @@ def __init__(self, self.world = obj.world self.local_transformer = LocalTransformer() self.constraint_ids: Dict[Link, int] = {} + self.saved_states: Dict[int, LinkState] = {} + + def save_state(self, state_id: int) -> None: + """ + Saves the state of this link, this includes the pose of the link. + """ + self.saved_states[state_id] = self.get_current_state() + + def restore_state(self, state_id: int) -> None: + """ + Restores the state of this link, this includes the pose of the link. + """ + self.constraint_ids = self.saved_states[state_id].constraint_ids + + def get_current_state(self): + return LinkState(self.constraint_ids.copy()) - def add_fixed_constraint_with_link(self, child_link: Link) -> None: + def add_fixed_constraint_with_link(self, child_link: Link) -> int: constraint_id = self.world.add_fixed_constraint(self, child_link, child_link.get_transform_from_link(self)) self.constraint_ids[child_link] = constraint_id child_link.constraint_ids[self] = constraint_id + return constraint_id + + def remove_constraint_with_link(self, child_link: Link) -> None: + self.world.remove_constraint(self.constraint_ids[child_link]) + del self.constraint_ids[child_link] + del child_link.constraint_ids[self] def get_object_id(self) -> int: return self.object.id @@ -963,11 +983,6 @@ def color(self) -> Color: def color(self, color: Color) -> None: self.world.set_object_link_color(self.object, self.id, color) - def remove_constraint_with(self, child_link: Link) -> None: - self.world.remove_constraint(self.constraint_ids[child_link]) - del self.constraint_ids[child_link] - del child_link.constraint_ids[self] - class RootLink(Link): @@ -983,6 +998,12 @@ def pose(self) -> Pose: return self.object.get_pose() +@dataclass +class ObjectState: + state_id: int + attachments: Dict[Object, Attachment] + + class Object: """ Represents a spawned Object in the World. @@ -1030,6 +1051,8 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) self.attachments: Dict[Object, Attachment] = {} + self.saved_states: Dict[int, ObjectState] = {} + # takes the state id as key and returns the attachments of the object at that state self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) @@ -1158,7 +1181,7 @@ def detach_all(self) -> None: def update_attachment_with_object(self, child_object: Object): self.attachments[child_object].update_transform_and_constraint() - def get_position(self) -> Pose.position: + def get_position(self) -> Point: """ Returns the position of this Object as a list of xyz. @@ -1207,11 +1230,14 @@ def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Op :param set_attachments: Whether to set the poses of the attached objects to this object or not. """ pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") + position, orientation = pose_in_map.to_list() if base: position = np.array(position) + self.base_origin_shift + self.world.reset_object_base_pose(self, position, orientation) self._current_pose = pose_in_map + if set_attachments: self._set_attached_objects_poses() @@ -1222,6 +1248,31 @@ def move_base_to_origin_pos(self) -> None: """ self.set_pose(self.get_pose(), base=True) + def save_state(self, state_id): + self.save_links_states(state_id) + self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) + + def save_links_states(self, state_id: int): + for link in self.links.values(): + link.save_state(state_id) + + def restore_state(self, state_id: int): + self.restore_links_states(state_id) + self.restore_attachments(state_id) + + def restore_attachments(self, state_id): + self.attachments = self.saved_states[state_id].attachments + + def restore_links_states(self, state_id): + for link in self.links.values(): + link.restore_state(state_id) + + def set_object_state(self, obj_state:ObjectState): + self.set_attachments(obj_state.attachments) + + def set_attachments(self, attachments: Dict[Object, Attachment]) -> None: + self.attachments = attachments + def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: """ Updates the positions of all attached objects. This is done @@ -1264,8 +1315,10 @@ def set_position(self, position: Union[Pose, Point], base=False) -> None: if isinstance(position, Pose): target_position = position.position pose.frame = position.frame - else: + elif isinstance(position, Point): target_position = position + else: + raise TypeError("The position has to be either a Pose or a Point") pose.pose.position = target_position pose.pose.orientation = self.get_orientation() @@ -1634,14 +1687,15 @@ def update_constraint(self): self.add_fixed_constraint() def add_fixed_constraint(self): - self.parent_link.add_fixed_constraint_with_link(self.child_link) + cid = self.parent_link.add_fixed_constraint_with_link(self.child_link) + self.constraint_id = cid def calculate_transform(self): return self.parent_link.get_transform_to_link(self.child_link) def remove_constraint_if_exists(self): if self.child_link in self.parent_link.constraint_ids: - self.parent_link.remove_constraint_with(self.child_link) + self.parent_link.remove_constraint_with_link(self.child_link) def get_inverse(self): attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, diff --git a/test/test_attachment.py b/test/test_attachment.py new file mode 100644 index 000000000..d99cb05fc --- /dev/null +++ b/test/test_attachment.py @@ -0,0 +1,42 @@ +import test_bullet_world + + +class TestAttachment(test_bullet_world.BulletWorldTest): + + def test_attach(self): + self.milk.attach(self.robot) + self.assertTrue(self.milk.attachments[self.robot]) + self.assertTrue(self.robot.attachments[self.milk]) + + def test_detach(self): + self.milk.attach(self.robot) + self.milk.detach(self.robot) + self.assertTrue(self.robot not in self.milk.attachments) + self.assertTrue(self.milk not in self.robot.attachments) + + def test_attachment_behavior(self): + self.robot.attach(self.milk) + + milk_pos = self.milk.get_position() + rob_pos = self.robot.get_position() + + rob_pos.x += 1 + self.robot.set_position(rob_pos) + + new_milk_pos = self.milk.get_position() + self.assertEqual(new_milk_pos.x, milk_pos.x + 1) + + def test_detachment_behavior(self): + self.robot.attach(self.milk) + + milk_pos = self.milk.get_position() + rob_pos = self.robot.get_position() + + self.robot.detach(self.milk) + rob_pos.x += 1 + self.robot.set_position(rob_pos) + + new_milk_pos = self.milk.get_position() + self.assertEqual(new_milk_pos.x, milk_pos.x) + + diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 6e62cd458..d847957bc 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -39,6 +39,20 @@ def test_robot_orientation(self): self.robot.set_orientation(Pose(orientation=[0, 0, 1, 1])) self.assertEqual(self.robot.links['head_pan_link'].position.z, head_position) + def test_save_and_restore_state(self): + self.robot.attach(self.milk) + state_id = self.world.save_state() + robot_link = self.robot.get_root_link() + milk_link = self.milk.get_root_link() + cid = robot_link.constraint_ids[milk_link] + self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) + self.world.remove_constraint(cid) + self.world.restore_state(state_id) + cid = robot_link.constraint_ids[milk_link] + self.assertTrue(milk_link in robot_link.constraint_ids) + self.assertTrue(self.milk in self.robot.attachments) + self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) + def tearDown(self): self.world.reset_world() diff --git a/test/test_links.py b/test/test_links.py new file mode 100644 index 000000000..0115c8c48 --- /dev/null +++ b/test/test_links.py @@ -0,0 +1,27 @@ +import test_bullet_world + + +class TestLinks(test_bullet_world.BulletWorldTest): + + def test_add_constraint(self): + milk_link = self.milk.get_root_link() + robot_link = self.robot.get_root_link() + robot_link.add_fixed_constraint_with_link(milk_link) + self.assertTrue(milk_link in robot_link.constraint_ids) + self.assertTrue(robot_link in milk_link.constraint_ids) + + def test_remove_constraint(self): + milk_link = self.milk.get_root_link() + robot_link = self.robot.get_root_link() + robot_link.add_fixed_constraint_with_link(milk_link) + robot_link.remove_constraint_with_link(milk_link) + self.assertTrue(milk_link not in robot_link.constraint_ids) + self.assertTrue(robot_link not in milk_link.constraint_ids) + + def test_transform_link(self): + milk_link = self.milk.get_root_link() + robot_link = self.robot.get_root_link() + milk_to_robot = milk_link.get_transform_to_link(robot_link) + robot_to_milk = robot_link.get_transform_to_link(milk_link) + self.assertAlmostEqual(robot_to_milk, milk_to_robot.invert()) + diff --git a/test/test_object.py b/test/test_object.py new file mode 100644 index 000000000..f04866517 --- /dev/null +++ b/test/test_object.py @@ -0,0 +1,42 @@ +import test_bullet_world +from pycram.pose import Pose +from geometry_msgs.msg import Point + + +class TestObject(test_bullet_world.BulletWorldTest): + + def test_set_position_as_point(self): + p = Point() + p.x = 1 + p.y = 2 + p.z = 3 + self.milk.set_position(p) + self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + + def test_set_position_as_pose(self): + self.milk.set_position(Pose([1, 2, 3])) + self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + + def test_save_state(self): + self.robot.attach(self.milk, parent_link="r_gripper_palm_link") + self.robot.save_state(1) + self.assertEqual(self.robot.saved_states[1].attachments, self.robot.attachments) + self.assertTrue(self.milk in self.robot.saved_states[1].attachments) + for link in self.robot.links.values(): + self.assertEqual(link.get_current_state(), link.saved_states[1]) + + def test_restore_state(self): + self.robot.attach(self.milk) + self.robot.save_state(1) + self.milk.save_state(1) + self.assertTrue(self.milk in self.robot.attachments) + self.robot.detach(self.milk) + self.assertTrue(self.milk not in self.robot.attachments) + self.robot.restore_state(1) + self.milk.restore_state(1) + self.assertTrue(self.milk in self.robot.attachments) + for link in self.robot.links.values(): + curr_state = link.get_current_state() + saved_state = link.saved_states[1] + self.assertEqual(curr_state, saved_state) + self.assertEqual(curr_state.constraint_ids, saved_state.constraint_ids) \ No newline at end of file From b1f2a35a9e05f600be67da1419e4685fca3789c3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Thu, 18 Jan 2024 18:58:58 +0100 Subject: [PATCH 039/195] [designator] removed MotionDesignatorDescription --- src/pycram/designator.py | 99 +- src/pycram/designators/actions/actions.py | 54 +- src/pycram/designators/motion_designator.py | 864 +++++++----------- src/pycram/process_module.py | 12 +- .../process_modules/boxy_process_modules.py | 25 +- .../process_modules/donbot_process_modules.py | 4 +- .../process_modules/pr2_process_modules.py | 46 +- test/local_transformer_tests.py | 2 +- 8 files changed, 386 insertions(+), 720 deletions(-) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 2319fe2dc..26d9e9efd 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -9,6 +9,7 @@ import rospy from .bullet_world import (Object as BulletWorldObject, BulletWorld) +from .enums import ObjectType from .helper import GeneratorList, bcolors from threading import Lock from time import time @@ -22,7 +23,6 @@ from .orm.action_designator import (Action as ORMAction) from .orm.object_designator import (Object as ORMObjectDesignator) -from .orm.motion_designator import (Motion as ORMMotionDesignator) from .orm.base import Quaternion, Position, Base, RobotState, ProcessMetaData from .task import with_tree @@ -361,103 +361,6 @@ def copy(self) -> Type[DesignatorDescription]: return self -class MotionDesignatorDescription(DesignatorDescription): - """ - Parent class of motion designator descriptions. - """ - - @dataclass - class Motion: - """ - Resolved motion designator which can be performed - """ - cmd: str - """ - Command of this motion designator, is used to match process modules to motion designator. Cmd is inherited by - every motion designator. - """ - - @with_tree - def perform(self): - """ - Passes this designator to the process module for execution. - - :return: The return value of the process module if there is any. - """ - raise NotImplementedError() - # return ProcessModule.perform(self) - - def to_sql(self) -> ORMMotionDesignator: - """ - Create an ORM object that corresponds to this description. - - :return: The created ORM object. - """ - return ORMMotionDesignator() - - def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: - """ - Add and commit this and all related objects to the session. - Auto-Incrementing primary keys and foreign keys have to be filled by this method. - - :param session: Session with a database that is used to add and commit the objects - :return: The completely instanced ORM motion. - """ - metadata = ProcessMetaData().insert(session) - - motion = self.to_sql() - motion.process_metadata_id = metadata.id - - return motion - - def ground(self) -> Motion: - """Fill all missing parameters and pass the designator to the process module. """ - raise NotImplementedError(f"{type(self)}.ground() is not implemented.") - - def __init__(self, resolver=None): - """ - Creates a new motion designator description - - :param resolver: An alternative resolver which overrides self.resolve() - """ - super().__init__(resolver) - - def get_slots(self): - """ - Returns a list of all slots of this description. Can be used for inspecting - different descriptions and debugging. - - :return: A list of all slots. - """ - return list(self.__dict__.keys()).remove('cmd') - - def _check_properties(self, desig: str, exclude: List[str] = []) -> None: - """ - Checks the properties of this description. It will be checked if any attribute is - None and if any attribute has to wrong type according to the type hints in - the description class. - It is possible to provide a list of attributes which should not be checked. - - :param desig: The current type of designator, will be used when raising an - Exception as output. - :param exclude: A list of properties which should not be checked. - """ - right_types = get_type_hints(self.Motion) - attributes = self.__dict__.copy() - del attributes["resolve"] - missing = [] - wrong_type = {} - current_type = {} - for k in attributes.keys(): - if attributes[k] == None and not attributes[k] in exclude: - missing.append(k) - elif type(attributes[k]) != right_types[k] and not attributes[k] in exclude: - wrong_type[k] = right_types[k] - current_type[k] = type(attributes[k]) - if missing != [] or wrong_type != {}: - raise ResolutionError(missing, wrong_type, current_type, desig) - - class ActionDesignatorDescription(DesignatorDescription): """ Abstract class for action designator descriptions. diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index add4bc650..ef47227ef 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -4,9 +4,10 @@ from pycram.designators.motion_designator import * from pycram.enums import Arms from pycram.task import with_tree -from dataclasses import dataclass +from dataclasses import dataclass, field from ..location_designator import CostmapLocation from ..object_designator import BelieveObject +from ...bullet_world import BulletWorld from ...helper import multiply_quaternions from ...local_transformer import LocalTransformer from ...orm.base import Base @@ -53,15 +54,20 @@ class ParkArmsActionPerformable(ActionAbstract): def perform(self) -> None: # create the keyword arguments kwargs = dict() + left_poses = None + right_poses = None # add park left arm if wanted if self.arm in [Arms.LEFT, Arms.BOTH]: kwargs["left_arm_config"] = "park" + left_poses = robot_description.get_static_joint_chain("left", kwargs["left_arm_config"]) # add park right arm if wanted if self.arm in [Arms.RIGHT, Arms.BOTH]: kwargs["right_arm_config"] = "park" - MoveArmJointsMotion(**kwargs).resolve().perform() + right_poses = robot_description.get_static_joint_chain("right", kwargs["right_arm_config"]) + + MoveArmJointsMotion(left_poses, right_poses).perform() def to_sql(self) -> ORMParkArmsAction: return ORMParkArmsAction(self.arm.name) @@ -86,7 +92,7 @@ class MoveTorsoActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - MoveJointsMotion([robot_description.torso_joint], [self.position]).resolve().perform() + MoveJointsMotion([robot_description.torso_joint], [self.position]).perform() def to_sql(self) -> ORMMoveTorsoAction: return ORMMoveTorsoAction(self.position) @@ -112,7 +118,7 @@ class SetGripperActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - MoveGripperMotion(gripper=self.gripper, motion=self.motion).resolve().perform() + MoveGripperMotion(gripper=self.gripper, motion=self.motion).perform() def to_sql(self) -> ORMSetGripperAction: return ORMSetGripperAction(self.gripper, self.motion) @@ -177,7 +183,7 @@ class PickUpActionPerformable(ActionAbstract): The grasp that should be used. For example, 'left' or 'right' """ - object_at_execution: Optional[ObjectDesignatorDescription.Object] = dataclasses.field(init=False) + object_at_execution: Optional[ObjectDesignatorDescription.Object] = field(init=False) """ The object at the time this Action got created. It is used to be a static, information holding entity. It is not updated when the BulletWorld object is changed. @@ -231,20 +237,20 @@ def perform(self) -> None: # Perform the motion with the prepose and open gripper BulletWorld.current_bullet_world.add_vis_axis(prepose) - MoveTCPMotion(prepose, self.arm).resolve().perform() - MoveGripperMotion(motion="open", gripper=self.arm).resolve().perform() + MoveTCPMotion(prepose, self.arm).perform() + MoveGripperMotion(motion="open", gripper=self.arm).perform() # Perform the motion with the adjusted pose -> actual grasp and close gripper BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() + MoveTCPMotion(adjusted_oTm, self.arm).perform() adjusted_oTm.pose.position.z += 0.03 - MoveGripperMotion(motion="close", gripper=self.arm).resolve().perform() + MoveGripperMotion(motion="close", gripper=self.arm).perform() tool_frame = robot_description.get_tool_frame(self.arm) robot.attach(object, tool_frame) # Lift object BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() + MoveTCPMotion(adjusted_oTm, self.arm).perform() # Remove the vis axis from the world BulletWorld.current_bullet_world.remove_vis_axis() @@ -292,12 +298,12 @@ def perform(self) -> None: target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() - MoveTCPMotion(target_diff, self.arm).resolve().perform() - MoveGripperMotion("open", self.arm).resolve().perform() + MoveTCPMotion(target_diff, self.arm).perform() + MoveGripperMotion("open", self.arm).perform() BulletWorld.robot.detach(self.object_designator.bullet_world_object) retract_pose = target_diff retract_pose.position.x -= 0.07 - MoveTCPMotion(retract_pose, self.arm).resolve().perform() + MoveTCPMotion(retract_pose, self.arm).perform() def to_sql(self) -> ORMPlaceAction: return ORMPlaceAction(self.arm) @@ -327,7 +333,7 @@ class NavigateActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - MoveMotion(self.target_location).resolve().perform() + MoveMotion(self.target_location).perform() def to_sql(self) -> ORMNavigateAction: return ORMNavigateAction() @@ -419,7 +425,7 @@ class LookAtActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - LookingMotion(target=self.target).resolve().perform() + LookingMotion(target=self.target).perform() def to_sql(self) -> ORMLookAtAction: return ORMLookAtAction() @@ -445,7 +451,7 @@ class DetectActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - return DetectingMotion(object_type=self.object_designator.type).resolve().perform() + return DetectingMotion(object_type=self.object_designator.type).perform() def to_sql(self) -> ORMDetectAction: return ORMDetectAction() @@ -477,9 +483,9 @@ class OpenActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: GraspingActionPerformable(self.arm, self.object_designator).perform() - OpeningMotion(self.object_designator, self.arm).resolve().perform() + OpeningMotion(self.object_designator, self.arm).perform() - MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() + MoveGripperMotion("open", self.arm, allow_gripper_collision=True).perform() def to_sql(self) -> ORMOpenAction: return ORMOpenAction(self.arm) @@ -511,9 +517,9 @@ class CloseActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: GraspingActionPerformable(self.arm, self.object_designator).perform() - ClosingMotion(self.object_designator, self.arm).resolve().perform() + ClosingMotion(self.object_designator, self.arm).perform() - MoveGripperMotion("open", self.arm, allow_gripper_collision=True).resolve().perform() + MoveGripperMotion("open", self.arm, allow_gripper_collision=True).perform() def to_sql(self) -> ORMCloseAction: return ORMCloseAction(self.arm) @@ -557,11 +563,11 @@ def perform(self) -> None: pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 - MoveTCPMotion(pre_grasp, self.arm).resolve().perform() - MoveGripperMotion("open", self.arm).resolve().perform() + MoveTCPMotion(pre_grasp, self.arm).perform() + MoveGripperMotion("open", self.arm).perform() - MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).resolve().perform() - MoveGripperMotion("close", self.arm, allow_gripper_collision=True).resolve().perform() + MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).perform() + MoveGripperMotion("close", self.arm, allow_gripper_collision=True).perform() def to_sql(self) -> ORMGraspingAction: return ORMGraspingAction(self.arm) diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index c6535a3a6..2ad0f6adb 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -1,691 +1,459 @@ -import dataclasses +import abc +import typing +from abc import ABC, abstractmethod +from dataclasses import dataclass from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..bullet_world import Object, BulletWorld -from ..designator import DesignatorError +from ..designator import ResolutionError +from ..enums import ObjectType +from ..orm.base import ProcessMetaData from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager -from ..robot_descriptions import robot_description -from ..designator import MotionDesignatorDescription from ..orm.motion_designator import (MoveMotion as ORMMoveMotion, AccessingMotion as ORMAccessingMotion, MoveTCPMotion as ORMMoveTCPMotion, LookingMotion as ORMLookingMotion, MoveGripperMotion as ORMMoveGripperMotion, DetectingMotion as ORMDetectingMotion, WorldStateDetectingMotion as ORMWorldStateDetectingMotion, - OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion) + OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion, + Motion as ORMMotionDesignator) -from typing import List, Dict, Callable, Optional +from typing import List, Dict, Callable, Optional, get_type_hints, Union, Any from ..pose import Pose from ..task import with_tree -class MoveMotion(MotionDesignatorDescription): - """ - Moves the robot to a designated location - """ +@dataclass +class BaseMotion(ABC): - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - target: Pose + @abstractmethod + def perform(self): """ - Location to which the robot should be moved + Passes this designator to the process module for execution. + + :return: The return value of the process module if there is any. """ + pass + # return ProcessModule.perform(self) - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.navigate().execute(self) - # return ProcessModule.perform(self) + @abstractmethod + def to_sql(self) -> ORMMotionDesignator: + """ + Create an ORM object that corresponds to this description. - def to_sql(self) -> ORMMoveMotion: - return ORMMoveMotion() + :return: The created ORM object. + """ + return ORMMotionDesignator() - def insert(self, session, *args, **kwargs) -> ORMMoveMotion: - motion = super().insert(session) + @abstractmethod + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + """ + Add and commit this and all related objects to the session. + Auto-Incrementing primary keys and foreign keys have to be filled by this method. - pose = self.target.insert(session) - motion.pose_id = pose.id + :param session: Session with a database that is used to add and commit the objects + :return: The completely instanced ORM motion. + """ + metadata = ProcessMetaData().insert(session) - session.add(motion) - session.commit() + motion = self.to_sql() + motion.process_metadata_id = metadata.id - return motion + return motion - def __init__(self, target: Pose, resolver: Callable = None): - """ - Navigates to robot to the given target + def __post_init__(self): + right_types = get_type_hints(self) + attributes = self.__dict__.copy() - :param target: Position and Orientation of the navigation goal - :param resolver: A method with which to resolve the description - """ - super().__init__(resolver) - self.cmd: str = "navigate" - self.target: Pose = target + missing = [] + wrong_type = {} + current_type = {} - def ground(self) -> Motion: - """ - Default resolver for moving the robot, this resolver simply creates the motion designator from the input of the - designator description. + for k in attributes.keys(): + attribute = attributes[k] + attribute_type = type(attributes[k]) + right_type = right_types[k] + types = typing.get_args(right_type) + if attribute is None: + if not any([x is type(None) for x in typing.get_args(right_type)]): + missing.append(k) + elif attribute_type is not right_type: + if attribute_type not in types: + if attribute_type not in [typing.get_origin(x) for x in types if x is not type(None)]: + wrong_type[k] = right_types[k] + current_type[k] = attribute_type + if missing != [] or wrong_type != {}: + raise ResolutionError(missing, wrong_type, current_type, self.__class__) - :return: A resolved and performable motion designator - """ - return self.Motion(self.cmd, self.target) +@dataclass +class MoveMotion(BaseMotion): + """ + Moves the robot to a designated location + """ -class PickUpMotion(MotionDesignatorDescription): + target: Pose """ - Lets the robot pick up a specific object + Location to which the robot should be moved """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object_desig: ObjectDesignatorDescription.Object - """ - Object designator describing the object to be picked up - """ - arm: str - """ - Arm that should be used for picking up the object - """ - grasp: str - """ - From which direction the object should be grasped, e.g. 'left', 'front', etc. - """ + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.navigate().execute(self) + # return ProcessModule.perform(self) - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.pick_up().execute(self) + def to_sql(self) -> ORMMoveMotion: + return ORMMoveMotion() - def __init__(self, object_desig: ObjectDesignatorDescription.Object, grasp: str = None, arm: str = None, - resolver: Callable = None): - """ - Motion designator implementation of the robot picking up an object. The robot will move its arm to the position - of the object and attach the object to the gripper of the robot. + def insert(self, session, *args, **kwargs) -> ORMMoveMotion: + motion = super().insert(session) - :param object_desig: Object designator of the object to be picked up - :param grasp: From which direction the object should be picked up - :param arm: Which arm should be used for picking up - :param resolver: Alternative resolver that produces a resolved and performable motion deisgnator - """ - super().__init__(resolver) - self.cmd: str = 'pick-up' - self.object_desig: ObjectDesignatorDescription.Object = object_desig - self.arm: Optional[str] = arm - self.grasp: Optional[str] = grasp + pose = self.target.insert(session) + motion.pose_id = pose.id - def ground(self): - """ - Default resolver for picking up. Checks if all parameter are present and will fill missing parameter. Optional - parameter ``arm`` and ``grasp`` will default to ``'left'``. + session.add(motion) + session.commit() - :return: A resolved motion designator that can be performed - """ - arm = "left" if not self.arm else self.arm - grasp = "left" if not self.grasp else self.grasp - return self.Motion(self.cmd, self.object_desig, arm, grasp) + return motion -class PlaceMotion(MotionDesignatorDescription): +@dataclass +class PickUpMotion(BaseMotion): """ - Lets the robot place an object that was picked up + Lets the robot pick up a specific object """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object: ObjectDesignatorDescription.Object - """ - Object designator of the object to be placed - """ - target: Pose - """ - Pose at which the object should be placed - """ - arm: str - """ - Arm that is currently holding the object - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.place().execute(self) + object_desig: ObjectDesignatorDescription.Object + """ + Object designator describing the object to be picked up + """ + arm: str + """ + Arm that should be used for picking up the object + """ + grasp: str + """ + From which direction the object should be grasped, e.g. 'left', 'front', etc. + """ - def __init__(self, object_desig: ObjectDesignatorDescription.Object, target: Pose, - arm: Optional[str] = None, resolver: Optional[Callable] = None): - """ - Places the object in object_desig at the position in target. If an arm is given then the arm is used, otherwise - arm defaults to ``'left'`` + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.pick_up().execute(self) - :param object_desig: Object designator describing the object to be placed - :param target: The target pose on which to place the object - :param arm: An arm to use for placing - :param resolver: An alternative resolver that resolves the list of parameters to a resolved motion designator. - """ - super().__init__(resolver) - self.cmd: str = 'place' - self.object_desig: ObjectDesignatorDescription.Object = object_desig - self.target: Pose = target - self.arm: str = arm + def to_sql(self) -> ORMMotionDesignator: + pass - def ground(self) -> Motion: - """ - Default resolver for placing an object which returns a resolved motion designator for the input. If no arm is - given then the arm parameter will default to ``'left'``. + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + pass - :return: A resolved performable motion designator - """ - arm = "left" if not self.arm else self.arm - return self.Motion(self.cmd, self.object_desig, self.target, arm) +@dataclass +class PlaceMotion(BaseMotion): + """ + Lets the robot place an object that was picked up + """ -class MoveTCPMotion(MotionDesignatorDescription): + object: ObjectDesignatorDescription.Object """ - Moves the Tool center point (TCP) of the robot + Object designator of the object to be placed + """ + target: Pose + """ + Pose at which the object should be placed + """ + arm: str + """ + Arm that is currently holding the object """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - target: Pose - """ - Target pose to which the TCP should be moved - """ - arm: str - """ - Arm with the TCP that should be moved to the target - """ - allow_gripper_collision: bool - """ - If the gripper can collide with something - """ + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.place().execute(self) - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.move_tcp().execute(self) + def to_sql(self) -> ORMMotionDesignator: + pass - def to_sql(self) -> ORMMoveTCPMotion: - return ORMMoveTCPMotion(self.arm, self.allow_gripper_collision) + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + pass - def insert(self, session: Session, *args, **kwargs) -> ORMMoveTCPMotion: - motion = super().insert(session) - pose = self.target.insert(session) - motion.pose_id = pose.id +@dataclass +class MoveTCPMotion(BaseMotion): + """ + Moves the Tool center point (TCP) of the robot + """ + + target: Pose + """ + Target pose to which the TCP should be moved + """ + arm: str + """ + Arm with the TCP that should be moved to the target + """ + allow_gripper_collision: Optional[bool] = None + """ + If the gripper can collide with something + """ - session.add(motion) - session.commit() + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.move_tcp().execute(self) - return motion + def to_sql(self) -> ORMMoveTCPMotion: + return ORMMoveTCPMotion(self.arm, self.allow_gripper_collision) - def __init__(self, target: Pose, arm: Optional[str] = None, - resolver: Optional[Callable] = None, allow_gripper_collision: Optional[bool] = None): - """ - Moves the TCP of the given arm to the given target pose. + def insert(self, session: Session, *args, **kwargs) -> ORMMoveTCPMotion: + motion = super().insert(session) - :param target: Target pose for the TCP - :param arm: Arm that should be moved - :param resolver: Alternative resolver which returns a resolved motion designator - :param allow_gripper_collision: If the gripper should be allowed to collide with something, only used on the real robot - """ - super().__init__(resolver) - self.cmd: str = 'move-tcp' - self.target: Pose = target - self.arm: Optional[str] = arm - self.allow_gripper_collision = allow_gripper_collision + pose = self.target.insert(session) + motion.pose_id = pose.id - def ground(self) -> Motion: - """ - Default resolver that returns a resolved motion designator, arm defaults to ``'left'`` if no arm is given. + session.add(motion) + session.commit() - :return: A resolved motion designator - """ - arm = "left" if not self.arm else self.arm - return self.Motion(self.cmd, self.target, arm, self.allow_gripper_collision) + return motion -class LookingMotion(MotionDesignatorDescription): +@dataclass +class LookingMotion(BaseMotion): """ Lets the robot look at a point """ + target: Pose - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - target: Pose - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.looking().execute(self) - - def to_sql(self) -> ORMLookingMotion: - return ORMLookingMotion() - - def insert(self, session: Session, *args, **kwargs) -> ORMLookingMotion: - motion = super().insert(session) - - pose = self.target.insert(session) - motion.pose_id = pose.id - - session.add(motion) - session.commit() + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.looking().execute(self) - return motion + def to_sql(self) -> ORMLookingMotion: + return ORMLookingMotion() - def __init__(self, target: Optional[Pose] = None, object: Optional[ObjectDesignatorDescription.Object] = None, - resolver: Optional[Callable] = None): - """ - Moves the head of the robot such that the camera points towards the given location. If ``target`` and ``object`` - are given ``target`` will be preferred. + def insert(self, session: Session, *args, **kwargs) -> ORMLookingMotion: + motion = super().insert(session) - :param target: Position and orientation of the target - :param object: An Object in the BulletWorld - :param resolver: Alternative resolver that returns a resolved motion designator for parameter - """ - super().__init__(resolver) - self.cmd: str = 'looking' - self.target: Optional[Pose] = target - self.object: Object = object.bullet_world_object if object else object + pose = self.target.insert(session) + motion.pose_id = pose.id - def ground(self) -> Motion: - """ - Default resolver for looking, chooses which pose to take if ``target`` and ``object`` are given. If both are given - ``target`` will be preferred. + session.add(motion) + session.commit() - :return: A resolved motion designator - """ - if not self.target and self.object: - self.target = self.object.get_pose() - return self.Motion(self.cmd, self.target) + return motion -class MoveGripperMotion(MotionDesignatorDescription): +@dataclass +class MoveGripperMotion(BaseMotion): """ Opens or closes the gripper """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - motion: str - """ - Motion that should be performed, either 'open' or 'close' - """ - gripper: str - """ - Name of the gripper that should be moved - """ - allow_gripper_collision: bool - """ - If the gripper is allowed to collide with something - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.move_gripper().execute(self) - - def to_sql(self) -> ORMMoveGripperMotion: - return ORMMoveGripperMotion(self.motion, self.gripper, self.allow_gripper_collision) - - def insert(self, session: Session, *args, **kwargs) -> ORMMoveGripperMotion: - motion = super().insert(session) + motion: str + """ + Motion that should be performed, either 'open' or 'close' + """ + gripper: str + """ + Name of the gripper that should be moved + """ + allow_gripper_collision: Optional[bool] = None + """ + If the gripper is allowed to collide with something + """ - session.add(motion) - session.commit() - return motion + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.move_gripper().execute(self) - def __init__(self, motion: str, gripper: str, resolver: Optional[Callable] = None, - allow_gripper_collision: Optional[bool] = None): - """ - Moves the gripper into a given position. + def to_sql(self) -> ORMMoveGripperMotion: + return ORMMoveGripperMotion(self.motion, self.gripper, self.allow_gripper_collision) - :param motion: Which motion to perform - :param gripper: Name of the gripper that should be moved - :param resolver: An alternative resolver that resolves the parameter to a motion designator - """ - super().__init__(resolver) - self.cmd: str = 'move-gripper' - self.motion: str = motion - self.gripper: str = gripper - self.allow_gripper_collision = allow_gripper_collision + def insert(self, session: Session, *args, **kwargs) -> ORMMoveGripperMotion: + motion = super().insert(session) - def ground(self) -> Motion: - """ - Default resolver for moving the gripper, simply returns a resolved motion designator + session.add(motion) + session.commit() + return motion - :return: A resolved motion designator - """ - return self.Motion(self.cmd, self.motion, self.gripper, self.allow_gripper_collision) - -class DetectingMotion(MotionDesignatorDescription): +@dataclass +class DetectingMotion(BaseMotion): """ Tries to detect an object in the FOV of the robot """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object_type: str - """ - Type of the object that should be detected - """ + object_type: ObjectType + """ + Type of the object that should be detected + """ - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - bullet_world_object = pm_manager.detecting().execute(self) - if not bullet_world_object: - raise PerceptionObjectNotFound( - f"Could not find an object with the type {self.object_type} in the FOV of the robot") - if ProcessModuleManager.execution_type == "real": - return RealObject.Object(bullet_world_object.name, bullet_world_object.type, - bullet_world_object, bullet_world_object.get_pose()) - - return ObjectDesignatorDescription.Object(bullet_world_object.name, bullet_world_object.type, - bullet_world_object) - - def to_sql(self) -> ORMDetectingMotion: - return ORMDetectingMotion(self.object_type) - - def insert(self, session: Session, *args, **kwargs) -> ORMDetectingMotion: - motion = super().insert(session) - session.add(motion) - session.commit() - return motion - - def __init__(self, object_type: str, resolver: Optional[Callable] = None): - """ - Checks for every object in the FOV of the robot if it fits the given object type. If the types match an object - designator describing the object will be returned. + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + bullet_world_object = pm_manager.detecting().execute(self) + if not bullet_world_object: + raise PerceptionObjectNotFound( + f"Could not find an object with the type {self.object_type} in the FOV of the robot") + if ProcessModuleManager.execution_type == "real": + return RealObject.Object(bullet_world_object.name, bullet_world_object.type, + bullet_world_object, bullet_world_object.get_pose()) - :param object_type: Type of the object which should be detected - :param resolver: An alternative resolver which returns a resolved motion designator - """ - super().__init__(resolver) - self.cmd: str = 'detecting' - self.object_type: str = object_type + return ObjectDesignatorDescription.Object(bullet_world_object.name, bullet_world_object.type, + bullet_world_object) - def ground(self) -> Motion: - """ - Default resolver for detecting, simply returns a resolver motion designator without checking. + def to_sql(self) -> ORMDetectingMotion: + return ORMDetectingMotion(self.object_type) - :return: A resolved motion designator - """ - return self.Motion(self.cmd, self.object_type) + def insert(self, session: Session, *args, **kwargs) -> ORMDetectingMotion: + motion = super().insert(session) + session.add(motion) + session.commit() + return motion -class MoveArmJointsMotion(MotionDesignatorDescription): +@dataclass +class MoveArmJointsMotion(BaseMotion): """ Moves the joints of each arm into the given position """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - left_arm_poses: Dict[str, float] - """ - Target positions for the left arm joints - """ - right_arm_poses: Dict[str, float] - """ - Target positions for the right arm joints - """ - - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.move_arm_joints().execute(self) - - def __init__(self, left_arm_config: Optional[str] = None, right_arm_config: Optional[str] = None, - left_arm_poses: Optional[dict] = None, right_arm_poses: Optional[dict] = None, - resolver: Optional[Callable] = None): - """ - Moves the arm joints, target positions can be either be pre-defined configurations (like 'park') or a dictionary - with joint names as keys and joint positions as values. If a configuration and a dictionary are given the - dictionary will be preferred. - - :param left_arm_config: Target configuration for the left arm - :param right_arm_config: Target configuration for the right arm - :param left_arm_poses: Target Dict for the left arm - :param right_arm_poses: Target Dict for the right arm - :param resolver: An alternative resolver that returns a resolved motion designator for the given parameters. - """ - super().__init__(resolver) - self.cmd = 'move-arm-joints' - self.left_arm_config: str = left_arm_config - self.right_arm_config: str = right_arm_config - self.left_arm_poses: Dict[str, float] = left_arm_poses - self.right_arm_poses: Dict[str, float] = right_arm_poses - - def ground(self) -> Motion: - """ - Default resolver for moving the arms, returns a resolved motion designator containing the target positions for - the left and right arm joints. + left_arm_poses: Optional[Dict[str, float]] + """ + Target positions for the left arm joints + """ + right_arm_poses: Optional[Dict[str, float]] + """ + Target positions for the right arm joints + """ - :return: A resolved and performable motion designator - """ - left_poses = None - right_poses = None + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.move_arm_joints().execute(self) - if self.left_arm_poses: - left_poses = self.left_arm_poses - elif self.left_arm_config: - left_poses = robot_description.get_static_joint_chain("left", self.left_arm_config) + def to_sql(self) -> ORMMotionDesignator: + pass - if self.right_arm_poses: - right_poses = self.right_arm_poses - elif self.right_arm_config: - right_poses = robot_description.get_static_joint_chain("right", self.right_arm_config) - return self.Motion(self.cmd, left_poses, right_poses) + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + pass -class WorldStateDetectingMotion(MotionDesignatorDescription): +@dataclass +class WorldStateDetectingMotion(BaseMotion): """ Detects an object based on the world state. """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object_type: str - """ - Object type that should be detected - """ - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.world_state_detecting().execute(self) - - def __init__(self, object_type: str, resolver: Optional[Callable] = None): - """ - Tries to find an object using the belief state (BulletWorld), if there is an object in the belief state matching - the given object type an object designator will be returned. + object_type: str + """ + Object type that should be detected + """ - :param object_type: The object type which should be detected - :param resolver: An alternative resolver that returns a resolved motion designator for the input parameter - """ - super().__init__(resolver) - self.cmd: str = 'world-state-detecting' - self.object_type: str = object_type + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.world_state_detecting().execute(self) - def ground(self) -> Motion: - """ - Default resolver for world state detecting which simply returns a resolved motion designator for the input - parameter. + def to_sql(self) -> ORMMotionDesignator: + pass - :return: A resolved motion designator - """ - return self.Motion(self.cmd, self.object_type) + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + pass -class MoveJointsMotion(MotionDesignatorDescription): +@dataclass +class MoveJointsMotion(BaseMotion): """ Moves any joint on the robot """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - names: list - """ - List of joint names that should be moved - """ - positions: list - """ - Target positions of joints, should correspond to the list of names - """ - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.move_joints().execute(self) - - def __init__(self, names: List[str], positions: List[float], resolver: Optional[Callable] = None): - """ - Moves the joints given by the list of names to the positions given by the list of positions. The index of a - joint name should correspond to the index of the target position. + names: list + """ + List of joint names that should be moved + """ + positions: list + """ + Target positions of joints, should correspond to the list of names + """ - :param names: List of joint names that should be moved - :param positions: List of joint positions that the joints should be moved in - :param resolver: An alternative resolver that resolves the input parameters to a performable motion designator. - """ - super().__init__(resolver) - self.cmd: str = "move-joints" - self.names: List[str] = names - self.positions: List[float] = positions + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.move_joints().execute(self) - def ground(self) -> Motion: - """ - Default resolver for move joints, checks if the length of both list match and checks if the target positions are - within the joint limits as stated in the URDF. + def to_sql(self) -> ORMMotionDesignator: + pass - :return: A resolved motion designator - """ - if len(self.names) != len(self.positions): - raise DesignatorError("[Motion Designator][Move Joints] The length of names and positions does not match") - for i in range(len(self.names)): - lower, upper = BulletWorld.robot.get_joint_limits(self.names[i]) - if self.positions[i] < lower or self.positions[i] > upper: - raise DesignatorError( - f"[Motion Designator][Move Joints] The given configuration for the Joint {self.names[i]} violates its limits") - return self.Motion(self.cmd, self.names, self.positions) + def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: + pass -class OpeningMotion(MotionDesignatorDescription): +@dataclass +class OpeningMotion(BaseMotion): """ Designator for opening container """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object_part: ObjectPart.Object - """ - Object designator for the drawer handle - """ - arm: str - """ - Arm that should be used - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.open().execute(self) - - def to_sql(self) -> ORMOpeningMotion: - return ORMOpeningMotion(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMOpeningMotion: - motion = super().insert(session) - - op = self.object_part.insert(session) - motion.object_id = op.id + object_part: ObjectPart.Object + """ + Object designator for the drawer handle + """ + arm: str + """ + Arm that should be used + """ - session.add(motion) - session.commit() + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.open().execute(self) - return motion + def to_sql(self) -> ORMOpeningMotion: + return ORMOpeningMotion(self.arm) - def __init__(self, object_part: ObjectPart.Object, arm: str, resolver: Optional[Callable] = None): - """ - Lets the robot open a container specified by the given parameter. This motion designator assumes that the handle - is already grasped. + def insert(self, session: Session, *args, **kwargs) -> ORMOpeningMotion: + motion = super().insert(session) - :param object_part: Object designator describing the handle of the drawer - :param arm: Arm that should be used - :param resolver: An alternative resolver - """ - super().__init__(resolver) - self.cmd: str = 'open' - self.objet_part = object_part - self.arm: str = arm + op = self.object_part.insert(session) + motion.object_id = op.id - def ground(self) -> Motion: - """ - Default resolver for opening motion designator, returns a resolved motion designator for the input parameters. + session.add(motion) + session.commit() - :return: A resolved motion designator - """ - return self.Motion(self.cmd, self.objet_part, self.arm) + return motion -class ClosingMotion(MotionDesignatorDescription): +@dataclass +class ClosingMotion(BaseMotion): """ Designator for closing a container """ - @dataclasses.dataclass - class Motion(MotionDesignatorDescription.Motion): - # cmd: str - object_part: ObjectPart.Object - """ - Object designator for the drawer handle - """ - arm: str - """ - Arm that should be used - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.close().execute(self) - - def to_sql(self) -> ORMClosingMotion: - return ORMClosingMotion(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMClosingMotion: - motion = super().insert(session) - - op = self.object_part.insert(session) - motion.object_id = op.id + object_part: ObjectPart.Object + """ + Object designator for the drawer handle + """ + arm: str + """ + Arm that should be used + """ - session.add(motion) - session.commit() + @with_tree + def perform(self): + pm_manager = ProcessModuleManager.get_manager() + return pm_manager.close().execute(self) - return motion + def to_sql(self) -> ORMClosingMotion: + return ORMClosingMotion(self.arm) - def __init__(self, object_part: ObjectPart.Object, arm: str, resolver: Optional[Callable] = None): - """ - Lets the robot close a container specified by the given parameter. This assumes that the handle is already grasped + def insert(self, session: Session, *args, **kwargs) -> ORMClosingMotion: + motion = super().insert(session) - :param object_part: Object designator describing the handle of the drawer - :param arm: Arm that should be used - :param resolver: An alternative resolver - """ - super().__init__(resolver) - self.cmd: str = 'close' - self.objet_part = object_part - self.arm: str = arm + op = self.object_part.insert(session) + motion.object_id = op.id - def ground(self) -> Motion: - """ - Default resolver for opening motion designator, returns a resolved motion designator for the input parameters. + session.add(motion) + session.commit() - :return: A resolved motion designator - """ - return self.Motion(self.cmd, self.objet_part, self.arm) + return motion diff --git a/src/pycram/process_module.py b/src/pycram/process_module.py index 92990c9ae..b1539a099 100644 --- a/src/pycram/process_module.py +++ b/src/pycram/process_module.py @@ -5,19 +5,13 @@ """ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations - import inspect import time from abc import ABC -from threading import Lock - import rospy - -from .designator import MotionDesignatorDescription -from .fluent import Fluent from typing import Callable, List, Type, Any, Union -from .robot_descriptions import robot_description +from .robot_descriptions import robot_description class ProcessModule: @@ -33,14 +27,14 @@ def __init__(self, lock): """Create a new process module.""" self._lock = lock - def _execute(self, designator: MotionDesignatorDescription.Motion) -> Any: + def _execute(self, designator) -> Any: """ Helper method for internal usage only. This method is to be overwritten instead of the execute method. """ pass - def execute(self, designator: MotionDesignatorDescription.Motion) -> Any: + def execute(self, designator) -> Any: """ Execute the given designator. If there is already another process module of the same kind the `self._lock` will lock this thread until the execution of that process module is finished. This implicitly queues the execution of diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 4ce16bf96..a455e6743 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -1,19 +1,14 @@ -import time from threading import Lock - import numpy as np -import pybullet as p - import pycram.bullet_world_reasoning as btr import pycram.helper as helper -from ..bullet_world import BulletWorld +from ..bullet_world import BulletWorld, Object from ..designators.motion_designator import * from ..enums import JointType from ..external_interfaces.ik import request_ik -from ..local_transformer import LocalTransformer as local_tf, LocalTransformer +from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description -from tf.transformations import euler_from_quaternion, quaternion_from_euler def _park_arms(arm): @@ -37,7 +32,7 @@ class BoxyNavigation(ProcessModule): The process module to move the robot from one position to another. """ - def _execute(self, desig: MoveMotion.Motion): + def _execute(self, desig: MoveMotion): robot = BulletWorld.robot robot.set_pose(desig.target) @@ -48,7 +43,7 @@ class BoxyPickUp(ProcessModule): The object has to be reachable for this process module to succeed. """ - def _execute(self, desig: PickUpMotion.Motion): + def _execute(self, desig: PickUpMotion): object = desig.object_desig.bullet_world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) @@ -70,7 +65,7 @@ class BoxyPlace(ProcessModule): This process module places an object at the given position in world coordinate frame. """ - def _execute(self, desig: PlaceMotion.Motion): + def _execute(self, desig: PlaceMotion): """ :param desig: A PlaceMotion @@ -96,7 +91,7 @@ class BoxyOpen(ProcessModule): Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. """ - def _execute(self, desig: OpeningMotion.Motion): + def _execute(self, desig: OpeningMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -115,7 +110,7 @@ class BoxyClose(ProcessModule): """ Low-level implementation that lets the robot close a grasped container, in simulation """ - def _execute(self, desig: ClosingMotion.Motion): + def _execute(self, desig: ClosingMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -210,7 +205,7 @@ class BoxyMoveTCP(ProcessModule): This process moves the tool center point of either the right or the left arm. """ - def _execute(self, desig: MoveTCPMotion.Motion): + def _execute(self, desig: MoveTCPMotion): target = desig.target robot = BulletWorld.robot @@ -223,7 +218,7 @@ class BoxyMoveArmJoints(ProcessModule): list that should be applied or a pre-defined position can be used, such as "parking" """ - def _execute(self, desig: MoveArmJointsMotion.Motion): + def _execute(self, desig: MoveArmJointsMotion): robot = BulletWorld.robot if desig.right_arm_poses: @@ -237,7 +232,7 @@ class BoxyWorldStateDetecting(ProcessModule): This process module detectes an object even if it is not in the field of view of the robot. """ - def _execute(self, desig: WorldStateDetectingMotion.Motion): + def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index ed5c8ae80..cd73d0895 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -161,7 +161,7 @@ class DonbotMoveJoints(ProcessModule): list that should be applied or a pre-defined position can be used, such as "parking" """ - def _execute(self, desig: MoveArmJointsMotion.Motion): + def _execute(self, desig: MoveArmJointsMotion): robot = BulletWorld.robot if desig.left_arm_poses: robot.set_joint_states(desig.left_arm_poses) @@ -172,7 +172,7 @@ class DonbotWorldStateDetecting(ProcessModule): This process module detectes an object even if it is not in the field of view of the robot. """ - def _execute(self, desig: WorldStateDetectingMotion.Motion): + def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 3930a8a9b..6bdc8d3df 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -50,7 +50,7 @@ class Pr2Navigation(ProcessModule): The process module to move the robot from one position to another. """ - def _execute(self, desig: MoveMotion.Motion): + def _execute(self, desig: MoveMotion): robot = BulletWorld.robot robot.set_pose(desig.target) @@ -61,7 +61,7 @@ class Pr2PickUp(ProcessModule): The object has to be reachable for this process module to succeed. """ - def _execute(self, desig: PickUpMotion.Motion): + def _execute(self, desig: PickUpMotion): object = desig.object_desig.bullet_world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) @@ -83,7 +83,7 @@ class Pr2Place(ProcessModule): This process module places an object at the given position in world coordinate frame. """ - def _execute(self, desig: PlaceMotion.Motion): + def _execute(self, desig: PlaceMotion): """ :param desig: A PlaceMotion @@ -109,7 +109,7 @@ class Pr2MoveHead(ProcessModule): This point can either be a position or an object. """ - def _execute(self, desig: LookingMotion.Motion): + def _execute(self, desig: LookingMotion): target = desig.target robot = BulletWorld.robot @@ -133,7 +133,7 @@ class Pr2MoveGripper(ProcessModule): Furthermore, it can only moved one gripper at a time. """ - def _execute(self, desig: MoveGripperMotion.Motion): + def _execute(self, desig: MoveGripperMotion): robot = BulletWorld.robot gripper = desig.gripper motion = desig.motion @@ -147,7 +147,7 @@ class Pr2Detecting(ProcessModule): the field of view of the robot. """ - def _execute(self, desig: DetectingMotion.Motion): + def _execute(self, desig: DetectingMotion): robot = BulletWorld.robot object_type = desig.object_type # Should be "wide_stereo_optical_frame" @@ -166,7 +166,7 @@ class Pr2MoveTCP(ProcessModule): This process moves the tool center point of either the right or the left arm. """ - def _execute(self, desig: MoveTCPMotion.Motion): + def _execute(self, desig: MoveTCPMotion): target = desig.target robot = BulletWorld.robot @@ -179,7 +179,7 @@ class Pr2MoveArmJoints(ProcessModule): list that should be applied or a pre-defined position can be used, such as "parking" """ - def _execute(self, desig: MoveArmJointsMotion.Motion): + def _execute(self, desig: MoveArmJointsMotion): robot = BulletWorld.robot if desig.right_arm_poses: @@ -192,7 +192,7 @@ class PR2MoveJoints(ProcessModule): """ Process Module for generic joint movements, is not confined to the arms but can move any joint of the robot """ - def _execute(self, desig: MoveJointsMotion.Motion): + def _execute(self, desig: MoveJointsMotion): robot = BulletWorld.robot robot.set_joint_states(dict(zip(desig.names, desig.positions))) @@ -202,7 +202,7 @@ class Pr2WorldStateDetecting(ProcessModule): This process module detectes an object even if it is not in the field of view of the robot. """ - def _execute(self, desig: WorldStateDetectingMotion.Motion): + def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] @@ -212,7 +212,7 @@ class Pr2Open(ProcessModule): Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. """ - def _execute(self, desig: OpeningMotion.Motion): + def _execute(self, desig: OpeningMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -232,7 +232,7 @@ class Pr2Close(ProcessModule): Low-level implementation that lets the robot close a grasped container, in simulation """ - def _execute(self, desig: ClosingMotion.Motion): + def _execute(self, desig: ClosingMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -266,20 +266,20 @@ class Pr2NavigationReal(ProcessModule): Process module for the real PR2 that sends a cartesian goal to giskard to move the robot base """ - def _execute(self, designator: MoveMotion.Motion) -> Any: + def _execute(self, designator: MoveMotion) -> Any: rospy.logdebug(f"Sending goal to giskard to Move the robot") giskard.achieve_cartesian_goal(designator.target, robot_description.base_link, "map") class Pr2PickUpReal(ProcessModule): - def _execute(self, designator: PickUpMotion.Motion) -> Any: + def _execute(self, designator: PickUpMotion) -> Any: pass class Pr2PlaceReal(ProcessModule): - def _execute(self, designator: MotionDesignatorDescription.Motion) -> Any: + def _execute(self, designator: BaseMotion) -> Any: pass @@ -289,7 +289,7 @@ class Pr2MoveHeadReal(ProcessModule): as the simulated one """ - def _execute(self, desig: LookingMotion.Motion): + def _execute(self, desig: LookingMotion): target = desig.target robot = BulletWorld.robot @@ -314,7 +314,7 @@ class Pr2DetectingReal(ProcessModule): for perception of the environment. """ - def _execute(self, designator: DetectingMotion.Motion) -> Any: + def _execute(self, designator: DetectingMotion) -> Any: query_result = query(ObjectDesignatorDescription(types=[designator.object_type])) # print(query_result) obj_pose = query_result["ClusterPoseBBAnnotator"] @@ -347,7 +347,7 @@ class Pr2MoveTCPReal(ProcessModule): Moves the tool center point of the real PR2 while avoiding all collisions """ - def _execute(self, designator: MoveTCPMotion.Motion) -> Any: + def _execute(self, designator: MoveTCPMotion) -> Any: lt = LocalTransformer() pose_in_map = lt.transform_pose(designator.target, "map") @@ -362,7 +362,7 @@ class Pr2MoveArmJointsReal(ProcessModule): Moves the arm joints of the real PR2 to the given configuration while avoiding all collisions """ - def _execute(self, designator: MoveArmJointsMotion.Motion) -> Any: + def _execute(self, designator: MoveArmJointsMotion) -> Any: joint_goals = {} if designator.left_arm_poses: joint_goals.update(designator.left_arm_poses) @@ -377,7 +377,7 @@ class Pr2MoveJointsReal(ProcessModule): Moves any joint using giskard, avoids all collisions while doint this. """ - def _execute(self, designator: MoveJointsMotion.Motion) -> Any: + def _execute(self, designator: MoveJointsMotion) -> Any: name_to_position = dict(zip(designator.names, designator.positions)) giskard.avoid_all_collisions() giskard.achieve_joint_goal(name_to_position) @@ -388,7 +388,7 @@ class Pr2MoveGripperReal(ProcessModule): Opens or closes the gripper of the real PR2, gripper uses an action server for this instead of giskard """ - def _execute(self, designator: MoveGripperMotion.Motion) -> Any: + def _execute(self, designator: MoveGripperMotion) -> Any: def activate_callback(): rospy.loginfo("Started gripper Movement") @@ -414,7 +414,7 @@ class Pr2OpenReal(ProcessModule): Tries to open an already grasped container """ - def _execute(self, designator: OpeningMotion.Motion) -> Any: + def _execute(self, designator: OpeningMotion) -> Any: giskard.achieve_open_container_goal(robot_description.get_tool_frame(designator.arm), designator.object_part.name) @@ -424,7 +424,7 @@ class Pr2CloseReal(ProcessModule): Tries to close an already grasped container """ - def _execute(self, designator: ClosingMotion.Motion) -> Any: + def _execute(self, designator: ClosingMotion) -> Any: giskard.achieve_close_container_goal(robot_description.get_tool_frame(designator.arm), designator.object_part.name) diff --git a/test/local_transformer_tests.py b/test/local_transformer_tests.py index 7629b2248..845ae9ac1 100644 --- a/test/local_transformer_tests.py +++ b/test/local_transformer_tests.py @@ -10,7 +10,7 @@ import bullet_world_testcase -class TestLocalTransformer(test_bullet_world.BulletWorldTestCase): +class TestLocalTransformer(bullet_world_testcase.BulletWorldTestCase): def test_singelton(self): l1 = LocalTransformer() From e29653713b4739ddfc1843d9e6cef21910a6ca64 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 18 Jan 2024 19:46:25 +0100 Subject: [PATCH 040/195] [WorldAbstractClass] Reseting the world now also has the option to remove all saved sates. world saved states is a list of int state ids WorldState data class moved to world_dataclasses.py added the method to remove physics simulator state add reset object method in the Object class. --- src/pycram/bullet_world.py | 7 ++++ src/pycram/world.py | 71 +++++++++++++++++++-------------- src/pycram/world_dataclasses.py | 9 ++++- test/test_object.py | 2 +- 4 files changed, 57 insertions(+), 32 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index ad1cc7abe..9445aca34 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -93,6 +93,7 @@ def add_constraint(self, constraint: Constraint) -> int: return constraint_id def remove_constraint(self, constraint_id): + print("Removing constraint with id: ", constraint_id) p.removeConstraint(constraint_id, physicsClientId=self.client_id) def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: @@ -327,6 +328,12 @@ def restore_physics_simulator_state(self, state_id): """ p.restoreState(state_id, physicsClientId=self.client_id) + def remove_physics_simulator_state(self, state_id: int): + """ + Removes the physics simulator state with the given unique state id. + """ + p.removeState(state_id, physicsClientId=self.client_id) + def add_vis_axis(self, pose: Pose, length: Optional[float] = 0.2) -> None: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index e3eb38116..f4ff2c2e9 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -33,21 +33,7 @@ from abc import ABC, abstractmethod from dataclasses import dataclass -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox - - -@dataclass -class WorldState: - state_id: int - attachments: Dict[Object, Dict[Object, Attachment]] - - -@dataclass -class CollisionCallbacks: - obj_1: Object - obj_2: Object - on_collision_cb: Callable - no_collision_cb: Optional[Callable] = None +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks class World(ABC): @@ -113,8 +99,7 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self._init_events() - self._saved_states: Dict[int, WorldState] = {} - # Different states of the world indexed by int state id. + self.saved_states: List[int] = [] def _init_events(self): self.detachment_event: Event = Event() @@ -597,6 +582,7 @@ def save_state(self) -> int: """ state_id = self.save_physics_simulator_state() self.save_objects_state(state_id) + self.saved_states.append(state_id) return state_id def save_objects_state(self, state_id: int): @@ -621,6 +607,13 @@ def save_physics_simulator_state(self) -> int: """ pass + @abstractmethod + def remove_physics_simulator_state(self, state_id: int): + """ + Removes the state of the physics simulator with the given id. + """ + pass + @abstractmethod def restore_physics_simulator_state(self, state_id: int): """ @@ -663,7 +656,8 @@ def register_two_objects_collision_callbacks(self, :param on_collision_callback: A function that should be called if the objects are in contact :param on_collision_removal_callback: A function that should be called if the objects are not in contact """ - self.coll_callbacks[(object_a, object_b)] = (on_collision_callback, on_collision_removal_callback) + self.coll_callbacks[(object_a, object_b)] = CollisionCallbacks(on_collision_callback, + on_collision_removal_callback) @classmethod def add_resource_path(cls, path: str) -> None: @@ -710,17 +704,24 @@ def get_object_from_prospection_object(self, prospection_object: Object) -> Obje except ValueError: raise ValueError("The given object is not in the shadow world.") - def reset_world(self) -> None: + def reset_world(self, remove_saved_states=True) -> None: """ Resets the World to the state it was first spawned in. All attached objects will be detached, all joints will be set to the default position of 0 and all objects will be set to the position and orientation in which they were spawned. """ + + if remove_saved_states: + self.remove_saved_states() + for obj in self.objects: - obj.detach_all() - obj.reset_all_joints_positions() - obj.set_pose(obj.original_pose) + obj.reset(remove_saved_states) + + def remove_saved_states(self): + for state_id in self.saved_states: + self.remove_physics_simulator_state(state_id) + self.saved_states = [] def update_transforms_for_objects_in_current_world(self) -> None: """ @@ -1066,7 +1067,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.world.set_robot_if_not_set(self) self.link_name_to_id[self.urdf_object.get_root()] = -1 self.link_id_to_name[-1] = self.urdf_object.get_root() - self.links = self._init_links() + self.links: Dict[str, Link] = self._init_links() self.update_link_transforms() self._current_joints_positions = {} @@ -1126,6 +1127,19 @@ def remove(self) -> None: if World.robot == self: World.robot = None + def reset(self, remove_saved_states=True) -> None: + """ + Resets the Object to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and the object will be set to the position and + orientation in which it was spawned. + """ + self.detach_all() + self.reset_all_joints_positions() + self.set_pose(self.original_pose) + if remove_saved_states: + self.saved_states = {} + def attach(self, child_object: Object, parent_link: Optional[str] = None, @@ -1267,11 +1281,10 @@ def restore_links_states(self, state_id): for link in self.links.values(): link.restore_state(state_id) - def set_object_state(self, obj_state:ObjectState): - self.set_attachments(obj_state.attachments) - - def set_attachments(self, attachments: Dict[Object, Attachment]) -> None: - self.attachments = attachments + def remove_saved_states(self): + self.saved_states = {} + for link in self.links.values(): + link.saved_states = {} def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: """ @@ -1662,8 +1675,6 @@ def __init__(self, """ self.parent_link = parent_link self.child_link = child_link - self.parent_object = parent_link.object - self.child_object = child_link.object self.bidirectional = bidirectional self._loose = False and not bidirectional diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 3910aae73..fb057aa3a 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,5 +1,5 @@ from dataclasses import dataclass -from typing import List, Optional, Tuple +from typing import List, Optional, Tuple, Callable from .enums import JointType @@ -63,6 +63,7 @@ def from_list(cls, point: List[float]): """ return cls(point[0], point[1], point[2]) + @dataclass class AxisAlignedBoundingBox: """ @@ -132,3 +133,9 @@ def get_max(self) -> List[float]: :return: The maximum point of the axis-aligned bounding box """ return [self.max_x, self.max_y, self.max_z] + + +@dataclass +class CollisionCallbacks: + on_collision_cb: Callable + no_collision_cb: Optional[Callable] = None \ No newline at end of file diff --git a/test/test_object.py b/test/test_object.py index f04866517..254495c5f 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -18,7 +18,7 @@ def test_set_position_as_pose(self): self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) def test_save_state(self): - self.robot.attach(self.milk, parent_link="r_gripper_palm_link") + self.robot.attach(self.milk) self.robot.save_state(1) self.assertEqual(self.robot.saved_states[1].attachments, self.robot.attachments) self.assertTrue(self.milk in self.robot.saved_states[1].attachments) From 7520c8a4fa4f72f2d29ad3d1c4285919a795a040 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 19 Jan 2024 14:51:57 +0100 Subject: [PATCH 041/195] merge dev into tests --- src/pycram/designators/actions/actions.py | 3 ++- .../default_process_modules.py | 26 +++++++++---------- test/test_language.py | 3 +++ 3 files changed, 18 insertions(+), 14 deletions(-) diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index ef47227ef..2497be648 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -301,7 +301,8 @@ def perform(self) -> None: MoveTCPMotion(target_diff, self.arm).perform() MoveGripperMotion("open", self.arm).perform() BulletWorld.robot.detach(self.object_designator.bullet_world_object) - retract_pose = target_diff + retract_pose = local_tf.transform_pose(target_diff, BulletWorld.robot.get_link_tf_frame( + robot_description.get_tool_frame(self.arm))) retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).perform() diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 390558bd9..9705722a4 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -5,7 +5,7 @@ from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld +from ..bullet_world import BulletWorld, Object from ..external_interfaces.ik import request_ik, IKError from ..helper import _apply_ik from ..local_transformer import LocalTransformer @@ -18,7 +18,7 @@ class DefaultNavigation(ProcessModule): The process module to move the robot from one position to another. """ - def _execute(self, desig: MoveMotion.Motion): + def _execute(self, desig: MoveMotion): robot = BulletWorld.robot robot.set_pose(desig.target) @@ -29,7 +29,7 @@ class DefaultPickUp(ProcessModule): The object has to be reachable for this process module to succeed. """ - def _execute(self, desig: PickUpMotion.Motion): + def _execute(self, desig: PickUpMotion): object = desig.object_desig.bullet_world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) @@ -51,7 +51,7 @@ class DefaultPlace(ProcessModule): This process module places an object at the given position in world coordinate frame. """ - def _execute(self, desig: PlaceMotion.Motion): + def _execute(self, desig: PlaceMotion): """ :param desig: A PlaceMotion @@ -71,7 +71,7 @@ class DefaultMoveHead(ProcessModule): This point can either be a position or an object. """ - def _execute(self, desig: LookingMotion.Motion): + def _execute(self, desig: LookingMotion): target = desig.target robot = BulletWorld.robot @@ -101,7 +101,7 @@ class DefaultMoveGripper(ProcessModule): Furthermore, it can only moved one gripper at a time. """ - def _execute(self, desig: MoveGripperMotion.Motion): + def _execute(self, desig: MoveGripperMotion): robot = BulletWorld.robot gripper = desig.gripper motion = desig.motion @@ -115,7 +115,7 @@ class DefaultDetecting(ProcessModule): the field of view of the robot. """ - def _execute(self, desig: DetectingMotion.Motion): + def _execute(self, desig: DetectingMotion): robot = BulletWorld.robot object_type = desig.object_type # Should be "wide_stereo_optical_frame" @@ -134,7 +134,7 @@ class DefaultMoveTCP(ProcessModule): This process moves the tool center point of either the right or the left arm. """ - def _execute(self, desig: MoveTCPMotion.Motion): + def _execute(self, desig: MoveTCPMotion): target = desig.target robot = BulletWorld.robot @@ -147,7 +147,7 @@ class DefaultMoveArmJoints(ProcessModule): list that should be applied or a pre-defined position can be used, such as "parking" """ - def _execute(self, desig: MoveArmJointsMotion.Motion): + def _execute(self, desig: MoveArmJointsMotion): robot = BulletWorld.robot if desig.right_arm_poses: @@ -159,7 +159,7 @@ def _execute(self, desig: MoveArmJointsMotion.Motion): class DefaultMoveJoints(ProcessModule): - def _execute(self, desig: MoveJointsMotion.Motion): + def _execute(self, desig: MoveJointsMotion): robot = BulletWorld.robot for joint, pose in zip(desig.names, desig.positions): robot.set_joint_state(joint, pose) @@ -170,7 +170,7 @@ class DefaultWorldStateDetecting(ProcessModule): This process module detectes an object even if it is not in the field of view of the robot. """ - def _execute(self, desig: WorldStateDetectingMotion.Motion): + def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] @@ -180,7 +180,7 @@ class DefaultOpen(ProcessModule): Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. """ - def _execute(self, desig: OpeningMotion.Motion): + def _execute(self, desig: OpeningMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -199,7 +199,7 @@ class DefaultClose(ProcessModule): """ Low-level implementation that lets the robot close a grasped container, in simulation """ - def _execute(self, desig: ClosingMotion.Motion): + def _execute(self, desig: ClosingMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) diff --git a/test/test_language.py b/test/test_language.py index 951db67c4..e63d5ec57 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -1,6 +1,8 @@ import threading +import time import unittest from pycram.designators.action_designator import * +from pycram.designators.object_designator import BelieveObject from pycram.enums import ObjectType, State from pycram.fluent import Fluent from pycram.plan_failures import PlanFailure @@ -8,6 +10,7 @@ from pycram.language import Sequential, Language, Parallel, TryAll, TryInOrder, Monitor, Repeat, Code, RenderTree from pycram.process_module import simulated_robot import test_bullet_world +from pycram.robot_descriptions import robot_description class LanguageTestCase(test_bullet_world.BulletWorldTest): From 51f88918d50bbcf9e31788b49a8688b4a6ee2c5b Mon Sep 17 00:00:00 2001 From: Vanessa Hassouna <33067562+sunava@users.noreply.github.com> Date: Fri, 19 Jan 2024 15:16:00 +0100 Subject: [PATCH 042/195] Update README.md, deleted Authors --- README.md | 9 --------- 1 file changed, 9 deletions(-) diff --git a/README.md b/README.md index 3e127326d..c243da496 100644 --- a/README.md +++ b/README.md @@ -92,12 +92,3 @@ how to do that take a look at the respective `README` file. If you encounter some error please first take a look at the [troubleshooting](https://pycram.readthedocs.io/en/latest/troubleshooting.html) section and see if the error is mentioned there. - -## Authors - -* **Jonas Dech** -* **Andy Augsten** -* **Dustin Augsten** -* **Christopher Pollok** -* **Thomas Lipps** -* **Benjamin Alt** From b499e7868284336fc4d52c221289203fbfc97988 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Fri, 19 Jan 2024 16:08:07 +0100 Subject: [PATCH 043/195] [bullet reasoning] Fixed wrong robot usage --- src/pycram/bullet_world_reasoning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/bullet_world_reasoning.py b/src/pycram/bullet_world_reasoning.py index 9a6c0ee94..3d6af78a9 100644 --- a/src/pycram/bullet_world_reasoning.py +++ b/src/pycram/bullet_world_reasoning.py @@ -320,7 +320,7 @@ def blocking(pose_or_object: Union[Object, Pose], target_map.orientation.w = grasp_orientation[3] try: - inv = request_ik(target_map, robot, joints, gripper_name) + inv = request_ik(target_map, shadow_robot, joints, gripper_name) except IKError as e: rospy.logerr(f"Pose is not reachable: {e}") return None From 62c5309aeb98b1df3e5eaa13734ba698f4a566b1 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 19 Jan 2024 17:01:35 +0100 Subject: [PATCH 044/195] [WorldAbstractClass] World reasoning is refactored to depend on abstract class. Not passing tests yet. --- doc/source/notebooks/intro.ipynb | 4 +- examples/intro.ipynb | 4 +- src/pycram/bullet_world.py | 42 +- src/pycram/costmaps.py | 12 +- src/pycram/external_interfaces/ik.py | 1 - src/pycram/helper.py | 23 +- src/pycram/old_world_reasoning.py | 365 +++++++++++ .../process_modules/boxy_process_modules.py | 20 +- .../process_modules/pr2_process_modules.py | 16 +- src/pycram/world.py | 26 +- src/pycram/world_reasoning.py | 577 +++++++++--------- test/test_bullet_world.py | 2 - test/test_bullet_world_reasoning.py | 9 +- 13 files changed, 736 insertions(+), 365 deletions(-) create mode 100644 src/pycram/old_world_reasoning.py diff --git a/doc/source/notebooks/intro.ipynb b/doc/source/notebooks/intro.ipynb index f5875cb3a..d38e92ecc 100644 --- a/doc/source/notebooks/intro.ipynb +++ b/doc/source/notebooks/intro.ipynb @@ -181,9 +181,7 @@ } ], "source": [ - "from pycram.bullet_world_reasoning import _get_images_for_target\n", - "\n", - "_get_images_for_target(Pose([1, 0, 1], [0, 0, 0, 1]), Pose([0.3, 0, 1], [0, 0, 0, 1]))" + "world.get_images_for_target(Pose([1, 0, 1], [0, 0, 0, 1]), Pose([0.3, 0, 1], [0, 0, 0, 1]))" ] }, { diff --git a/examples/intro.ipynb b/examples/intro.ipynb index f5875cb3a..d38e92ecc 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -181,9 +181,7 @@ } ], "source": [ - "from pycram.bullet_world_reasoning import _get_images_for_target\n", - "\n", - "_get_images_for_target(Pose([1, 0, 1], [0, 0, 0, 1]), Pose([0.3, 0, 1], [0, 0, 0, 1]))" + "world.get_images_for_target(Pose([1, 0, 1], [0, 0, 0, 1]), Pose([0.3, 0, 1], [0, 0, 0, 1]))" ] }, { diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 9445aca34..137764fc0 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -152,6 +152,12 @@ def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: """ return Pose(*p.getLinkState(obj_id, link_id, physicsClientId=self.client_id)[4:6]) + def perform_collision_detection(self) -> None: + """ + Performs collision detection and updates the contact points. + """ + p.performCollisionDetection(physicsClientId=self.client_id) + def get_object_contact_points(self, obj: Object) -> List: """l.update_transforms_for_object(self.milk) Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned @@ -160,7 +166,7 @@ def get_object_contact_points(self, obj: Object) -> List: :param obj: The object. :return: A list of all contact points with other objects """ - return p.getContactPoints(obj.id) + return p.getContactPoints(obj.id, physicsClientId=self.client_id) def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: """ @@ -170,7 +176,7 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> :param obj2: The second object. :return: A list of all contact points between the two objects. """ - return p.getContactPoints(obj1.id, obj2.id) + return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.client_id) def get_object_joint_names(self, obj_id: int) -> List[str]: """ @@ -200,7 +206,7 @@ def get_object_number_of_joints(self, obj_id: int) -> int: :param obj_id: The object """ - return p.getNumJoints(obj_id, self.client_id) + return p.getNumJoints(obj_id, physicsClientId=self.client_id) def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ @@ -374,6 +380,36 @@ def remove_vis_axis(self) -> None: p.removeBody(id) self.vis_axis = [] + def get_images_for_target(self, + target_pose: Pose, + cam_pose: Pose, + size: Optional[int] = 256) -> List[np.ndarray]: + """ + Calculates the view and projection Matrix and returns 3 images: + + 1. An RGB image + 2. A depth image + 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. + + From the given target_pose and cam_pose only the position is used. + + :param cam_pose: The pose of the camera + :param target_pose: The pose to which the camera should point to + :param size: The height and width of the images in pixel + :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. + """ + # TODO: Might depend on robot cameras, if so please add these camera parameters to RobotDescription object + # TODO: of your robot with a CameraDescription object. + fov = 90 + aspect = size / size + near = 0.2 + far = 100 + + view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) + projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) + return list(p.getCameraImage(size, size, view_matrix, projection_matrix, + physicsClientId=self.client_id))[2:5] + class Gui(threading.Thread): """ diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index b0d2f5ccb..100ecbdbf 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -10,7 +10,6 @@ import time from .bullet_world import BulletWorld from pycram.world import UseProspectionWorld, Object, Link -from .world_reasoning import _get_images_for_target from .world_dataclasses import AxisAlignedBoundingBox from nav_msgs.msg import OccupancyGrid, MapMetaData from typing import Tuple, List, Union, Optional @@ -500,22 +499,19 @@ def _create_images(self) -> List[np.ndarray]: origin_copy = self.origin.copy() origin_copy.position.y += 1 images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) + self.world.get_images_for_target(origin_copy, camera_pose, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.x -= 1 - images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) + images.append(self.world.get_images_for_target(origin_copy, camera_pose, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.y -= 1 - images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) + images.append(self.world.get_images_for_target(origin_copy, camera_pose, size=self.size)[1]) origin_copy = self.origin.copy() origin_copy.position.x += 1 - images.append( - _get_images_for_target(origin_copy, camera_pose, BulletWorld.current_world, size=self.size)[1]) + images.append(self.world.get_images_for_target(origin_copy, camera_pose, size=self.size)[1]) for i in range(0, 4): images[i] = self._depth_buffer_to_meter(images[i]) diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index f0aeaac94..664d5133d 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -125,7 +125,6 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str end_effector = robot_description.get_child(joints[-1]) target_torso = local_transformer.transform_pose_to_target_frame(target_pose, robot.links[base_link].tf_frame) - # target_torso = _transform_to_torso(pose, shadow_robot) diff = calculate_wrist_tool_offset(end_effector, gripper, robot) target_diff = target_torso.to_transform("target").inverse_times(diff).to_pose() diff --git a/src/pycram/helper.py b/src/pycram/helper.py index c098eca99..090ac17ff 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -11,18 +11,15 @@ from typing import Tuple, Callable import numpy as np -import pybullet as p from pytransform3d.rotations import quaternion_wxyz_from_xyzw, quaternion_xyzw_from_wxyz from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform from macropy.core.quotes import ast_literal, q from .world import Object as BulletWorldObject -from .local_transformer import LocalTransformer from .pose import Transform, Pose -from .robot_descriptions import robot_description -import os import math + class bcolors: """ Color codes which can be used to highlight Text in the Terminal. For example, @@ -59,28 +56,10 @@ def _apply_ik(robot: BulletWorldObject, joint_poses: List[float], joints: List[s # robot.set_joint_state(joints[i], joint_poses[i]) -def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robot: BulletWorldObject) -> Tuple[ - List[float], List[float]]: - map_T_torso = robot.links[robot_description.torso_link].pose_as_list - torso_T_map = p.invertTransform(map_T_torso[0], map_T_torso[1]) - map_T_target = pose_and_rotation - torso_T_target = p.multiplyTransforms(torso_T_map[0], torso_T_map[1], map_T_target[0], map_T_target[1]) - return torso_T_target - - def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: BulletWorldObject) -> Transform: return robot.links[wrist_frame].get_transform_to_link(robot.links[tool_frame]) -def inverseTimes(transform1: Tuple[List[float], List[float]], transform2: Tuple[List[float], List[float]]) -> Tuple[ - List[float], List[float]]: - """ - Like a Minus for Transforms, this subtracts the second transform from the first. - """ - inv = p.invertTransform(transform2[0], transform2[1]) - return p.multiplyTransforms(transform1[0], transform1[1], inv[0], inv[1]) - - def transform(pose: List[float], transformation: List[float], local_coords=False): # TODO: if pose is a list of position and orientation calculate new pose w/ orientation too diff --git a/src/pycram/old_world_reasoning.py b/src/pycram/old_world_reasoning.py new file mode 100644 index 000000000..452cce72c --- /dev/null +++ b/src/pycram/old_world_reasoning.py @@ -0,0 +1,365 @@ +import pybullet as p +import itertools +import numpy as np +import rospy + +from .world import _world_and_id, Object, UseProspectionWorld +from .bullet_world import BulletWorld +from .external_interfaces.ik import request_ik +from .local_transformer import LocalTransformer +from .plan_failures import IKError +from .robot_descriptions import robot_description +from .helper import _apply_ik +from .pose import Pose, Transform +from typing import List, Tuple, Optional, Union, Dict + + +class ReasoningError(Exception): + def __init__(self, *args, **kwargs): + Exception.__init__(self, *args, **kwargs) + + +class CollisionError(Exception): + def __init__(self, *args, **kwargs): + Exception.__init__(self, *args, **kwargs) + + +def _get_joint_names(robot: Object, tip_link: str) -> List[str]: + res = [] + for i in range(p.getNumJoints(robot.id)): + info = p.getJointInfo(robot.id, i) + if info[2] != p.JOINT_FIXED: + res.append(info[1]) + return res + + +def _get_images_for_target(target_pose: Pose, + cam_pose: Pose, + world: Optional[BulletWorld] = None, + size: Optional[int] = 256) -> List[np.ndarray]: + """ + Calculates the view and projection Matrix and returns 3 images: + + 1. An RGB image + 2. A depth image + 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. + + From the given target_pose and cam_pose only the position is used. + + :param cam_pose: The pose of the camera + :param target_pose: The pose to which the camera should point to + :param size: The height and width of the images in pixel + :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. + """ + world, world_id = _world_and_id(world) + # TODO: Might depend on robot cameras, if so please add these camera parameters to RobotDescription object + # TODO: of your robot with a CameraDescription object. + fov = 90 + aspect = size / size + near = 0.2 + far = 100 + + view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) + projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) + return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=world_id))[2:5] + + +def _get_joint_ranges(robot: Object) -> Tuple[List, List, List, List, List]: + """ + Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. + Fixed joints will be skipped because they don't have limits or ranges. + + :param robot: The robot for whom the values should be calculated + :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping + """ + ll, ul, jr, rp, jd = [], [], [], [], [] + + for i in range(0, p.getNumJoints(robot.id)): + info = p.getJointInfo(robot.id, i) + if info[3] > -1: + ll.append(info[8]) + ul.append(info[9]) + jr.append(info[9] - info[8]) + rp.append(p.getJointState(robot.id, i)[0]) + jd.append(info[6]) + + return ll, ul, jr, rp, jd + + +def stable(object: Object, + world: Optional[BulletWorld] = None) -> bool: + """ + Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating physics + in the BulletWorld. This will be done by simulating the world for 10 seconds and compare the previous coordinates + with the coordinates after the simulation. + + :param object: The object which should be checked + :param world: The BulletWorld if more than one BulletWorld is active + :return: True if the given object is stable in the world False else + """ + world, world_id = _world_and_id(world) + shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) + with UseProspectionWorld(): + coords_prev = shadow_obj.get_position_as_list() + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) + + # one Step is approximately 1/240 seconds + BulletWorld.current_world.simulate(2) + # coords_past = p.getBasePositionAndOrientation(object.id, physicsClientId=world_id)[0] + coords_past = shadow_obj.get_position_as_list() + + # p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) + coords_prev = list(map(lambda n: round(n, 3), coords_prev)) + coords_past = list(map(lambda n: round(n, 3), coords_past)) + return coords_past == coords_prev + + +def contact(object1: Object, + object2: Object, + return_links: bool = False) -> Union[bool, Tuple[bool, List]]: + """ + Checks if two objects are in contact or not. If the links should be returned then the output will also contain a + list of tuples where the first element is the link name of 'object1' and the second element is the link name of + 'object2'. + + :param object1: The first object + :param object2: The second object + :param return_links: If the respective links on the objects that are in contact should be returned. + :return: True if the two objects are in contact False else. If links should be returned a list of links in contact + """ + + with UseProspectionWorld(): + shadow_obj1 = BulletWorld.current_world.get_prospection_object_from_object(object1) + shadow_obj2 = BulletWorld.current_world.get_prospection_object_from_object(object2) + p.performCollisionDetection(BulletWorld.current_world.client_id) + con_points = p.getContactPoints(shadow_obj1.id, shadow_obj2.id, + physicsClientId=BulletWorld.current_world.client_id) + + if return_links: + contact_links = [] + for point in con_points: + contact_links.append((shadow_obj1.get_link_by_id(point[3]), shadow_obj2.get_link_by_id(point[4]))) + return con_points != (), contact_links + + else: + return con_points != () + + +def visible(object: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None, + threshold: float = 0.8, + world: Optional[BulletWorld] = None) -> bool: + """ + Checks if an object is visible from a given position. This will be achieved by rendering the object + alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the + absolut count of pixels. + + :param object: The object for which the visibility should be checked + :param camera_pose: The pose of the camera in map frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :param threshold: The minimum percentage of the object that needs to be visible for this method to return true + :param world: The BulletWorld if more than one BulletWorld is active + :return: True if the object is visible from the camera_position False if not + """ + front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis + with UseProspectionWorld(): + shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) + if BulletWorld.robot: + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + for obj in BulletWorld.current_world.objects: + if obj == shadow_obj or BulletWorld.robot and obj == shadow_robot: + continue + else: + obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + world_to_cam = camera_pose.to_transform("camera") + cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") + target_point = (world_to_cam * cam_to_point).to_pose() + # target_point = p.multiplyTransforms(world_to_cam.translation_as_list(), world_to_cam.rotation_as_list(), cam_to_point.translation_as_list(), [0, 0, 0, 1]) + # print(target_point) + + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] + flat_list = list(itertools.chain.from_iterable(seg_mask)) + max_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) + p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) + if max_pixel == 0: + # Object is not visible + return False + + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] + flat_list = list(itertools.chain.from_iterable(seg_mask)) + real_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) + + return real_pixel / max_pixel > threshold > 0 + + +def occluding(object: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None, + world: Optional[BulletWorld] = None) -> List[Object]: + """ + Lists all objects which are occluding the given object. This works similar to 'visible'. + First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. + After that the complete scene will be rendered and the previous saved pixel positions will be compared to the + actual pixels, if in one pixel another object is visible ot will be saved as occluding. + + :param object: The object for which occlusion should be checked + :param camera_pose: The pose of the camera in world coordinate frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :param world: The BulletWorld if more than one BulletWorld is active + :return: A list of occluding objects + """ + front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis + world, world_id = _world_and_id(world) + # occ_world = world.copy() + # state = p.saveState(physicsClientId=occ_world.client_id) + with UseProspectionWorld(): + state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) + for obj in BulletWorld.current_world.objects: + if obj.name == BulletWorld.robot.name: + continue + elif object.get_pose() == obj.get_pose(): + object = obj + else: + obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + world_to_cam = camera_pose.to_transform("camera") + cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") + target_point = (world_to_cam * cam_to_point).to_pose() + + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] + + # All indices where the object that could be occluded is in the image + # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension + pix = np.dstack((seg_mask == object.id).nonzero())[0] + + p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) + + occluding = [] + seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] + for c in pix: + if not seg_mask[c[0]][c[1]] == object.id: + occluding.append(seg_mask[c[0]][c[1]]) + + occ_objects = list(set(map(BulletWorld.current_world.get_object_by_id, occluding))) + occ_objects = list(map(world.get_object_from_prospection_object, occ_objects)) + + return occ_objects + + +def reachable(pose: Union[Object, Pose], + robot: Object, + gripper_name: str, + threshold: float = 0.01) -> bool: + """ + Checks if the robot can reach a given position. To determine this the inverse kinematics are + calculated and applied. Afterward the distance between the position and the given end effector is calculated, if + it is smaller than the threshold the reasoning query returns True, if not it returns False. + + :param pose: The position and rotation or Object for which reachability should be checked or an Object + :param robot: The robot that should reach for the position + :param gripper_name: The name of the end effector + :param threshold: The threshold between the end effector and the position. + :return: True if the end effector is closer than the threshold to the target position, False in every other case + """ + if type(pose) == Object: + pose = pose.get_pose() + + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" + joints = robot_description.chains[arm].joints + try: + inv = request_ik(pose, shadow_robot, joints, gripper_name) + except IKError as e: + return False + + _apply_ik(shadow_robot, inv, joints) + + diff = pose.dist(shadow_robot.links[gripper_name].pose) + + return diff < threshold + + +def blocking(pose_or_object: Union[Object, Pose], + robot: Object, + gripper_name: str, + grasp: str = None) -> Union[List[Object], None]: + """ + Checks if any objects are blocking another object when a robot tries to pick it. This works + similar to the reachable predicate. First the inverse kinematics between the robot and the object will be calculated + and applied. Then it will be checked if the robot is in contact with any object except the given one. If the given + pose or Object is not reachable None will be returned + + :param pose_or_object: The object or pose for which blocking objects should be found + :param robot: The robot Object who reaches for the object + :param gripper_name: The name of the end effector of the robot + :param grasp: The grasp type with which the object should be grasped + :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose + or object is not reachable. + """ + if type(pose_or_object) == Object: + input_pose = pose_or_object.get_pose() + else: + input_pose = pose_or_object + + shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" + joints = robot_description.chains[arm].joints + local_transformer = LocalTransformer() + + target_map = local_transformer.transform_pose_to_target_frame(input_pose, "map") + if grasp: + grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) + target_map.orientation.x = grasp_orientation[0] + target_map.orientation.y = grasp_orientation[1] + target_map.orientation.z = grasp_orientation[2] + target_map.orientation.w = grasp_orientation[3] + + try: + inv = request_ik(target_map, shadow_robot, joints, gripper_name) + except IKError as e: + rospy.logerr(f"Pose is not reachable: {e}") + return None + _apply_ik(shadow_robot, inv, joints) + + block = [] + for obj in BulletWorld.current_world.objects: + if contact(shadow_robot, obj): + block.append(BulletWorld.current_world.get_object_from_prospection_object(obj)) + return block + + +def supporting(object1: Object, + object2: Object) -> bool: + """ + Checks if one object is supporting another object. An object supports another object if they are in + contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) + + :param object1: Object that is supported + :param object2: Object that supports the first object + :return: True if the second object is in contact with the first one and the second one ist above the first False else + """ + return contact(object1, object2) and object2.get_position().z > object1.get_position().z + + +def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], link_name: str) -> Pose: + """ + Returns the pose a link would be in if the given joint configuration would be applied to the object. This is done + by using the respective object in the shadow world and applying the joint configuration to this one. After applying + the joint configuration the link position is taken from there. + + :param object: Object of which the link is a part + :param joint_config: Dict with the goal joint configuration + :param link_name: Name of the link for which the pose should be returned + :return: The pose of the link after applying the joint configuration + """ + shadow_object = BulletWorld.current_world.get_prospection_object_from_object(object) + with UseProspectionWorld(): + for joint, pose in joint_config.items(): + shadow_object.set_joint_position(joint, pose) + return shadow_object.links[link_name].pose \ No newline at end of file diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index ad2932322..27e4d08c4 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -1,17 +1,27 @@ import time from threading import Lock +from typing import Tuple, List import pybullet as p import pycram.world_reasoning as btr import pycram.helper as helper -from ..bullet_world import BulletWorld +from ..bullet_world import BulletWorld, Object as BulletWorldObject from ..external_interfaces.ik import request_ik from ..local_transformer import LocalTransformer as local_tf from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description +def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robot: BulletWorldObject) -> Tuple[ + List[float], List[float]]: + map_T_torso = robot.links[robot_description.torso_link].pose_as_list + torso_T_map = p.invertTransform(map_T_torso[0], map_T_torso[1]) + map_T_target = pose_and_rotation + torso_T_target = p.multiplyTransforms(torso_T_map[0], torso_T_map[1], map_T_target[0], map_T_target[1]) + return torso_T_target + + def _park_arms(arm): """ Defines the joint poses for the parking positions of the arms of Boxy and applies them to the @@ -60,7 +70,7 @@ def _execute(self, desig): robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(solution['grasp']) target = [object.get_position(), grasp] - target = helper._transform_to_torso(target, robot) + target = _transform_to_torso(target, robot) arm = "left" if solution['gripper'] == robot_description.get_tool_frame("left") else "right" joints = robot_description._safely_access_chains(arm).joints #tip = "r_wrist_roll_link" if solution['gripper'] == "r_gripper_tool_frame" else "l_wrist_roll_link" @@ -83,7 +93,7 @@ def _execute(self, desig): object = solution['object'] robot = BulletWorld.robot target = object.get_position_and_orientation() - target = helper._transform_to_torso(target, robot) + target = _transform_to_torso(target, robot) arm = "left" if solution['gripper'] == robot_description.get_tool_frame("left") else "right" joints = robot_description._safely_access_chains(arm).joints #tip = "r_wrist_roll_link" if solution['gripper'] == "r_gripper_tool_frame" else "l_wrist_roll_link" @@ -113,7 +123,7 @@ def _execute(self, desig): robot.set_joint_position(robot_description.torso_joint, -0.1) arm = "left" if solution['gripper'] == robot_description.get_tool_frame("left") else "right" joints = robot_description._safely_access_chains(arm).joints - target = helper._transform_to_torso(kitchen.links[drawer_handle].pose, robot) + target = _transform_to_torso(kitchen.links[drawer_handle].pose, robot) inv = request_ik(robot_description.base_frame, gripper, target , robot, joints ) helper._apply_ik(robot, inv, gripper) time.sleep(0.2) @@ -121,7 +131,7 @@ def _execute(self, desig): robot.set_position([cur_pose[0]-dis, cur_pose[1], cur_pose[2]]) han_pose = kitchen.links[drawer_handle].position new_p = [[han_pose[0] - dis, han_pose[1], han_pose[2]], kitchen.links[drawer_handle].orientation] - new_p = helper._transform_to_torso(new_p, robot) + new_p = _transform_to_torso(new_p, robot) inv = request_ik(robot_description.base_frame, gripper, new_p, robot, joints) helper._apply_ik(robot, inv, gripper) kitchen.set_joint_position(drawer_joint, 0.3) diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 8c96af6e7..93254ba0e 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -1,4 +1,3 @@ -from abc import ABC from threading import Lock from typing import Any @@ -6,17 +5,12 @@ import pycram.world_reasoning as btr import numpy as np -import time import rospy -import pybullet as p - -from ..plan_failures import EnvironmentManipulationImpossible -from ..robot_descriptions import robot_description -from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld, Object -from ..helper import transform -from ..external_interfaces.ik import request_ik, IKError -from ..helper import _transform_to_torso, _apply_ik, calculate_wrist_tool_offset, inverseTimes + + +from ..process_module import ProcessModule +from ..external_interfaces.ik import request_ik +from ..helper import _apply_ik from ..local_transformer import LocalTransformer from ..designators.motion_designator import * from ..enums import JointType, ObjectType diff --git a/src/pycram/world.py b/src/pycram/world.py index f4ff2c2e9..fa5b50d3d 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -13,7 +13,6 @@ from tf.transformations import quaternion_from_euler from typing import List, Optional, Dict, Tuple, Callable from typing import Union -from copy import deepcopy import numpy as np import rospkg @@ -298,6 +297,13 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: # Simulation runs at 240 Hz time.sleep(self.simulation_time_step) + @abstractmethod + def perform_collision_detection(self) -> None: + """ + Checks for collisions between all objects in the World and updates the contact points. + """ + pass + @abstractmethod def get_object_contact_points(self, obj: Object) -> List: """ @@ -626,6 +632,24 @@ def restore_objects_states(self, state_id: int): for obj in self.objects: obj.restore_state(state_id) + def get_images_for_target(self, + target_pose: Pose, + cam_pose: Pose, + size: Optional[int] = 256) -> List[np.ndarray]: + """ + Calculates the view and projection Matrix and returns 3 images: + + 1. An RGB image + 2. A depth image + 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. + + :param cam_pose: The pose of the camera + :param target_pose: The pose to which the camera should point to + :param size: The height and width of the images in pixel + :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. + """ + pass + def _copy(self) -> World: """ Copies this World into another and returns it. The other World diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 1e5f48c3e..d992fd0a0 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -4,12 +4,12 @@ import rospy from .world import _world_and_id, Object, UseProspectionWorld -from .bullet_world import BulletWorld +from .world import World from .external_interfaces.ik import request_ik from .local_transformer import LocalTransformer from .plan_failures import IKError from .robot_descriptions import robot_description -from .helper import _transform_to_torso, _apply_ik, calculate_wrist_tool_offset, inverseTimes +from .helper import _apply_ik from .pose import Pose, Transform from typing import List, Tuple, Optional, Union, Dict @@ -24,46 +24,6 @@ def __init__(self, *args, **kwargs): Exception.__init__(self, *args, **kwargs) -def _get_joint_names(robot: Object, tip_link: str) -> List[str]: - res = [] - for i in range(p.getNumJoints(robot.id)): - info = p.getJointInfo(robot.id, i) - if info[2] != p.JOINT_FIXED: - res.append(info[1]) - return res - - -def _get_images_for_target(target_pose: Pose, - cam_pose: Pose, - world: Optional[BulletWorld] = None, - size: Optional[int] = 256) -> List[np.ndarray]: - """ - Calculates the view and projection Matrix and returns 3 images: - - 1. An RGB image - 2. A depth image - 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. - - From the given target_pose and cam_pose only the position is used. - - :param cam_pose: The pose of the camera - :param target_pose: The pose to which the camera should point to - :param size: The height and width of the images in pixel - :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. - """ - world, world_id = _world_and_id(world) - # TODO: Might depend on robot cameras, if so please add these camera parameters to RobotDescription object - # TODO: of your robot with a CameraDescription object. - fov = 90 - aspect = size / size - near = 0.2 - far = 100 - - view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) - projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) - return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=world_id))[2:5] - - def _get_joint_ranges(robot: Object) -> Tuple[List, List, List, List, List]: """ Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. @@ -86,280 +46,287 @@ def _get_joint_ranges(robot: Object) -> Tuple[List, List, List, List, List]: return ll, ul, jr, rp, jd -def stable(object: Object, - world: Optional[BulletWorld] = None) -> bool: - """ - Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating physics - in the BulletWorld. This will be done by simulating the world for 10 seconds and compare the previous coordinates - with the coordinates after the simulation. - - :param object: The object which should be checked - :param world: The BulletWorld if more than one BulletWorld is active - :return: True if the given object is stable in the world False else +def _try_to_reach_or_grasp(pose_or_object: Union[Pose, Object], prospection_robot: Object, gripper_name: str, + grasp: Optional[str] = None) -> Union[Pose, None]: """ - world, world_id = _world_and_id(world) - shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) - with UseProspectionWorld(): - coords_prev = shadow_obj.get_position_as_list() - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) - - # one Step is approximately 1/240 seconds - BulletWorld.current_world.simulate(2) - # coords_past = p.getBasePositionAndOrientation(object.id, physicsClientId=world_id)[0] - coords_past = shadow_obj.get_position_as_list() - - # p.restoreState(state, physicsClientId=BulletWorld.current_bullet_world.client_id) - coords_prev = list(map(lambda n: round(n, 3), coords_prev)) - coords_past = list(map(lambda n: round(n, 3), coords_past)) - return coords_past == coords_prev - - -def contact(object1: Object, - object2: Object, - return_links: bool = False) -> Union[bool, Tuple[bool, List]]: - """ - Checks if two objects are in contact or not. If the links should be returned then the output will also contain a - list of tuples where the first element is the link name of 'object1' and the second element is the link name of - 'object2'. - - :param object1: The first object - :param object2: The second object - :param return_links: If the respective links on the objects that are in contact should be returned. - :return: True if the two objects are in contact False else. If links should be returned a list of links in contact - """ - - with UseProspectionWorld(): - shadow_obj1 = BulletWorld.current_world.get_prospection_object_from_object(object1) - shadow_obj2 = BulletWorld.current_world.get_prospection_object_from_object(object2) - p.performCollisionDetection(BulletWorld.current_world.client_id) - con_points = p.getContactPoints(shadow_obj1.id, shadow_obj2.id, - physicsClientId=BulletWorld.current_world.client_id) - - if return_links: - contact_links = [] - for point in con_points: - contact_links.append((shadow_obj1.get_link_by_id(point[3]), shadow_obj2.get_link_by_id(point[4]))) - return con_points != (), contact_links + Checks if the robot can reach a given position and optionally also grasp an object. + To determine this the inverse kinematics are calculated and applied. - else: - return con_points != () - - -def visible(object: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None, - threshold: float = 0.8, - world: Optional[BulletWorld] = None) -> bool: - """ - Checks if an object is visible from a given position. This will be achieved by rendering the object - alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the - absolut count of pixels. - - :param object: The object for which the visibility should be checked - :param camera_pose: The pose of the camera in map frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :param threshold: The minimum percentage of the object that needs to be visible for this method to return true - :param world: The BulletWorld if more than one BulletWorld is active - :return: True if the object is visible from the camera_position False if not - """ - front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - with UseProspectionWorld(): - shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) - if BulletWorld.robot: - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - for obj in BulletWorld.current_world.objects: - if obj == shadow_obj or BulletWorld.robot and obj == shadow_robot: - continue - else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - world_to_cam = camera_pose.to_transform("camera") - cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") - target_point = (world_to_cam * cam_to_point).to_pose() - # target_point = p.multiplyTransforms(world_to_cam.translation_as_list(), world_to_cam.rotation_as_list(), cam_to_point.translation_as_list(), [0, 0, 0, 1]) - # print(target_point) - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - flat_list = list(itertools.chain.from_iterable(seg_mask)) - max_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) - p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) - if max_pixel == 0: - # Object is not visible - return False - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - flat_list = list(itertools.chain.from_iterable(seg_mask)) - real_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) - - return real_pixel / max_pixel > threshold > 0 - - -def occluding(object: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None, - world: Optional[BulletWorld] = None) -> List[Object]: - """ - Lists all objects which are occluding the given object. This works similar to 'visible'. - First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. - After that the complete scene will be rendered and the previous saved pixel positions will be compared to the - actual pixels, if in one pixel another object is visible ot will be saved as occluding. - - :param object: The object for which occlusion should be checked - :param camera_pose: The pose of the camera in world coordinate frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :param world: The BulletWorld if more than one BulletWorld is active - :return: A list of occluding objects - """ - front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - world, world_id = _world_and_id(world) - # occ_world = world.copy() - # state = p.saveState(physicsClientId=occ_world.client_id) - with UseProspectionWorld(): - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - for obj in BulletWorld.current_world.objects: - if obj.name == BulletWorld.robot.name: - continue - elif object.get_pose() == obj.get_pose(): - object = obj - else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - world_to_cam = camera_pose.to_transform("camera") - cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") - target_point = (world_to_cam * cam_to_point).to_pose() - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - - # All indices where the object that could be occluded is in the image - # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension - pix = np.dstack((seg_mask == object.id).nonzero())[0] - - p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) - - occluding = [] - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - for c in pix: - if not seg_mask[c[0]][c[1]] == object.id: - occluding.append(seg_mask[c[0]][c[1]]) - - occ_objects = list(set(map(BulletWorld.current_world.get_object_by_id, occluding))) - occ_objects = list(map(world.get_object_from_prospection_object, occ_objects)) - - return occ_objects - - -def reachable(pose: Union[Object, Pose], - robot: Object, - gripper_name: str, - threshold: float = 0.01) -> bool: - """ - Checks if the robot can reach a given position. To determine this the inverse kinematics are - calculated and applied. Afterward the distance between the position and the given end effector is calculated, if - it is smaller than the threshold the reasoning query returns True, if not it returns False. - - :param pose: The position and rotation or Object for which reachability should be checked or an Object - :param robot: The robot that should reach for the position + :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object + :param prospection_robot: The robot that should reach for the position :param gripper_name: The name of the end effector - :param threshold: The threshold between the end effector and the position. - :return: True if the end effector is closer than the threshold to the target position, False in every other case - """ - if type(pose) == Object: - pose = pose.get_pose() - - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" - joints = robot_description.chains[arm].joints - try: - inv = request_ik(pose, shadow_robot, joints, gripper_name) - except IKError as e: - return False - - _apply_ik(shadow_robot, inv, joints) - - diff = pose.dist(shadow_robot.links[gripper_name].pose) - - return diff < threshold - - -def blocking(pose_or_object: Union[Object, Pose], - robot: Object, - gripper_name: str, - grasp: str = None) -> Union[List[Object], None]: - """ - Checks if any objects are blocking another object when a robot tries to pick it. This works - similar to the reachable predicate. First the inverse kinematics between the robot and the object will be calculated - and applied. Then it will be checked if the robot is in contact with any object except the given one. If the given - pose or Object is not reachable None will be returned - - :param pose_or_object: The object or pose for which blocking objects should be found - :param robot: The robot Object who reaches for the object - :param gripper_name: The name of the end effector of the robot :param grasp: The grasp type with which the object should be grasped - :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose - or object is not reachable. """ - if type(pose_or_object) == Object: + if isinstance(pose_or_object, Object): input_pose = pose_or_object.get_pose() else: input_pose = pose_or_object - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" - joints = robot_description.chains[arm].joints + arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" + joints = robot_description.chains[arm].joints + target_pose = input_pose + if grasp: local_transformer = LocalTransformer() - target_map = local_transformer.transform_pose_to_target_frame(input_pose, "map") - if grasp: - grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) - target_map.orientation.x = grasp_orientation[0] - target_map.orientation.y = grasp_orientation[1] - target_map.orientation.z = grasp_orientation[2] - target_map.orientation.w = grasp_orientation[3] - - try: - inv = request_ik(target_map, robot, joints, gripper_name) - except IKError as e: - rospy.logerr(f"Pose is not reachable: {e}") - return None - _apply_ik(shadow_robot, inv, joints) - - block = [] - for obj in BulletWorld.current_world.objects: - if contact(shadow_robot, obj): - block.append(BulletWorld.current_world.get_object_from_prospection_object(obj)) - return block - - -def supporting(object1: Object, - object2: Object) -> bool: - """ - Checks if one object is supporting another object. An object supports another object if they are in - contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) + grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) + target_map.orientation.x = grasp_orientation[0] + target_map.orientation.y = grasp_orientation[1] + target_map.orientation.z = grasp_orientation[2] + target_map.orientation.w = grasp_orientation[3] + target_pose = target_map + + try: + inv = request_ik(target_pose, prospection_robot, joints, gripper_name) + except IKError as e: + rospy.logerr(f"Pose is not reachable: {e}") + return None + _apply_ik(prospection_robot, inv, joints) + + return target_pose + + +class WorldReasoning: + + def __init__(self, world: World): + self.world = world + + def stable(self, obj: Object) -> bool: + """ + Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating physics + in the BulletWorld. This will be done by simulating the world for 10 seconds and compare the previous coordinates + with the coordinates after the simulation. + + :param obj: The object which should be checked + :return: True if the given object is stable in the world False else + """ + prospection_obj = self.world.get_prospection_object_from_object(obj) + with UseProspectionWorld(): + coords_prev = prospection_obj.get_position_as_list() + self.world.set_gravity([0, 0, -9.8]) + + self.world.simulate(2) + coords_past = prospection_obj.get_position_as_list() + + coords_prev = list(map(lambda n: round(n, 3), coords_prev)) + coords_past = list(map(lambda n: round(n, 3), coords_past)) + return coords_past == coords_prev + + def contact(self, + object1: Object, + object2: Object, + return_links: bool = False) -> Union[bool, Tuple[bool, List]]: + """ + Checks if two objects are in contact or not. If the links should be returned then the output will also contain a + list of tuples where the first element is the link name of 'object1' and the second element is the link name of + 'object2'. + + :param object1: The first object + :param object2: The second object + :param return_links: If the respective links on the objects that are in contact should be returned. + :return: True if the two objects are in contact False else. If links should be returned a list of links in contact + """ + + with UseProspectionWorld(): + prospection_obj1 = self.world.get_prospection_object_from_object(object1) + prospection_obj2 = self.world.get_prospection_object_from_object(object2) + + self.world.perform_collision_detection() + con_points = self.world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) + + if return_links: + contact_links = [] + for point in con_points: + contact_links.append((prospection_obj1.get_link_by_id(point[3]), prospection_obj2.get_link_by_id(point[4]))) + return con_points != (), contact_links - :param object1: Object that is supported - :param object2: Object that supports the first object - :return: True if the second object is in contact with the first one and the second one ist above the first False else - """ - return contact(object1, object2) and object2.get_position().z > object1.get_position().z + else: + return con_points != () + def get_visible_objects(self, camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None) -> Tuple[np.ndarray, Pose]: -def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], link_name: str) -> Pose: - """ - Returns the pose a link would be in if the given joint configuration would be applied to the object. This is done - by using the respective object in the shadow world and applying the joint configuration to this one. After applying - the joint configuration the link position is taken from there. - - :param object: Object of which the link is a part - :param joint_config: Dict with the goal joint configuration - :param link_name: Name of the link for which the pose should be returned - :return: The pose of the link after applying the joint configuration - """ - shadow_object = BulletWorld.current_world.get_prospection_object_from_object(object) - with UseProspectionWorld(): - for joint, pose in joint_config.items(): - shadow_object.set_joint_position(joint, pose) - return shadow_object.links[link_name].pose + front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis + + world_to_cam = camera_pose.to_transform("camera") + + cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", + "point") + target_point = (world_to_cam * cam_to_point).to_pose() + + seg_mask = self.world.get_images_for_target(target_point, world_to_cam.to_pose())[2] + + return seg_mask, target_point + + def visible(self, + obj: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None, + threshold: float = 0.8) -> bool: + """ + Checks if an object is visible from a given position. This will be achieved by rendering the object + alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the + absolut count of pixels. + + :param obj: The object for which the visibility should be checked + :param camera_pose: The pose of the camera in map frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :param threshold: The minimum percentage of the object that needs to be visible for this method to return true. + :return: True if the object is visible from the camera_position False if not + """ + with UseProspectionWorld(): + prospection_obj = self.world.get_prospection_object_from_object(obj) + if World.robot: + prospection_robot = self.world.get_prospection_object_from_object(World.robot) + + state_id = self.world.save_state() + for obj in self.world.objects: + if obj == prospection_obj or World.robot and obj == prospection_robot: + continue + else: + obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) + flat_list = list(itertools.chain.from_iterable(seg_mask)) + max_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) + self.world.restore_state(state_id) + + if max_pixel == 0: + # Object is not visible + return False + + seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] + flat_list = list(itertools.chain.from_iterable(seg_mask)) + real_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) + + return real_pixel / max_pixel > threshold > 0 + + def occluding(self, + obj: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None) -> List[Object]: + """ + Lists all objects which are occluding the given object. This works similar to 'visible'. + First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. + After that the complete scene will be rendered and the previous saved pixel positions will be compared to the + actual pixels, if in one pixel another object is visible ot will be saved as occluding. + + :param obj: The object for which occlusion should be checked + :param camera_pose: The pose of the camera in world coordinate frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :return: A list of occluding objects + """ + + with UseProspectionWorld(): + state_id = self.world.save_state() + for other_obj in self.world.objects: + if other_obj.name == self.world.robot.name: + continue + elif obj.get_pose() == other_obj.get_pose(): + obj = other_obj + else: + obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) + + # All indices where the object that could be occluded is in the image + # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension + pix = np.dstack((seg_mask == obj.id).nonzero())[0] + + self.world.restore_state(state_id) + + occluding = [] + seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] + for c in pix: + if not seg_mask[c[0]][c[1]] == obj.id: + occluding.append(seg_mask[c[0]][c[1]]) + + occ_objects = list(set(map(self.world.get_object_by_id, occluding))) + occ_objects = list(map(self.world.get_object_from_prospection_object, occ_objects)) + + return occ_objects + + def reachable(self, + pose_or_object: Union[Object, Pose], + robot: Object, + gripper_name: str, + threshold: float = 0.01) -> bool: + """ + Checks if the robot can reach a given position. To determine this the inverse kinematics are + calculated and applied. Afterward the distance between the position and the given end effector is calculated, if + it is smaller than the threshold the reasoning query returns True, if not it returns False. + + :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object + :param robot: The robot that should reach for the position + :param gripper_name: The name of the end effector + :param threshold: The threshold between the end effector and the position. + :return: True if the end effector is closer than the threshold to the target position, False in every other case + """ + + prospection_robot = self.world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + target_pose = _try_to_reach_or_grasp(pose_or_object, robot, gripper_name) + + if not target_pose: + return False + + diff = target_pose.dist(prospection_robot.links[gripper_name].pose) + + return diff < threshold + + def blocking(self, + pose_or_object: Union[Object, Pose], + robot: Object, + gripper_name: str, + grasp: str = None) -> Union[List[Object], None]: + """ + Checks if any objects are blocking another object when a robot tries to pick it. This works + similar to the reachable predicate. First the inverse kinematics between the robot and the object will be + calculated and applied. Then it will be checked if the robot is in contact with any object except the given one. + If the given pose or Object is not reachable None will be returned + + :param pose_or_object: The object or pose for which blocking objects should be found + :param robot: The robot Object who reaches for the object + :param gripper_name: The name of the end effector of the robot + :param grasp: The grasp type with which the object should be grasped + :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose + or object is not reachable. + """ + prospection_robot = self.world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + _try_to_reach_or_grasp(pose_or_object, robot, gripper_name, grasp) + + block = [] + for obj in self.world.objects: + if self.contact(prospection_robot, obj): + block.append(self.world.get_object_from_prospection_object(obj)) + return block + + def supporting(self, + object1: Object, + object2: Object) -> bool: + """ + Checks if one object is supporting another object. An object supports another object if they are in + contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) + + :param object1: Object that is supported + :param object2: Object that supports the first object + :return: True if the second object is in contact with the first one and the second one ist above the first False else + """ + return self.contact(object1, object2) and object2.get_position().z > object1.get_position().z + + def link_pose_for_joint_config(self, obj: Object, joint_config: Dict[str, float], link_name: str) -> Pose: + """ + Returns the pose a link would be in if the given joint configuration would be applied to the object. + This is done by using the respective object in the prospection world and applying the joint configuration + to this one. After applying the joint configuration the link position is taken from there. + + :param obj: Object of which the link is a part + :param joint_config: Dict with the goal joint configuration + :param link_name: Name of the link for which the pose should be returned + :return: The pose of the link after applying the joint configuration + """ + prospection_object = self.world.get_prospection_object_from_object(obj) + with UseProspectionWorld(): + for joint, pose in joint_config.items(): + prospection_object.set_joint_position(joint, pose) + return prospection_object.links[link_name].pose diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index d847957bc..52ab7c386 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -1,6 +1,5 @@ import unittest -import numpy as np from pycram.bullet_world import BulletWorld from pycram.world import Object, fix_missing_inertial from pycram.pose import Pose @@ -9,7 +8,6 @@ from pycram.enums import ObjectType import os import xml.etree.ElementTree as ET -import tf class BulletWorldTest(unittest.TestCase): diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index 2fc1055cd..b7463873f 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -1,7 +1,8 @@ import time from test_bullet_world import BulletWorldTest -import pycram.world_reasoning as btr +from pycram.world_reasoning import WorldReasoning +import pycram.old_world_reasoning as btr from pycram.pose import Pose from pycram.robot_descriptions import robot_description @@ -9,12 +10,14 @@ class TestBulletWorldReasoning(BulletWorldTest): def test_contact(self): + # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1, 1, 1])) self.cereal.set_pose(Pose([1, 1, 1])) time.sleep(1) self.assertTrue(btr.contact(self.milk, self.cereal)) def test_visible(self): + # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1.5, 0, 1.2])) self.robot.set_pose(Pose()) time.sleep(1) @@ -22,22 +25,26 @@ def test_visible(self): robot_description.front_facing_axis)) def test_occluding(self): + # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([3, 0, 1.2])) self.robot.set_pose(Pose()) self.assertTrue(btr.occluding(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, robot_description.front_facing_axis) != []) def test_reachable(self): + # btr = WorldReasoning(self.world) self.robot.set_pose(Pose()) self.assertTrue(btr.reachable(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right"))) self.assertFalse(btr.reachable(Pose([2, 2, 1]), self.robot, robot_description.get_tool_frame("right"))) def test_blocking(self): + # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([0.5, -0.7, 1])) self.robot.set_pose(Pose()) time.sleep(1) self.assertTrue(btr.blocking(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right")) != []) def test_supporting(self): + # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1.3, 0, 0.9])) self.assertTrue(btr.supporting(self.kitchen, self.milk)) From 371d72c01fa4bbef5fb5bf6b920b4a686483e28c Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Mon, 22 Jan 2024 00:24:39 +0100 Subject: [PATCH 045/195] [AbstractWorld] WorldReasoning is now abstracted from pybullet tests are passing created two methods _try_to_reach, try_to_reach_with_grasp in the ik.py --- src/pycram/bullet_world.py | 90 ++++--- src/pycram/external_interfaces/ik.py | 60 ++++- src/pycram/helper.py | 6 +- src/pycram/old_world_reasoning.py | 365 --------------------------- src/pycram/world.py | 40 ++- src/pycram/world_reasoning.py | 104 ++------ test/test_bullet_world_reasoning.py | 23 +- 7 files changed, 194 insertions(+), 494 deletions(-) delete mode 100644 src/pycram/old_world_reasoning.py diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 137764fc0..e5d341959 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -96,6 +96,24 @@ def remove_constraint(self, constraint_id): print("Removing constraint with id: ", constraint_id) p.removeConstraint(constraint_id, physicsClientId=self.client_id) + def get_object_joint_rest_pose(self, obj: Object, joint_name: str) -> float: + """ + Get the joint rest pose of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] + + def get_object_joint_damping(self, obj: Object, joint_name: str) -> float: + """ + Get the joint damping of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[6] + def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: """ Get the joint upper limit of an articulated object @@ -124,7 +142,7 @@ def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: :param joint_name: Name of the joint for which the axis should be returned. :return: The axis a vector of xyz """ - return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], self.client_id)[13] + return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[13] def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: """ @@ -134,7 +152,7 @@ def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: :param joint_name: Joint name for which the type should be returned :return: The type of the joint """ - joint_type = p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], self.client_id)[2] + joint_type = p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[2] return JointType(joint_type) def get_object_joint_position(self, obj: Object, joint_name: str) -> float: @@ -183,14 +201,14 @@ def get_object_joint_names(self, obj_id: int) -> List[str]: Get the names of all joints of an articulated object. """ num_joints = self.get_object_number_of_joints(obj_id) - return [p.getJointInfo(obj_id, i, self.client_id)[1].decode('utf-8') for i in range(num_joints)] + return [p.getJointInfo(obj_id, i, physicsClientId=self.client_id)[1].decode('utf-8') for i in range(num_joints)] def get_object_link_names(self, obj_id: int) -> List[str]: """ Get the names of all joints of an articulated object. """ num_links = self.get_object_number_of_links(obj_id) - return [p.getJointInfo(obj_id, i, self.client_id)[12].decode('utf-8') for i in range(num_links)] + return [p.getJointInfo(obj_id, i, physicsClientId=self.client_id)[12].decode('utf-8') for i in range(num_links)] def get_object_number_of_links(self, obj_id: int) -> int: """ @@ -227,13 +245,13 @@ def reset_object_base_pose(self, obj: Object, position: List[float], orientation :param position: The new position of the object as a vector of x,y,z :param orientation: The new orientation of the object as a quaternion of x,y,z,w """ - p.resetBasePositionAndOrientation(obj.id, position, orientation, self.client_id) + p.resetBasePositionAndOrientation(obj.id, position, orientation, physicsClientId=self.client_id) def step(self): """ Step the world simulation using forward dynamics """ - p.stepSimulation(self.client_id) + p.stepSimulation(physicsClientId=self.client_id) def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): """ @@ -278,7 +296,7 @@ def get_object_link_aabb(self, obj_id: int, link_id: int) -> AxisAlignedBounding Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. """ - return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj_id, link_id, self.client_id)) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj_id, link_id, physicsClientId=self.client_id)) def set_realtime(self, real_time: bool) -> None: """ @@ -287,7 +305,7 @@ def set_realtime(self, real_time: bool) -> None: :param real_time: Whether the World should simulate Physics in real time. """ - p.setRealTimeSimulation(1 if real_time else 0, self.client_id) + p.setRealTimeSimulation(1 if real_time else 0, physicsClientId=self.client_id) def set_gravity(self, gravity_vector: List[float]) -> None: """ @@ -309,7 +327,7 @@ def disconnect_from_physics_server(self): """ Disconnects the world from the physics server. """ - p.disconnect(self.client_id) + p.disconnect(physicsClientId=self.client_id) def join_threads(self): """ @@ -325,7 +343,7 @@ def save_physics_simulator_state(self) -> int: """ Saves the state of the physics simulator and returns the unique id of the state. """ - return p.saveState(self.client_id) + return p.saveState(physicsClientId=self.client_id) def restore_physics_simulator_state(self, state_id): """ @@ -353,11 +371,14 @@ def add_vis_axis(self, pose: Pose, position, orientation = pose.to_list() vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01]) + rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01], + physicsClientId=self.client_id) vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01]) + rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01], + physicsClientId=self.client_id) vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length]) + rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length], + physicsClientId=self.client_id) obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], basePosition=position, baseOrientation=orientation, @@ -368,7 +389,8 @@ def add_vis_axis(self, pose: Pose, linkParentIndices=[0, 0, 0], linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1]) + linkCollisionShapeIndices=[-1, -1, -1], + physicsClientId=self.client_id) self.vis_axis.append(obj) @@ -377,7 +399,7 @@ def remove_vis_axis(self) -> None: Removes all spawned vis axis objects that are currently in this BulletWorld. """ for id in self.vis_axis: - p.removeBody(id) + p.removeBody(id, physicsClientId=self.client_id) self.vis_axis = [] def get_images_for_target(self, @@ -405,8 +427,9 @@ def get_images_for_target(self, near = 0.2 far = 100 - view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) - projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) + view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1], + physicsClientId=self.client_id) + projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far, physicsClientId=self.client_id) return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=self.client_id))[2:5] @@ -434,21 +457,23 @@ def run(self): self.world.client_id = p.connect(p.GUI) # Disable the side windows of the GUI - p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) + p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0, physicsClientId=self.world.client_id) # Change the init camera pose p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1]) + cameraTargetPosition=[-2, 0, 1], physicsClientId=self.world.client_id) # Get the initial camera target location - cameraTargetPosition = p.getDebugVisualizerCamera()[11] + cameraTargetPosition = p.getDebugVisualizerCamera(physicsClientId=self.world.client_id)[11] - sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1]) + sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1], + physicsClientId=self.world.client_id) # Create a sphere with a radius of 0.05 and a mass of 0 sphereUid = p.createMultiBody(baseMass=0.0, baseInertialFramePosition=[0, 0, 0], baseVisualShapeIndex=sphereVisualId, - basePosition=cameraTargetPosition) + basePosition=cameraTargetPosition, + physicsClientId=self.world.client_id) # Define the maxSpeed, used in calculations maxSpeed = 16 @@ -467,17 +492,18 @@ def run(self): # Loop to update the camera position based on keyboard events while p.isConnected(self.world.client_id): # Monitor user input - keys = p.getKeyboardEvents() - mouse = p.getMouseEvents() + keys = p.getKeyboardEvents(physicalClientId=self.world.client_id) + mouse = p.getMouseEvents(physicalClientId=self.world.client_id) # Get infos about the camera - width, height, dist = p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], \ - p.getDebugVisualizerCamera()[10] - cameraTargetPosition = p.getDebugVisualizerCamera()[11] + width, height, dist = (p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[0], + p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[1], + p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[10]) + cameraTargetPosition = p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[11] # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + xVec = [p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[2][i] for i in [0, 4, 8]] + yVec = [p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[2][i] for i in [2, 6, 10]] zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] # Check the mouse state @@ -617,8 +643,10 @@ def run(self): dist += dist * 0.02 * speedMult p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition) + cameraTargetPosition=cameraTargetPosition, + physicsClientId=self.world.client_id) if visible == 0: cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) + p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1], + physicsClientId=self.world.client_id) time.sleep(1. / 80.) \ No newline at end of file diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 664d5133d..262a3c063 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -1,4 +1,4 @@ -from typing import List +from typing import List, Union import pybullet as p import rospy @@ -8,7 +8,7 @@ from sensor_msgs.msg import JointState from ..world import Object -from ..helper import calculate_wrist_tool_offset +from ..helper import calculate_wrist_tool_offset, _apply_ik from ..local_transformer import LocalTransformer from ..pose import Pose, Transform from ..robot_descriptions import robot_description @@ -106,6 +106,62 @@ def call_ik(root_link: str, tip_link: str, target_pose: Pose, robot_object: Obje return resp.solution.joint_state.position +def try_to_reach_with_grasp(pose_or_object: Union[Pose, Object], + prospection_robot: Object, gripper_name: str, + grasp: str) -> Union[Pose, None]: + """ + Checks if the robot can reach a given position with a specific grasp orientation. + To determine this the inverse kinematics are calculated and applied. + + :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object + :param prospection_robot: The robot that should reach for the position + :param gripper_name: The name of the end effector + :param grasp: The grasp type with which the object should be grasped + """ + + input_pose = pose_or_object.get_pose() if isinstance(pose_or_object, Object) else pose_or_object + + target_pose = apply_grasp_orientation_to_pose(grasp, input_pose) + + return try_to_reach(target_pose, prospection_robot, gripper_name) + + +def apply_grasp_orientation_to_pose(grasp: str, pose: Pose) -> Pose: + """ + Applies the orientation of a grasp to a given pose. This is done by using the grasp orientation + of the given grasp and applying it to the given pose. + + :param grasp: The name of the grasp + :param pose: The pose to which the grasp orientation should be applied + """ + local_transformer = LocalTransformer() + target_map = local_transformer.transform_pose_to_target_frame(pose, "map") + grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) + target_map.orientation.x = grasp_orientation[0] + target_map.orientation.y = grasp_orientation[1] + target_map.orientation.z = grasp_orientation[2] + target_map.orientation.w = grasp_orientation[3] + return target_map + + +def try_to_reach(pose_or_object: Union[Pose, Object], prospection_robot: Object, + gripper_name: str) -> Union[Pose, None]: + + input_pose = pose_or_object.get_pose() if isinstance(pose_or_object, Object) else pose_or_object + + arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" + joints = robot_description.chains[arm].joints + + try: + inv = request_ik(input_pose, prospection_robot, joints, gripper_name) + except IKError as e: + rospy.logerr(f"Pose is not reachable: {e}") + return None + _apply_ik(prospection_robot, inv, joints) + + return input_pose + + def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str) -> List[float]: """ Top-level method to request ik solution for a given pose. Before calling the ik service the links directly before diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 090ac17ff..f2ca1ace5 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -15,7 +15,7 @@ from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform from macropy.core.quotes import ast_literal, q -from .world import Object as BulletWorldObject +from .world import Object as WorldObject from .pose import Transform, Pose import math @@ -39,7 +39,7 @@ class bcolors: UNDERLINE = '\033[4m' -def _apply_ik(robot: BulletWorldObject, joint_poses: List[float], joints: List[str]) -> None: +def _apply_ik(robot: WorldObject, joint_poses: List[float], joints: List[str]) -> None: """ Apllies a list of joint poses calculated by an inverse kinematics solver to a robot @@ -56,7 +56,7 @@ def _apply_ik(robot: BulletWorldObject, joint_poses: List[float], joints: List[s # robot.set_joint_state(joints[i], joint_poses[i]) -def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: BulletWorldObject) -> Transform: +def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: WorldObject) -> Transform: return robot.links[wrist_frame].get_transform_to_link(robot.links[tool_frame]) diff --git a/src/pycram/old_world_reasoning.py b/src/pycram/old_world_reasoning.py deleted file mode 100644 index 452cce72c..000000000 --- a/src/pycram/old_world_reasoning.py +++ /dev/null @@ -1,365 +0,0 @@ -import pybullet as p -import itertools -import numpy as np -import rospy - -from .world import _world_and_id, Object, UseProspectionWorld -from .bullet_world import BulletWorld -from .external_interfaces.ik import request_ik -from .local_transformer import LocalTransformer -from .plan_failures import IKError -from .robot_descriptions import robot_description -from .helper import _apply_ik -from .pose import Pose, Transform -from typing import List, Tuple, Optional, Union, Dict - - -class ReasoningError(Exception): - def __init__(self, *args, **kwargs): - Exception.__init__(self, *args, **kwargs) - - -class CollisionError(Exception): - def __init__(self, *args, **kwargs): - Exception.__init__(self, *args, **kwargs) - - -def _get_joint_names(robot: Object, tip_link: str) -> List[str]: - res = [] - for i in range(p.getNumJoints(robot.id)): - info = p.getJointInfo(robot.id, i) - if info[2] != p.JOINT_FIXED: - res.append(info[1]) - return res - - -def _get_images_for_target(target_pose: Pose, - cam_pose: Pose, - world: Optional[BulletWorld] = None, - size: Optional[int] = 256) -> List[np.ndarray]: - """ - Calculates the view and projection Matrix and returns 3 images: - - 1. An RGB image - 2. A depth image - 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. - - From the given target_pose and cam_pose only the position is used. - - :param cam_pose: The pose of the camera - :param target_pose: The pose to which the camera should point to - :param size: The height and width of the images in pixel - :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. - """ - world, world_id = _world_and_id(world) - # TODO: Might depend on robot cameras, if so please add these camera parameters to RobotDescription object - # TODO: of your robot with a CameraDescription object. - fov = 90 - aspect = size / size - near = 0.2 - far = 100 - - view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) - projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) - return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=world_id))[2:5] - - -def _get_joint_ranges(robot: Object) -> Tuple[List, List, List, List, List]: - """ - Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. - Fixed joints will be skipped because they don't have limits or ranges. - - :param robot: The robot for whom the values should be calculated - :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping - """ - ll, ul, jr, rp, jd = [], [], [], [], [] - - for i in range(0, p.getNumJoints(robot.id)): - info = p.getJointInfo(robot.id, i) - if info[3] > -1: - ll.append(info[8]) - ul.append(info[9]) - jr.append(info[9] - info[8]) - rp.append(p.getJointState(robot.id, i)[0]) - jd.append(info[6]) - - return ll, ul, jr, rp, jd - - -def stable(object: Object, - world: Optional[BulletWorld] = None) -> bool: - """ - Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating physics - in the BulletWorld. This will be done by simulating the world for 10 seconds and compare the previous coordinates - with the coordinates after the simulation. - - :param object: The object which should be checked - :param world: The BulletWorld if more than one BulletWorld is active - :return: True if the given object is stable in the world False else - """ - world, world_id = _world_and_id(world) - shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) - with UseProspectionWorld(): - coords_prev = shadow_obj.get_position_as_list() - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - p.setGravity(0, 0, -9.8, BulletWorld.current_world.client_id) - - # one Step is approximately 1/240 seconds - BulletWorld.current_world.simulate(2) - # coords_past = p.getBasePositionAndOrientation(object.id, physicsClientId=world_id)[0] - coords_past = shadow_obj.get_position_as_list() - - # p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) - coords_prev = list(map(lambda n: round(n, 3), coords_prev)) - coords_past = list(map(lambda n: round(n, 3), coords_past)) - return coords_past == coords_prev - - -def contact(object1: Object, - object2: Object, - return_links: bool = False) -> Union[bool, Tuple[bool, List]]: - """ - Checks if two objects are in contact or not. If the links should be returned then the output will also contain a - list of tuples where the first element is the link name of 'object1' and the second element is the link name of - 'object2'. - - :param object1: The first object - :param object2: The second object - :param return_links: If the respective links on the objects that are in contact should be returned. - :return: True if the two objects are in contact False else. If links should be returned a list of links in contact - """ - - with UseProspectionWorld(): - shadow_obj1 = BulletWorld.current_world.get_prospection_object_from_object(object1) - shadow_obj2 = BulletWorld.current_world.get_prospection_object_from_object(object2) - p.performCollisionDetection(BulletWorld.current_world.client_id) - con_points = p.getContactPoints(shadow_obj1.id, shadow_obj2.id, - physicsClientId=BulletWorld.current_world.client_id) - - if return_links: - contact_links = [] - for point in con_points: - contact_links.append((shadow_obj1.get_link_by_id(point[3]), shadow_obj2.get_link_by_id(point[4]))) - return con_points != (), contact_links - - else: - return con_points != () - - -def visible(object: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None, - threshold: float = 0.8, - world: Optional[BulletWorld] = None) -> bool: - """ - Checks if an object is visible from a given position. This will be achieved by rendering the object - alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the - absolut count of pixels. - - :param object: The object for which the visibility should be checked - :param camera_pose: The pose of the camera in map frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :param threshold: The minimum percentage of the object that needs to be visible for this method to return true - :param world: The BulletWorld if more than one BulletWorld is active - :return: True if the object is visible from the camera_position False if not - """ - front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - with UseProspectionWorld(): - shadow_obj = BulletWorld.current_world.get_prospection_object_from_object(object) - if BulletWorld.robot: - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - for obj in BulletWorld.current_world.objects: - if obj == shadow_obj or BulletWorld.robot and obj == shadow_robot: - continue - else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - world_to_cam = camera_pose.to_transform("camera") - cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") - target_point = (world_to_cam * cam_to_point).to_pose() - # target_point = p.multiplyTransforms(world_to_cam.translation_as_list(), world_to_cam.rotation_as_list(), cam_to_point.translation_as_list(), [0, 0, 0, 1]) - # print(target_point) - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - flat_list = list(itertools.chain.from_iterable(seg_mask)) - max_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) - p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) - if max_pixel == 0: - # Object is not visible - return False - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - flat_list = list(itertools.chain.from_iterable(seg_mask)) - real_pixel = sum(list(map(lambda x: 1 if x == shadow_obj.id else 0, flat_list))) - - return real_pixel / max_pixel > threshold > 0 - - -def occluding(object: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None, - world: Optional[BulletWorld] = None) -> List[Object]: - """ - Lists all objects which are occluding the given object. This works similar to 'visible'. - First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. - After that the complete scene will be rendered and the previous saved pixel positions will be compared to the - actual pixels, if in one pixel another object is visible ot will be saved as occluding. - - :param object: The object for which occlusion should be checked - :param camera_pose: The pose of the camera in world coordinate frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :param world: The BulletWorld if more than one BulletWorld is active - :return: A list of occluding objects - """ - front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - world, world_id = _world_and_id(world) - # occ_world = world.copy() - # state = p.saveState(physicsClientId=occ_world.client_id) - with UseProspectionWorld(): - state = p.saveState(physicsClientId=BulletWorld.current_world.client_id) - for obj in BulletWorld.current_world.objects: - if obj.name == BulletWorld.robot.name: - continue - elif object.get_pose() == obj.get_pose(): - object = obj - else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - world_to_cam = camera_pose.to_transform("camera") - cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", "point") - target_point = (world_to_cam * cam_to_point).to_pose() - - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - - # All indices where the object that could be occluded is in the image - # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension - pix = np.dstack((seg_mask == object.id).nonzero())[0] - - p.restoreState(state, physicsClientId=BulletWorld.current_world.client_id) - - occluding = [] - seg_mask = _get_images_for_target(target_point, world_to_cam.to_pose(), BulletWorld.current_world)[2] - for c in pix: - if not seg_mask[c[0]][c[1]] == object.id: - occluding.append(seg_mask[c[0]][c[1]]) - - occ_objects = list(set(map(BulletWorld.current_world.get_object_by_id, occluding))) - occ_objects = list(map(world.get_object_from_prospection_object, occ_objects)) - - return occ_objects - - -def reachable(pose: Union[Object, Pose], - robot: Object, - gripper_name: str, - threshold: float = 0.01) -> bool: - """ - Checks if the robot can reach a given position. To determine this the inverse kinematics are - calculated and applied. Afterward the distance between the position and the given end effector is calculated, if - it is smaller than the threshold the reasoning query returns True, if not it returns False. - - :param pose: The position and rotation or Object for which reachability should be checked or an Object - :param robot: The robot that should reach for the position - :param gripper_name: The name of the end effector - :param threshold: The threshold between the end effector and the position. - :return: True if the end effector is closer than the threshold to the target position, False in every other case - """ - if type(pose) == Object: - pose = pose.get_pose() - - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" - joints = robot_description.chains[arm].joints - try: - inv = request_ik(pose, shadow_robot, joints, gripper_name) - except IKError as e: - return False - - _apply_ik(shadow_robot, inv, joints) - - diff = pose.dist(shadow_robot.links[gripper_name].pose) - - return diff < threshold - - -def blocking(pose_or_object: Union[Object, Pose], - robot: Object, - gripper_name: str, - grasp: str = None) -> Union[List[Object], None]: - """ - Checks if any objects are blocking another object when a robot tries to pick it. This works - similar to the reachable predicate. First the inverse kinematics between the robot and the object will be calculated - and applied. Then it will be checked if the robot is in contact with any object except the given one. If the given - pose or Object is not reachable None will be returned - - :param pose_or_object: The object or pose for which blocking objects should be found - :param robot: The robot Object who reaches for the object - :param gripper_name: The name of the end effector of the robot - :param grasp: The grasp type with which the object should be grasped - :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose - or object is not reachable. - """ - if type(pose_or_object) == Object: - input_pose = pose_or_object.get_pose() - else: - input_pose = pose_or_object - - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" - joints = robot_description.chains[arm].joints - local_transformer = LocalTransformer() - - target_map = local_transformer.transform_pose_to_target_frame(input_pose, "map") - if grasp: - grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) - target_map.orientation.x = grasp_orientation[0] - target_map.orientation.y = grasp_orientation[1] - target_map.orientation.z = grasp_orientation[2] - target_map.orientation.w = grasp_orientation[3] - - try: - inv = request_ik(target_map, shadow_robot, joints, gripper_name) - except IKError as e: - rospy.logerr(f"Pose is not reachable: {e}") - return None - _apply_ik(shadow_robot, inv, joints) - - block = [] - for obj in BulletWorld.current_world.objects: - if contact(shadow_robot, obj): - block.append(BulletWorld.current_world.get_object_from_prospection_object(obj)) - return block - - -def supporting(object1: Object, - object2: Object) -> bool: - """ - Checks if one object is supporting another object. An object supports another object if they are in - contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) - - :param object1: Object that is supported - :param object2: Object that supports the first object - :return: True if the second object is in contact with the first one and the second one ist above the first False else - """ - return contact(object1, object2) and object2.get_position().z > object1.get_position().z - - -def link_pose_for_joint_config(object: Object, joint_config: Dict[str, float], link_name: str) -> Pose: - """ - Returns the pose a link would be in if the given joint configuration would be applied to the object. This is done - by using the respective object in the shadow world and applying the joint configuration to this one. After applying - the joint configuration the link position is taken from there. - - :param object: Object of which the link is a part - :param joint_config: Dict with the goal joint configuration - :param link_name: Name of the link for which the pose should be returned - :return: The pose of the link after applying the joint configuration - """ - shadow_object = BulletWorld.current_world.get_prospection_object_from_object(object) - with UseProspectionWorld(): - for joint, pose in joint_config.items(): - shadow_object.set_joint_position(joint, pose) - return shadow_object.links[link_name].pose \ No newline at end of file diff --git a/src/pycram/world.py b/src/pycram/world.py index fa5b50d3d..5a89c4b63 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -325,6 +325,44 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> """ pass + def get_joint_ranges(self) -> Tuple[List, List, List, List, List]: + """ + Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. + Fixed joints will be skipped because they don't have limits or ranges. + + :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping + """ + ll, ul, jr, rp, jd = [], [], [], [], [] + joint_names = self.get_object_joint_names(self.robot.id) + for name in joint_names: + joint_type = self.get_object_joint_type(self.robot, name) + if joint_type != JointType.FIXED: + ll.append(self.get_object_joint_lower_limit(self.robot, name)) + ul.append(self.get_object_joint_upper_limit(self.robot, name)) + jr.append(ul[-1] - ll[-1]) + rp.append(self.get_object_joint_rest_pose(self.robot, name)) + jd.append(self.get_object_joint_damping(self.robot, name)) + + return ll, ul, jr, rp, jd + + def get_object_joint_rest_pose(self, obj: Object, joint_name: str) -> float: + """ + Get the rest pose of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + pass + + def get_object_joint_damping(self, obj: Object, joint_name: str) -> float: + """ + Get the damping of a joint of an articulated object + + :param obj: The object + :param joint_name: The name of the joint + """ + pass + @abstractmethod def get_object_joint_names(self, obj_id: int) -> List[str]: """ @@ -716,7 +754,7 @@ def get_prospection_object_from_object(self, obj: Object) -> Object: def get_object_from_prospection_object(self, prospection_object: Object) -> Object: """ Returns the corresponding object from the main World for a given - object in the shadow world. If the given object is not in the shadow + object in the prospection world. If the given object is not in the prospection world an error will be raised. :param prospection_object: The object for which the corresponding object in the main World should be found. diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index d992fd0a0..32f294fa3 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -1,16 +1,11 @@ -import pybullet as p import itertools import numpy as np -import rospy -from .world import _world_and_id, Object, UseProspectionWorld +from .world import Object, UseProspectionWorld from .world import World -from .external_interfaces.ik import request_ik -from .local_transformer import LocalTransformer -from .plan_failures import IKError from .robot_descriptions import robot_description -from .helper import _apply_ik from .pose import Pose, Transform +from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp from typing import List, Tuple, Optional, Union, Dict @@ -24,67 +19,6 @@ def __init__(self, *args, **kwargs): Exception.__init__(self, *args, **kwargs) -def _get_joint_ranges(robot: Object) -> Tuple[List, List, List, List, List]: - """ - Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. - Fixed joints will be skipped because they don't have limits or ranges. - - :param robot: The robot for whom the values should be calculated - :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping - """ - ll, ul, jr, rp, jd = [], [], [], [], [] - - for i in range(0, p.getNumJoints(robot.id)): - info = p.getJointInfo(robot.id, i) - if info[3] > -1: - ll.append(info[8]) - ul.append(info[9]) - jr.append(info[9] - info[8]) - rp.append(p.getJointState(robot.id, i)[0]) - jd.append(info[6]) - - return ll, ul, jr, rp, jd - - -def _try_to_reach_or_grasp(pose_or_object: Union[Pose, Object], prospection_robot: Object, gripper_name: str, - grasp: Optional[str] = None) -> Union[Pose, None]: - """ - Checks if the robot can reach a given position and optionally also grasp an object. - To determine this the inverse kinematics are calculated and applied. - - :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object - :param prospection_robot: The robot that should reach for the position - :param gripper_name: The name of the end effector - :param grasp: The grasp type with which the object should be grasped - """ - if isinstance(pose_or_object, Object): - input_pose = pose_or_object.get_pose() - else: - input_pose = pose_or_object - - arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" - joints = robot_description.chains[arm].joints - target_pose = input_pose - if grasp: - local_transformer = LocalTransformer() - target_map = local_transformer.transform_pose_to_target_frame(input_pose, "map") - grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) - target_map.orientation.x = grasp_orientation[0] - target_map.orientation.y = grasp_orientation[1] - target_map.orientation.z = grasp_orientation[2] - target_map.orientation.w = grasp_orientation[3] - target_pose = target_map - - try: - inv = request_ik(target_pose, prospection_robot, joints, gripper_name) - except IKError as e: - rospy.logerr(f"Pose is not reachable: {e}") - return None - _apply_ik(prospection_robot, inv, joints) - - return target_pose - - class WorldReasoning: def __init__(self, world: World): @@ -130,13 +64,14 @@ def contact(self, prospection_obj1 = self.world.get_prospection_object_from_object(object1) prospection_obj2 = self.world.get_prospection_object_from_object(object2) - self.world.perform_collision_detection() - con_points = self.world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) + World.current_world.perform_collision_detection() + con_points = World.current_world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) if return_links: contact_links = [] for point in con_points: - contact_links.append((prospection_obj1.get_link_by_id(point[3]), prospection_obj2.get_link_by_id(point[4]))) + contact_links.append((prospection_obj1.get_link_by_id(point[3]), + prospection_obj2.get_link_by_id(point[4]))) return con_points != (), contact_links else: @@ -153,7 +88,7 @@ def get_visible_objects(self, camera_pose: Pose, "point") target_point = (world_to_cam * cam_to_point).to_pose() - seg_mask = self.world.get_images_for_target(target_point, world_to_cam.to_pose())[2] + seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] return seg_mask, target_point @@ -178,8 +113,8 @@ def visible(self, if World.robot: prospection_robot = self.world.get_prospection_object_from_object(World.robot) - state_id = self.world.save_state() - for obj in self.world.objects: + state_id = World.current_world.save_state() + for obj in World.current_world.objects: if obj == prospection_obj or World.robot and obj == prospection_robot: continue else: @@ -188,13 +123,13 @@ def visible(self, seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) flat_list = list(itertools.chain.from_iterable(seg_mask)) max_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) - self.world.restore_state(state_id) + World.current_world.restore_state(state_id) if max_pixel == 0: # Object is not visible return False - seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] + seg_mask = World.current_world.get_images_for_target(target_point, camera_pose)[2] flat_list = list(itertools.chain.from_iterable(seg_mask)) real_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) @@ -224,7 +159,7 @@ def occluding(self, elif obj.get_pose() == other_obj.get_pose(): obj = other_obj else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + other_obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) @@ -240,7 +175,7 @@ def occluding(self, if not seg_mask[c[0]][c[1]] == obj.id: occluding.append(seg_mask[c[0]][c[1]]) - occ_objects = list(set(map(self.world.get_object_by_id, occluding))) + occ_objects = list(set(map(World.current_world.get_object_by_id, occluding))) occ_objects = list(map(self.world.get_object_from_prospection_object, occ_objects)) return occ_objects @@ -264,12 +199,13 @@ def reachable(self, prospection_robot = self.world.get_prospection_object_from_object(robot) with UseProspectionWorld(): - target_pose = _try_to_reach_or_grasp(pose_or_object, robot, gripper_name) + target_pose = try_to_reach(pose_or_object, prospection_robot, gripper_name) if not target_pose: return False - diff = target_pose.dist(prospection_robot.links[gripper_name].pose) + gripper_pose = prospection_robot.links[gripper_name].pose + diff = target_pose.dist(gripper_pose) return diff < threshold @@ -291,12 +227,16 @@ def blocking(self, :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose or object is not reachable. """ + prospection_robot = self.world.get_prospection_object_from_object(robot) with UseProspectionWorld(): - _try_to_reach_or_grasp(pose_or_object, robot, gripper_name, grasp) + if grasp: + try_to_reach_with_grasp(pose_or_object, prospection_robot, gripper_name, grasp) + else: + try_to_reach(pose_or_object, prospection_robot, gripper_name) block = [] - for obj in self.world.objects: + for obj in World.current_world.objects: if self.contact(prospection_robot, obj): block.append(self.world.get_object_from_prospection_object(obj)) return block diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index b7463873f..4375ca52e 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -2,49 +2,52 @@ from test_bullet_world import BulletWorldTest from pycram.world_reasoning import WorldReasoning -import pycram.old_world_reasoning as btr from pycram.pose import Pose from pycram.robot_descriptions import robot_description +use_new = True + class TestBulletWorldReasoning(BulletWorldTest): def test_contact(self): - # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1, 1, 1])) self.cereal.set_pose(Pose([1, 1, 1])) time.sleep(1) + btr = WorldReasoning(self.world) self.assertTrue(btr.contact(self.milk, self.cereal)) def test_visible(self): - # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1.5, 0, 1.2])) self.robot.set_pose(Pose()) time.sleep(1) + btr = WorldReasoning(self.world) self.assertTrue(btr.visible(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, - robot_description.front_facing_axis)) + robot_description.front_facing_axis)) def test_occluding(self): - # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([3, 0, 1.2])) self.robot.set_pose(Pose()) + btr = WorldReasoning(self.world) self.assertTrue(btr.occluding(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, - robot_description.front_facing_axis) != []) + robot_description.front_facing_axis) != []) def test_reachable(self): - # btr = WorldReasoning(self.world) self.robot.set_pose(Pose()) + time.sleep(1) + btr = WorldReasoning(self.world) self.assertTrue(btr.reachable(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right"))) self.assertFalse(btr.reachable(Pose([2, 2, 1]), self.robot, robot_description.get_tool_frame("right"))) def test_blocking(self): - # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([0.5, -0.7, 1])) self.robot.set_pose(Pose()) time.sleep(1) - self.assertTrue(btr.blocking(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right")) != []) + btr = WorldReasoning(self.world) + self.assertTrue( + btr.blocking(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right")) != []) def test_supporting(self): - # btr = WorldReasoning(self.world) self.milk.set_pose(Pose([1.3, 0, 0.9])) + btr = WorldReasoning(self.world) self.assertTrue(btr.supporting(self.kitchen, self.milk)) From 95fcdac9e9a478936381419ec462cf67719dbf6d Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 22 Jan 2024 10:14:26 +0100 Subject: [PATCH 046/195] [Bullet World] Increse world sync frequency Hopefully fixes the sometimes failing blocking test --- src/pycram/bullet_world.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 114d21cd7..a60d72a35 100644 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -480,7 +480,7 @@ def run(self): self.check_for_pause() # self.check_for_equal() - time.sleep(1 / 240) + time.sleep(1 / 360) self.add_obj_queue.join() self.remove_obj_queue.join() From 3fc7046547c0410ba41bcb781fdb0626375be7e4 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 22 Jan 2024 10:28:58 +0100 Subject: [PATCH 047/195] [general] maintenance --- package.xml | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/package.xml b/package.xml index af7fee250..f3b332d63 100644 --- a/package.xml +++ b/package.xml @@ -1,33 +1,25 @@ pycram - 0.0.0 + 0.0.1 The pycram package - Andy Augsten - Dustin Augsten + Jonas Dech - TODO + GPLv3 - - - - - - - - + https://pycram.readthedocs.io/en/latest/ @@ -44,13 +36,23 @@ + catkin + rospy + std_msgs + rospy + std_msgs + rospy + std_msgs + geometry_msgs + geometry_msgs + From e1c84c1aa56e0396ce87ef2bc84178d309913b5e Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 22 Jan 2024 11:10:33 +0100 Subject: [PATCH 048/195] [ci] fixed failing ci --- .github/workflows/pycram-ci.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/pycram-ci.yml b/.github/workflows/pycram-ci.yml index c7bf4db3c..2c0e299c9 100644 --- a/.github/workflows/pycram-ci.yml +++ b/.github/workflows/pycram-ci.yml @@ -69,16 +69,16 @@ jobs: catkin_make echo 'export ROS_HOSTNAME=localhost' >> ~/.bashrc echo 'source $GITHUB_WORKSPACE/ros_ws/devel/setup.bash' >> ~/.bashrc + - name: Upgrade pip + run: | + sudo pip3 install --upgrade pip - name: Install requirements run: | cd $GITHUB_WORKSPACE/ros_ws/src/pycram sudo pip3 install -r requirements.txt - - name: upgrade numpy - run: | - sudo pip3 install --upgrade numpy - name: install additional requirements run: | - sudo pip3 install pytest pyjpt mlflow + sudo pip3 install --ignore-installed pytest pyjpt mlflow - name: start roscore run: | roslaunch pycram ik_and_description.launch & From 5833a9de6cfb831817c1377c9d54178a7a7fa4e2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Mon, 22 Jan 2024 16:24:09 +0100 Subject: [PATCH 049/195] [test] updated orm querying; added docstrings to actions and motions --- src/pycram/designators/action_designator.py | 3 +- src/pycram/designators/actions/actions.py | 134 ++++++++++++------ src/pycram/designators/motion_designator.py | 21 +-- .../resolver/location/database_location.py | 26 ++-- test/test_database_merger.py | 4 +- test/test_database_resolver.py | 23 +-- test/test_orm.py | 70 ++++----- 7 files changed, 162 insertions(+), 119 deletions(-) diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index f8b9d347f..828dc2bdb 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -1,6 +1,5 @@ import itertools -from typing import Union -from .motion_designator import * +from typing_extensions import List, Union, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart from ..enums import Arms from ..designator import ActionDesignatorDescription diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 2497be648..83ca6c29f 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -1,5 +1,5 @@ import abc -from typing import Union +from typing_extensions import Union from pycram.designator import ActionDesignatorDescription from pycram.designators.motion_designator import * from pycram.enums import Arms @@ -27,62 +27,36 @@ class ActionAbstract(ActionDesignatorDescription.Action, abc.ABC): @abc.abstractmethod def perform(self) -> None: - """Perform the action.""" + """ + Perform the action. Will be overwritten by each action. + """ pass @abc.abstractmethod def to_sql(self) -> Action: - """Convert this action to its ORM equivalent.""" + """ + Convert this action to its ORM equivalent. Will be overwritten by each action. + """ pass @abc.abstractmethod def insert(self, session: Session, **kwargs) -> Action: - """Insert this action into the database.""" - action = super().insert(session) - return action - - -@dataclass -class ParkArmsActionPerformable(ActionAbstract): - - arm: Arms - """ - Entry from the enum for which arm should be parked - """ - - @with_tree - def perform(self) -> None: - # create the keyword arguments - kwargs = dict() - left_poses = None - right_poses = None - - # add park left arm if wanted - if self.arm in [Arms.LEFT, Arms.BOTH]: - kwargs["left_arm_config"] = "park" - left_poses = robot_description.get_static_joint_chain("left", kwargs["left_arm_config"]) - - # add park right arm if wanted - if self.arm in [Arms.RIGHT, Arms.BOTH]: - kwargs["right_arm_config"] = "park" - right_poses = robot_description.get_static_joint_chain("right", kwargs["right_arm_config"]) + """ + Insert this action into the database. - MoveArmJointsMotion(left_poses, right_poses).perform() - - def to_sql(self) -> ORMParkArmsAction: - return ORMParkArmsAction(self.arm.name) + :param session: Session with a database that is used to add and commit the objects + :param kwargs: Possible extra keyword arguments + :return: The completely instanced ORM object + """ - def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: action = super().insert(session) - session.add(action) - session.commit() return action @dataclass class MoveTorsoActionPerformable(ActionAbstract): """ - Performable Move Torso Action designator. + Move the torso of the robot up and down. """ position: float @@ -106,6 +80,9 @@ def insert(self, session: Session, **kwargs) -> ORMMoveTorsoAction: @dataclass class SetGripperActionPerformable(ActionAbstract): + """ + Set the gripper state of the robot. + """ gripper: str """ @@ -132,6 +109,11 @@ def insert(self, session: Session, *args, **kwargs) -> ORMSetGripperAction: @dataclass class ReleaseActionPerformable(ActionAbstract): + """ + Releases an Object from the robot. + + Note: This action can not ve used yet. + """ gripper: str @@ -149,6 +131,11 @@ def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: @dataclass class GripActionPerformable(ActionAbstract): + """ + Grip an object with the robot. + + Note: This action can not be used yet. + """ gripper: str object_designator: ObjectDesignatorDescription.Object @@ -165,8 +152,51 @@ def insert(self, session: Session, *args, **kwargs) -> Base: raise NotImplementedError() +@dataclass +class ParkArmsActionPerformable(ActionAbstract): + """ + Park the arms of the robot. + """ + + arm: Arms + """ + Entry from the enum for which arm should be parked + """ + + @with_tree + def perform(self) -> None: + # create the keyword arguments + kwargs = dict() + left_poses = None + right_poses = None + + # add park left arm if wanted + if self.arm in [Arms.LEFT, Arms.BOTH]: + kwargs["left_arm_config"] = "park" + left_poses = robot_description.get_static_joint_chain("left", kwargs["left_arm_config"]) + + # add park right arm if wanted + if self.arm in [Arms.RIGHT, Arms.BOTH]: + kwargs["right_arm_config"] = "park" + right_poses = robot_description.get_static_joint_chain("right", kwargs["right_arm_config"]) + + MoveArmJointsMotion(left_poses, right_poses).perform() + + def to_sql(self) -> ORMParkArmsAction: + return ORMParkArmsAction(self.arm.name) + + def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: + action = super().insert(session) + session.add(action) + session.commit() + return action + + @dataclass class PickUpActionPerformable(ActionAbstract): + """ + Let the robot pick up an object. + """ object_designator: ObjectDesignatorDescription.Object """ @@ -272,6 +302,9 @@ def insert(self, session: Session, **kwargs) -> ORMPickUpAction: @dataclass class PlaceActionPerformable(ActionAbstract): + """ + Places an Object at a position using an arm. + """ object_designator: ObjectDesignatorDescription.Object """ @@ -326,6 +359,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMPlaceAction: @dataclass class NavigateActionPerformable(ActionAbstract): + """ + Navigates the Robot to a position. + """ target_location: Pose """ @@ -353,6 +389,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMNavigateAction: @dataclass class TransportActionPerformable(ActionAbstract): + """ + Transports an object to a position using an arm + """ object_designator: ObjectDesignatorDescription.Object """ @@ -418,6 +457,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMTransportAction: @dataclass class LookAtActionPerformable(ActionAbstract): + """ + Lets the robot look at a position. + """ target: Pose """ @@ -444,6 +486,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMLookAtAction: @dataclass class DetectActionPerformable(ActionAbstract): + """ + Detects an object that fits the object description and returns an object designator describing the object. + """ object_designator: ObjectDesignatorDescription.Object """ @@ -471,6 +516,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMDetectAction: @dataclass class OpenActionPerformable(ActionAbstract): + """ + Opens a container like object + """ object_designator: ObjectPart.Object """ @@ -505,6 +553,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMOpenAction: @dataclass class CloseActionPerformable(ActionAbstract): + """ + Closes a container like object. + """ object_designator: ObjectPart.Object """ @@ -539,6 +590,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMCloseAction: @dataclass class GraspingActionPerformable(ActionAbstract): + """ + Grasps an object described by the given Object Designator description + """ arm: str """ diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 2ad0f6adb..44b131aa5 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -1,5 +1,3 @@ -import abc -import typing from abc import ABC, abstractmethod from dataclasses import dataclass @@ -17,7 +15,7 @@ OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion, Motion as ORMMotionDesignator) -from typing import List, Dict, Callable, Optional, get_type_hints, Union, Any +from typing_extensions import Dict, Optional, get_type_hints, get_args, get_origin from ..pose import Pose from ..task import with_tree @@ -28,9 +26,7 @@ class BaseMotion(ABC): @abstractmethod def perform(self): """ - Passes this designator to the process module for execution. - - :return: The return value of the process module if there is any. + Passes this designator to the process module for execution. Will be overwritten by each motion. """ pass # return ProcessModule.perform(self) @@ -38,7 +34,7 @@ def perform(self): @abstractmethod def to_sql(self) -> ORMMotionDesignator: """ - Create an ORM object that corresponds to this description. + Create an ORM object that corresponds to this description. Will be overwritten by each motion. :return: The created ORM object. """ @@ -51,6 +47,8 @@ def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: Auto-Incrementing primary keys and foreign keys have to be filled by this method. :param session: Session with a database that is used to add and commit the objects + :param args: Possible extra arguments + :param kwargs: Possible extra keyword arguments :return: The completely instanced ORM motion. """ metadata = ProcessMetaData().insert(session) @@ -61,6 +59,9 @@ def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: return motion def __post_init__(self): + """ + Checks if types are missing or wrong + """ right_types = get_type_hints(self) attributes = self.__dict__.copy() @@ -72,13 +73,13 @@ def __post_init__(self): attribute = attributes[k] attribute_type = type(attributes[k]) right_type = right_types[k] - types = typing.get_args(right_type) + types = get_args(right_type) if attribute is None: - if not any([x is type(None) for x in typing.get_args(right_type)]): + if not any([x is type(None) for x in get_args(right_type)]): missing.append(k) elif attribute_type is not right_type: if attribute_type not in types: - if attribute_type not in [typing.get_origin(x) for x in types if x is not type(None)]: + if attribute_type not in [get_origin(x) for x in types if x is not type(None)]: wrong_type[k] = right_types[k] current_type[k] = attribute_type if missing != [] or wrong_type != {}: diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 4febdf360..d613b99a3 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -1,6 +1,7 @@ import numpy as np import sqlalchemy.orm import sqlalchemy.sql +from sqlalchemy import select, Select from tf import transformations import pycram.designators.location_designator import pycram.task @@ -34,25 +35,24 @@ def __init__(self, target, session: sqlalchemy.orm.Session = None, super().__init__(target, reachable_for, None, reachable_arm, resolver) self.session = session - def create_query_from_occupancy_costmap(self) -> sqlalchemy.orm.Query: + def create_query_from_occupancy_costmap(self) -> Select: """ Create a query that queries all relative robot positions from an object that are not occluded using an OccupancyCostmap. """ robot_pos = sqlalchemy.orm.aliased(Position) - object_pos = sqlalchemy.orm.aliased(Position) # query all relative robot positions in regard to an objects position # make sure to order the joins() correctly - query = (self.session.query(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, Position.x, - Position.y).join(TaskTreeNode.code) - .join(Code.designator.of_type(PickUpAction)) - .join(PickUpAction.robot_state) - .join(RobotState.pose) - .join(orm.base.Pose.position) - .join(PickUpAction.object).filter(Object.type == self.target.type) - .filter(TaskTreeNode.status == "SUCCEEDED")) + query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, Position.x, Position.y) + .join(TaskTreeNode.code) + .join(Code.designator.of_type(PickUpAction)) + .join(PickUpAction.robot_state) + .join(RobotState.pose) + .join(orm.base.Pose.position) + .join(PickUpAction.object).where(Object.type == self.target.type) + .where(TaskTreeNode.status == "SUCCEEDED")) # create Occupancy costmap for the target object position, orientation = self.target.pose.to_list() @@ -94,7 +94,7 @@ def create_query_from_occupancy_costmap(self) -> sqlalchemy.orm.Query: robot_pos.y >= rectangle[1][0], robot_pos.y < rectangle[1][1])) # query = self.model.bind({"x": list(rectangle[0]), "y": list(rectangle[1])}) - return query.filter(sqlalchemy.or_(*filters)) + return query.where(sqlalchemy.or_(*filters)) def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLocation.Location: """ @@ -112,7 +112,7 @@ def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLoc return result def __iter__(self) -> JPTCostmapLocation.Location: - query = self.create_query_from_occupancy_costmap().limit(200) - samples = query.all() + statement = self.create_query_from_occupancy_costmap().limit(200) + samples = self.session.execute(statement).all() for sample in samples: yield self.sample_to_location(sample) diff --git a/test/test_database_merger.py b/test/test_database_merger.py index f3e8b0472..79743f904 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -40,7 +40,7 @@ def __init__(self): @with_tree def pick_and_place_plan(self): with simulated_robot: - ParkArmsAction.Action(Arms.BOTH).perform() + ParkArmsActionPerformable(Arms.BOTH).perform() MoveTorsoAction([0.3]).resolve().perform() pickup_pose = CostmapLocation(target=self.cereal_desig.resolve(), reachable_for=self.robot_desig).resolve() pickup_arm = pickup_pose.reachable_arms[0] @@ -59,7 +59,7 @@ def pick_and_place_plan(self): PlaceAction(self.cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform() - ParkArmsAction.Action(Arms.BOTH).perform() + ParkArmsActionPerformable(Arms.BOTH).perform() class MergerTestCaseBase(unittest.TestCase): diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 4c7d10822..e03f6d5db 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -5,10 +5,11 @@ import pycram.plan_failures from pycram import task from pycram.bullet_world import BulletWorld, Object -from pycram.designators import action_designator, object_designator +from pycram.designators import action_designator from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ NavigateActionPerformable from pycram.orm.base import Base +from pycram.designators.object_designator import ObjectDesignatorDescription from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot from pycram.pose import Pose @@ -48,26 +49,28 @@ def setUpClass(cls) -> None: cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False cls.engine = sqlalchemy.create_engine(pycrorm_uri) - cls.session = sqlalchemy.orm.Session(bind=cls.engine) def setUp(self) -> None: self.world.reset_bullet_world() pycram.orm.base.Base.metadata.create_all(self.engine) + self.session = sqlalchemy.orm.Session(bind=self.engine) self.session.commit() def tearDown(self) -> None: self.world.reset_bullet_world() pycram.task.reset_tree() + pycram.orm.base.ProcessMetaData.reset() + self.session.rollback() + pycram.orm.base.Base.metadata.drop_all(self.engine) + self.session.close() @classmethod def tearDownClass(cls) -> None: cls.world.exit() - cls.session.commit() - cls.session.close() @with_tree def plan(self): - object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + object_description = ObjectDesignatorDescription(names=["milk"]) description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) with simulated_robot: NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() @@ -86,10 +89,9 @@ def test_costmap_no_obstacles(self): with simulated_robot: # action_designator.NavigateAction.Action(sample.pose).perform() - action_designator.MoveTorsoAction.Action(sample.torso_height).perform() - PickUpActionPerformable( - object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() + PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, + grasp=sample.grasp).perform() @unittest.skip def test_costmap_with_obstacles(self): @@ -104,11 +106,12 @@ def test_costmap_with_obstacles(self): MoveTorsoActionPerformable(sample.torso_height).perform() try: PickUpActionPerformable( - object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), + ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure: continue return + kitchen.remove() raise pycram.plan_failures.PlanFailure() diff --git a/test/test_orm.py b/test/test_orm.py index 0a70b99b4..8d7293b09 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -1,9 +1,7 @@ import os import unittest - -import sqlalchemy +from sqlalchemy import select import sqlalchemy.orm - import pycram.orm.action_designator import pycram.orm.base import pycram.orm.motion_designator @@ -26,7 +24,7 @@ class ORMTestSchema(unittest.TestCase): - engine: sqlalchemy.engine.Engine + engine: sqlalchemy.engine session: sqlalchemy.orm.Session @classmethod @@ -99,51 +97,45 @@ def tearDown(self): pycram.orm.base.Base.metadata.drop_all(self.engine) self.session.close() - @classmethod - def TearDownClass(cls): - super().tearDownClass() - cls.session.commit() - cls.session.close() - def test_node(self): """Test if the objects in the database is equal with the objects that got serialized.""" self.plan() pycram.orm.base.ProcessMetaData().description = "Unittest" pycram.task.task_tree.root.insert(self.session, ) - node_results = self.session.query(pycram.orm.task.TaskTreeNode).all() + node_results = self.session.scalars(select(pycram.orm.task.TaskTreeNode)).all() self.assertEqual(len(node_results), len(pycram.task.task_tree.root)) - code_results = self.session.query(pycram.orm.task.Code).all() + code_results = self.session.scalars(select(pycram.orm.task.Code)).all() self.assertEqual(len(code_results), len(pycram.task.task_tree.root)) - position_results = self.session.query(pycram.orm.base.Position).all() + position_results = self.session.scalars(select(pycram.orm.base.Position)).all() self.assertEqual(14, len(position_results)) - quaternion_results = self.session.query(pycram.orm.base.Quaternion).all() + quaternion_results = self.session.scalars(select(pycram.orm.base.Quaternion)).all() self.assertEqual(14, len(quaternion_results)) - park_arms_results = self.session.query(pycram.orm.action_designator.ParkArmsAction).all() + park_arms_results = self.session.scalars(select(pycram.orm.action_designator.ParkArmsAction)).all() self.assertEqual(0, len(park_arms_results)) - navigate_results = self.session.query(pycram.orm.action_designator.NavigateAction).all() + navigate_results = self.session.scalars(select(pycram.orm.action_designator.NavigateAction)).all() self.assertEqual(1, len(navigate_results)) - action_results = self.session.query(pycram.orm.action_designator.Action).all() + action_results = self.session.scalars(select(pycram.orm.action_designator.Action)).all() self.assertEqual(4, len(action_results)) def test_metadata_existence(self): pycram.orm.base.ProcessMetaData().description = "metadata_existence_test" self.plan() pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.base.Pose).all() + result = self.session.scalars(select(pycram.orm.base.Pose)).all() self.assertTrue(all([r.process_metadata is not None for r in result])) def test_task_tree_node_parents(self): self.plan() pycram.orm.base.ProcessMetaData().description = "task_tree_node_parents_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.task.TaskTreeNode).all() + result = self.session.scalars(select(pycram.orm.task.TaskTreeNode)).all() self.assertTrue([result[i].parent == result[result[i].parent_id - 1] for i in range(len(result)) if result[i].parent_id is not None]) @@ -151,23 +143,23 @@ def test_meta_data(self): self.plan() pycram.orm.base.ProcessMetaData().description = "Unittest" pycram.task.task_tree.root.insert(self.session, ) - metadata_results = self.session.query(pycram.orm.base.ProcessMetaData).all() + metadata_results = self.session.scalars(select(pycram.orm.base.ProcessMetaData)).all() self.assertEqual(1, len(metadata_results)) - action_results = self.session.query(pycram.orm.action_designator.Action).all() + action_results = self.session.scalars(select(pycram.orm.action_designator.Action)).all() self.assertTrue(all([a.process_metadata_id for a in action_results])) - park_arms_results = self.session.query(pycram.orm.action_designator.ParkArmsAction).all() + park_arms_results = self.session.scalars(select(pycram.orm.action_designator.ParkArmsAction)).all() self.assertTrue(all([a.process_metadata_id for a in park_arms_results])) - object_results = self.session.query(pycram.orm.object_designator.Object).all() + object_results = self.session.scalars(select(pycram.orm.object_designator.Object)).all() self.assertTrue(all([o.process_metadata_id for o in object_results])) def test_meta_data_alternation(self): self.plan() pycram.orm.base.ProcessMetaData().description = "meta_data_alternation_test" pycram.task.task_tree.root.insert(self.session, ) - metadata_result = self.session.query(pycram.orm.base.ProcessMetaData).first() + metadata_result = self.session.scalars(select(pycram.orm.base.ProcessMetaData)).first() self.assertEqual(metadata_result.description, "meta_data_alternation_test") @@ -187,14 +179,14 @@ def test_pose(self): self.plan() pycram.orm.base.ProcessMetaData().description = "pose_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.base.Pose).all() + result = self.session.scalars(select(pycram.orm.base.Pose)).all() self.assertTrue(all([r.position is not None and r.orientation is not None for r in result])) def test_pose_mixin(self): self.plan() pycram.orm.base.ProcessMetaData().description = "pose_mixin_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.base.RobotState).all() + result = self.session.scalars(select(pycram.orm.base.RobotState)).all() self.assertTrue(all([r.pose is not None and r.pose_id == r.pose.id for r in result])) @@ -242,8 +234,8 @@ def test_plan_serialization(self): pycram.orm.base.ProcessMetaData().description = "Unittest" tt = pycram.task.task_tree tt.insert(self.session) - action_results = self.session.query(pycram.orm.action_designator.Action).all() - motion_results = self.session.query(pycram.orm.motion_designator.Motion).all() + action_results = self.session.scalars(select(pycram.orm.action_designator.Action)).all() + motion_results = self.session.scalars(select(pycram.orm.motion_designator.Motion)).all() self.assertEqual(len(tt) - 2, len(action_results) + len(motion_results)) @@ -270,19 +262,13 @@ def tearDown(self): pycram.orm.base.Base.metadata.drop_all(self.engine) self.session.close() - @classmethod - def TearDownClass(cls): - super().tearDownClass() - cls.session.commit() - cls.session.close() - def test_code_designator_type(self): action = NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])) with simulated_robot: action.perform() pycram.orm.base.ProcessMetaData().description = "code_designator_type_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.task.Code).filter(pycram.orm.task.Code.function == "perform").all() + result = self.session.scalars(select(pycram.orm.task.Code).where(pycram.orm.task.Code.function == "perform")).all() self.assertEqual(result[0].designator.dtype, action_designator.NavigateAction.__name__) self.assertEqual(result[1].designator.dtype, motion_designator.MoveMotion.__name__) @@ -292,7 +278,7 @@ def test_parkArmsAction(self): action.perform() pycram.orm.base.ProcessMetaData().description = "parkArmsAction_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.action_designator.ParkArmsAction).all() + result = self.session.scalars(select(pycram.orm.action_designator.ParkArmsAction)).all() self.assertTrue(all([result[i+1].dtype is not pycram.orm.action_designator.Action.dtype if result[i].dtype is pycram.orm.action_designator.ParkArmsAction.dtype else None for i in range(len(result)-1)])) @@ -305,8 +291,8 @@ def test_transportAction(self): action.perform() pycram.orm.base.ProcessMetaData().description = "transportAction_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.action_designator.TransportAction).all() - milk_object = self.session.query(pycram.orm.object_designator.Object).first() + result = self.session.scalars(select(pycram.orm.action_designator.TransportAction)).all() + milk_object = self.session.scalars(select(pycram.orm.object_designator.Object)).first() self.assertEqual(milk_object.pose, result[0].object.pose) def test_lookAt_and_detectAction(self): @@ -319,7 +305,7 @@ def test_lookAt_and_detectAction(self): action.perform() pycram.orm.base.ProcessMetaData().description = "detectAction_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.action_designator.DetectAction).all() + result = self.session.scalars(select(pycram.orm.action_designator.DetectAction)).all() self.assertEqual(result[0].object.name, "milk") def test_setGripperAction(self): @@ -328,7 +314,7 @@ def test_setGripperAction(self): action.perform() pycram.orm.base.ProcessMetaData().description = "setGripperAction_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.query(pycram.orm.action_designator.SetGripperAction).all() + result = self.session.scalars(select(pycram.orm.action_designator.SetGripperAction)).all() self.assertEqual(result[0].gripper, "left") self.assertEqual(result[0].motion, "open") @@ -348,8 +334,8 @@ def test_open_and_closeAction(self): pycram.orm.base.ProcessMetaData().description = "open_and_closeAction_test" pycram.task.task_tree.root.insert(self.session) - open_result = self.session.query(pycram.orm.action_designator.OpenAction).all() - close_result = self.session.query(pycram.orm.action_designator.CloseAction).all() + open_result = self.session.scalars(select(pycram.orm.action_designator.OpenAction)).all() + close_result = self.session.scalars(select(pycram.orm.action_designator.CloseAction)).all() self.assertTrue(open_result is not None) self.assertEqual(open_result[0].object.name, "handle_cab10_t") self.assertTrue(close_result is not None) From 4081685b100771fa2cf7d75bb47d41a7519cf637 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Mon, 22 Jan 2024 18:20:31 +0100 Subject: [PATCH 050/195] [test] fixed an issue where the orm session was not properly clossed after test --- test/test_orm.py | 32 +++----------------------------- 1 file changed, 3 insertions(+), 29 deletions(-) diff --git a/test/test_orm.py b/test/test_orm.py index 8d7293b09..e4c2a7f25 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -190,14 +190,13 @@ def test_pose_mixin(self): self.assertTrue(all([r.pose is not None and r.pose_id == r.pose.id for r in result])) -class ORMObjectDesignatorTestCase(BulletWorldTestCase): +class ORMObjectDesignatorTestCase(ORMTestSchema, BulletWorldTestCase): """Test ORM functionality with a plan including object designators. """ engine: sqlalchemy.engine.Engine session: sqlalchemy.orm.Session - @with_tree - def plan(self): + def test_plan_serialization(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) self.assertEqual(description.ground().object_designator.name, "milk") @@ -206,37 +205,12 @@ def plan(self): MoveTorsoActionPerformable(0.3).perform() PickUpActionPerformable(object_description.resolve(), "left", "front").perform() description.resolve().perform() - - @classmethod - def setUpClass(cls): - super().setUpClass() - cls.engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False) - cls.session = sqlalchemy.orm.Session(bind=cls.engine) - - def setUp(self): - super().setUp() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session.commit() - - def tearDown(self): - super().tearDown() - pycram.orm.base.Base.metadata.drop_all(self.engine) - pycram.task.reset_tree() - - @classmethod - def tearDownClass(cls): - super().tearDownClass() - cls.session.commit() - cls.session.close() - - def test_plan_serialization(self): - self.plan() pycram.orm.base.ProcessMetaData().description = "Unittest" tt = pycram.task.task_tree tt.insert(self.session) action_results = self.session.scalars(select(pycram.orm.action_designator.Action)).all() motion_results = self.session.scalars(select(pycram.orm.motion_designator.Motion)).all() - self.assertEqual(len(tt) - 2, len(action_results) + len(motion_results)) + self.assertEqual(len(tt) - 1, len(action_results) + len(motion_results)) class ORMActionDesignatorTestCase(BulletWorldTestCase): From 624bb8c8ca9c520d84e660ed7378d55b9ab42fd6 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 23 Jan 2024 14:13:11 +0100 Subject: [PATCH 051/195] [WorldAbstractClass] world_reasoning.py is not a class anymore. --- src/pycram/world_reasoning.py | 525 ++++++++++++++-------------- test/test_bullet_world_reasoning.py | 10 +- 2 files changed, 268 insertions(+), 267 deletions(-) diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 32f294fa3..35fca3d44 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -1,272 +1,279 @@ import itertools +from typing import List, Tuple, Optional, Union, Dict + import numpy as np +from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp +from .pose import Pose, Transform +from .robot_descriptions import robot_description from .world import Object, UseProspectionWorld from .world import World -from .robot_descriptions import robot_description -from .pose import Pose, Transform -from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp -from typing import List, Tuple, Optional, Union, Dict class ReasoningError(Exception): - def __init__(self, *args, **kwargs): - Exception.__init__(self, *args, **kwargs) + def __init__(*args, **kwargs): + Exception.__init__(*args, **kwargs) class CollisionError(Exception): - def __init__(self, *args, **kwargs): - Exception.__init__(self, *args, **kwargs) - - -class WorldReasoning: - - def __init__(self, world: World): - self.world = world - - def stable(self, obj: Object) -> bool: - """ - Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating physics - in the BulletWorld. This will be done by simulating the world for 10 seconds and compare the previous coordinates - with the coordinates after the simulation. - - :param obj: The object which should be checked - :return: True if the given object is stable in the world False else - """ - prospection_obj = self.world.get_prospection_object_from_object(obj) - with UseProspectionWorld(): - coords_prev = prospection_obj.get_position_as_list() - self.world.set_gravity([0, 0, -9.8]) - - self.world.simulate(2) - coords_past = prospection_obj.get_position_as_list() - - coords_prev = list(map(lambda n: round(n, 3), coords_prev)) - coords_past = list(map(lambda n: round(n, 3), coords_past)) - return coords_past == coords_prev - - def contact(self, - object1: Object, - object2: Object, - return_links: bool = False) -> Union[bool, Tuple[bool, List]]: - """ - Checks if two objects are in contact or not. If the links should be returned then the output will also contain a - list of tuples where the first element is the link name of 'object1' and the second element is the link name of - 'object2'. - - :param object1: The first object - :param object2: The second object - :param return_links: If the respective links on the objects that are in contact should be returned. - :return: True if the two objects are in contact False else. If links should be returned a list of links in contact - """ - - with UseProspectionWorld(): - prospection_obj1 = self.world.get_prospection_object_from_object(object1) - prospection_obj2 = self.world.get_prospection_object_from_object(object2) - - World.current_world.perform_collision_detection() - con_points = World.current_world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) - - if return_links: - contact_links = [] - for point in con_points: - contact_links.append((prospection_obj1.get_link_by_id(point[3]), - prospection_obj2.get_link_by_id(point[4]))) - return con_points != (), contact_links - + def __init__(*args, **kwargs): + Exception.__init__(*args, **kwargs) + + +def stable(obj: Object) -> bool: + """ + Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating + physics in the BulletWorld. This will be done by simulating the world for 10 seconds and compare + the previous coordinates with the coordinates after the simulation. + + :param obj: The object which should be checked + :return: True if the given object is stable in the world False else + """ + prospection_obj = World.current_world.get_prospection_object_from_object(obj) + with UseProspectionWorld(): + coords_prev = prospection_obj.get_position_as_list() + World.current_world.set_gravity([0, 0, -9.8]) + + World.current_world.simulate(2) + coords_past = prospection_obj.get_position_as_list() + + coords_prev = list(map(lambda n: round(n, 3), coords_prev)) + coords_past = list(map(lambda n: round(n, 3), coords_past)) + return coords_past == coords_prev + + +def contact( + object1: Object, + object2: Object, + return_links: bool = False) -> Union[bool, Tuple[bool, List]]: + """ + Checks if two objects are in contact or not. If the links should be returned then the output will also contain a + list of tuples where the first element is the link name of 'object1' and the second element is the link name of + 'object2'. + + :param object1: The first object + :param object2: The second object + :param return_links: If the respective links on the objects that are in contact should be returned. + :return: True if the two objects are in contact False else. If links should be returned a list of links in contact + """ + + with UseProspectionWorld(): + prospection_obj1 = World.current_world.get_prospection_object_from_object(object1) + prospection_obj2 = World.current_world.get_prospection_object_from_object(object2) + + World.current_world.perform_collision_detection() + con_points = World.current_world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) + + if return_links: + contact_links = [] + for point in con_points: + contact_links.append((prospection_obj1.get_link_by_id(point[3]), + prospection_obj2.get_link_by_id(point[4]))) + return con_points != (), contact_links + + else: + return con_points != () + + +def get_visible_objects( + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None) -> Tuple[np.ndarray, Pose]: + front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis + + world_to_cam = camera_pose.to_transform("camera") + + cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", + "point") + target_point = (world_to_cam * cam_to_point).to_pose() + + seg_mask = World.current_world.get_images_for_target(target_point, camera_pose)[2] + + return seg_mask, target_point + + +def visible( + obj: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None, + threshold: float = 0.8) -> bool: + """ + Checks if an object is visible from a given position. This will be achieved by rendering the object + alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the + absolut count of pixels. + + :param obj: The object for which the visibility should be checked + :param camera_pose: The pose of the camera in map frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :param threshold: The minimum percentage of the object that needs to be visible for this method to return true. + :return: True if the object is visible from the camera_position False if not + """ + with UseProspectionWorld(): + prospection_obj = World.current_world.get_prospection_object_from_object(obj) + if World.robot: + prospection_robot = World.current_world.get_prospection_object_from_object(World.robot) + + state_id = World.current_world.save_state() + for obj in World.current_world.objects: + if obj == prospection_obj or World.robot and obj == prospection_robot: + continue else: - return con_points != () - - def get_visible_objects(self, camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None) -> Tuple[np.ndarray, Pose]: - - front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis - - world_to_cam = camera_pose.to_transform("camera") - - cam_to_point = Transform(list(np.multiply(front_facing_axis, 2)), [0, 0, 0, 1], "camera", - "point") - target_point = (world_to_cam * cam_to_point).to_pose() - - seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] - - return seg_mask, target_point - - def visible(self, - obj: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None, - threshold: float = 0.8) -> bool: - """ - Checks if an object is visible from a given position. This will be achieved by rendering the object - alone and counting the visible pixel, then rendering the complete scene and compare the visible pixels with the - absolut count of pixels. - - :param obj: The object for which the visibility should be checked - :param camera_pose: The pose of the camera in map frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :param threshold: The minimum percentage of the object that needs to be visible for this method to return true. - :return: True if the object is visible from the camera_position False if not - """ - with UseProspectionWorld(): - prospection_obj = self.world.get_prospection_object_from_object(obj) - if World.robot: - prospection_robot = self.world.get_prospection_object_from_object(World.robot) - - state_id = World.current_world.save_state() - for obj in World.current_world.objects: - if obj == prospection_obj or World.robot and obj == prospection_robot: - continue - else: - obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) - flat_list = list(itertools.chain.from_iterable(seg_mask)) - max_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) - World.current_world.restore_state(state_id) - - if max_pixel == 0: - # Object is not visible - return False - - seg_mask = World.current_world.get_images_for_target(target_point, camera_pose)[2] - flat_list = list(itertools.chain.from_iterable(seg_mask)) - real_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) - - return real_pixel / max_pixel > threshold > 0 - - def occluding(self, - obj: Object, - camera_pose: Pose, - front_facing_axis: Optional[List[float]] = None) -> List[Object]: - """ - Lists all objects which are occluding the given object. This works similar to 'visible'. - First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. - After that the complete scene will be rendered and the previous saved pixel positions will be compared to the - actual pixels, if in one pixel another object is visible ot will be saved as occluding. - - :param obj: The object for which occlusion should be checked - :param camera_pose: The pose of the camera in world coordinate frame - :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :return: A list of occluding objects - """ - - with UseProspectionWorld(): - state_id = self.world.save_state() - for other_obj in self.world.objects: - if other_obj.name == self.world.robot.name: - continue - elif obj.get_pose() == other_obj.get_pose(): - obj = other_obj - else: - other_obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - - seg_mask, target_point = self.get_visible_objects(camera_pose, front_facing_axis) - - # All indices where the object that could be occluded is in the image - # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension - pix = np.dstack((seg_mask == obj.id).nonzero())[0] - - self.world.restore_state(state_id) - - occluding = [] - seg_mask = self.world.get_images_for_target(target_point, camera_pose)[2] - for c in pix: - if not seg_mask[c[0]][c[1]] == obj.id: - occluding.append(seg_mask[c[0]][c[1]]) - - occ_objects = list(set(map(World.current_world.get_object_by_id, occluding))) - occ_objects = list(map(self.world.get_object_from_prospection_object, occ_objects)) - - return occ_objects - - def reachable(self, - pose_or_object: Union[Object, Pose], - robot: Object, - gripper_name: str, - threshold: float = 0.01) -> bool: - """ - Checks if the robot can reach a given position. To determine this the inverse kinematics are - calculated and applied. Afterward the distance between the position and the given end effector is calculated, if - it is smaller than the threshold the reasoning query returns True, if not it returns False. - - :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object - :param robot: The robot that should reach for the position - :param gripper_name: The name of the end effector - :param threshold: The threshold between the end effector and the position. - :return: True if the end effector is closer than the threshold to the target position, False in every other case - """ - - prospection_robot = self.world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - target_pose = try_to_reach(pose_or_object, prospection_robot, gripper_name) - - if not target_pose: - return False - - gripper_pose = prospection_robot.links[gripper_name].pose - diff = target_pose.dist(gripper_pose) - - return diff < threshold - - def blocking(self, - pose_or_object: Union[Object, Pose], - robot: Object, - gripper_name: str, - grasp: str = None) -> Union[List[Object], None]: - """ - Checks if any objects are blocking another object when a robot tries to pick it. This works - similar to the reachable predicate. First the inverse kinematics between the robot and the object will be - calculated and applied. Then it will be checked if the robot is in contact with any object except the given one. - If the given pose or Object is not reachable None will be returned - - :param pose_or_object: The object or pose for which blocking objects should be found - :param robot: The robot Object who reaches for the object - :param gripper_name: The name of the end effector of the robot - :param grasp: The grasp type with which the object should be grasped - :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose - or object is not reachable. - """ - - prospection_robot = self.world.get_prospection_object_from_object(robot) - with UseProspectionWorld(): - if grasp: - try_to_reach_with_grasp(pose_or_object, prospection_robot, gripper_name, grasp) + obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + seg_mask, target_point = get_visible_objects(camera_pose, front_facing_axis) + flat_list = list(itertools.chain.from_iterable(seg_mask)) + max_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) + World.current_world.restore_state(state_id) + + if max_pixel == 0: + # Object is not visible + return False + + seg_mask = World.current_world.get_images_for_target(target_point, camera_pose)[2] + flat_list = list(itertools.chain.from_iterable(seg_mask)) + real_pixel = sum(list(map(lambda x: 1 if x == prospection_obj.id else 0, flat_list))) + + return real_pixel / max_pixel > threshold > 0 + + +def occluding( + obj: Object, + camera_pose: Pose, + front_facing_axis: Optional[List[float]] = None) -> List[Object]: + """ + Lists all objects which are occluding the given object. This works similar to 'visible'. + First the object alone will be rendered and the position of the pixels of the object in the picture will be saved. + After that the complete scene will be rendered and the previous saved pixel positions will be compared to the + actual pixels, if in one pixel another object is visible ot will be saved as occluding. + + :param obj: The object for which occlusion should be checked + :param camera_pose: The pose of the camera in world coordinate frame + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :return: A list of occluding objects + """ + + with UseProspectionWorld(): + state_id = World.current_world.save_state() + for other_obj in World.current_world.objects: + if other_obj.name == World.current_world.robot.name: + continue + elif obj.get_pose() == other_obj.get_pose(): + obj = other_obj else: - try_to_reach(pose_or_object, prospection_robot, gripper_name) - - block = [] - for obj in World.current_world.objects: - if self.contact(prospection_robot, obj): - block.append(self.world.get_object_from_prospection_object(obj)) - return block - - def supporting(self, - object1: Object, - object2: Object) -> bool: - """ - Checks if one object is supporting another object. An object supports another object if they are in - contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) - - :param object1: Object that is supported - :param object2: Object that supports the first object - :return: True if the second object is in contact with the first one and the second one ist above the first False else - """ - return self.contact(object1, object2) and object2.get_position().z > object1.get_position().z - - def link_pose_for_joint_config(self, obj: Object, joint_config: Dict[str, float], link_name: str) -> Pose: - """ - Returns the pose a link would be in if the given joint configuration would be applied to the object. - This is done by using the respective object in the prospection world and applying the joint configuration - to this one. After applying the joint configuration the link position is taken from there. - - :param obj: Object of which the link is a part - :param joint_config: Dict with the goal joint configuration - :param link_name: Name of the link for which the pose should be returned - :return: The pose of the link after applying the joint configuration - """ - prospection_object = self.world.get_prospection_object_from_object(obj) - with UseProspectionWorld(): - for joint, pose in joint_config.items(): - prospection_object.set_joint_position(joint, pose) - return prospection_object.links[link_name].pose + other_obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) + + seg_mask, target_point = get_visible_objects(camera_pose, front_facing_axis) + + # All indices where the object that could be occluded is in the image + # [0] at the end is to reduce by one dimension because dstack adds an unnecessary dimension + pix = np.dstack(np.nonzero(seg_mask == obj.id))[0] + + World.current_world.restore_state(state_id) + + occluding_obj_ids = [] + seg_mask = World.current_world.get_images_for_target(target_point, camera_pose)[2] + for c in pix: + if not seg_mask[c[0]][c[1]] == obj.id: + occluding_obj_ids.append(seg_mask[c[0]][c[1]]) + + occ_objects = list(set(map(World.current_world.get_object_by_id, occluding_obj_ids))) + occ_objects = list(map(World.current_world.get_object_from_prospection_object, occ_objects)) + + return occ_objects + + +def reachable( + pose_or_object: Union[Object, Pose], + robot: Object, + gripper_name: str, + threshold: float = 0.01) -> bool: + """ + Checks if the robot can reach a given position. To determine this the inverse kinematics are + calculated and applied. Afterward the distance between the position and the given end effector is calculated, if + it is smaller than the threshold the reasoning query returns True, if not it returns False. + + :param pose_or_object: The position and rotation or Object for which reachability should be checked or an Object + :param robot: The robot that should reach for the position + :param gripper_name: The name of the end effector + :param threshold: The threshold between the end effector and the position. + :return: True if the end effector is closer than the threshold to the target position, False in every other case + """ + + prospection_robot = World.current_world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + target_pose = try_to_reach(pose_or_object, prospection_robot, gripper_name) + + if not target_pose: + return False + + gripper_pose = prospection_robot.links[gripper_name].pose + diff = target_pose.dist(gripper_pose) + + return diff < threshold + + +def blocking( + pose_or_object: Union[Object, Pose], + robot: Object, + gripper_name: str, + grasp: str = None) -> Union[List[Object], None]: + """ + Checks if any objects are blocking another object when a robot tries to pick it. This works + similar to the reachable predicate. First the inverse kinematics between the robot and the object will be + calculated and applied. Then it will be checked if the robot is in contact with any object except the given one. + If the given pose or Object is not reachable None will be returned + + :param pose_or_object: The object or pose for which blocking objects should be found + :param robot: The robot Object who reaches for the object + :param gripper_name: The name of the end effector of the robot + :param grasp: The grasp type with which the object should be grasped + :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose + or object is not reachable. + """ + + prospection_robot = World.current_world.get_prospection_object_from_object(robot) + with UseProspectionWorld(): + if grasp: + try_to_reach_with_grasp(pose_or_object, prospection_robot, gripper_name, grasp) + else: + try_to_reach(pose_or_object, prospection_robot, gripper_name) + + block = [] + for obj in World.current_world.objects: + if contact(prospection_robot, obj): + block.append(World.current_world.get_object_from_prospection_object(obj)) + return block + + +def supporting( + object1: Object, + object2: Object) -> bool: + """ + Checks if one object is supporting another object. An object supports another object if they are in + contact and the second object is above the first one. (e.g. a Bottle will be supported by a table) + + :param object1: Object that is supported + :param object2: Object that supports the first object + :return: True if the second object is in contact with the first one and the second is above the first else False + """ + return contact(object1, object2) and object2.get_position().z > object1.get_position().z + + +def link_pose_for_joint_config( + obj: Object, + joint_config: Dict[str, float], + link_name: str) -> Pose: + """ + Returns the pose a link would be in if the given joint configuration would be applied to the object. + This is done by using the respective object in the prospection world and applying the joint configuration + to this one. After applying the joint configuration the link position is taken from there. + + :param obj: Object of which the link is a part + :param joint_config: Dict with the goal joint configuration + :param link_name: Name of the link for which the pose should be returned + :return: The pose of the link after applying the joint configuration + """ + prospection_object = World.current_world.get_prospection_object_from_object(obj) + with UseProspectionWorld(): + for joint, pose in joint_config.items(): + prospection_object.set_joint_position(joint, pose) + return prospection_object.links[link_name].pose diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index 4375ca52e..2c6f2338d 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -1,7 +1,7 @@ import time from test_bullet_world import BulletWorldTest -from pycram.world_reasoning import WorldReasoning +import pycram.world_reasoning as btr from pycram.pose import Pose from pycram.robot_descriptions import robot_description @@ -14,28 +14,24 @@ def test_contact(self): self.milk.set_pose(Pose([1, 1, 1])) self.cereal.set_pose(Pose([1, 1, 1])) time.sleep(1) - btr = WorldReasoning(self.world) self.assertTrue(btr.contact(self.milk, self.cereal)) def test_visible(self): self.milk.set_pose(Pose([1.5, 0, 1.2])) self.robot.set_pose(Pose()) time.sleep(1) - btr = WorldReasoning(self.world) self.assertTrue(btr.visible(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, - robot_description.front_facing_axis)) + robot_description.front_facing_axis)) def test_occluding(self): self.milk.set_pose(Pose([3, 0, 1.2])) self.robot.set_pose(Pose()) - btr = WorldReasoning(self.world) self.assertTrue(btr.occluding(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, robot_description.front_facing_axis) != []) def test_reachable(self): self.robot.set_pose(Pose()) time.sleep(1) - btr = WorldReasoning(self.world) self.assertTrue(btr.reachable(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right"))) self.assertFalse(btr.reachable(Pose([2, 2, 1]), self.robot, robot_description.get_tool_frame("right"))) @@ -43,11 +39,9 @@ def test_blocking(self): self.milk.set_pose(Pose([0.5, -0.7, 1])) self.robot.set_pose(Pose()) time.sleep(1) - btr = WorldReasoning(self.world) self.assertTrue( btr.blocking(Pose([0.5, -0.7, 1]), self.robot, robot_description.get_tool_frame("right")) != []) def test_supporting(self): self.milk.set_pose(Pose([1.3, 0, 0.9])) - btr = WorldReasoning(self.world) self.assertTrue(btr.supporting(self.kitchen, self.milk)) From 8583fd1994f52203b24391fccb921d21960308da Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 23 Jan 2024 22:41:35 +0100 Subject: [PATCH 052/195] [WorldAbstractClass] (in progress) implementing abstract shape creation and visualization for usage in costmap for example. --- src/pycram/bullet_world.py | 19 +++++- src/pycram/costmaps.py | 109 ++++++++++++++++---------------- src/pycram/enums.py | 13 ++++ src/pycram/world.py | 36 ++++++++++- src/pycram/world_dataclasses.py | 102 +++++++++++++++++++++++++++++- 5 files changed, 216 insertions(+), 63 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index e5d341959..0a9d24a62 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -7,13 +7,13 @@ import numpy as np import pybullet as p -import rospy import rosgraph +import rospy from .enums import JointType, ObjectType from .pose import Pose from .world import World, Object -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody class BulletWorld(World): @@ -402,6 +402,19 @@ def remove_vis_axis(self) -> None: p.removeBody(id, physicsClientId=self.client_id) self.vis_axis = [] + def create_multi_body(self, multi_body: MultiBody) -> int: + return p.createMultiBody(baseVisualShapeIndex=-MultiBody.base_visual_shape_index, + linkVisualShapeIndices=MultiBody.link_visual_shape_indices, + basePosition=MultiBody.base_position, baseOrientation=MultiBody.base_orientation, + linkPositions=MultiBody.link_positions, linkMasses=MultiBody.link_masses, + linkOrientations=MultiBody.link_orientations, + linkInertialFramePositions=MultiBody.link_inertial_frame_positions, + linkInertialFrameOrientations=MultiBody.link_inertial_frame_orientations, + linkParentIndices=MultiBody.link_parent_indices, + linkJointTypes=MultiBody.link_joint_types, + linkJointAxis=MultiBody.link_joint_axis, + linkCollisionShapeIndices=MultiBody.link_collision_shape_indices) + def get_images_for_target(self, target_pose: Pose, cam_pose: Pose, @@ -649,4 +662,4 @@ def run(self): cameraTargetPosition = (0.0, -50, 50) p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1], physicsClientId=self.world.client_id) - time.sleep(1. / 80.) \ No newline at end of file + time.sleep(1. / 80.) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 100ecbdbf..0fe5af279 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -1,43 +1,48 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations +from typing import Tuple, List, Optional + +import matplotlib.pyplot as plt import numpy as np +import psutil import pybullet as p import rospy -import matplotlib.pyplot as plt from matplotlib import colors -import psutil -import time -from .bullet_world import BulletWorld -from pycram.world import UseProspectionWorld, Object, Link -from .world_dataclasses import AxisAlignedBoundingBox from nav_msgs.msg import OccupancyGrid, MapMetaData -from typing import Tuple, List, Union, Optional +from pycram.world import UseProspectionWorld, Object, Link from .local_transformer import LocalTransformer from .pose import Pose +from .world import World +from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, BoxShapeData, MultiBody, Color class Costmap: """ The base class of all Costmaps which implements the visualization of costmaps - in the BulletWorld. + in the World. """ def __init__(self, resolution: float, height: int, width: int, origin: Pose, - map: np.ndarray): + map: np.ndarray, + world: Optional[World] = None): """ The constructor of the base class of all Costmaps. - :param resolution: The distance in metre in the real world which is represented by a single entry in the costmap. + :param resolution: The distance in metre in the real-world which is + represented by a single entry in the costmap. :param height: The height of the costmap. :param width: The width of the costmap. - :param origin: The origin of the costmap, in world coordinate frame. The origin of the costmap is located in the centre of the costmap + :param origin: The origin of the costmap, in world coordinate frame. The origin of the costmap is located in the + centre of the costmap. :param map: The costmap represents as a 2D numpy array. + :param world: The World for which the costmap should be created. """ + self.world = world if world else World.current_world self.resolution: float = resolution self.size: int = height self.height: int = height @@ -49,18 +54,15 @@ def __init__(self, resolution: float, def visualize(self) -> None: """ - Visualizes a costmap in the BulletWorld, the visualisation works by + Visualizes a costmap in the World, the visualisation works by subdividing the costmap in rectangles which are then visualized as pybullet visual shapes. """ - if self.vis_ids != []: + if self.vis_ids: return # working on a copy of the costmap, since found rectangles are deleted map = np.copy(self.map) - curr_width = 0 - curr_height = 0 - curr_pose = [] boxes = [] # Finding all rectangles in the costmap for i in range(0, map.shape[0]): @@ -76,13 +78,13 @@ def visualize(self) -> None: # Creation of the visual shapes, for documentation of the visual shapes # please look here: https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.q1gn7v6o58bf for box in boxes: - visual = p.createVisualShape(p.GEOM_BOX, - halfExtents=[(box[1] * self.resolution) / 2, (box[2] * self.resolution) / 2, - 0.001], - rgbaColor=[1, 0, 0, 0.6], - visualFramePosition=[(box[0][0] + box[1] / 2) * self.resolution, - (box[0][1] + box[2] / 2) * self.resolution, 0.]) + box_shape_data = BoxShapeData([(box[1] * self.resolution) / 2, (box[2] * self.resolution) / 2, 0.001]) + visual_frame_position = [(box[0][0] + box[1] / 2) * self.resolution, + (box[0][1] + box[2] / 2) * self.resolution, 0.] + visual_shape = BoxVisualShape(Color(1, 0, 0, 0.6), visual_frame_position, box_shape_data) + visual = self.world.create_box_visual_shape(visual_shape) cells.append(visual) + # Set to 127 for since this is the maximal amount of links in a multibody for cell_parts in self._chunks(cells, 127): # Dummy paramater since these are needed to spawn visual shapes as a @@ -94,24 +96,21 @@ def visualize(self) -> None: link_joints = [p.JOINT_FIXED for c in cell_parts] link_collision = [-1 for c in cell_parts] link_joint_axis = [[1, 0, 0] for c in cell_parts] - # The position at which the multibody will be spawned. Offset such that - # the origin referes to the centre of the costmap. - # origin_pose = self.origin.position_as_list() - # base_pose = [origin_pose[0] - self.height / 2 * self.resolution, - # origin_pose[1] - self.width / 2 * self.resolution, origin_pose[2]] offset = [[-self.height / 2 * self.resolution, -self.width / 2 * self.resolution, 0.05], [0, 0, 0, 1]] new_pose = p.multiplyTransforms(self.origin.position_as_list(), self.origin.orientation_as_list(), offset[0], offset[1]) - map_obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=cell_parts, - basePosition=new_pose[0], baseOrientation=new_pose[1], linkPositions=link_poses, - # [0, 0, 1, 0] - linkMasses=link_masses, linkOrientations=link_orientations, - linkInertialFramePositions=link_poses, - linkInertialFrameOrientations=link_orientations, linkParentIndices=link_parent, - linkJointTypes=link_joints, linkJointAxis=link_joint_axis, - linkCollisionShapeIndices=link_collision) + multi_body = MultiBody(base_visual_shape_index=-1, base_position=new_pose[0], base_orientation=new_pose[1], + link_visual_shape_indices=cell_parts, link_positions=link_poses, + link_orientations=link_orientations, link_masses=link_masses, + link_inertial_frame_positions=link_poses, + link_inertial_frame_orientations=link_orientations, + link_parent_indices=link_parent, link_joint_types=link_joints, + link_joint_axis=link_joint_axis, + link_collision_shape_indices=link_collision) + + map_obj = self.world.create_multi_body(multi_body) self.vis_ids.append(map_obj) def _chunks(self, lst: List, n: int) -> List: @@ -127,7 +126,7 @@ def _chunks(self, lst: List, n: int) -> List: def close_visualization(self) -> None: """ - Removes the visualization from the BulletWorld. + Removes the visualization from the World. """ for id in self.vis_ids: p.removeBody(id) @@ -151,7 +150,7 @@ def _find_consectuive_line(self, start: Tuple[int, int], map: np.ndarray) -> int return lenght return lenght - def _find_max_box_height(self, start: Tuple[int, int], lenght: int, map: np.ndarray) -> int: + def _find_max_box_height(self, start: Tuple[int, int], length: int, map: np.ndarray) -> int: """ Finds the maximal height for a rectangle with a given width in a costmap. The method traverses one row at a time and checks if all entries for the @@ -166,7 +165,7 @@ def _find_max_box_height(self, start: Tuple[int, int], lenght: int, map: np.ndar height, width = map.shape curr_height = 1 for i in range(start[0], height): - for j in range(start[1], start[1] + lenght): + for j in range(start[1], start[1] + length): if map[i][j] <= 0: return curr_height curr_height += 1 @@ -235,9 +234,9 @@ def __init__(self, distance_to_obstacle: float, inflated. Meaning that obstacles in the costmap are growing bigger by this distance. :param from_ros: This determines if the Occupancy map should be created - from the map provided by the ROS map_server or from the BulletWorld. + from the map provided by the ROS map_server or from the World. If True then the map from the ROS map_server will be used otherwise - the Occupancy map will be created from the BulletWorld. + the Occupancy map will be created from the World. :param size: The length of the side of the costmap. The costmap will be created as a square. This will only be used if from_ros is False. :param resolution: The resolution of this costmap. This determines how much @@ -281,7 +280,7 @@ def _calculate_diff_origin(self, height: int, width: int) -> Pose: """ actual_origin = [int(height / 2) * self.resolution, int(width / 2) * self.resolution, 0] origin = np.array(self.meta_origin) + np.array(actual_origin) - return Pose(origin) + return Pose(origin.tolist()) @staticmethod def _get_map() -> np.ndarray: @@ -361,7 +360,7 @@ def create_sub_map(self, sub_origin: Pose, size: int) -> Costmap: def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: """ - Creates an Occupancy Costmap for the specified BulletWorld. + Creates an Occupancy Costmap for the specified World. This map marks every position as valid that has no object above it. After creating the costmap the distance to obstacle parameter is applied. @@ -388,15 +387,16 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: for n in self._chunks(np.array(rays), 16380): with UseProspectionWorld(): r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=BulletWorld.current_world.client_id) + physicsClientId=World.current_world.client_id) while r_t is None: r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=BulletWorld.current_world.client_id) + physicsClientId=World.current_world.client_id) j += len(n) - if BulletWorld.robot: - shadow_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) - attached_objs = BulletWorld.robot.attachments.keys() - attached_objs_shadow_id = [BulletWorld.current_world.get_prospection_object_from_object(x).id for x in + if World.robot: + shadow_robot = World.current_world.get_prospection_object_from_object(World.robot) + attached_objs = World.robot.attachments.keys() + attached_objs_shadow_id = [World.current_world.get_prospection_object_from_object(x).id for x + in attached_objs] res[i:j] = [ 1 if ray[0] == -1 or ray[0] == shadow_robot.id or ray[0] in attached_objs_shadow_id else 0 for @@ -450,7 +450,7 @@ def __init__(self, min_height: float, size: Optional[int] = 100, resolution: Optional[float] = 0.02, origin: Optional[Pose] = None, - world: Optional[BulletWorld] = None): + world: Optional[World] = None): """ Visibility Costmaps show for every position around the origin pose if the origin can be seen from this pose. The costmap is able to deal with height differences of the camera while in a single position, for example, if @@ -466,12 +466,11 @@ def __init__(self, min_height: float, costmap represents. :param origin: The pose in world coordinate frame around which the costmap should be created. - :param world: The BulletWorld for which the costmap should be created. + :param world: The World for which the costmap should be created. """ if (11 * size ** 2 + size ** 3) * 2 > psutil.virtual_memory().available: raise OSError("Not enough free RAM to calculate a costmap of this size") - self.world = world if world else BulletWorld.current_world self.map = np.zeros((size, size)) self.size = size self.resolution = resolution @@ -584,7 +583,7 @@ def _generate_map(self): depth_indices[int(self.size / 2), int(self.size / 2), 1] = 1 # Calculate columns for the respective position in the costmap - columns = np.around(((depth_indices[:, :, :1] / depth_indices[:, :, 1:2]) \ + columns = np.around(((depth_indices[:, :, :1] / depth_indices[:, :, 1:2]) * (self.size / 2)) + self.size / 2).reshape((self.size, self.size)).astype('int16') # An array with size * size that contains the euclidean distance to the @@ -691,9 +690,9 @@ def __init__(self, object, urdf_link_name, size=100, resolution=0.02, world=None :param object: The object of which the link is a part :param urdf_link_name: The link name, as stated in the URDF :param resolution: Resolution of the final costmap - :param world: The BulletWorld from which the costmap should be created + :param world: The World from which the costmap should be created """ - self.world: BulletWorld = world if world else BulletWorld.current_world + self.world: World = world if world else World.current_world self.object: Object = object self.link: Link = object.links[urdf_link_name] self.resolution: float = resolution @@ -723,7 +722,7 @@ def get_aabb_for_link(self) -> AxisAlignedBoundingBox: :return: Two points in world coordinate space, which span a rectangle """ - prospection_object = BulletWorld.current_world.get_prospection_object_from_object(self.object) + prospection_object = World.current_world.get_prospection_object_from_object(self.object) with UseProspectionWorld(): prospection_object.set_orientation(Pose(orientation=[0, 0, 0, 1])) link_pose_trans = self.link.transform diff --git a/src/pycram/enums.py b/src/pycram/enums.py index 40257a3c2..79238403d 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -2,6 +2,8 @@ from enum import Enum, auto +import pybullet + class Arms(Enum): """Enum for Arms.""" @@ -57,3 +59,14 @@ class ObjectType(Enum): ENVIRONMENT = auto() GENERIC_OBJECT = auto() + +class Shape(Enum): + """ + Enum for visual shapes of objects + """ + SPHERE = 2 + BOX = 3 + CYLINDER = 4 + MESH = 5 + PLANE = 6 + CAPSULE = 7 diff --git a/src/pycram/world.py b/src/pycram/world.py index 5a89c4b63..5e9c1f46d 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -32,7 +32,9 @@ from abc import ABC, abstractmethod from dataclasses import dataclass -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks +from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks, + MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, + CapsuleVisualShape, PlaneVisualShape, MeshVisualShape) class World(ABC): @@ -698,7 +700,8 @@ def _copy(self) -> World: """ world = World("DIRECT", False, World.simulation_time_step) for obj in self.objects: - o = Object(obj.name, obj.obj_type, obj.path, Pose(obj.get_position(), obj.get_orientation()), world, + obj_pose = Pose(obj.get_position_as_list(), obj.get_orientation_as_list()) + o = Object(obj.name, obj.obj_type, obj.path, obj_pose, world, obj.color) for joint in obj.joint_name_to_id: o.set_joint_position(joint, obj.get_joint_position(joint)) @@ -793,6 +796,30 @@ def update_transforms_for_objects_in_current_world(self) -> None: for obj in list(self.current_world.objects): obj.update_link_transforms(curr_time) + def create_visual_shape(self, visual_shape: VisualShape) -> int: + raise NotImplementedError + + def create_multi_body(self, multi_body: MultiBody) -> int: + raise NotImplementedError + + def create_box_visual_shape(self, shape_data: BoxVisualShape) -> int: + raise NotImplementedError + + def create_cylinder_visual_shape(self, shape_data: CylinderVisualShape) -> int: + raise NotImplementedError + + def create_sphere_visual_shape(self, shape_data: SphereVisualShape) -> int: + raise NotImplementedError + + def create_capsule_visual_shape(self, shape_data: CapsuleVisualShape) -> int: + raise NotImplementedError + + def create_plane_visual_shape(self, shape_data: PlaneVisualShape) -> int: + raise NotImplementedError + + def create_mesh_visual_shape(self, shape_data: MeshVisualShape) -> int: + raise NotImplementedError + class UseProspectionWorld: """ @@ -1602,7 +1629,10 @@ def set_color(self, color: Color, link: Optional[str] = "") -> None: self.world.set_object_color(self, color, link) def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: - return self.world.get_color_of_object(self, link) + if link is None: + return self.world.get_color_of_object(self) + else: + return self.world.get_color_of_object_link(self, link) def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_aabb(self) diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index fb057aa3a..8c22c7fa9 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,6 +1,6 @@ from dataclasses import dataclass from typing import List, Optional, Tuple, Callable -from .enums import JointType +from .enums import JointType, Shape @dataclass @@ -138,4 +138,102 @@ def get_max(self) -> List[float]: @dataclass class CollisionCallbacks: on_collision_cb: Callable - no_collision_cb: Optional[Callable] = None \ No newline at end of file + no_collision_cb: Optional[Callable] = None + + +@dataclass +class MultiBody: + base_visual_shape_index: int + base_position: List[float] + base_orientation: List[float] + link_visual_shape_indices: List[int] + link_positions: List[List[float]] + link_orientations: List[List[float]] + link_masses: List[float] + link_inertial_frame_positions: List[List[float]] + link_inertial_frame_orientations: List[List[float]] + link_parent_indices: List[int] + link_joint_types: List[JointType] + link_joint_axis: List[List[float]] + link_collision_shape_indices: List[int] + + +@dataclass +class ShapeData: + pass + + +@dataclass +class BoxShapeData(ShapeData): + half_extents: List[float] + + +@dataclass +class SphereShapeData(ShapeData): + radius: float + + +@dataclass +class CapsuleShapeData(ShapeData): + radius: float + length: float + + +@dataclass +class CylinderShapeData(ShapeData): + radius: float + length: float + + +@dataclass +class MeshShapeData(ShapeData): + mesh_scale: List[float] + mesh_file_name: str + + +@dataclass +class PlaneShapeData(ShapeData): + normal: List[float] + + +@dataclass +class VisualShape: + rgba_color: Color + visual_frame_position: List[float] + shape_data: ShapeData + + +@dataclass +class BoxVisualShape(VisualShape): + shape_data: BoxShapeData + visual_geometry_type = Shape.BOX + + +@dataclass +class SphereVisualShape(VisualShape): + shape_data: SphereShapeData + visual_geometry_type = Shape.SPHERE + + +@dataclass +class CapsuleVisualShape(VisualShape): + shape_data: CapsuleShapeData + visual_geometry_type = Shape.CAPSULE + + +@dataclass +class CylinderVisualShape(VisualShape): + shape_data: CylinderShapeData + visual_geometry_type = Shape.CYLINDER + + +@dataclass +class MeshVisualShape(VisualShape): + visual_geometry_type = Shape.MESH + shape_data: MeshShapeData + + +@dataclass +class PlaneVisualShape(VisualShape): + shape_data: PlaneShapeData + visual_geometry_type = Shape.PLANE From ed33735dcf5c4fab1039dd947f73d0cbfc7a36e7 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 24 Jan 2024 12:09:31 +0100 Subject: [PATCH 053/195] Merge branch 'dev' of github.com:cram2/pycram into abstract_world --- src/neem_interface_python | 2 +- src/pycram/costmaps.py | 3 ++- src/pycram/designator.py | 2 +- src/pycram/designators/action_designator.py | 21 ++++++++++--------- src/pycram/external_interfaces/ik.py | 6 +++--- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/local_transformer.py | 4 ++-- src/pycram/pose_generator_and_validator.py | 6 +++--- .../process_modules/pr2_process_modules.py | 14 ++++++------- src/pycram/world.py | 6 +++--- test/bullet_world_testcase.py | 11 +++------- test/test_failure_handling.py | 4 ++-- test/test_language.py | 6 +++--- test/test_local_transformer.py | 4 ++-- 14 files changed, 44 insertions(+), 47 deletions(-) diff --git a/src/neem_interface_python b/src/neem_interface_python index 51aa0f9a3..05ad42c41 160000 --- a/src/neem_interface_python +++ b/src/neem_interface_python @@ -1 +1 @@ -Subproject commit 51aa0f9a3b38fde3156bdf29be7aad7bb9547926 +Subproject commit 05ad42c41042335dd2287d865f6a37c115ea8ffe diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 0fe5af279..e0acabd03 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -48,7 +48,7 @@ def __init__(self, resolution: float, self.height: int = height self.width: int = width local_transformer = LocalTransformer() - self.origin: Pose = local_transformer.transform_pose_to_target_frame(origin, 'map') + self.origin: Pose = local_transformer.transform_pose(origin, 'map') self.map: np.ndarray = map self.vis_ids: List[int] = [] @@ -471,6 +471,7 @@ def __init__(self, min_height: float, if (11 * size ** 2 + size ** 3) * 2 > psutil.virtual_memory().available: raise OSError("Not enough free RAM to calculate a costmap of this size") + self.world = world if world else World.current_world self.map = np.zeros((size, size)) self.size = size self.resolution = resolution diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 209373022..65aedce37 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -701,7 +701,7 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: :return: The adjusted grasp pose """ lt = LocalTransformer() - pose_in_object = lt.transform_pose_to_target_frame(pose, self.bullet_world_object.tf_frame) + pose_in_object = lt.transform_pose(pose, self.bullet_world_object.tf_frame) special_knowledge = [] # Initialize as an empty list if self.obj_type in SPECIAL_KNOWLEDGE: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 852569b45..91d5fff85 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -310,11 +310,11 @@ def perform(self) -> None: # oTm = Object Pose in Frame map oTm = object.get_pose() # Transform the object pose to the object frame, basically the origin of the object frame - mTo = object.local_transformer.transform_pose_to_target_frame(oTm, object.tf_frame) + mTo = object.local_transformer.transform_pose(oTm, object.tf_frame) # Adjust the pose according to the special knowledge of the object designator adjusted_pose = self.object_designator.special_knowledge_adjustment_pose(self.grasp, mTo) # Transform the adjusted pose to the map frame - adjusted_oTm = object.local_transformer.transform_pose_to_target_frame(adjusted_pose, "map") + adjusted_oTm = object.local_transformer.transform_pose(adjusted_pose, "map") # multiplying the orientation therefore "rotating" it, to get the correct orientation of the gripper ori = multiply_quaternions([adjusted_oTm.orientation.x, adjusted_oTm.orientation.y, adjusted_oTm.orientation.z, adjusted_oTm.orientation.w], @@ -330,11 +330,11 @@ def perform(self) -> None: # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" gripper_frame = robot.links[robot_description.get_tool_frame(self.arm)].tf_frame # First rotate the gripper, so the further calculations makes sense - tmp_for_rotate_pose = object.local_transformer.transform_pose_to_target_frame(adjusted_oTm, gripper_frame) + tmp_for_rotate_pose = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) tmp_for_rotate_pose.pose.position.x = 0 tmp_for_rotate_pose.pose.position.y = 0 tmp_for_rotate_pose.pose.position.z = -0.1 - gripper_rotate_pose = object.local_transformer.transform_pose_to_target_frame(tmp_for_rotate_pose, "map") + gripper_rotate_pose = object.local_transformer.transform_pose(tmp_for_rotate_pose, "map") #Perform Gripper Rotate # BulletWorld.current_bullet_world.add_vis_axis(gripper_rotate_pose) @@ -437,16 +437,17 @@ def perform(self) -> None: # Transformations such that the target position is the position of the object and not the tcp tool_name = robot_description.get_tool_frame(self.arm) - tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, - BulletWorld.robot.links[tool_name].tf_frame) + tcp_to_object = local_tf.transform_pose(object_pose, + BulletWorld.robot.links[tool_name].tf_frame) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() MoveTCPMotion(target_diff, self.arm).resolve().perform() MoveGripperMotion("open", self.arm).resolve().perform() BulletWorld.robot.detach(self.object_designator.bullet_world_object) - retract_pose = local_tf.transform_pose(target_diff,BulletWorld.robot.get_link_tf_frame( - robot_description.get_tool_frame(self.arm))) + retract_pose = local_tf.transform_pose( + target_diff, + BulletWorld.robot.links[robot_description.get_tool_frame(self.arm)].tf_frame) retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).resolve().perform() @@ -887,8 +888,8 @@ def perform(self) -> Any: lt = LocalTransformer() gripper_name = robot_description.get_tool_frame(self.arm) - object_pose_in_gripper = lt.transform_pose_to_target_frame(object_pose, - BulletWorld.robot.links[gripper_name].tf_frame) + object_pose_in_gripper = lt.transform_pose(object_pose, + BulletWorld.robot.links[gripper_name].tf_frame) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 262a3c063..b7d1fb50b 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -45,7 +45,7 @@ def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_ob :return: A moveit_msgs/PositionIKRequest message containing all the information from the parameter """ local_transformer = LocalTransformer() - target_pose = local_transformer.transform_pose_to_target_frame(target_pose, robot_object.links[root_link].tf_frame) + target_pose = local_transformer.transform_pose(target_pose, robot_object.links[root_link].tf_frame) robot_state = RobotState() joint_state = JointState() @@ -135,7 +135,7 @@ def apply_grasp_orientation_to_pose(grasp: str, pose: Pose) -> Pose: :param pose: The pose to which the grasp orientation should be applied """ local_transformer = LocalTransformer() - target_map = local_transformer.transform_pose_to_target_frame(pose, "map") + target_map = local_transformer.transform_pose(pose, "map") grasp_orientation = robot_description.grasps.get_orientation_for_grasp(grasp) target_map.orientation.x = grasp_orientation[0] target_map.orientation.y = grasp_orientation[1] @@ -180,7 +180,7 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str # Get link after last joint in chain end_effector = robot_description.get_child(joints[-1]) - target_torso = local_transformer.transform_pose_to_target_frame(target_pose, robot.links[base_link].tf_frame) + target_torso = local_transformer.transform_pose(target_pose, robot.links[base_link].tf_frame) diff = calculate_wrist_tool_offset(end_effector, gripper, robot) target_diff = target_torso.to_transform("target").inverse_times(diff).to_pose() diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index b2574b55b..fbfad9b5a 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -129,7 +129,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti source = query_result.res[0].poseSource[i] lt = LocalTransformer() - pose = lt.transform_pose_to_target_frame(pose, "map") + pose = lt.transform_pose(pose, "map") pose_candidates[source] = pose diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index 05d149277..ebbe4e64d 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -55,7 +55,7 @@ def __init__(self): # If the singelton was already initialized self._initialized = True - def transform_pose_to_target_frame(self, pose: Pose, target_frame: str) -> Union[Pose, None]: + def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: """ Transforms a given pose to the target frame after updating the transforms for all objects in the current world. @@ -115,5 +115,5 @@ def transformPose(self, target_frame, ps) -> Pose: Alias for :func:`~LocalTransformer.transform_pose_to_target_frame` to avoid confusion since a similar method exists in the super class. """ - return self.transform_pose_to_target_frame(ps, target_frame) + return self.transform_pose(ps, target_frame) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index ff761aa6e..2aa5797af 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -152,7 +152,7 @@ def reachability_validator(pose: Pose, if robot in allowed_collision.keys(): allowed_robot_links = allowed_collision[robot] - joint_state_before_ik=robot._current_joint_states + joint_state_before_ik=robot._current_joints_positions try: # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) resp = request_ik(target, robot, left_joints, left_gripper) @@ -175,7 +175,7 @@ def reachability_validator(pose: Pose, except IKError: pass finally: - robot.set_joint_states(joint_state_before_ik) + robot.set_positions_of_all_joints(joint_state_before_ik) try: # resp = request_ik(base_link, end_effector, target_diff, robot, right_joints) @@ -199,6 +199,6 @@ def reachability_validator(pose: Pose, except IKError: pass finally: - robot.set_joint_states(joint_state_before_ik) + robot.set_positions_of_all_joints(joint_state_before_ik) return res, arms diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 87b699d3d..5f432560b 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -91,7 +91,7 @@ def _execute(self, desig: PlaceMotion.Motion): object_pose = object.get_pose() local_tf = LocalTransformer() tool_name = robot_description.get_tool_frame(arm) - tcp_to_object = local_tf.transform_pose_to_target_frame(object_pose, robot.links[tool_name].tf_frame) + tcp_to_object = local_tf.transform_pose(object_pose, robot.links[tool_name].tf_frame) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) @@ -109,8 +109,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.links["head_pan_link"].tf_frame) - pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.links["head_tilt_link"].tf_frame) + pose_in_pan = local_transformer.transform_pose(target, robot.links["head_pan_link"].tf_frame) + pose_in_tilt = local_transformer.transform_pose(target, robot.links["head_tilt_link"].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -289,8 +289,8 @@ def _execute(self, desig: LookingMotion.Motion): robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose_to_target_frame(target, robot.links["head_pan_link"].tf_frame) - pose_in_tilt = local_transformer.transform_pose_to_target_frame(target, robot.links["head_tilt_link"].tf_frame) + pose_in_pan = local_transformer.transform_pose(target, robot.links["head_pan_link"].tf_frame) + pose_in_tilt = local_transformer.transform_pose(target, robot.links["head_tilt_link"].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -315,7 +315,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose_to_target_frame(obj_pose, BulletWorld.robot.links["torso_lift_link"].tf_frame) + obj_pose = lt.transform_pose(obj_pose, BulletWorld.robot.links["torso_lift_link"].tf_frame) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 @@ -344,7 +344,7 @@ class Pr2MoveTCPReal(ProcessModule): def _execute(self, designator: MoveTCPMotion.Motion) -> Any: lt = LocalTransformer() - pose_in_map = lt.transform_pose_to_target_frame(designator.target, "map") + pose_in_map = lt.transform_pose(designator.target, "map") if designator.allow_gripper_collision: giskard.allow_gripper_collision(designator.arm) diff --git a/src/pycram/world.py b/src/pycram/world.py index 5e9c1f46d..4113dd1cb 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1015,7 +1015,7 @@ def get_transform_from_link(self, link: Link) -> Transform: return self.get_pose_wrt_link(link).to_transform(self.tf_frame) def get_pose_wrt_link(self, link: Link) -> Pose: - return self.local_transformer.transform_pose_to_target_frame(self.pose, link.tf_frame) + return self.local_transformer.transform_pose(self.pose, link.tf_frame) def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_link_aabb(self.object.id, self.id) @@ -1131,7 +1131,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.color: Color = color self.local_transformer = LocalTransformer() - self.original_pose = self.local_transformer.transform_pose_to_target_frame(pose, "map") + self.original_pose = self.local_transformer.transform_pose(pose, "map") position, orientation = self.original_pose.to_list() self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) self._current_pose = self.original_pose @@ -1332,7 +1332,7 @@ def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Op :param base: If True places the object base instead of origin at the specified position and orientation :param set_attachments: Whether to set the poses of the attached objects to this object or not. """ - pose_in_map = self.local_transformer.transform_pose_to_target_frame(pose, "map") + pose_in_map = self.local_transformer.transform_pose(pose, "map") position, orientation = pose_in_map.to_list() if base: diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index b34b434c4..b3fb307eb 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -1,15 +1,10 @@ import unittest -import numpy as np -import rospkg - -from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial +from pycram.bullet_world import BulletWorld, Object from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule from pycram.enums import ObjectType -import os -import tf class BulletWorldTestCase(unittest.TestCase): @@ -26,14 +21,14 @@ def setUpClass(cls): ProcessModule.execution_delay = False def setUp(self): - self.world.reset_bullet_world() + self.world.reset_world() # DO NOT WRITE TESTS HERE!!! # Test related to the BulletWorld should be written in test_bullet_world.py # Tests in here would not be properly executed in the CI def tearDown(self): - self.world.reset_bullet_world() + self.world.reset_world() @classmethod def tearDownClass(cls): diff --git a/test/test_failure_handling.py b/test/test_failure_handling.py index ab0a8491b..d23a9d93b 100644 --- a/test/test_failure_handling.py +++ b/test/test_failure_handling.py @@ -34,7 +34,7 @@ def setUpClass(cls): ProcessModule.execution_delay = True def setUp(self): - self.world.reset_bullet_world() + self.world.reset_world() def test_retry_with_success(self): with simulated_robot: @@ -46,7 +46,7 @@ def test_retry_with_failure(self): Retry(DummyActionDesignator(), max_tries=5).perform() def tearDown(self): - self.world.reset_bullet_world() + self.world.reset_world() @classmethod def tearDownClass(cls): diff --git a/test/test_language.py b/test/test_language.py index 951db67c4..7470ed751 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -144,11 +144,11 @@ def test_perform_desig(self): with simulated_robot: plan.perform() self.assertEqual(self.robot.get_pose(), Pose([1, 1, 0])) - self.assertEqual(self.robot.get_joint_state("torso_lift_joint"), 0.3) + self.assertEqual(self.robot.get_joint_position("torso_lift_joint"), 0.3) for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - self.assertEqual(self.world.robot.get_joint_state(joint), pose) + self.assertEqual(self.world.robot.get_joint_position(joint), pose) for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - self.assertEqual(self.world.robot.get_joint_state(joint), pose) + self.assertEqual(self.world.robot.get_joint_position(joint), pose) def test_perform_code(self): def test_set(param): diff --git a/test/test_local_transformer.py b/test/test_local_transformer.py index 4b4705eda..4cad086e7 100644 --- a/test/test_local_transformer.py +++ b/test/test_local_transformer.py @@ -22,7 +22,7 @@ def test_transform_pose(self): l.setTransform(Transform([1, 1, 1], [0, 0, 0, 1], "map", "test_frame")) p = Pose() - transformed_pose = l.transform_pose_to_target_frame(p, "test_frame") + transformed_pose = l.transform_pose(p, "test_frame") self.assertTrue(transformed_pose.position_as_list() == [-1, -1, -1]) self.assertTrue(transformed_pose.orientation_as_list() == [0, 0, 0, 1]) @@ -33,7 +33,7 @@ def test_transform_pose_position(self): l.setTransform(Transform([1, 1, 1], [0, 0, 0, 1], "map", "test_frame")) p = Pose() - transformed_pose = l.transform_pose_to_target_frame(p, "test_frame") + transformed_pose = l.transform_pose(p, "test_frame") self.assertTrue(transformed_pose.position == transformed_pose.pose.position) From 49a70264ab1c3df776cda17b9f944c5acd46b060 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 24 Jan 2024 12:25:25 +0100 Subject: [PATCH 054/195] Merge branch 'dev' of github.com:cram2/pycram into abstract_world (fixed missing import and use of World instead of BulletWorld in test_database_resolver.py) --- test/test_database_resolver.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index ea22b3c3c..18d7c047b 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -5,6 +5,7 @@ import pycram.plan_failures from pycram.world import Object from pycram import task +from pycram.world import World from pycram.designators import action_designator, object_designator from pycram.orm.base import Base from pycram.process_module import ProcessModule @@ -32,7 +33,7 @@ @unittest.skipIf(not jpt_installed, "jpt is not installed but needed for the definition of DatabaseCostmapLocations. " "Install via 'pip install pyjpt'") class DatabaseResolverTestCase(unittest.TestCase,): - world: BulletWorld + world: World milk: Object robot: Object engine: sqlalchemy.engine.Engine @@ -41,7 +42,7 @@ class DatabaseResolverTestCase(unittest.TestCase,): @classmethod def setUpClass(cls) -> None: global pycrorm_uri - cls.world = BulletWorld("DIRECT") + cls.world = World("DIRECT") cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False @@ -49,12 +50,12 @@ def setUpClass(cls) -> None: cls.session = sqlalchemy.orm.Session(bind=cls.engine) def setUp(self) -> None: - self.world.reset_bullet_world() + self.world.reset_world() pycram.orm.base.Base.metadata.create_all(self.engine) self.session.commit() def tearDown(self) -> None: - self.world.reset_bullet_world() + self.world.reset_world() pycram.task.reset_tree() @classmethod From 3916ded30093fe135f70531d4f7abacc60f258f8 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 24 Jan 2024 21:58:06 +0100 Subject: [PATCH 055/195] [Abstract World] (check TODOs) Costmaps now is independent of pybullet, HSR module is improved but still dependent on pybullet, designators are independent of pybullet. --- src/pycram/bullet_world.py | 19 ++++- src/pycram/costmaps.py | 31 ++++---- src/pycram/designator.py | 30 ++++---- src/pycram/designators/action_designator.py | 38 +++++----- src/pycram/designators/location_designator.py | 39 +++++----- src/pycram/designators/motion_designator.py | 2 +- src/pycram/designators/object_designator.py | 31 ++++---- src/pycram/pose_generator_and_validator.py | 30 ++++---- .../process_modules/boxy_process_modules.py | 16 ++-- .../default_process_modules.py | 16 ++-- .../process_modules/donbot_process_modules.py | 4 +- .../process_modules/hsr_process_modules.py | 76 ++++++++++--------- .../process_modules/pr2_process_modules.py | 16 ++-- src/pycram/world.py | 59 +++++++++----- src/pycram/world_dataclasses.py | 14 ++-- test/test_action_designator.py | 6 +- 16 files changed, 231 insertions(+), 196 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 173420bfa..74766046c 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -13,7 +13,10 @@ from .enums import JointType, ObjectType from .pose import Pose from .world import World, Object -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody +from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape, + CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, + MeshVisualShape) +from dataclasses import asdict class BulletWorld(World): @@ -404,6 +407,20 @@ def remove_vis_axis(self) -> None: p.removeBody(id, physicsClientId=self.client_id) self.vis_axis = [] + def ray_test(self, from_position: List[float], to_position: List[float]) -> int: + res = p.rayTest(from_position, to_position, physicsClientId=self.client_id) + return res[0][0] + + def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[List[float]], + num_threads: int = 1) -> List[int]: + return p.rayTestBatch(from_positions, to_positions, numThreads=num_threads, + physicsClientId=self.client_id) + + def create_visual_shape(self, visual_shape: VisualShape) -> int: + return p.createVisualShape(visual_shape.visual_geometry_type, rgbaColor=visual_shape.rgba_color, + visualFramePosition=visual_shape.visual_frame_position, + physicsClientId=self.client_id, **asdict(visual_shape.shape_data)) + def create_multi_body(self, multi_body: MultiBody) -> int: return p.createMultiBody(baseVisualShapeIndex=-MultiBody.base_visual_shape_index, linkVisualShapeIndices=MultiBody.link_visual_shape_indices, diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index e0acabd03..6e0154e2e 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -6,16 +6,15 @@ import matplotlib.pyplot as plt import numpy as np import psutil -import pybullet as p import rospy from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData from pycram.world import UseProspectionWorld, Object, Link from .local_transformer import LocalTransformer -from .pose import Pose +from .pose import Pose, Transform from .world import World -from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, BoxShapeData, MultiBody, Color +from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, BoxShapeData, MultiBody, Color, JointType class Costmap: @@ -82,7 +81,7 @@ def visualize(self) -> None: visual_frame_position = [(box[0][0] + box[1] / 2) * self.resolution, (box[0][1] + box[2] / 2) * self.resolution, 0.] visual_shape = BoxVisualShape(Color(1, 0, 0, 0.6), visual_frame_position, box_shape_data) - visual = self.world.create_box_visual_shape(visual_shape) + visual = self.world.create_visual_shape(visual_shape) cells.append(visual) # Set to 127 for since this is the maximal amount of links in a multibody @@ -93,13 +92,15 @@ def visualize(self) -> None: link_orientations = [[0, 0, 0, 1] for c in cell_parts] link_masses = [1.0 for c in cell_parts] link_parent = [0 for c in cell_parts] - link_joints = [p.JOINT_FIXED for c in cell_parts] + link_joints = [JointType.FIXED for c in cell_parts] link_collision = [-1 for c in cell_parts] link_joint_axis = [[1, 0, 0] for c in cell_parts] - offset = [[-self.height / 2 * self.resolution, -self.width / 2 * self.resolution, 0.05], [0, 0, 0, 1]] - new_pose = p.multiplyTransforms(self.origin.position_as_list(), self.origin.orientation_as_list(), - offset[0], offset[1]) + offset = Transform([-self.height / 2 * self.resolution, -self.width / 2 * self.resolution, 0.05], + [0, 0, 0, 1]) + origin = Transform(self.origin.position_as_list(), self.origin.orientation_as_list()) + new_transform = origin * offset + new_pose = new_transform.to_pose().to_list() multi_body = MultiBody(base_visual_shape_index=-1, base_position=new_pose[0], base_orientation=new_pose[1], link_visual_shape_indices=cell_parts, link_positions=link_poses, @@ -128,8 +129,8 @@ def close_visualization(self) -> None: """ Removes the visualization from the World. """ - for id in self.vis_ids: - p.removeBody(id) + for v_id in self.vis_ids: + self.world.remove_object(v_id) self.vis_ids = [] def _find_consectuive_line(self, start: Tuple[int, int], map: np.ndarray) -> int: @@ -224,7 +225,8 @@ def __init__(self, distance_to_obstacle: float, from_ros: Optional[bool] = False, size: Optional[int] = 100, resolution: Optional[float] = 0.02, - origin: Optional[Pose] = None): + origin: Optional[Pose] = None, + world: Optional[World] = None): """ Constructor for the Occupancy costmap, the actual costmap is received from the ROS map_server and wrapped by this class. Meta-data about the @@ -246,6 +248,7 @@ def __init__(self, distance_to_obstacle: float, be in the middle of the costmap. This parameter is only used if from_ros is False. """ + self.world = world if world else World.current_world if from_ros: meta = self._get_map_metadata() self.original_map = np.reshape(self._get_map(), (meta.height, meta.width)) @@ -386,11 +389,9 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: j = 0 for n in self._chunks(np.array(rays), 16380): with UseProspectionWorld(): - r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=World.current_world.client_id) + r_t = self.world.ray_test_batch(n[:, 0], n[:, 1], num_threads=0) while r_t is None: - r_t = p.rayTestBatch(n[:, 0], n[:, 1], numThreads=0, - physicsClientId=World.current_world.client_id) + r_t = self.world.ray_test_batch(n[:, 0], n[:, 1], num_threads=0) j += len(n) if World.robot: shadow_robot = World.current_world.get_prospection_object_from_object(World.robot) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 65aedce37..8f5c70a8a 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -3,14 +3,12 @@ import dataclasses from abc import ABC, abstractmethod -from copy import copy from inspect import isgenerator, isgeneratorfunction from sqlalchemy.orm.session import Session import rospy -from .world import Object as BulletWorldObject -from pycram.bullet_world import BulletWorld +from .world import World, Object as WorldObject from .helper import GeneratorList, bcolors from threading import Lock from time import time @@ -487,9 +485,9 @@ class Action: """ def __post_init__(self): - self.robot_position = BulletWorld.robot.get_pose() - self.robot_torso_height = BulletWorld.robot.get_joint_position(robot_description.torso_joint) - self.robot_type = BulletWorld.robot.obj_type + self.robot_position = World.robot.get_pose() + self.robot_torso_height = World.robot.get_joint_position(robot_description.torso_joint) + self.robot_type = World.robot.obj_type @with_tree def perform(self) -> Any: @@ -612,20 +610,20 @@ class Object: Type of the object """ - bullet_world_object: Optional[BulletWorldObject] + world_object: Optional[WorldObject] """ - Reference to the BulletWorld object + Reference to the World object """ _pose: Optional[Callable] = dataclasses.field(init=False) """ A callable returning the pose of this object. The _pose member is used overwritten for data copies - which will not update when the original bullet_world_object is moved. + which will not update when the original world_object is moved. """ def __post_init__(self): - if self.bullet_world_object: - self._pose = self.bullet_world_object.get_pose + if self.world_object: + self._pose = self.world_object.get_pose def to_sql(self) -> ORMObjectDesignator: """ @@ -658,7 +656,7 @@ def insert(self, session: Session) -> ORMObjectDesignator: def data_copy(self) -> 'ObjectDesignatorDescription.Object': """ - :return: A copy containing only the fields of this class. The BulletWorldObject attached to this pycram + :return: A copy containing only the fields of this class. The WorldObject attached to this pycram object is not copied. The _pose gets set to a method that statically returns the pose of the object when this method was called. """ @@ -701,7 +699,7 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: :return: The adjusted grasp pose """ lt = LocalTransformer() - pose_in_object = lt.transform_pose(pose, self.bullet_world_object.tf_frame) + pose_in_object = lt.transform_pose(pose, self.world_object.tf_frame) special_knowledge = [] # Initialize as an empty list if self.obj_type in SPECIAL_KNOWLEDGE: @@ -751,7 +749,7 @@ def __init__(self, names: Optional[List[str]] = None, types: Optional[List[str]] def ground(self) -> Union[Object, bool]: """ - Return the first object from the bullet world that fits the description. + Return the first object from the world that fits the description. :return: A resolved object designator """ @@ -763,8 +761,8 @@ def __iter__(self) -> Iterable[Object]: :yield: A resolved object designator """ - # for every bullet world object - for obj in BulletWorld.current_world.objects: + # for every world object + for obj in World.current_world.objects: # skip if name does not match specification if self.names and obj.name not in self.names: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 91d5fff85..142b21bdf 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -1,7 +1,5 @@ -import dataclasses import itertools -import time -from typing import List, Optional, Any, Tuple, Union +from typing import Any, Union import sqlalchemy.orm @@ -12,18 +10,18 @@ from ..orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, PickUpAction as ORMPickUpAction, PlaceAction as ORMPlaceAction, MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, - Action as ORMAction, LookAtAction as ORMLookAtAction, + LookAtAction as ORMLookAtAction, DetectAction as ORMDetectAction, TransportAction as ORMTransportAction, OpenAction as ORMOpenAction, CloseAction as ORMCloseAction, GraspingAction as ORMGraspingAction) -from ..orm.base import Quaternion, Position, Base, RobotState, ProcessMetaData +from ..orm.base import Base from ..plan_failures import ObjectUnfetchable, ReachabilityFailure from ..robot_descriptions import robot_description from ..task import with_tree from ..enums import Arms from ..designator import ActionDesignatorDescription -from ..bullet_world import BulletWorld +from ..world import World from ..pose import Pose from ..helper import multiply_quaternions @@ -295,16 +293,16 @@ class Action(ActionDesignatorDescription.Action): object_at_execution: Optional[ObjectDesignatorDescription.Object] = dataclasses.field(init=False) """ The object at the time this Action got created. It is used to be a static, information holding entity. It is - not updated when the BulletWorld object is changed. + not updated when the World object is changed. """ @with_tree def perform(self) -> None: # Store the object's data copy at execution self.object_at_execution = self.object_designator.data_copy() - robot = BulletWorld.robot + robot = World.robot # Retrieve object and robot from designators - object = self.object_designator.bullet_world_object + object = self.object_designator.world_object # Get grasp orientation and target pose grasp = robot_description.grasps.get_orientation_for_grasp(self.grasp) # oTm = Object Pose in Frame map @@ -337,7 +335,7 @@ def perform(self) -> None: gripper_rotate_pose = object.local_transformer.transform_pose(tmp_for_rotate_pose, "map") #Perform Gripper Rotate - # BulletWorld.current_bullet_world.add_vis_axis(gripper_rotate_pose) + # World.current_world.add_vis_axis(gripper_rotate_pose) # MoveTCPMotion(gripper_rotate_pose, self.arm).resolve().perform() oTg = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) @@ -345,12 +343,12 @@ def perform(self) -> None: prepose = object.local_transformer.transform_pose(oTg, "map") # Perform the motion with the prepose and open gripper - BulletWorld.current_world.add_vis_axis(prepose) + World.current_world.add_vis_axis(prepose) MoveTCPMotion(prepose, self.arm).resolve().perform() MoveGripperMotion(motion="open", gripper=self.arm).resolve().perform() # Perform the motion with the adjusted pose -> actual grasp and close gripper - BulletWorld.current_world.add_vis_axis(adjusted_oTm) + World.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() adjusted_oTm.pose.position.z += 0.03 MoveGripperMotion(motion="close", gripper=self.arm).resolve().perform() @@ -358,11 +356,11 @@ def perform(self) -> None: robot.attach(object, tool_frame) # Lift object - BulletWorld.current_world.add_vis_axis(adjusted_oTm) + World.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm).resolve().perform() # Remove the vis axis from the world - BulletWorld.current_world.remove_vis_axis() + World.current_world.remove_vis_axis() def to_sql(self) -> ORMPickUpAction: return ORMPickUpAction(self.arm, self.grasp) @@ -432,22 +430,22 @@ class Action(ActionDesignatorDescription.Action): @with_tree def perform(self) -> None: - object_pose = self.object_designator.bullet_world_object.get_pose() + object_pose = self.object_designator.world_object.get_pose() local_tf = LocalTransformer() # Transformations such that the target position is the position of the object and not the tcp tool_name = robot_description.get_tool_frame(self.arm) tcp_to_object = local_tf.transform_pose(object_pose, - BulletWorld.robot.links[tool_name].tf_frame) + World.robot.links[tool_name].tf_frame) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() MoveTCPMotion(target_diff, self.arm).resolve().perform() MoveGripperMotion("open", self.arm).resolve().perform() - BulletWorld.robot.detach(self.object_designator.bullet_world_object) + World.robot.detach(self.object_designator.world_object) retract_pose = local_tf.transform_pose( target_diff, - BulletWorld.robot.links[robot_description.get_tool_frame(self.arm)].tf_frame) + World.robot.links[robot_description.get_tool_frame(self.arm)].tf_frame) retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).resolve().perform() @@ -884,12 +882,12 @@ def perform(self) -> Any: if isinstance(self.object_desig, ObjectPart.Object): object_pose = self.object_desig.part_pose else: - object_pose = self.object_desig.bullet_world_object.get_pose() + object_pose = self.object_desig.world_object.get_pose() lt = LocalTransformer() gripper_name = robot_description.get_tool_frame(self.arm) object_pose_in_gripper = lt.transform_pose(object_pose, - BulletWorld.robot.links[gripper_name].tf_frame) + World.robot.links[gripper_name].tf_frame) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index d726f8957..8e55b147f 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -1,17 +1,14 @@ import dataclasses -import time -from typing import List, Tuple, Union, Iterable, Optional, Callable +from typing import List, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..world import Object, UseProspectionWorld -from ..bullet_world import BulletWorld +from ..world import World, UseProspectionWorld from ..world_reasoning import link_pose_for_joint_config -from ..designator import Designator, DesignatorError, LocationDesignatorDescription +from ..designator import DesignatorError, LocationDesignatorDescription from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap from ..robot_descriptions import robot_description from ..enums import JointType from ..helper import transform -from ..plan_failures import EnvironmentManipulationImpossible from ..pose_generator_and_validator import pose_generator, visibility_validator, reachability_validator, \ generate_orientation from ..robot_description import ManipulatorDescription @@ -161,7 +158,7 @@ def __iter__(self): max_height = list(robot_description.cameras.values())[0].max_height # This ensures that the costmaps always get a position as their origin. if isinstance(self.target, ObjectDesignatorDescription.Object): - target_pose = self.target.bullet_world_object.get_pose() + target_pose = self.target.world_object.get_pose() else: target_pose = self.target.copy() @@ -180,8 +177,8 @@ def __iter__(self): final_map += visible if self.visible_for or self.reachable_for: - robot_object = self.visible_for.bullet_world_object if self.visible_for else self.reachable_for.bullet_world_object - test_robot = BulletWorld.current_world.get_prospection_object_from_object(robot_object) + robot_object = self.visible_for.world_object if self.visible_for else self.reachable_for.world_object + test_robot = World.current_world.get_prospection_object_from_object(robot_object) with UseProspectionWorld(): @@ -190,7 +187,7 @@ def __iter__(self): arms = None if self.visible_for: res = res and visibility_validator(maybe_pose, test_robot, target_pose, - BulletWorld.current_world) + World.current_world) if self.reachable_for: hand_links = [] for name, chain in robot_description.chains.items(): @@ -230,7 +227,7 @@ def __init__(self, handle_desig: ObjectPart.Object, robot_desig: ObjectDesignato """ super().__init__(resolver) self.handle: ObjectPart.Object = handle_desig - self.robot: ObjectDesignatorDescription.Object = robot_desig.bullet_world_object + self.robot: ObjectDesignatorDescription.Object = robot_desig.world_object def ground(self) -> Location: """ @@ -257,23 +254,23 @@ def __iter__(self) -> Location: final_map = occupancy + gaussian - test_robot = BulletWorld.current_world.get_prospection_object_from_object(self.robot) + test_robot = World.current_world.get_prospection_object_from_object(self.robot) # Find a Joint of type prismatic which is above the handle in the URDF tree - container_joint = self.handle.bullet_world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) + container_joint = self.handle.world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) - init_pose = link_pose_for_joint_config(self.handle.bullet_world_object, { - container_joint: self.handle.bullet_world_object.get_joint_limits(container_joint)[0]}, + init_pose = link_pose_for_joint_config(self.handle.world_object, { + container_joint: self.handle.world_object.get_joint_limits(container_joint)[0]}, self.handle.name) # Calculate the pose the handle would be in if the drawer was to be fully opened - goal_pose = link_pose_for_joint_config(self.handle.bullet_world_object, { - container_joint: self.handle.bullet_world_object.get_joint_limits(container_joint)[1] - 0.05}, + goal_pose = link_pose_for_joint_config(self.handle.world_object, { + container_joint: self.handle.world_object.get_joint_limits(container_joint)[1] - 0.05}, self.handle.name) # Handle position for calculating rotation of the final pose - half_pose = link_pose_for_joint_config(self.handle.bullet_world_object, { - container_joint: self.handle.bullet_world_object.get_joint_limits(container_joint)[1] / 1.5}, + half_pose = link_pose_for_joint_config(self.handle.world_object, { + container_joint: self.handle.world_object.get_joint_limits(container_joint)[1] / 1.5}, self.handle.name) with UseProspectionWorld(): @@ -336,10 +333,10 @@ def __iter__(self): :yield: An instance of SemanticCostmapLocation.Location with the found valid position of the Costmap. """ - sem_costmap = SemanticCostmap(self.part_of.bullet_world_object, self.urdf_link_name) + sem_costmap = SemanticCostmap(self.part_of.world_object, self.urdf_link_name) height_offset = 0 if self.for_object: - min_p, max_p = self.for_object.bullet_world_object.get_aabb().get_min_max_points() + min_p, max_p = self.for_object.world_object.get_aabb().get_min_max_points() height_offset = (max_p.z - min_p.z) / 2 for maybe_pose in pose_generator(sem_costmap): maybe_pose.position.z += height_offset diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index c602227c2..247f1d508 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -291,7 +291,7 @@ def __init__(self, target: Optional[Pose] = None, object: Optional[ObjectDesigna super().__init__(resolver) self.cmd: str = 'looking' self.target: Optional[Pose] = target - self.object: Object = object.bullet_world_object if object else object + self.object: Object = object.world_object if object else object def ground(self) -> Motion: """ diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 7ba1491b3..d7d28507a 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,9 +1,8 @@ import dataclasses -from typing import List, Union, Optional, Callable, Tuple, Iterable +from typing import List, Optional, Callable import sqlalchemy.orm -from ..bullet_world import BulletWorld -from pycram.world import Object as BulletWorldObject -from ..designator import DesignatorDescription, ObjectDesignatorDescription +from pycram.world import World, Object as WorldObject +from ..designator import ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) from ..pose import Pose @@ -95,9 +94,9 @@ def __iter__(self): :yield: A resolved Object designator """ for name in self.names: - if name in self.part_of.bullet_world_object.link_name_to_id.keys(): - yield self.Object(name, self.type, self.part_of.bullet_world_object, - self.part_of.bullet_world_object.links[name].pose) + if name in self.part_of.world_object.link_name_to_id.keys(): + yield self.Object(name, self.type, self.part_of.world_object, + self.part_of.world_object.links[name].pose) class LocatedObject(ObjectDesignatorDescription): @@ -137,7 +136,7 @@ class RealObject(ObjectDesignatorDescription): """ Object designator representing an object in the real world, when resolving this object designator description ] RoboKudo is queried to perceive an object fitting the given criteria. Afterward the resolver tries to match - the found object to an Object in the BulletWorld. + the found object to an Object in the World. """ @dataclasses.dataclass @@ -148,28 +147,28 @@ class Object(ObjectDesignatorDescription.Object): """ def __init__(self, names: Optional[List[str]] = None, types: Optional[List[str]] = None, - bullet_world_object: BulletWorldObject = None, resolver: Optional[Callable] = None): + world_object: WorldObject = None, resolver: Optional[Callable] = None): """ :param names: :param types: - :param bullet_world_object: + :param world_object: :param resolver: """ super().__init__(resolver) self.types: Optional[List[str]] = types self.names: Optional[List[str]] = names - self.bullet_world_object: BulletWorldObject = bullet_world_object + self.world_object: WorldObject = world_object def __iter__(self): """ - Queries RoboKudo for objects that fit the description and then iterates over all BulletWorld objects that have - the same type to match a BulletWorld object to the real object. + Queries RoboKudo for objects that fit the description and then iterates over all World objects that have + the same type to match a World object to the real object. - :yield: A resolved object designator with reference bullet world object + :yield: A resolved object designator with reference world object """ object_candidates = query(self) for obj_desig in object_candidates: - for bullet_obj in BulletWorld.get_objects_by_type(obj_desig.obj_type): - obj_desig.bullet_world_object = bullet_obj + for world_obj in World.get_objects_by_type(obj_desig.obj_type): + obj_desig.world_object = world_obj yield obj_desig diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 2aa5797af..131d87124 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -1,10 +1,8 @@ import tf import numpy as np -import rospy -import pybullet as p from .world import Object -from .bullet_world import BulletWorld +from .bullet_world import World from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform @@ -12,7 +10,7 @@ from .external_interfaces.ik import request_ik from .plan_failures import IKError from .helper import _apply_ik -from typing import Type, Tuple, List, Union, Dict, Iterable +from typing import Tuple, List, Union, Dict, Iterable def pose_generator(costmap: Costmap, number_of_samples=100, orientation_generator=None) -> Iterable: @@ -79,11 +77,11 @@ def generate_orientation(position: List[float], origin: Pose) -> List[float]: def visibility_validator(pose: Pose, robot: Object, object_or_pose: Union[Object, Pose], - world: BulletWorld) -> bool: + world: World) -> bool: """ This method validates if the robot can see the target position from a given pose candidate. The target position can either be a position, in world coordinate - system, or an object in the BulletWorld. The validation is done by shooting a + system, or an object in the World. The validation is done by shooting a ray from the camera to the target position and checking that it does not collide with anything else. @@ -91,23 +89,23 @@ def visibility_validator(pose: Pose, :param robot: The robot object for which this should be validated :param object_or_pose: The target position or object for which the pose candidate should be validated. - :param world: The BulletWorld instance in which this should be validated. + :param world: The World instance in which this should be validated. :return: True if the target is visible for the robot, None in any other case. """ robot_pose = robot.get_pose() - if type(object_or_pose) == Object: + if isinstance(object_or_pose, Object): robot.set_pose(pose) camera_pose = robot.links[robot_description.get_camera_frame()].pose robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - ray = p.rayTest(camera_pose.position_as_list(), object_or_pose.get_pose().position_as_list(), - physicsClientId=world.client_id) - res = ray[0][0] == object_or_pose.id + ray = world.ray_test(camera_pose.position_as_list(), object_or_pose.get_position_as_list()) + res = ray == object_or_pose.id else: robot.set_pose(pose) camera_pose = robot.links[robot_description.get_camera_frame()].pose robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) - ray = p.rayTest(camera_pose.position_as_list(), object_or_pose, physicsClientId=world.client_id) - res = ray[0][0] == -1 + # TODO: Check if this is correct + ray = world.ray_test(camera_pose.position_as_list(), object_or_pose) + res = ray == -1 robot.set_pose(robot_pose) return res @@ -123,7 +121,7 @@ def reachability_validator(pose: Pose, the validator returns True and False in any other case. :param pose: The pose candidate for which the reachability should be validated - :param robot: The robot object in the BulletWorld for which the reachability + :param robot: The robot object in the World for which the reachability should be validated. :param target: The target position or object instance which should be the target for reachability. @@ -158,7 +156,7 @@ def reachability_validator(pose: Pose, resp = request_ik(target, robot, left_joints, left_gripper) _apply_ik(robot, resp, left_joints) - for obj in BulletWorld.current_world.objects: + for obj in World.current_world.objects: if obj.name == "floor": continue in_contact, contact_links = contact(robot, obj, return_links=True) @@ -182,7 +180,7 @@ def reachability_validator(pose: Pose, resp = request_ik(target, robot, right_joints, right_gripper) _apply_ik(robot, resp, right_joints) - for obj in BulletWorld.current_world.objects: + for obj in World.current_world.objects: if obj.name == "floor": continue in_contact, contact_links = contact(robot, obj, return_links=True) diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index e0173e0bc..a8185b760 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -59,7 +59,7 @@ class BoxyPickUp(ProcessModule): """ def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.bullet_world_object + object = desig.object_desig.world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) target = object.get_pose() @@ -86,7 +86,7 @@ def _execute(self, desig: PlaceMotion.Motion): :param desig: A PlaceMotion :return: """ - object = desig.object.bullet_world_object + object = desig.object.world_object robot = BulletWorld.robot arm = desig.arm @@ -107,7 +107,7 @@ class BoxyOpen(ProcessModule): """ def _execute(self, desig: OpeningMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -116,8 +116,8 @@ def _execute(self, desig: OpeningMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( container_joint)[1]) @@ -126,7 +126,7 @@ class BoxyClose(ProcessModule): Low-level implementation that lets the robot close a grasped container, in simulation """ def _execute(self, desig: ClosingMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -135,8 +135,8 @@ def _execute(self, desig: ClosingMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( container_joint)[0]) diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 390558bd9..84567c3b9 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -30,7 +30,7 @@ class DefaultPickUp(ProcessModule): """ def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.bullet_world_object + object = desig.object_desig.world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) target = object.get_pose() @@ -57,7 +57,7 @@ def _execute(self, desig: PlaceMotion.Motion): :param desig: A PlaceMotion :return: """ - object = desig.object.bullet_world_object + object = desig.object.world_object robot = BulletWorld.robot arm = desig.arm @@ -181,7 +181,7 @@ class DefaultOpen(ProcessModule): """ def _execute(self, desig: OpeningMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -190,8 +190,8 @@ def _execute(self, desig: OpeningMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( container_joint)[1]) @@ -200,7 +200,7 @@ class DefaultClose(ProcessModule): Low-level implementation that lets the robot close a grasped container, in simulation """ def _execute(self, desig: ClosingMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -209,8 +209,8 @@ def _execute(self, desig: ClosingMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( container_joint)[0]) diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 12bad2cf3..45cf31899 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -45,7 +45,7 @@ class DonbotPickUp(ProcessModule): """ def _execute(self, desig): - object = desig.object_desig.bullet_world_object + object = desig.object_desig.world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) target = object.get_pose() @@ -65,7 +65,7 @@ class DonbotPlace(ProcessModule): """ def _execute(self, desig): - object = desig.object.bullet_world_object + object = desig.object.world_object robot = BulletWorld.robot # Transformations such that the target position is the position of the object and not the tcp diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 02ca0edcf..5bd04c89e 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -1,8 +1,10 @@ from threading import Lock +from typing import Optional from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld +from ..world import World +from ..pose import Pose, Point from ..helper import _apply_ik import pycram.world_reasoning as btr import pybullet as p @@ -10,14 +12,26 @@ import time +def calculate_and_apply_ik(robot, gripper: str, target_position: Point, max_iterations: Optional[int] = None): + """ + Calculates the inverse kinematics for the given target pose and applies it to the robot. + """ + inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), target_position, + maxNumIterations=max_iterations) + # TODO: Check if this is correct (getting the arm and using its joints), previously joints was not provided. + arm = "right" if gripper == robot_description.get_tool_frame("right") else "left" + joints = robot_description.chains[arm].joints + _apply_ik(robot, inv, joints) + + def _park_arms(arm): """ Defines the joint poses for the parking positions of the arm of HSR and applies them to the - in the BulletWorld defined robot. + in the World defined robot. :return: None """ - robot = BulletWorld.robot + robot = World.robot if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): robot.set_joint_position(joint, pose) @@ -31,8 +45,8 @@ class HSRNavigation(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == 'navigate': - robot = BulletWorld.robot - robot.set_position_and_orientation(solution['target'], solution['orientation']) + robot = World.robot + robot.set_pose(Pose(solution['target'], solution['orientation'])) class HSRPickUp(ProcessModule): @@ -44,13 +58,13 @@ class HSRPickUp(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == 'pick': - object = solution['object'] - robot = BulletWorld.robot - target = object.get_position() - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(solution['gripper']), target, - maxNumIterations=100) - _apply_ik(robot, inv) - robot.attach(object, solution['gripper']) + obj = solution['object'] + robot = World.robot + target = obj.get_position() + + calculate_and_apply_ik(robot, solution['gripper'], target, 100) + + robot.attach(obj, solution['gripper']) time.sleep(0.5) @@ -62,12 +76,10 @@ class HSRPlace(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == 'place': - object = solution['object'] - robot = BulletWorld.robot - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(solution['gripper']), solution['target'], - maxNumIterations=100) - _apply_ik(robot, inv) - robot.detach(object) + obj = solution['object'] + robot = World.robot + calculate_and_apply_ik(robot, solution['gripper'], solution['target'], 100) + robot.detach(obj) time.sleep(0.5) @@ -83,19 +95,16 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == 'access': kitchen = solution['part_of'] - robot = BulletWorld.robot + robot = World.robot gripper = solution['gripper'] drawer_handle = solution['drawer_handle'] drawer_joint = solution['drawer_joint'] dis = solution['distance'] - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), - kitchen.links[drawer_handle].position) - _apply_ik(robot, inv) + calculate_and_apply_ik(robot, gripper, kitchen.links[drawer_handle].position) time.sleep(0.2) han_pose = kitchen.links[drawer_handle].position - new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) - _apply_ik(robot, inv) + new_p = Point(han_pose[0] - dis, han_pose[1], han_pose[2]) + calculate_and_apply_ik(robot, gripper, new_p) kitchen.set_joint_position(drawer_joint, 0.3) time.sleep(0.5) @@ -123,7 +132,7 @@ def _execute(self, desig): if solutions['cmd'] == 'looking': target = solutions['target'] if target == 'forward' or target == 'down': - robot = BulletWorld.robot + robot = World.robot for joint, state in robot_description.get_static_joint_chain("neck", target).items(): robot.set_joint_position(joint, state) else: @@ -139,7 +148,7 @@ class HSRMoveGripper(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "move-gripper": - robot = BulletWorld.robot + robot = World.robot gripper = solution['gripper'] motion = solution['motion'] for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): @@ -156,12 +165,12 @@ class HSRDetecting(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "detecting": - robot = BulletWorld.robot + robot = World.robot object_type = solution['object_type'] cam_frame_name = solution['cam_frame'] front_facing_axis = solution['front_facing_axis'] - objects = BulletWorld.current_world.get_objects_by_type(object_type) + objects = World.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): return obj @@ -177,9 +186,8 @@ def _execute(self, desig): if solution['cmd'] == "move-tcp": target = solution['target'] gripper = solution['gripper'] - robot = BulletWorld.robot - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), target) - _apply_ik(robot, inv) + robot = World.robot + calculate_and_apply_ik(robot, gripper, target) time.sleep(0.5) @@ -192,7 +200,7 @@ class HSRMoveJoints(ProcessModule): def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "move-arm-joints": - robot = BulletWorld.robot + robot = World.robot left_arm_poses = solution['left_arm_poses'] if type(left_arm_poses) == dict: @@ -213,7 +221,7 @@ def _execute(self, desig): solution = desig.reference() if solution['cmd'] == "world-state-detecting": obj_type = solution['object_type'] - return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, World.current_world.objects))[0] class HSRManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 5f432560b..88b5a1b6d 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -56,7 +56,7 @@ class Pr2PickUp(ProcessModule): """ def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.bullet_world_object + object = desig.object_desig.world_object robot = BulletWorld.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) target = object.get_pose() @@ -83,7 +83,7 @@ def _execute(self, desig: PlaceMotion.Motion): :param desig: A PlaceMotion :return: """ - object = desig.object.bullet_world_object + object = desig.object.world_object robot = BulletWorld.robot arm = desig.arm @@ -208,7 +208,7 @@ class Pr2Open(ProcessModule): """ def _execute(self, desig: OpeningMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -217,8 +217,8 @@ def _execute(self, desig: OpeningMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_position(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_position(container_joint, + part_of_object.get_joint_limits( container_joint)[1]) @@ -228,7 +228,7 @@ class Pr2Close(ProcessModule): """ def _execute(self, desig: ClosingMotion.Motion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) @@ -237,8 +237,8 @@ def _execute(self, desig: ClosingMotion.Motion): _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_position(container_joint, - part_of_object.get_joint_limits( + desig.object_part.world_object.set_joint_position(container_joint, + part_of_object.get_joint_limits( container_joint)[0]) diff --git a/src/pycram/world.py b/src/pycram/world.py index 4113dd1cb..4f8222036 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -45,8 +45,8 @@ class World(ABC): current_world: World = None """ Global reference to the currently used World, usually this is the - graphical one. However, if you are inside a Use_shadow_world() environment the current_world points to the - shadow world. In this way you can comfortably use the current_world, which should point towards the World + graphical one. However, if you are inside a UseProspectionWorld() environment the current_world points to the + prospection world. In this way you can comfortably use the current_world, which should point towards the World used at the moment. """ @@ -533,7 +533,7 @@ def get_manipulation_event(self) -> Event: @abstractmethod def set_realtime(self, real_time: bool) -> None: """ - Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only + Enables the real time simulation of Physics in the World. By default, this is disabled and Physics is only simulated to reason about it. :param real_time: Whether the World should simulate Physics in real time. @@ -579,7 +579,7 @@ def robot_is_set() -> bool: def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: """ - Closes the World as well as the shadow world, also collects any other thread that is running. + Closes the World as well as the prospection world, also collects any other thread that is running. """ if wait_time_before_exit_in_secs is not None: time.sleep(wait_time_before_exit_in_secs) @@ -727,7 +727,7 @@ def register_two_objects_collision_callbacks(self, @classmethod def add_resource_path(cls, path: str) -> None: """ - Adds a resource path in which the BulletWorld will search for files. This resource directory is searched if an + Adds a resource path in which the World will search for files. This resource directory is searched if an Object is spawned only with a filename. :param path: A path in the filesystem in which to search for files. @@ -767,7 +767,7 @@ def get_object_from_prospection_object(self, prospection_object: Object) -> Obje try: return list(object_map.keys())[list(object_map.values()).index(prospection_object)] except ValueError: - raise ValueError("The given object is not in the shadow world.") + raise ValueError("The given object is not in the prospection world.") def reset_world(self, remove_saved_states=True) -> None: """ @@ -796,6 +796,30 @@ def update_transforms_for_objects_in_current_world(self) -> None: for obj in list(self.current_world.objects): obj.update_link_transforms(curr_time) + @abstractmethod + def ray_test(self, from_position: List[float], to_position: List[float]) -> int: + """ Cast a ray and return the first object hit, if any. + + param from_position: The starting position of the ray in Cartesian world coordinates. + param to_position: The ending position of the ray in Cartesian world coordinates. + return: The object id of the first object hit, or -1 if no object was hit. + """ + pass + + @abstractmethod + def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[List[float]], + num_threads: int = 1) -> List[int]: + """ Cast a batch of rays and return the result for each of the rays (first object hit, if any. or -1) + Takes optional argument num_threads to specify the number of threads to use + to compute the ray intersections for the batch. Specify 0 to let simulator decide, 1 (default) for single + core execution, 2 or more to select the number of threads to use. + + param from_positions: The starting positions of the rays in Cartesian world coordinates. + param to_positions: The ending positions of the rays in Cartesian world coordinates. + param num_threads: The number of threads to use to compute the ray intersections for the batch. + """ + pass + def create_visual_shape(self, visual_shape: VisualShape) -> int: raise NotImplementedError @@ -871,7 +895,7 @@ def __init__(self, world: World, prospection_world: World): self.add_obj_queue: Queue = Queue() self.remove_obj_queue: Queue = Queue() self.pause_sync: bool = False - # Maps bullet to prospection world objects + # Maps world to prospection world objects self.object_mapping: Dict[Object, Object] = {} self.equal_states = False @@ -1239,7 +1263,7 @@ def attach(self, saving the transformation between the given link, if there is one, and the base pose of the other object. Additionally, the name of the link, to which the object is attached, will be saved. - Furthermore, a constraint of pybullet will be created so the attachment + Furthermore, a simulator constraint will be created so the attachment also works while simulation. Loose attachments means that the attachment will only be one-directional. For example, if this object moves the other, attached, object will also move but not the other way around. @@ -1263,7 +1287,7 @@ def detach(self, child_object: Object) -> None: """ Detaches another object from this object. This is done by deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of pybullet. + and deleting the constraint of the simulator. Afterward the detachment event of the corresponding World will be fired. :param child_object: The object which should be detached @@ -1462,7 +1486,7 @@ def _get_link_name_to_id_map(self) -> Dict[str, int]: def get_joint_id(self, name: str) -> int: """ - Returns the unique id for a joint name. As used by PyBullet. + Returns the unique id for a joint name. As used by the world/simulator. :param name: The joint name :return: The unique id @@ -1502,9 +1526,9 @@ def get_link_by_id(self, link_id: int) -> Link: def get_joint_by_id(self, joint_id: int) -> str: """ - Returns the joint name for a unique PyBullet id + Returns the joint name for a unique world id - :param joint_id: The Pybullet id of for joint + :param joint_id: The world id of for joint :return: The joint name """ return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] @@ -1564,8 +1588,7 @@ def get_joint_position(self, joint_name: str) -> float: def contact_points(self) -> List: """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ + Returns a list of contact points of this Object with other Objects. :return: A list of all contact points with other objects """ @@ -1574,8 +1597,6 @@ def contact_points(self) -> List: def contact_points_simulated(self) -> List: """ Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ :return: A list of contact points between this Object and other Objects """ @@ -1935,8 +1956,8 @@ def _is_cached(path: str, name: str, cach_dir: str) -> bool: def _correct_urdf_string(urdf_string: str) -> str: """ - Changes paths for files in the URDF from ROS paths to paths in the file system. Since PyBullet can't deal with ROS - package paths. + Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legac) + can't deal with ROS package paths. :param urdf_string: The name of the URDf on the parameter server :return: The URDF string with paths in the filesystem instead of ROS packages @@ -1957,7 +1978,7 @@ def _correct_urdf_string(urdf_string: str) -> str: def fix_missing_inertial(urdf_string: str) -> str: """ Insert inertial tags for every URDF link that has no inertia. - This is used to prevent PyBullet from dumping warnings in the terminal + This is used to prevent Legacy(PyBullet) from dumping warnings in the terminal :param urdf_string: The URDF description as string :returns: The new, corrected URDF description as string. diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 8c22c7fa9..5c4e20c9e 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -174,15 +174,13 @@ class SphereShapeData(ShapeData): @dataclass -class CapsuleShapeData(ShapeData): - radius: float +class CapsuleShapeData(SphereShapeData): length: float @dataclass -class CylinderShapeData(ShapeData): - radius: float - length: float +class CylinderShapeData(CapsuleShapeData): + pass @dataclass @@ -201,6 +199,7 @@ class VisualShape: rgba_color: Color visual_frame_position: List[float] shape_data: ShapeData + visual_geometry_type: Shape @dataclass @@ -216,14 +215,13 @@ class SphereVisualShape(VisualShape): @dataclass -class CapsuleVisualShape(VisualShape): +class CapsuleVisualShape(SphereVisualShape): shape_data: CapsuleShapeData visual_geometry_type = Shape.CAPSULE @dataclass -class CylinderVisualShape(VisualShape): - shape_data: CylinderShapeData +class CylinderVisualShape(CapsuleVisualShape): visual_geometry_type = Shape.CYLINDER diff --git a/test/test_action_designator.py b/test/test_action_designator.py index b0bc2f62b..d6867b6f5 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -64,7 +64,7 @@ def test_pick_up(self): action_designator.NavigateAction.Action(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() action_designator.MoveTorsoAction.Action(0.3).perform() description.resolve().perform() - self.assertTrue(object_description.resolve().bullet_world_object in self.robot.attachments.keys()) + self.assertTrue(object_description.resolve().world_object in self.robot.attachments.keys()) def test_place(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) @@ -75,7 +75,7 @@ def test_place(self): action_designator.MoveTorsoAction.Action(0.3).perform() action_designator.PickUpAction.Action(object_description.resolve(), "left", "front").perform() description.resolve().perform() - self.assertFalse(object_description.resolve().bullet_world_object in self.robot.attachments.keys()) + self.assertFalse(object_description.resolve().world_object in self.robot.attachments.keys()) def test_look_at(self): description = action_designator.LookAtAction([Pose([1, 0, 1])]) @@ -94,7 +94,7 @@ def test_detect(self): detected_object = description.resolve().perform() self.assertEqual(detected_object.name, "milk") self.assertEqual(detected_object.obj_type, ObjectType.MILK) - self.assertEqual(detected_object.bullet_world_object, self.milk) + self.assertEqual(detected_object.world_object, self.milk) # Skipped since open and close work only in the apartment at the moment @unittest.skip From 6c4e42cb6a4817001c22490f4f61de9b29713a6d Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Jan 2024 14:41:58 +0100 Subject: [PATCH 056/195] [Abstract World] Corrected setting position of object to allow lists. --- src/pycram/world.py | 8 +++++--- test/test_object.py | 4 ++++ 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 4f8222036..c1c41b206 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1443,11 +1443,13 @@ def set_position(self, position: Union[Pose, Point], base=False) -> None: pose.frame = position.frame elif isinstance(position, Point): target_position = position + elif isinstance(position, list): + target_position = position else: - raise TypeError("The position has to be either a Pose or a Point") + raise TypeError("The given position has to be a Pose, Point or a list of xyz.") - pose.pose.position = target_position - pose.pose.orientation = self.get_orientation() + pose.position = target_position + pose.orientation = self.get_orientation() self.set_pose(pose, base=base) def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: diff --git a/test/test_object.py b/test/test_object.py index 254495c5f..43100b8ce 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -17,6 +17,10 @@ def test_set_position_as_pose(self): self.milk.set_position(Pose([1, 2, 3])) self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + def test_set_position_as_list(self): + self.milk.set_position([1, 2, 3]) + self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + def test_save_state(self): self.robot.attach(self.milk) self.robot.save_state(1) From 11fbdc443a5f08f8fc83c2c08479b921db42de20 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Jan 2024 15:59:45 +0100 Subject: [PATCH 057/195] [Abstract World] Corrected setting position of object to allow lists and points. --- src/pycram/pose.py | 3 ++- test/test_bullet_world.py | 1 - test/test_object.py | 6 +----- 3 files changed, 3 insertions(+), 7 deletions(-) diff --git a/src/pycram/pose.py b/src/pycram/pose.py index cd30c2d4b..3a6cf54bc 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -100,7 +100,8 @@ def position(self, value) -> None: :param value: List or geometry_msgs/Pose message for the position """ - if not type(value) == list and not type(value) == tuple and not type(value) == GeoPose: + if (not type(value) == list and not type(value) == tuple and not type(value) == GeoPose + and not type(value) == Point): print(type(value)) rospy.logwarn("Position can only be a list or geometry_msgs/Pose") return diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index f60e42a79..881412e1c 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -20,7 +20,6 @@ def test_object_movement(self): def test_robot_orientation(self): self.robot.set_pose(Pose([0, 1, 1])) head_position = self.robot.links['head_pan_link'].position.z - #self.robot.set_orientation(list(2*tf.transformations.quaternion_from_euler(0, 0, np.pi, axes="sxyz"))) self.robot.set_orientation(Pose(orientation=[0, 0, 1, 1])) self.assertEqual(self.robot.links['head_pan_link'].position.z, head_position) diff --git a/test/test_object.py b/test/test_object.py index 43100b8ce..ece06cc46 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -6,11 +6,7 @@ class TestObject(test_bullet_world.BulletWorldTest): def test_set_position_as_point(self): - p = Point() - p.x = 1 - p.y = 2 - p.z = 3 - self.milk.set_position(p) + self.milk.set_position(Point(1, 2, 3)) self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) def test_set_position_as_pose(self): From f139b2a994a8ac2c2225b90effe7f852b6d34f8f Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Jan 2024 16:17:48 +0100 Subject: [PATCH 058/195] [Abstract World] updated method names in bullet_world.ipynb --- doc/source/notebooks/bullet_world.ipynb | 178 ++++++++++++++++-------- 1 file changed, 119 insertions(+), 59 deletions(-) diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index 39a9e1d8f..a2ce21a1d 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -17,8 +17,8 @@ "id": "23bbba35", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:48.492859720Z", - "start_time": "2023-11-30T09:27:47.729848173Z" + "end_time": "2024-01-25T15:12:30.985683070Z", + "start_time": "2024-01-25T15:12:30.145357542Z" } }, "outputs": [ @@ -31,12 +31,47 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/action_designator.py:10: SAWarning: Implicitly combining column Designator.dtype with column Action.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", - " class Action(MapperArgsMixin, Designator):\n", - "/home/bassioun/cram_ws/src/pycram/src/pycram/orm/motion_designator.py:16: SAWarning: Implicitly combining column Designator.dtype with column Motion.dtype under attribute 'dtype'. Please configure one or more attributes for these same-named columns explicitly.\n", - " class Motion(MapperArgsMixin, Designator):\n", - "[WARN] [1701336468.169695]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1701336468.173591]: Failed to import Giskard messages\n" + "[WARN] [1706195550.581271]: Failed to import Giskard messages\n", + "[WARN] [1706195550.584688]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "Exception in thread Thread-11:\n", + "Traceback (most recent call last):\n", + " File \"/usr/lib/python3.8/threading.py\", line 932, in _bootstrap_inner\n", + " self.run()\n", + " File \"/home/bassioun/cram_ws/src/pycram/src/pycram/bullet_world.py\", line 527, in run\n", + " keys = p.getKeyboardEvents(physicalClientId=self.world.client_id)\n", + "TypeError: 'physicalClientId' is an invalid keyword argument for this function\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "argc=2\n", + "argv[0] = --unused\n", + "argv[1] = --start_demo_name=Physics Server\n", + "ExampleBrowserThreadFunc started\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "Creating context\n", + "Created GL 3.3 context\n", + "Direct GLX rendering context obtained\n", + "Making context current\n", + "GL_VENDOR=NVIDIA Corporation\n", + "GL_RENDERER=NVIDIA GeForce RTX 4070/PCIe/SSE2\n", + "GL_VERSION=3.3.0 NVIDIA 535.154.05\n", + "GL_SHADING_LANGUAGE_VERSION=3.30 NVIDIA via Cg compiler\n", + "pthread_getconcurrency()=0\n", + "Version = 3.3.0 NVIDIA 535.154.05\n", + "Vendor = NVIDIA Corporation\n", + "Renderer = NVIDIA GeForce RTX 4070/PCIe/SSE2\n", + "b3Printf: Selected demo: Physics Server\n", + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "MotionThreadFunc thread started\n" ] } ], @@ -73,12 +108,12 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 18, "id": "b1e6ed82", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T08:32:14.940359764Z", - "start_time": "2023-11-30T08:32:14.691411659Z" + "end_time": "2024-01-25T15:15:13.021035123Z", + "start_time": "2024-01-25T15:15:12.770510755Z" } }, "outputs": [], @@ -100,8 +135,8 @@ "id": "48a3aed2", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:52.209614939Z", - "start_time": "2023-11-30T09:27:52.159974972Z" + "end_time": "2024-01-25T15:12:45.684564926Z", + "start_time": "2024-01-25T15:12:45.625809554Z" } }, "outputs": [], @@ -135,8 +170,8 @@ "id": "4ae2bc42", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:57.498773893Z", - "start_time": "2023-11-30T09:27:57.497252820Z" + "end_time": "2024-01-25T15:12:49.219929668Z", + "start_time": "2024-01-25T15:12:49.218144234Z" } }, "outputs": [], @@ -150,8 +185,8 @@ "id": "4adc7b11", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:57.867485393Z", - "start_time": "2023-11-30T09:27:57.865626321Z" + "end_time": "2024-01-25T15:12:51.501613968Z", + "start_time": "2024-01-25T15:12:51.498849668Z" } }, "outputs": [], @@ -165,8 +200,8 @@ "id": "f91d1809", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:58.203719277Z", - "start_time": "2023-11-30T09:27:58.201735028Z" + "end_time": "2024-01-25T15:12:53.093477139Z", + "start_time": "2024-01-25T15:12:53.091079615Z" } }, "outputs": [], @@ -188,8 +223,8 @@ "id": "1db2aa78", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:27:59.859274393Z", - "start_time": "2023-11-30T09:27:59.856354972Z" + "end_time": "2024-01-25T15:12:55.623481479Z", + "start_time": "2024-01-25T15:12:55.617521322Z" } }, "outputs": [ @@ -210,8 +245,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1701336478\n", - " nsecs: 200602293\n", + " secs: 1706195573\n", + " nsecs: 89663267\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -251,8 +286,8 @@ "id": "10a493b1", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:02.809496385Z", - "start_time": "2023-11-30T09:28:02.808590814Z" + "end_time": "2024-01-25T15:13:00.617061159Z", + "start_time": "2024-01-25T15:13:00.545727421Z" } }, "outputs": [], @@ -266,8 +301,8 @@ "id": "275372e3", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:03.828259221Z", - "start_time": "2023-11-30T09:28:03.825819607Z" + "end_time": "2024-01-25T15:13:02.886236097Z", + "start_time": "2024-01-25T15:13:02.883330740Z" } }, "outputs": [], @@ -289,8 +324,8 @@ "id": "dff85834", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:05.435992616Z", - "start_time": "2023-11-30T09:28:05.433266300Z" + "end_time": "2024-01-25T15:13:05.361953697Z", + "start_time": "2024-01-25T15:13:05.354577792Z" } }, "outputs": [], @@ -312,11 +347,19 @@ "id": "b0bba145", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:06.817969292Z", - "start_time": "2023-11-30T09:28:06.815384873Z" + "end_time": "2024-01-25T15:13:08.363391145Z", + "start_time": "2024-01-25T15:13:08.361381235Z" } }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Removing constraint with id: 1\n" + ] + } + ], "source": [ "cereal.detach(milk)" ] @@ -338,8 +381,8 @@ "id": "edf5cb72", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:13.754327852Z", - "start_time": "2023-11-30T09:28:10.551209150Z" + "end_time": "2024-01-25T15:13:17.474926968Z", + "start_time": "2024-01-25T15:13:13.769261909Z" } }, "outputs": [ @@ -347,7 +390,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "{'base_link': 0, 'base_bellow_link': 1, 'base_laser_link': 2, 'fl_caster_rotation_link': 3, 'fl_caster_l_wheel_link': 4, 'fl_caster_r_wheel_link': 5, 'fr_caster_rotation_link': 6, 'fr_caster_l_wheel_link': 7, 'fr_caster_r_wheel_link': 8, 'bl_caster_rotation_link': 9, 'bl_caster_l_wheel_link': 10, 'bl_caster_r_wheel_link': 11, 'br_caster_rotation_link': 12, 'br_caster_l_wheel_link': 13, 'br_caster_r_wheel_link': 14, 'torso_lift_link': 15, 'l_torso_lift_side_plate_link': 16, 'r_torso_lift_side_plate_link': 17, 'imu_link': 18, 'head_pan_link': 19, 'head_tilt_link': 20, 'head_plate_frame': 21, 'sensor_mount_link': 22, 'high_def_frame': 23, 'high_def_optical_frame': 24, 'double_stereo_link': 25, 'wide_stereo_link': 26, 'wide_stereo_optical_frame': 27, 'wide_stereo_l_stereo_camera_frame': 28, 'wide_stereo_l_stereo_camera_optical_frame': 29, 'wide_stereo_r_stereo_camera_frame': 30, 'wide_stereo_r_stereo_camera_optical_frame': 31, 'narrow_stereo_link': 32, 'narrow_stereo_optical_frame': 33, 'narrow_stereo_l_stereo_camera_frame': 34, 'narrow_stereo_l_stereo_camera_optical_frame': 35, 'narrow_stereo_r_stereo_camera_frame': 36, 'narrow_stereo_r_stereo_camera_optical_frame': 37, 'projector_wg6802418_frame': 38, 'projector_wg6802418_child_frame': 39, 'laser_tilt_mount_link': 40, 'laser_tilt_link': 41, 'r_shoulder_pan_link': 42, 'r_shoulder_lift_link': 43, 'r_upper_arm_roll_link': 44, 'r_upper_arm_link': 45, 'r_elbow_flex_link': 46, 'r_forearm_roll_link': 47, 'r_forearm_link': 48, 'r_wrist_flex_link': 49, 'r_wrist_roll_link': 50, 'r_gripper_palm_link': 51, 'r_gripper_led_frame': 52, 'r_gripper_motor_accelerometer_link': 53, 'r_gripper_tool_frame': 54, 'r_gripper_motor_slider_link': 55, 'r_gripper_motor_screw_link': 56, 'r_gripper_l_finger_link': 57, 'r_gripper_l_finger_tip_link': 58, 'r_gripper_r_finger_link': 59, 'r_gripper_r_finger_tip_link': 60, 'r_gripper_l_finger_tip_frame': 61, 'r_forearm_cam_frame': 62, 'r_forearm_cam_optical_frame': 63, 'l_shoulder_pan_link': 64, 'l_shoulder_lift_link': 65, 'l_upper_arm_roll_link': 66, 'l_upper_arm_link': 67, 'l_elbow_flex_link': 68, 'l_forearm_roll_link': 69, 'l_forearm_link': 70, 'l_wrist_flex_link': 71, 'l_wrist_roll_link': 72, 'l_gripper_palm_link': 73, 'l_gripper_led_frame': 74, 'l_gripper_motor_accelerometer_link': 75, 'l_gripper_tool_frame': 76, 'l_gripper_motor_slider_link': 77, 'l_gripper_motor_screw_link': 78, 'l_gripper_l_finger_link': 79, 'l_gripper_l_finger_tip_link': 80, 'l_gripper_r_finger_link': 81, 'l_gripper_r_finger_tip_link': 82, 'l_gripper_l_finger_tip_frame': 83, 'l_forearm_cam_frame': 84, 'l_forearm_cam_optical_frame': 85, 'torso_lift_motor_screw_link': 86, 'base_footprint': -1}\n" + "{'base_link': , 'base_footprint': , 'base_bellow_link': , 'base_laser_link': , 'fl_caster_rotation_link': , 'fl_caster_l_wheel_link': , 'fl_caster_r_wheel_link': , 'fr_caster_rotation_link': , 'fr_caster_l_wheel_link': , 'fr_caster_r_wheel_link': , 'bl_caster_rotation_link': , 'bl_caster_l_wheel_link': , 'bl_caster_r_wheel_link': , 'br_caster_rotation_link': , 'br_caster_l_wheel_link': , 'br_caster_r_wheel_link': , 'torso_lift_link': , 'l_torso_lift_side_plate_link': , 'r_torso_lift_side_plate_link': , 'torso_lift_motor_screw_link': , 'imu_link': , 'head_pan_link': , 'head_tilt_link': , 'head_plate_frame': , 'sensor_mount_link': , 'high_def_frame': , 'high_def_optical_frame': , 'double_stereo_link': , 'wide_stereo_link': , 'wide_stereo_optical_frame': , 'wide_stereo_l_stereo_camera_frame': , 'wide_stereo_l_stereo_camera_optical_frame': , 'wide_stereo_r_stereo_camera_frame': , 'wide_stereo_r_stereo_camera_optical_frame': , 'narrow_stereo_link': , 'narrow_stereo_optical_frame': , 'narrow_stereo_l_stereo_camera_frame': , 'narrow_stereo_l_stereo_camera_optical_frame': , 'narrow_stereo_r_stereo_camera_frame': , 'narrow_stereo_r_stereo_camera_optical_frame': , 'projector_wg6802418_frame': , 'projector_wg6802418_child_frame': , 'laser_tilt_mount_link': , 'laser_tilt_link': , 'r_shoulder_pan_link': , 'r_shoulder_lift_link': , 'r_upper_arm_roll_link': , 'r_upper_arm_link': , 'r_forearm_roll_link': , 'r_elbow_flex_link': , 'r_forearm_link': , 'r_wrist_flex_link': , 'r_wrist_roll_link': , 'r_gripper_palm_link': , 'r_gripper_led_frame': , 'r_gripper_motor_accelerometer_link': , 'r_gripper_tool_frame': , 'r_gripper_motor_slider_link': , 'r_gripper_motor_screw_link': , 'r_gripper_l_finger_link': , 'r_gripper_r_finger_link': , 'r_gripper_l_finger_tip_link': , 'r_gripper_r_finger_tip_link': , 'r_gripper_l_finger_tip_frame': , 'l_shoulder_pan_link': , 'l_shoulder_lift_link': , 'l_upper_arm_roll_link': , 'l_upper_arm_link': , 'l_forearm_roll_link': , 'l_elbow_flex_link': , 'l_forearm_link': , 'l_wrist_flex_link': , 'l_wrist_roll_link': , 'l_gripper_palm_link': , 'l_gripper_led_frame': , 'l_gripper_motor_accelerometer_link': , 'l_gripper_tool_frame': , 'l_gripper_motor_slider_link': , 'l_gripper_motor_screw_link': , 'l_gripper_l_finger_link': , 'l_gripper_r_finger_link': , 'l_gripper_l_finger_tip_link': , 'l_gripper_r_finger_tip_link': , 'l_gripper_l_finger_tip_frame': , 'l_forearm_cam_frame': , 'l_forearm_cam_optical_frame': , 'r_forearm_cam_frame': , 'r_forearm_cam_optical_frame': }\n" ] } ], @@ -370,8 +413,8 @@ "id": "51b59ffd", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:17.138722982Z", - "start_time": "2023-11-30T09:28:17.136550048Z" + "end_time": "2024-01-25T15:13:25.916641115Z", + "start_time": "2024-01-25T15:13:25.914531215Z" } }, "outputs": [ @@ -392,8 +435,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1701336493\n", - " nsecs: 695036649\n", + " secs: 1706195605\n", + " nsecs: 914234161\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -432,12 +475,12 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 14, "id": "38a8aef4", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:19.963901990Z", - "start_time": "2023-11-30T09:28:19.914673646Z" + "end_time": "2024-01-25T15:13:51.297038606Z", + "start_time": "2024-01-25T15:13:51.284471328Z" } }, "outputs": [ @@ -454,11 +497,11 @@ "source": [ "print(f\"Joint limits: {pr2.get_joint_limits('torso_lift_joint')}\")\n", "\n", - "print(f\"Current Joint state: {pr2.get_joint_state('torso_lift_joint')}\")\n", + "print(f\"Current Joint state: {pr2.get_joint_position('torso_lift_joint')}\")\n", "\n", - "pr2.set_joint_state(\"torso_lift_joint\", 0.2)\n", + "pr2.set_joint_position(\"torso_lift_joint\", 0.2)\n", "\n", - "print(f\"New Joint state: {pr2.get_joint_state('torso_lift_joint')}\")" + "print(f\"New Joint state: {pr2.get_joint_position('torso_lift_joint')}\")" ] }, { @@ -472,12 +515,12 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": 15, "id": "5eee9b8a", "metadata": { "ExecuteTime": { - "end_time": "2023-11-30T09:28:22.289708761Z", - "start_time": "2023-11-30T09:28:22.287988559Z" + "end_time": "2024-01-25T15:14:04.637139529Z", + "start_time": "2024-01-25T15:14:04.594359252Z" } }, "outputs": [ @@ -485,7 +528,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "Pr2 forearm color: (0.699999988079071, 0.699999988079071, 0.699999988079071, 1.0)\n" + "Pr2 forearm color: Color(R=0.699999988079071, G=0.699999988079071, B=0.699999988079071, A=1.0)\n" ] } ], @@ -495,9 +538,14 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": 16, "id": "07aa1c3f", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T15:14:13.906293669Z", + "start_time": "2024-01-25T15:14:13.900095646Z" + } + }, "outputs": [], "source": [ "pr2.set_color([1, 0, 0], \"r_forearm_link\")" @@ -513,25 +561,37 @@ }, { "cell_type": "code", - "execution_count": 19, + "execution_count": 17, "id": "2a78715b", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T15:14:50.452351191Z", + "start_time": "2024-01-25T15:14:50.437446512Z" + } + }, "outputs": [ { "data": { - "text/plain": [ - "((-0.0015000000000000005, -0.0015000000000000005, 0.06949999999999999),\n", - " (0.0015000000000000005, 0.0015000000000000005, 0.0725))" - ] + "text/plain": "AxisAlignedBoundingBox(min_x=-0.0015000000000000005, min_y=-0.0015000000000000005, min_z=0.06949999999999999, max_x=0.0015000000000000005, max_y=0.0015000000000000005, max_z=0.0725)" }, - "execution_count": 19, + "execution_count": 17, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "pr2.get_AABB()" + "pr2.get_aabb()" ] + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false + }, + "id": "b4093cc83958ab47" } ], "metadata": { From c267c68bea92bf742c6015fcfd601db5d9b328d8 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Jan 2024 21:56:20 +0100 Subject: [PATCH 059/195] [Abstract World] applying code review edits, stopped at get_link_color in world.py --- doc/source/notebooks/bullet_world.ipynb | 4 +- examples/bullet_world.ipynb | 235 ++++++++++++++------ src/pycram/bullet_world.py | 99 ++++----- src/pycram/costmaps.py | 2 +- src/pycram/enums.py | 8 + src/pycram/ros/viz_marker_publisher.py | 2 +- src/pycram/world.py | 275 ++++++++++++++---------- src/pycram/world_dataclasses.py | 8 +- test/bullet_world_testcase.py | 4 +- test/test_bullet_world.py | 4 - test/test_database_merger.py | 4 +- test/test_database_resolver.py | 4 +- test/test_failure_handling.py | 4 +- test/test_jpt_resolver.py | 3 +- 14 files changed, 407 insertions(+), 249 deletions(-) diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index a2ce21a1d..c9a0def28 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -533,7 +533,7 @@ } ], "source": [ - "print(f\"Pr2 forearm color: {pr2.get_color('r_forearm_link')}\")" + "print(f\"Pr2 forearm color: {pr2.links['r_forearm_link'].color}\")" ] }, { @@ -548,7 +548,7 @@ }, "outputs": [], "source": [ - "pr2.set_color([1, 0, 0], \"r_forearm_link\")" + "pr2.links[\"r_forearm_link\"].color = [1, 0, 0, 1]" ] }, { diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index b735ca76c..d36ce6737 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -15,16 +15,63 @@ "cell_type": "code", "execution_count": 1, "id": "23bbba35", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:09.773814091Z", + "start_time": "2024-01-25T18:29:08.901441651Z" + } + }, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" + "pybullet build time: Nov 28 2023 23:51:11\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1706207349.376331]: Failed to import Giskard messages\n", + "[WARN] [1706207349.395439]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "Exception in thread Thread-11:\n", + "Traceback (most recent call last):\n", + " File \"/usr/lib/python3.8/threading.py\", line 932, in _bootstrap_inner\n", + " self.run()\n", + " File \"/home/bassioun/cram_ws/src/pycram/src/pycram/bullet_world.py\", line 527, in run\n", + " keys = p.getKeyboardEvents(physicalClientId=self.world.client_id)\n", + "TypeError: 'physicalClientId' is an invalid keyword argument for this function\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "argc=2\n", + "argv[0] = --unused\n", + "argv[1] = --start_demo_name=Physics Server\n", + "ExampleBrowserThreadFunc started\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "Creating context\n", + "Created GL 3.3 context\n", + "Direct GLX rendering context obtained\n", + "Making context current\n", + "GL_VENDOR=NVIDIA Corporation\n", + "GL_RENDERER=NVIDIA GeForce RTX 4070/PCIe/SSE2\n", + "GL_VERSION=3.3.0 NVIDIA 535.154.05\n", + "GL_SHADING_LANGUAGE_VERSION=3.30 NVIDIA via Cg compiler\n", + "pthread_getconcurrency()=0\n", + "Version = 3.3.0 NVIDIA 535.154.05\n", + "Vendor = NVIDIA Corporation\n", + "Renderer = NVIDIA GeForce RTX 4070/PCIe/SSE2\n", + "b3Printf: Selected demo: Physics Server\n", + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "MotionThreadFunc thread started\n" ] } ], @@ -81,7 +128,12 @@ "cell_type": "code", "execution_count": 2, "id": "48a3aed2", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:17.841474190Z", + "start_time": "2024-01-25T18:29:17.782682388Z" + } + }, "outputs": [], "source": [ "from pycram.bullet_world import Object\n", @@ -111,7 +163,12 @@ "cell_type": "code", "execution_count": 3, "id": "4ae2bc42", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:23.208599020Z", + "start_time": "2024-01-25T18:29:23.206209707Z" + } + }, "outputs": [], "source": [ "milk.set_position(Pose([1, 1, 1]))" @@ -121,7 +178,12 @@ "cell_type": "code", "execution_count": 4, "id": "4adc7b11", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:23.675871190Z", + "start_time": "2024-01-25T18:29:23.673804147Z" + } + }, "outputs": [], "source": [ "milk.set_orientation(Pose(orientation=[1,0, 0, 1]))" @@ -131,7 +193,12 @@ "cell_type": "code", "execution_count": 5, "id": "f91d1809", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:24.180713247Z", + "start_time": "2024-01-25T18:29:24.175368603Z" + } + }, "outputs": [], "source": [ "milk.set_pose(Pose([0, 0, 1], [0, 0, 0, 1]))" @@ -147,9 +214,14 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 6, "id": "1db2aa78", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:29:58.869360443Z", + "start_time": "2024-01-25T18:29:58.827502541Z" + } + }, "outputs": [ { "name": "stdout", @@ -168,8 +240,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1690203002\n", - " nsecs: 93374252\n", + " secs: 1706207364\n", + " nsecs: 174507617\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -205,9 +277,14 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 7, "id": "10a493b1", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:02.056106044Z", + "start_time": "2024-01-25T18:30:02.001333744Z" + } + }, "outputs": [], "source": [ "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", pose=Pose([1, 0, 1]))" @@ -215,9 +292,14 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 8, "id": "275372e3", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:03.288290549Z", + "start_time": "2024-01-25T18:30:03.283992204Z" + } + }, "outputs": [], "source": [ "milk.attach(cereal)" @@ -233,9 +315,14 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 9, "id": "dff85834", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:05.029258354Z", + "start_time": "2024-01-25T18:30:05.026329993Z" + } + }, "outputs": [], "source": [ "milk.set_position(Pose([1,1,1]))" @@ -251,10 +338,23 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 10, "id": "b0bba145", - "metadata": {}, - "outputs": [], + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:06.737363899Z", + "start_time": "2024-01-25T18:30:06.734694119Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Removing constraint with id: 1\n" + ] + } + ], "source": [ "cereal.detach(milk)" ] @@ -272,29 +372,20 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 11, "id": "edf5cb72", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:13.548802172Z", + "start_time": "2024-01-25T18:30:13.540787905Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "{'base_link': 0, 'base_bellow_link': 1, 'base_laser_link': 2, 'fl_caster_rotation_link': 3, 'fl_caster_l_wheel_link': 4, 'fl_caster_r_wheel_link': 5, 'fr_caster_rotation_link': 6, 'fr_caster_l_wheel_link': 7, 'fr_caster_r_wheel_link': 8, 'bl_caster_rotation_link': 9, 'bl_caster_l_wheel_link': 10, 'bl_caster_r_wheel_link': 11, 'br_caster_rotation_link': 12, 'br_caster_l_wheel_link': 13, 'br_caster_r_wheel_link': 14, 'torso_lift_link': 15, 'l_torso_lift_side_plate_link': 16, 'r_torso_lift_side_plate_link': 17, 'imu_link': 18, 'head_pan_link': 19, 'head_tilt_link': 20, 'head_plate_frame': 21, 'sensor_mount_link': 22, 'high_def_frame': 23, 'high_def_optical_frame': 24, 'double_stereo_link': 25, 'wide_stereo_link': 26, 'wide_stereo_optical_frame': 27, 'wide_stereo_l_stereo_camera_frame': 28, 'wide_stereo_l_stereo_camera_optical_frame': 29, 'wide_stereo_r_stereo_camera_frame': 30, 'wide_stereo_r_stereo_camera_optical_frame': 31, 'narrow_stereo_link': 32, 'narrow_stereo_optical_frame': 33, 'narrow_stereo_l_stereo_camera_frame': 34, 'narrow_stereo_l_stereo_camera_optical_frame': 35, 'narrow_stereo_r_stereo_camera_frame': 36, 'narrow_stereo_r_stereo_camera_optical_frame': 37, 'projector_wg6802418_frame': 38, 'projector_wg6802418_child_frame': 39, 'laser_tilt_mount_link': 40, 'laser_tilt_link': 41, 'r_shoulder_pan_link': 42, 'r_shoulder_lift_link': 43, 'r_upper_arm_roll_link': 44, 'r_upper_arm_link': 45, 'r_elbow_flex_link': 46, 'r_forearm_roll_link': 47, 'r_forearm_link': 48, 'r_wrist_flex_link': 49, 'r_wrist_roll_link': 50, 'r_gripper_palm_link': 51, 'r_gripper_led_frame': 52, 'r_gripper_motor_accelerometer_link': 53, 'r_gripper_tool_frame': 54, 'r_gripper_motor_slider_link': 55, 'r_gripper_motor_screw_link': 56, 'r_gripper_l_finger_link': 57, 'r_gripper_l_finger_tip_link': 58, 'r_gripper_r_finger_link': 59, 'r_gripper_r_finger_tip_link': 60, 'r_gripper_l_finger_tip_frame': 61, 'r_forearm_cam_frame': 62, 'r_forearm_cam_optical_frame': 63, 'l_shoulder_pan_link': 64, 'l_shoulder_lift_link': 65, 'l_upper_arm_roll_link': 66, 'l_upper_arm_link': 67, 'l_elbow_flex_link': 68, 'l_forearm_roll_link': 69, 'l_forearm_link': 70, 'l_wrist_flex_link': 71, 'l_wrist_roll_link': 72, 'l_gripper_palm_link': 73, 'l_gripper_led_frame': 74, 'l_gripper_motor_accelerometer_link': 75, 'l_gripper_tool_frame': 76, 'l_gripper_motor_slider_link': 77, 'l_gripper_motor_screw_link': 78, 'l_gripper_l_finger_link': 79, 'l_gripper_l_finger_tip_link': 80, 'l_gripper_r_finger_link': 81, 'l_gripper_r_finger_tip_link': 82, 'l_gripper_l_finger_tip_frame': 83, 'l_forearm_cam_frame': 84, 'l_forearm_cam_optical_frame': 85, 'torso_lift_motor_screw_link': 86, 'base_footprint': -1}\n" - ] - }, - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" + "{'base_link': , 'base_footprint': , 'base_bellow_link': , 'base_laser_link': , 'fl_caster_rotation_link': , 'fl_caster_l_wheel_link': , 'fl_caster_r_wheel_link': , 'fr_caster_rotation_link': , 'fr_caster_l_wheel_link': , 'fr_caster_r_wheel_link': , 'bl_caster_rotation_link': , 'bl_caster_l_wheel_link': , 'bl_caster_r_wheel_link': , 'br_caster_rotation_link': , 'br_caster_l_wheel_link': , 'br_caster_r_wheel_link': , 'torso_lift_link': , 'l_torso_lift_side_plate_link': , 'r_torso_lift_side_plate_link': , 'torso_lift_motor_screw_link': , 'imu_link': , 'head_pan_link': , 'head_tilt_link': , 'head_plate_frame': , 'sensor_mount_link': , 'high_def_frame': , 'high_def_optical_frame': , 'double_stereo_link': , 'wide_stereo_link': , 'wide_stereo_optical_frame': , 'wide_stereo_l_stereo_camera_frame': , 'wide_stereo_l_stereo_camera_optical_frame': , 'wide_stereo_r_stereo_camera_frame': , 'wide_stereo_r_stereo_camera_optical_frame': , 'narrow_stereo_link': , 'narrow_stereo_optical_frame': , 'narrow_stereo_l_stereo_camera_frame': , 'narrow_stereo_l_stereo_camera_optical_frame': , 'narrow_stereo_r_stereo_camera_frame': , 'narrow_stereo_r_stereo_camera_optical_frame': , 'projector_wg6802418_frame': , 'projector_wg6802418_child_frame': , 'laser_tilt_mount_link': , 'laser_tilt_link': , 'r_shoulder_pan_link': , 'r_shoulder_lift_link': , 'r_upper_arm_roll_link': , 'r_upper_arm_link': , 'r_forearm_roll_link': , 'r_elbow_flex_link': , 'r_forearm_link': , 'r_wrist_flex_link': , 'r_wrist_roll_link': , 'r_gripper_palm_link': , 'r_gripper_led_frame': , 'r_gripper_motor_accelerometer_link': , 'r_gripper_tool_frame': , 'r_gripper_motor_slider_link': , 'r_gripper_motor_screw_link': , 'r_gripper_l_finger_link': , 'r_gripper_r_finger_link': , 'r_gripper_l_finger_tip_link': , 'r_gripper_r_finger_tip_link': , 'r_gripper_l_finger_tip_frame': , 'l_shoulder_pan_link': , 'l_shoulder_lift_link': , 'l_upper_arm_roll_link': , 'l_upper_arm_link': , 'l_forearm_roll_link': , 'l_elbow_flex_link': , 'l_forearm_link': , 'l_wrist_flex_link': , 'l_wrist_roll_link': , 'l_gripper_palm_link': , 'l_gripper_led_frame': , 'l_gripper_motor_accelerometer_link': , 'l_gripper_tool_frame': , 'l_gripper_motor_slider_link': , 'l_gripper_motor_screw_link': , 'l_gripper_l_finger_link': , 'l_gripper_r_finger_link': , 'l_gripper_l_finger_tip_link': , 'l_gripper_r_finger_tip_link': , 'l_gripper_l_finger_tip_frame': , 'l_forearm_cam_frame': , 'l_forearm_cam_optical_frame': , 'r_forearm_cam_frame': , 'r_forearm_cam_optical_frame': }\n" ] } ], @@ -313,9 +404,14 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 12, "id": "51b59ffd", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:26.283263579Z", + "start_time": "2024-01-25T18:30:26.259577324Z" + } + }, "outputs": [ { "name": "stdout", @@ -334,8 +430,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1690203043\n", - " nsecs: 303540229\n", + " secs: 1706207426\n", + " nsecs: 257559537\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -374,9 +470,14 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 13, "id": "38a8aef4", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:51.633276335Z", + "start_time": "2024-01-25T18:30:51.590393104Z" + } + }, "outputs": [ { "name": "stdout", @@ -391,11 +492,11 @@ "source": [ "print(f\"Joint limits: {pr2.get_joint_limits('torso_lift_joint')}\")\n", "\n", - "print(f\"Current Joint state: {pr2.get_joint_state('torso_lift_joint')}\")\n", + "print(f\"Current Joint state: {pr2.get_joint_position('torso_lift_joint')}\")\n", "\n", - "pr2.set_joint_state(\"torso_lift_joint\", 0.2)\n", + "pr2.set_joint_position(\"torso_lift_joint\", 0.2)\n", "\n", - "print(f\"New Joint state: {pr2.get_joint_state('torso_lift_joint')}\")" + "print(f\"New Joint state: {pr2.get_joint_position('torso_lift_joint')}\")" ] }, { @@ -409,15 +510,20 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": 14, "id": "5eee9b8a", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:57.200886492Z", + "start_time": "2024-01-25T18:30:57.198278714Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Pr2 forearm color: (0.699999988079071, 0.699999988079071, 0.699999988079071, 1.0)\n" + "Pr2 forearm color: Color(R=0.699999988079071, G=0.699999988079071, B=0.699999988079071, A=1.0)\n" ] } ], @@ -427,9 +533,14 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": 15, "id": "07aa1c3f", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:30:59.531448130Z", + "start_time": "2024-01-25T18:30:59.523750241Z" + } + }, "outputs": [], "source": [ "pr2.set_color([1, 0, 0], \"r_forearm_link\")" @@ -445,24 +556,26 @@ }, { "cell_type": "code", - "execution_count": 19, + "execution_count": 16, "id": "2a78715b", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-25T18:31:05.700993547Z", + "start_time": "2024-01-25T18:31:05.677436085Z" + } + }, "outputs": [ { "data": { - "text/plain": [ - "((-0.0015000000000000005, -0.0015000000000000005, 0.06949999999999999),\n", - " (0.0015000000000000005, 0.0015000000000000005, 0.0725))" - ] + "text/plain": "AxisAlignedBoundingBox(min_x=-0.0015000000000000005, min_y=-0.0015000000000000005, min_z=0.06949999999999999, max_x=0.0015000000000000005, max_y=0.0015000000000000005, max_z=0.0725)" }, - "execution_count": 19, + "execution_count": 16, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "pr2.get_AABB()" + "pr2.get_aabb()" ] } ], diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 74766046c..4d85f7c5b 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -10,12 +10,10 @@ import rosgraph import rospy -from .enums import JointType, ObjectType +from .enums import JointType, ObjectType, WorldMode from .pose import Pose -from .world import World, Object -from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape, - CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, - MeshVisualShape) +from .world import World, Object, Link +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape from dataclasses import asdict @@ -30,16 +28,16 @@ class is the main interface to the Bullet Physics Engine and should be used to s if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): rospy.init_node('pycram') - def __init__(self, mode: str = "GUI", is_prospection_world: bool = False, sim_time_step=0.004167): # 240 Hz + def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: bool = False, sim_frequency=240): """ Creates a new simulation, the type decides of the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. The BulletWorld object also initializes the Events for attachment, detachment and for manipulating the world. - :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default parameter is "GUI" + :param mode: Can either be "GUI" for rendered window or "DIRECT" for non-rendered. The default is "GUI" :param is_prospection_world: For internal usage, decides if this BulletWorld should be used as a shadow world. """ - super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_time_step=sim_time_step) + super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_frequency=sim_frequency) self._gui_thread: Gui = Gui(self, mode) self._gui_thread.start() @@ -58,19 +56,13 @@ def __init__(self, mode: str = "GUI", is_prospection_world: bool = False, sim_ti if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: return p.loadURDF(path, basePosition=pose.position_as_list(), baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) - def remove_object(self, obj_id: int) -> None: - """ - Remove an object by its ID. - - :param obj_id: The unique id of the object to be removed. - """ - - p.removeBody(obj_id, self.client_id) + def remove_object(self, obj: Object) -> None: + p.removeBody(obj.id, self.client_id) def add_constraint(self, constraint: Constraint) -> int: """ @@ -99,7 +91,7 @@ def remove_constraint(self, constraint_id): print("Removing constraint with id: ", constraint_id) p.removeConstraint(constraint_id, physicsClientId=self.client_id) - def get_object_joint_rest_pose(self, obj: Object, joint_name: str) -> float: + def get_joint_rest_pose(self, obj: Object, joint_name: str) -> float: """ Get the joint rest pose of an articulated object @@ -108,7 +100,7 @@ def get_object_joint_rest_pose(self, obj: Object, joint_name: str) -> float: """ return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] - def get_object_joint_damping(self, obj: Object, joint_name: str) -> float: + def get_joint_damping(self, obj: Object, joint_name: str) -> float: """ Get the joint damping of an articulated object @@ -167,11 +159,11 @@ def get_object_joint_position(self, obj: Object, joint_name: str) -> float: """ return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] - def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: + def get_link_pose(self, link: Link) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. """ - return Pose(*p.getLinkState(obj_id, link_id, physicsClientId=self.client_id)[4:6]) + return Pose(*p.getLinkState(link.get_object_id(), link.id, physicsClientId=self.client_id)[4:6]) def perform_collision_detection(self) -> None: """ @@ -180,13 +172,15 @@ def perform_collision_detection(self) -> None: p.performCollisionDetection(physicsClientId=self.client_id) def get_object_contact_points(self, obj: Object) -> List: - """l.update_transforms_for_object(self.milk) - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the returned - list please look at `PyBullet Doc `_ + """ + Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the + returned list please look at: + `PyBullet Doc `_ :param obj: The object. :return: A list of all contact points with other objects """ + self.perform_collision_detection() return p.getContactPoints(obj.id, physicsClientId=self.client_id) def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: @@ -197,39 +191,40 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> :param obj2: The second object. :return: A list of all contact points between the two objects. """ + self.perform_collision_detection() return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.client_id) - def get_object_joint_names(self, obj_id: int) -> List[str]: + def get_joint_names(self, obj: Object) -> List[str]: """ Get the names of all joints of an articulated object. """ - num_joints = self.get_object_number_of_joints(obj_id) - return [p.getJointInfo(obj_id, i, physicsClientId=self.client_id)[1].decode('utf-8') for i in range(num_joints)] + num_joints = self.get_number_of_joints(obj) + return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[1].decode('utf-8') for i in range(num_joints)] - def get_object_link_names(self, obj_id: int) -> List[str]: + def get_link_names(self, obj: Object) -> List[str]: """ Get the names of all joints of an articulated object. """ - num_links = self.get_object_number_of_links(obj_id) - return [p.getJointInfo(obj_id, i, physicsClientId=self.client_id)[12].decode('utf-8') for i in range(num_links)] + num_links = self.get_number_of_links(obj) + return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[12].decode('utf-8') for i in range(num_links)] - def get_object_number_of_links(self, obj_id: int) -> int: + def get_number_of_links(self, obj: Object) -> int: """ Get the number of links of an articulated object - :param obj_id: The object + :param obj: The object """ - return self.get_object_number_of_joints(obj_id) + return self.get_number_of_joints(obj) - def get_object_number_of_joints(self, obj_id: int) -> int: + def get_number_of_joints(self, obj: Object) -> int: """ Get the number of joints of an articulated object - :param obj_id: The object + :param obj: The object """ - return p.getNumJoints(obj_id, physicsClientId=self.client_id) + return p.getNumJoints(obj, physicsClientId=self.client_id) - def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -256,23 +251,22 @@ def step(self): """ p.stepSimulation(physicsClientId=self.client_id) - def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): + def set_link_color(self, link: Link, rgba_color: Color): """ - Changes the color of a link of this object, the color has to be given as a 4 element list + Changes the rgba_color of a link of this object, the rgba_color has to be given as a 4 element list of RGBA values. - :param obj: The object which should be colored - :param link_id: The link id of the link which should be colored - :param rgba_color: The color as RGBA values between 0 and 1 + :param link: The link which should be colored. + :param rgba_color: The rgba_color as RGBA values between 0 and 1 """ - p.changeVisualShape(obj.id, link_id, rgbaColor=rgba_color, physicsClientId=self.client_id) + p.changeVisualShape(link.get_object_id(), link.id, rgbaColor=rgba_color, physicsClientId=self.client_id) - def get_color_of_object_link(self, obj: Object, link_name: str) -> Color: - return self.get_colors_of_all_links_of_object(obj)[link_name] + def get_link_color(self, link: Link) -> Color: + return self.get_colors_of_all_links_of_object(link.object)[link.name] def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: """ - Get the RGBA colors of each link in the object as a dictionary from link name to color. + Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. :param obj: The object :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. @@ -403,8 +397,8 @@ def remove_vis_axis(self) -> None: """ Removes all spawned vis axis objects that are currently in this BulletWorld. """ - for id in self.vis_axis: - p.removeBody(id, physicsClientId=self.client_id) + for vis_id in self.vis_axis: + p.removeBody(vis_id, physicsClientId=self.client_id) self.vis_axis = [] def ray_test(self, from_position: List[float], to_position: List[float]) -> int: @@ -468,14 +462,15 @@ def get_images_for_target(self, class Gui(threading.Thread): """ - For internal use only. Creates a new thread for the physics simulation that is active until closed by :func:`~World.exit` + For internal use only. Creates a new thread for the physics simulation that is active until closed by + :func:`~World.exit` Also contains the code for controlling the camera. """ - def __init__(self, world: World, mode: str): + def __init__(self, world: World, mode: WorldMode): threading.Thread.__init__(self) self.world = world - self.mode: str = mode + self.mode: WorldMode = mode def run(self): """ @@ -483,7 +478,7 @@ def run(self): if it is still active. If it is the thread will be suspended for 1/80 seconds, if it is not the method and thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. """ - if self.mode != "GUI": + if self.mode == WorldMode.DIRECT: self.world.client_id = p.connect(p.DIRECT) else: self.world.client_id = p.connect(p.GUI) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 6e0154e2e..50049d873 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -747,7 +747,7 @@ def plot_grid(data: np.ndarray) -> None: fig, ax = plt.subplots() ax.imshow(data, cmap=cmap) # draw gridlines - # ax.grid(which='major', axis='both', linestyle='-', color='k', linewidth=1) + # ax.grid(which='major', axis='both', linestyle='-', rgba_color='k', linewidth=1) ax.set_xticks(np.arange(0.5, rows, 1)); ax.set_yticks(np.arange(0.5, cols, 1)); plt.tick_params(axis='both', labelsize=0, length=0) diff --git a/src/pycram/enums.py b/src/pycram/enums.py index dffdfe8b1..f9f87b798 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -78,3 +78,11 @@ class Shape(Enum): MESH = 5 PLANE = 6 CAPSULE = 7 + + +class WorldMode(Enum): + """ + Enum for the different modes of the world. + """ + GUI = "GUI" + DIRECT = "DIRECT" diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 9d629aa52..0eb2cb5b2 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -77,7 +77,7 @@ def _make_marker_array(self) -> MarkerArray: link_pose_with_origin = link_pose * link_origin msg.pose = link_pose_with_origin.to_pose().pose - color = [1, 1, 1, 1] if obj.link_name_to_id[link] == -1 else obj.get_color(link) + color = [1, 1, 1, 1] if obj.link_name_to_id[link] == -1 else obj.get_color() msg.color = ColorRGBA(*color) msg.lifetime = rospy.Duration(1) diff --git a/src/pycram/world.py b/src/pycram/world.py index c1c41b206..a9e0994a0 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -11,8 +11,8 @@ from queue import Queue import tf from tf.transformations import quaternion_from_euler -from typing import List, Optional, Dict, Tuple, Callable -from typing import Union +from typing_extensions import List, Optional, Dict, Tuple, Callable +from typing_extensions import Union import numpy as np import rospkg @@ -24,7 +24,7 @@ from .event import Event from .robot_descriptions import robot_description -from .enums import JointType, ObjectType +from .enums import JointType, ObjectType, WorldMode from .local_transformer import LocalTransformer from sensor_msgs.msg import JointState @@ -39,10 +39,17 @@ class World(ABC): """ - The World Class represents the physics Simulation and belief state. + The World Class represents the physics Simulation and belief state, it is the main interface for reasoning about + the World. This is implemented as a singleton, the current World can be accessed via the static variable + current_world which is managed by the World class itself. """ - current_world: World = None + simulation_frequency: float + """ + Global reference for the simulation frequency (Hz), used in calculating the equivalent real time in the simulation. + """ + + current_world: Optional[World] = None """ Global reference to the currently used World, usually this is the graphical one. However, if you are inside a UseProspectionWorld() environment the current_world points to the @@ -50,24 +57,18 @@ class World(ABC): used at the moment. """ - robot: Object = None + robot: Optional[Object] = None """ Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the URDF with the name of the URDF on the parameter server. """ - data_directory: List[str] = [os.path.dirname(__file__) + "/../../resources"] + data_directory: List[str] = [os.path.join(os.path.dirname(__file__), '..', '..', 'resources')] """ Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ - simulation_time_step: float = None - """ - Global reference for the simulation time step, this is used to calculate the frequency of the simulation, - and also for calculating the equivalent real time for the simulation. - """ - - def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: float): + def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequency: float): """ Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the background. There can only be one rendered simulation. @@ -79,7 +80,7 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: if World.current_world is None: World.current_world = self - World.simulation_time_step = simulation_time_step + World.simulation_frequency = simulation_frequency self.is_prospection_world: bool = is_prospection_world self._init_and_sync_prospection_world() @@ -93,7 +94,7 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self.client_id: int = -1 # This is used to connect to the physics server (allows multiple clients) - self.mode: str = mode + self.mode: WorldMode = mode # The mode of the simulation, can be "GUI" or "DIRECT" self.coll_callbacks: Dict[Tuple[Object, Object], CollisionCallbacks] = {} @@ -103,27 +104,44 @@ def __init__(self, mode: str, is_prospection_world: bool, simulation_time_step: self.saved_states: List[int] = [] def _init_events(self): + """ + Initializes dynamic events that can be used to react to changes in the World. + """ self.detachment_event: Event = Event() self.attachment_event: Event = Event() self.manipulation_event: Event = Event() def _init_and_sync_prospection_world(self): + """ + Initializes the prospection world and the synchronization between the main and the prospection world. + """ self._init_prospection_world() self._sync_prospection_world() def _update_local_transformer_worlds(self): + """ + Updates the local transformer worlds with the current world and prospection world. + """ self.local_transformer.world = self self.local_transformer.prospection_world = self.prospection_world def _init_prospection_world(self): + """ + Initializes the prospection world, if this is a prospection world itself it will not create another prospection, + world, but instead set the prospection world to None, else it will create a prospection world. + """ if self.is_prospection_world: # then no need to add another prospection world self.prospection_world = None else: - self.prospection_world: World = self.__class__("DIRECT", + self.prospection_world: World = self.__class__(WorldMode.DIRECT, True, - World.simulation_time_step) + World.simulation_frequency) def _sync_prospection_world(self): + """ + Synchronizes the prospection world with the main world, this means that every object in the main world will be + added to the prospection world and vice versa. + """ if self.is_prospection_world: # then no need to add another prospection world self.world_sync = None else: @@ -131,11 +149,21 @@ def _sync_prospection_world(self): self.world_sync.start() @property - def simulation_frequency(self): - return int(1/World.simulation_time_step) + def simulation_time_step(self): + """ + The time step of the simulation in seconds. + """ + return 1/World.simulation_frequency @abstractmethod - def load_urdf_at_pose_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: + """ + Loads a URDF file at the given pose and returns the id of the loaded object. + + :param path: The path to the URDF file. + :param pose: The pose at which the object should be loaded. + :return: The id of the loaded object. + """ pass def get_objects_by_name(self, name: str) -> List[Object]: @@ -166,11 +194,11 @@ def get_object_by_id(self, obj_id: int) -> Object: return list(filter(lambda obj: obj.id == obj_id, self.objects))[0] @abstractmethod - def remove_object(self, obj_id: int) -> None: + def remove_object(self, obj: Object) -> None: """ - Remove an object by its ID. + Remove an object from the world. - :param obj_id: The unique id of the object to be removed. + :param obj: The object to be removed. """ pass @@ -178,9 +206,12 @@ def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_par """ Creates a fixed joint constraint between the given parent and child links, the joint frame will be at the origin of the child link frame, and would have the same orientation - as the child link frame. if no link is given, the base link will be used (id = -1). + as the child link frame. - returns the constraint id + :param parent_link: The constrained link of the parent object. + :param child_link: The constrained link of the child object. + :param child_to_parent_transform: The transform from the child link frame to the parent link frame. + :return: The unique id of the created constraint. """ constraint = Constraint(parent_obj_id=parent_link.get_object_id(), @@ -199,12 +230,19 @@ def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_par @abstractmethod def add_constraint(self, constraint: Constraint) -> int: """ - Add a constraint between two objects so that they become attached + Add a constraint between two objects links so that they become attached for example. + + :param constraint: The constraint data used to create the constraint. """ pass @abstractmethod - def remove_constraint(self, constraint_id): + def remove_constraint(self, constraint_id) -> None: + """ + Remove a constraint by its ID. + + :param constraint_id: The unique id of the constraint to be removed. + """ pass def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: @@ -213,7 +251,7 @@ def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, :param obj: The object. :param joint_name: The name of the joint. - :return: A tuple containing the upper and the lower limits of the joint. + :return: A tuple containing the upper and the lower limits of the joint respectively. """ return self.get_object_joint_upper_limit(obj, joint_name), self.get_object_joint_lower_limit(obj, joint_name) @@ -242,11 +280,11 @@ def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: @abstractmethod def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. + Returns the axis along/around which a joint is moving. The given joint_name has to be part of this object. - :param obj: The object + :param obj: The object. :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz + :return: The axis which is a 3D vector of xyz values. """ pass @@ -255,26 +293,30 @@ def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: """ Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - :param obj: The object - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint + :param obj: The object. + :param joint_name: Joint name for which the type should be returned. + :return: The type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. """ pass @abstractmethod def get_object_joint_position(self, obj: Object, joint_name: str) -> float: """ - Get the state of a joint of an articulated object + Get the position of a joint of an articulated object - :param obj: The object - :param joint_name: The name of the joint + :param obj: The object. + :param joint_name: The name of the joint. + :return: The joint position as a float. """ pass @abstractmethod - def get_object_link_pose(self, obj_id: int, link_id: int) -> Pose: + def get_link_pose(self, link: Link) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. + + :param link: The link as a Link object. + :return: The pose of the link as a Pose object. """ pass @@ -296,7 +338,6 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: elif callbacks.no_collision_cb is not None: callbacks.no_collision_cb() if real_time: - # Simulation runs at 240 Hz time.sleep(self.simulation_time_step) @abstractmethod @@ -309,7 +350,7 @@ def perform_collision_detection(self) -> None: @abstractmethod def get_object_contact_points(self, obj: Object) -> List: """ - Returns a list of contact points of this Object with other Objects. + Returns a list of contact points of this Object with all other Objects. :param obj: The object. :return: A list of all contact points with other objects @@ -335,65 +376,75 @@ def get_joint_ranges(self) -> Tuple[List, List, List, List, List]: :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping """ ll, ul, jr, rp, jd = [], [], [], [], [] - joint_names = self.get_object_joint_names(self.robot.id) + joint_names = self.get_joint_names(self.robot) for name in joint_names: joint_type = self.get_object_joint_type(self.robot, name) if joint_type != JointType.FIXED: ll.append(self.get_object_joint_lower_limit(self.robot, name)) ul.append(self.get_object_joint_upper_limit(self.robot, name)) jr.append(ul[-1] - ll[-1]) - rp.append(self.get_object_joint_rest_pose(self.robot, name)) - jd.append(self.get_object_joint_damping(self.robot, name)) + rp.append(self.get_joint_rest_pose(self.robot, name)) + jd.append(self.get_joint_damping(self.robot, name)) return ll, ul, jr, rp, jd - def get_object_joint_rest_pose(self, obj: Object, joint_name: str) -> float: + def get_joint_rest_pose(self, obj: Object, joint_name: str) -> float: """ Get the rest pose of a joint of an articulated object - :param obj: The object - :param joint_name: The name of the joint + :param obj: The object. + :param joint_name: The name of the joint. + :return: The rest pose of the joint. """ pass - def get_object_joint_damping(self, obj: Object, joint_name: str) -> float: + def get_joint_damping(self, obj: Object, joint_name: str) -> float: """ Get the damping of a joint of an articulated object - :param obj: The object - :param joint_name: The name of the joint + :param obj: The object. + :param joint_name: The name of the joint. + :return: The damping of the joint. """ pass @abstractmethod - def get_object_joint_names(self, obj_id: int) -> List[str]: + def get_joint_names(self, obj: Object) -> List[str]: """ Get the names of all joints of an articulated object. + :param obj: The object. + :return: A list of all joint names of the object. """ pass @abstractmethod - def get_object_link_names(self, obj_id: int) -> List[str]: + def get_link_names(self, obj: Object) -> List[str]: """ Get the names of all links of an articulated object. + :param obj: The object. + :return: A list of all link names of the object. """ pass @abstractmethod - def get_object_number_of_joints(self, obj_id: int) -> int: + def get_number_of_joints(self, obj: Object) -> int: """ Get the number of joints of an articulated object + :param obj: The object. + :return: The number of joints of the object. """ pass - def get_object_number_of_links(self, obj_id: int) -> int: + def get_number_of_links(self, obj: Object) -> int: """ Get the number of links of an articulated object + :param obj: The object. + :return: The number of links of the object. """ pass @abstractmethod - def reset_object_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -422,53 +473,52 @@ def step(self): """ pass - def set_object_color(self, obj: Object, color: Color, link: Optional[str] = ""): + def set_object_color(self, obj: Object, rgba_color: Color): """ Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. + of RGBA values. :param obj: The object which should be colored - :param color: The color as Color object with RGBA values between 0 and 1 - :param link: The link name of the link which should be colored - """ - if link == "": - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if obj.link_name_to_id != {}: - for link_id in obj.link_name_to_id.values(): - self.set_object_link_color(obj, link_id, color) - else: - self.set_object_link_color(obj, -1, color) + :param rgba_color: The color as Color object with RGBA values between 0 and 1 + """ + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if obj.links != {}: + for link in obj.links.values(): + self.set_link_color(link, rgba_color) else: - self.set_object_link_color(obj, obj.link_name_to_id[link], color) + self.set_link_color(obj.get_root_link(), rgba_color) @abstractmethod - def set_object_link_color(self, obj: Object, link_id: int, rgba_color: Color): + def set_link_color(self, link: Link, rgba_color: Color): """ - Changes the color of a link of this object, the color has to be given as Color object. + Changes the rgba_color of a link of this object, the rgba_color has to be given as Color object. - :param obj: The object which should be colored - :param link_id: The link id of the link which should be colored - :param rgba_color: The color as Color object with RGBA values between 0 and 1 + :param link: The link which should be colored. + :param rgba_color: The rgba_color as Color object with RGBA values between 0 and 1. """ pass @abstractmethod - def get_color_of_object_link(self, obj: Object, link_name: str) -> Color: + def get_link_color(self, link: Link) -> Color: + """ + This method returns the rgba_color of this link. + :param link: The link for which the rgba_color should be returned. + :return: The rgba_color as Color object with RGBA values between 0 and 1. + """ pass def get_color_of_object(self, obj: Object) -> Union[Color, Dict[str, Color]]: """ - This method returns the color of this object. The return is either: + This method returns the rgba_color of this object. The return is either: 1. A Color object with RGBA values, this is the case if the object only has one link (this happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the color as value. The color is given as a Color Object. - Please keep in mind that not every link may have a color. This is dependent on the URDF from which the + 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. + Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which the object is spawned. - :param obj: The object for which the color should be returned. + :param obj: The object for which the rgba_color should be returned. """ link_to_color_dict = self.get_colors_of_all_links_of_object(obj) @@ -480,7 +530,7 @@ def get_color_of_object(self, obj: Object) -> Union[Color, Dict[str, Color]]: @abstractmethod def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: """ - Get the RGBA colors of each link in the object as a dictionary from link name to color. + Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. :param obj: The object :return: A dictionary with link names as keys and a Color object for each link as value. @@ -698,7 +748,7 @@ def _copy(self) -> World: :return: The reference to the new World """ - world = World("DIRECT", False, World.simulation_time_step) + world = World(WorldMode.DIRECT, False, World.simulation_frequency) for obj in self.objects: obj_pose = Pose(obj.get_position_as_list(), obj.get_orientation_as_list()) o = Object(obj.name, obj.obj_type, obj.path, obj_pose, world, @@ -856,11 +906,11 @@ class UseProspectionWorld: """ def __init__(self): - self.prev_world: World = None + self.prev_world: Optional[World] = None def __enter__(self): if not World.current_world.is_prospection_world: - time.sleep(20 * World.simulation_time_step) + time.sleep(20 * World.current_world.simulation_time_step) # blocks until the adding queue is ready World.current_world.world_sync.add_obj_queue.join() @@ -913,7 +963,7 @@ def run(self): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.prospection_world, color, world object] + # [name, type, path, position, orientation, self.world.prospection_world, rgba_color, world object] o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) # Maps the World object to the prospection world object self.object_mapping[obj[7]] = o @@ -1065,7 +1115,7 @@ def pose(self) -> Pose: """ The pose of the link relative to the world frame. """ - return self.world.get_object_link_pose(self.object.id, self.id) + return self.world.get_link_pose(self) @property def pose_as_list(self) -> List[List[float]]: @@ -1091,11 +1141,11 @@ def collision(self) -> Collision: @property def color(self) -> Color: - return self.world.get_color_of_object_link(self.object, self.name) + return self.world.get_link_color(self) @color.setter - def color(self, color: Color) -> None: - self.world.set_object_link_color(self.object, self.id, color) + def color(self, color: List[float]) -> None: + self.world.set_link_color(self, Color.from_rgba(color)) class RootLink(Link): @@ -1131,7 +1181,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, """ The constructor loads the urdf file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. - The color parameter is only used when loading .stl or .obj files, + The rgba_color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object @@ -1141,7 +1191,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, :param pose: The pose at which the Object should be spawned :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used. - :param color: The color with which the object should be spawned. + :param color: The rgba_color with which the object should be spawned. :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ @@ -1235,7 +1285,7 @@ def remove(self) -> None: self.world.world_sync.remove_obj_queue.put(self) self.world.world_sync.remove_obj_queue.join() - self.world.remove_object(self.id) + self.world.remove_object(self) if World.robot == self: World.robot = None @@ -1474,7 +1524,7 @@ def _get_joint_name_to_id_map(self) -> Dict[str, int]: """ Creates a dictionary which maps the joint names to their unique ids. """ - joint_names = self.world.get_object_joint_names(self.id) + joint_names = self.world.get_joint_names(self) n_joints = len(joint_names) return dict(zip(joint_names, range(n_joints))) @@ -1482,7 +1532,7 @@ def _get_link_name_to_id_map(self) -> Dict[str, int]: """ Creates a dictionary which maps the link names to their unique ids. """ - link_names = self.world.get_object_link_names(self.id) + link_names = self.world.get_link_names(self) n_links = len(link_names) return dict(zip(link_names, range(n_links))) @@ -1552,7 +1602,7 @@ def set_positions_of_all_joints(self, joint_poses: dict) -> None: :return: """ for joint_name, joint_position in joint_poses.items(): - self.world.reset_object_joint_position(self, joint_name, joint_position) + self.world.reset_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position self._set_attached_objects_poses() @@ -1575,7 +1625,7 @@ def set_joint_position(self, joint_name: str, joint_position: float) -> None: logging.error(f"The given joint position was: {joint_position}") # Temporarily disabled because kdl outputs values exciting joint limits # return - self.world.reset_object_joint_position(self, joint_name, joint_position) + self.world.reset_joint_position(self, joint_name, joint_position) self._current_joints_positions[joint_name] = joint_position self._set_attached_objects_poses() @@ -1640,22 +1690,17 @@ def update_pose_from_tf(self, frame: str) -> None: position[0][2]] self.set_position(Pose(position, orientation)) - def set_color(self, color: Color, link: Optional[str] = "") -> None: + def set_color(self, color: Color) -> None: """ - Changes the color of this object, the color has to be given as a list - of RGBA values. Optionally a link name can can be provided, if no link - name is provided all links of this object will be colored. + Changes the rgba_color of this object, the rgba_color has to be given as a list + of RGBA values. All links of this object will be colored. - :param color: The color as RGBA values between 0 and 1 - :param link: The link name of the link which should be colored + :param color: The rgba_color as RGBA values between 0 and 1 """ - self.world.set_object_color(self, color, link) + self.world.set_object_color(self, color) - def get_color(self, link: Optional[str] = None) -> Union[Color, Dict[str, Color], None]: - if link is None: - return self.world.get_color_of_object(self) - else: - return self.world.get_color_of_object_link(self, link) + def get_color(self) -> Union[Color, Dict[str, Color]]: + return self.world.get_color_of_object(self) def get_aabb(self) -> AxisAlignedBoundingBox: return self.world.get_object_aabb(self) @@ -1707,7 +1752,7 @@ def get_joint_type(self, joint_name: str) -> JointType: def find_joint_above(self, link_name: str, joint_type: JointType) -> str: """ - Traverses the chain from 'link_name' to the URDF origin and returns the first joint that is of type 'joint_type'. + Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. :param link_name: Link name above which the joint should be found :param joint_type: Joint type that should be searched for @@ -1859,7 +1904,7 @@ def _load_object(name: str, color: Color, ignore_cached_files: bool) -> Tuple[int, str]: """ - Loads an object to the given World with the given position and orientation. The color will only be + Loads an object to the given World with the given position and orientation. The rgba_color will only be used when an .obj or .stl file is given. If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created and this URDf file will be loaded instead. @@ -1872,7 +1917,7 @@ def _load_object(name: str, :param position: The position in which the object should be spawned :param orientation: The orientation in which the object should be spawned :param world: The World to which the Object should be spawned - :param color: The color of the object, only used when .obj or .stl file is given + :param color: The rgba_color of the object, only used when .obj or .stl file is given :param ignore_cached_files: Whether to ignore files in the cache directory. :return: The unique id of the object and the path to the file used for spawning """ @@ -1924,7 +1969,7 @@ def _load_object(name: str, path = cach_dir + name + ".urdf" try: - obj = world.load_urdf_at_pose_and_get_object_id(path, Pose(position, orientation)) + obj = world.load_urdf_and_get_object_id(path, Pose(position, orientation)) return obj, path except Exception as e: logging.error( @@ -2043,13 +2088,13 @@ def fix_link_attributes(urdf_string: str) -> str: def _generate_urdf_file(name: str, path: str, color: Color, cach_dir: str) -> str: """ - Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given color will be + Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name as filename. :param name: The name of the object :param path: The path to the .obj or .stl file - :param color: The color which should be used for the material tag + :param color: The rgba_color which should be used for the material tag :param cach_dir The absolute file path to the cach directory in the pycram package :return: The absolute path of the created file """ @@ -2061,7 +2106,7 @@ def _generate_urdf_file(name: str, path: str, color: Color, cach_dir: str) -> st \n \ \n \ \n \ - \n \ + \n \ \n \ \n \ \n \ diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 5c4e20c9e..474c6f86d 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -6,7 +6,7 @@ @dataclass class Color: """ - Dataclass for storing color as an RGBA value. + Dataclass for storing rgba_color as an RGBA value. """ R: float = 1 G: float = 1 @@ -16,7 +16,7 @@ class Color: @classmethod def from_rgba(cls, rgba: List[float]): """ - Sets the color from a list of RGBA values. + Sets the rgba_color from a list of RGBA values. :param rgba: The list of RGBA values """ @@ -24,9 +24,9 @@ def from_rgba(cls, rgba: List[float]): def get_rgba(self) -> List[float]: """ - Returns the color as a list of RGBA values. + Returns the rgba_color as a list of RGBA values. - :return: The color as a list of RGBA values + :return: The rgba_color as a list of RGBA values """ return [self.R, self.G, self.B, self.A] diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index b3fb307eb..755dfbb9a 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -4,7 +4,7 @@ from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule -from pycram.enums import ObjectType +from pycram.enums import ObjectType, WorldMode class BulletWorldTestCase(unittest.TestCase): @@ -13,7 +13,7 @@ class BulletWorldTestCase(unittest.TestCase): @classmethod def setUpClass(cls): - cls.world = BulletWorld("DIRECT") + cls.world = BulletWorld(WorldMode.DIRECT) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 881412e1c..91639d8ca 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -4,11 +4,8 @@ from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose -import numpy as np from pycram.world import fix_missing_inertial import xml.etree.ElementTree as ET -import tf - class BulletWorldTest(BulletWorldTestCase): @@ -51,4 +48,3 @@ def test_inertial(self): resulting_tree = ET.ElementTree(ET.fromstring(result)) for element in resulting_tree.iter("link"): self.assertTrue(len([*element.iter("inertial")]) > 0) - diff --git a/test/test_database_merger.py b/test/test_database_merger.py index 56bd90bce..cbd26b731 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -8,7 +8,7 @@ from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.process_module import simulated_robot -from pycram.enums import Arms, ObjectType +from pycram.enums import Arms, ObjectType, WorldMode from pycram.task import with_tree import pycram.task from pycram.bullet_world import Object @@ -27,7 +27,7 @@ class Configuration: class ExamplePlans: def __init__(self): - self.world = BulletWorld("DIRECT") + self.world = BulletWorld(WorldMode.DIRECT) self.pr2 = Object("pr2", ObjectType.ROBOT, "pr2.urdf") self.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") self.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 18d7c047b..6df2a71bc 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -13,7 +13,7 @@ from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.task import with_tree -from pycram.enums import ObjectType +from pycram.enums import ObjectType, WorldMode # check if jpt is installed jpt_installed = True @@ -42,7 +42,7 @@ class DatabaseResolverTestCase(unittest.TestCase,): @classmethod def setUpClass(cls) -> None: global pycrorm_uri - cls.world = World("DIRECT") + cls.world = World(WorldMode.DIRECT) cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False diff --git a/test/test_failure_handling.py b/test/test_failure_handling.py index d23a9d93b..7a97d308a 100644 --- a/test/test_failure_handling.py +++ b/test/test_failure_handling.py @@ -5,7 +5,7 @@ from pycram.bullet_world import BulletWorld, Object from pycram.designator import ActionDesignatorDescription from pycram.designators.action_designator import ParkArmsAction -from pycram.enums import ObjectType, Arms +from pycram.enums import ObjectType, Arms, WorldMode from pycram.failure_handling import Retry from pycram.plan_failures import PlanFailure from pycram.process_module import ProcessModule, simulated_robot @@ -29,7 +29,7 @@ class FailureHandlingTest(unittest.TestCase): @classmethod def setUpClass(cls): - cls.world = BulletWorld("DIRECT") + cls.world = BulletWorld(WorldMode.DIRECT) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = True diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index ff80a0714..4ffad3d4c 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -12,6 +12,7 @@ from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description from pycram.pose import Pose +from pycram.enums import WorldMode # check if jpt is installed jpt_installed = True @@ -53,7 +54,7 @@ def setUpClass(cls) -> None: cls.model = mlflow.pyfunc.load_model( model_uri="mlflow-artifacts:/0/9150dd1fb353494d807261928cea6e8c/artifacts/grasping").unwrap_python_model() \ .model - cls.world = BulletWorld("DIRECT") + cls.world = BulletWorld(WorldMode.DIRECT) cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([3, 3, 0.75])) cls.robot = Object(robot_description.name, "pr2", robot_description.name + ".urdf") ProcessModule.execution_delay = False From 685025a76be4ce2ab7b1be73acdebf8adb7d2c44 Mon Sep 17 00:00:00 2001 From: Nils Leusmann Date: Fri, 26 Jan 2024 10:03:22 +0100 Subject: [PATCH 060/195] The IK Server seems to have troubles if the retract_target_pose is not in map frame + bug fixing --- src/pycram/pose_generator_and_validator.py | 28 ++++++++++++---------- 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 0b39af7ee..02f74db2a 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -136,38 +136,42 @@ def reachability_validator(pose: Pose, target = target.get_pose() robot.set_pose(pose) + res = False + arms = [] for name, chain in robot_description.chains.items(): if isinstance(chain, ManipulatorDescription): - retract_traget_pose = LocalTransformer().transform_pose(target,robot.get_link_tf_frame(chain.tool_frame)) - #BulletWorld.robot.get_link_tf_frame(robot_description.get_tool_frame(chain.tool_frame))) - retract_traget_pose.position.x -= 0.07 # Care hard coded value copied from PlaceAction class + retract_target_pose = LocalTransformer().transform_pose(target, robot.get_link_tf_frame(chain.tool_frame)) + retract_target_pose.position.x -= 0.07 # Care hard coded value copied from PlaceAction class + + # retract_pose needs to be in world frame? + retract_target_pose = LocalTransformer().transform_pose(retract_target_pose, "map") + + joints = robot_description.chains[name].joints + tool_frame = robot_description.get_tool_frame(name) - joints = robot_description.chains[chain.name].joints # TODO Make orientation adhere to grasping orientation - res = False - arms = [] in_contact = False joint_state_before_ik = robot._current_joint_states try: # test the possible solution and apply it to the robot - resp = request_ik(target, robot, chain.joints, chain.tool_frame) + resp = request_ik(target, robot, joints, tool_frame) _apply_ik(robot, resp, joints) in_contact = collision_check(robot, allowed_collision) if not in_contact: # only check for retract pose if pose worked - resp = request_ik(retract_traget_pose, robot, chain.joints, chain.tool_frame) + resp = request_ik(retract_target_pose, robot, joints, tool_frame) _apply_ik(robot, resp, joints) in_contact = collision_check(robot, allowed_collision) if not in_contact: - arms.append(chain.name) - res = True + arms.append(name) except IKError: pass finally: robot.set_joint_states(joint_state_before_ik) - - return res, arms + if arms: + res = True + return res, arms def collision_check(robot, allowed_collision): From 3054f5ef6229af6d081049d123e5fd0971ae481f Mon Sep 17 00:00:00 2001 From: Arthur Niedzwiecki Date: Fri, 26 Jan 2024 10:56:33 +0100 Subject: [PATCH 061/195] [doc] Remove ipython install --- doc/source/installation.rst | 5 ----- 1 file changed, 5 deletions(-) diff --git a/doc/source/installation.rst b/doc/source/installation.rst index dda84a2a1..49498a283 100644 --- a/doc/source/installation.rst +++ b/doc/source/installation.rst @@ -161,11 +161,6 @@ After installing pandoc, install sphinx on your device. sudo apt install python3-sphinx -Install IPython - -.. code-block:: shell - - sudo pip3 install ipython Install the requirements in your python interpreter. From f6dd146402985fe9eb1473754a57bd3a6c11ae84 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 26 Jan 2024 12:21:53 +0100 Subject: [PATCH 062/195] [test] fixed orm test inheritance pattern --- test/bullet_world_testcase.py | 2 + test/test_orm.py | 69 ++++++++--------------------------- 2 files changed, 18 insertions(+), 53 deletions(-) diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index b34b434c4..8687a294a 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -3,6 +3,7 @@ import numpy as np import rospkg +import pycram.task from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial from pycram.pose import Pose from pycram.robot_descriptions import robot_description @@ -34,6 +35,7 @@ def setUp(self): def tearDown(self): self.world.reset_bullet_world() + pycram.task.reset_tree() @classmethod def tearDownClass(cls): diff --git a/test/test_orm.py b/test/test_orm.py index e4c2a7f25..4c5063fc7 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -23,7 +23,7 @@ from pycram.task import with_tree -class ORMTestSchema(unittest.TestCase): +class DatabaseTestCaseMixin(BulletWorldTestCase): engine: sqlalchemy.engine session: sqlalchemy.orm.Session @@ -45,12 +45,8 @@ def tearDown(self): pycram.orm.base.Base.metadata.drop_all(self.engine) self.session.close() - @classmethod - def TearDownClass(cls): - super().tearDownClass() - cls.session.commit() - cls.session.close() +class ORMTestSchemaTestCase(DatabaseTestCaseMixin, unittest.TestCase): def test_schema_creation(self): pycram.orm.base.Base.metadata.create_all(self.engine) self.session.commit() @@ -75,27 +71,18 @@ def test_schema_creation(self): self.assertTrue("CloseAction" in tables) -class ORMTaskTreeTestCase(test_task_tree.TaskTreeTestCase): - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - - @classmethod - def setUpClass(cls): - super().setUpClass() - cls.engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False) - - def setUp(self): - super().setUp() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() +class ORMTaskTreeTestCase(DatabaseTestCaseMixin): - def tearDown(self): - super().tearDown() - pycram.task.reset_tree() - pycram.orm.base.ProcessMetaData.reset() - pycram.orm.base.Base.metadata.drop_all(self.engine) - self.session.close() + @with_tree + def plan(self): + object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) + self.assertEqual(description.ground().object_designator.name, "milk") + with simulated_robot: + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + description.resolve().perform() def test_node(self): """Test if the objects in the database is equal with the objects that got serialized.""" @@ -163,7 +150,7 @@ def test_meta_data_alternation(self): self.assertEqual(metadata_result.description, "meta_data_alternation_test") -class MixinTestCase(ORMTestSchema, BulletWorldTestCase): +class MixinTestCase(DatabaseTestCaseMixin): @with_tree def plan(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) @@ -190,12 +177,9 @@ def test_pose_mixin(self): self.assertTrue(all([r.pose is not None and r.pose_id == r.pose.id for r in result])) -class ORMObjectDesignatorTestCase(ORMTestSchema, BulletWorldTestCase): +class ORMObjectDesignatorTestCase(DatabaseTestCaseMixin): """Test ORM functionality with a plan including object designators. """ - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - def test_plan_serialization(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) @@ -213,28 +197,7 @@ def test_plan_serialization(self): self.assertEqual(len(tt) - 1, len(action_results) + len(motion_results)) -class ORMActionDesignatorTestCase(BulletWorldTestCase): - - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - - @classmethod - def setUpClass(cls): - super().setUpClass() - cls.engine = sqlalchemy.create_engine("sqlite+pysqlite:///:memory:", echo=False) - - def setUp(self): - super().setUp() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() - - def tearDown(self): - super().tearDown() - pycram.task.reset_tree() - pycram.orm.base.ProcessMetaData.reset() - pycram.orm.base.Base.metadata.drop_all(self.engine) - self.session.close() +class ORMActionDesignatorTestCase(DatabaseTestCaseMixin): def test_code_designator_type(self): action = NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])) From 1aaa11e5ec4f0f2e409e5ac8988beadaeb5d8669 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 26 Jan 2024 23:22:09 +0100 Subject: [PATCH 063/195] [Abstract World] documenting Object class and cleaning it. --- examples/bullet_world.ipynb | 4 +- src/pycram/bullet_world.py | 16 +- src/pycram/costmaps.py | 8 +- src/pycram/designators/location_designator.py | 4 +- src/pycram/enums.py | 3 - src/pycram/pose.py | 3 +- .../resolver/location/giskard_location.py | 2 +- src/pycram/world.py | 607 ++++++++++++------ src/pycram/world_dataclasses.py | 38 +- src/pycram/world_reasoning.py | 20 +- 10 files changed, 463 insertions(+), 242 deletions(-) diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index d36ce6737..c487ec212 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -528,7 +528,7 @@ } ], "source": [ - "print(f\"Pr2 forearm color: {pr2.get_color('r_forearm_link')}\")" + "print(f\"Pr2 forearm color: {pr2.links['r_forearm_link'].color}\")" ] }, { @@ -543,7 +543,7 @@ }, "outputs": [], "source": [ - "pr2.set_color([1, 0, 0], \"r_forearm_link\")" + "pr2.links[\"r_forearm_link\"].color = [1, 0, 0]" ] }, { diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 4d85f7c5b..82e57c3b8 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -61,7 +61,7 @@ def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: basePosition=pose.position_as_list(), baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) - def remove_object(self, obj: Object) -> None: + def remove_object_from_simulator(self, obj: Object) -> None: p.removeBody(obj.id, self.client_id) def add_constraint(self, constraint: Constraint) -> int: @@ -78,7 +78,7 @@ def add_constraint(self, constraint: Constraint) -> int: parent_link_id, constraint.child_obj_id, child_link_id, - constraint.joint_type.as_int(), + constraint.joint_type.value, constraint.joint_axis_in_child_link_frame, constraint.joint_frame_position_wrt_parent_origin, constraint.joint_frame_position_wrt_child_origin, @@ -222,7 +222,7 @@ def get_number_of_joints(self, obj: Object) -> int: :param obj: The object """ - return p.getNumJoints(obj, physicsClientId=self.client_id) + return p.getNumJoints(obj.id, physicsClientId=self.client_id) def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ @@ -262,9 +262,9 @@ def set_link_color(self, link: Link, rgba_color: Color): p.changeVisualShape(link.get_object_id(), link.id, rgbaColor=rgba_color, physicsClientId=self.client_id) def get_link_color(self, link: Link) -> Color: - return self.get_colors_of_all_links_of_object(link.object)[link.name] + return self.get_colors_of_object_links(link.object)[link.name] - def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: + def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. @@ -278,7 +278,7 @@ def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: link_to_color = dict(zip(links, colors)) return link_to_color - def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: + def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. @@ -288,12 +288,12 @@ def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: """ return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.client_id)) - def get_object_link_aabb(self, obj_id: int, link_id: int) -> AxisAlignedBoundingBox: + def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. """ - return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj_id, link_id, physicsClientId=self.client_id)) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(link.get_object_id(), link.id, physicsClientId=self.client_id)) def set_realtime(self, real_time: bool) -> None: """ diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 50049d873..c56812631 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -394,9 +394,9 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: r_t = self.world.ray_test_batch(n[:, 0], n[:, 1], num_threads=0) j += len(n) if World.robot: - shadow_robot = World.current_world.get_prospection_object_from_object(World.robot) + shadow_robot = World.current_world.get_prospection_object_for_object(World.robot) attached_objs = World.robot.attachments.keys() - attached_objs_shadow_id = [World.current_world.get_prospection_object_from_object(x).id for x + attached_objs_shadow_id = [World.current_world.get_prospection_object_for_object(x).id for x in attached_objs] res[i:j] = [ @@ -724,13 +724,13 @@ def get_aabb_for_link(self) -> AxisAlignedBoundingBox: :return: Two points in world coordinate space, which span a rectangle """ - prospection_object = World.current_world.get_prospection_object_from_object(self.object) + prospection_object = World.current_world.get_prospection_object_for_object(self.object) with UseProspectionWorld(): prospection_object.set_orientation(Pose(orientation=[0, 0, 0, 1])) link_pose_trans = self.link.transform inverse_trans = link_pose_trans.invert() prospection_object.set_orientation(inverse_trans.to_pose()) - return self.link.get_aabb() + return self.link.get_axis_aligned_bounding_box() cmap = colors.ListedColormap(['white', 'black', 'green', 'red', 'blue']) diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 8e55b147f..6060d0205 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -178,7 +178,7 @@ def __iter__(self): if self.visible_for or self.reachable_for: robot_object = self.visible_for.world_object if self.visible_for else self.reachable_for.world_object - test_robot = World.current_world.get_prospection_object_from_object(robot_object) + test_robot = World.current_world.get_prospection_object_for_object(robot_object) with UseProspectionWorld(): @@ -254,7 +254,7 @@ def __iter__(self) -> Location: final_map = occupancy + gaussian - test_robot = World.current_world.get_prospection_object_from_object(self.robot) + test_robot = World.current_world.get_prospection_object_for_object(self.robot) # Find a Joint of type prismatic which is above the handle in the URDF tree container_joint = self.handle.world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) diff --git a/src/pycram/enums.py b/src/pycram/enums.py index f9f87b798..3b7280ad6 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -30,9 +30,6 @@ class JointType(Enum): PLANAR = 3 FIXED = 4 - def as_int(self): - return self.value - class Grasp(Enum): """ diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 3a6cf54bc..8cdd39d11 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -307,7 +307,8 @@ def __init__(self, translation: Optional[List[float]] = None, rotation: Optional @classmethod def from_pose_and_child_frame(cls, pose: Pose, child_frame_name: str) -> Transform: - return cls(pose.position_as_list(), pose.orientation_as_list(), pose.frame, child_frame_name) + return cls(pose.position_as_list(), pose.orientation_as_list(), pose.frame, child_frame_name, + time=pose.header.stamp) @staticmethod def from_transform_stamped(transform_stamped: TransformStamped) -> Transform: diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 88479c50d..9d6122aa2 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -28,7 +28,7 @@ def __iter__(self) -> CostmapLocation.Location: pose_left, end_config_left = self._get_reachable_pose_for_arm(self.target, robot_description.get_tool_frame("left")) - test_robot = BulletWorld.current_world.get_prospection_object_from_object(BulletWorld.robot) + test_robot = BulletWorld.current_world.get_prospection_object_for_object(BulletWorld.robot) with UseProspectionWorld(): valid, arms = reachability_validator(pose_right, test_robot, self.target, {}) if valid: diff --git a/src/pycram/world.py b/src/pycram/world.py index a9e0994a0..6ca2bd4bc 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -31,10 +31,9 @@ from .pose import Pose, Transform from abc import ABC, abstractmethod -from dataclasses import dataclass from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks, MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, - CapsuleVisualShape, PlaneVisualShape, MeshVisualShape) + CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, LinkState, ObjectState) class World(ABC): @@ -194,13 +193,36 @@ def get_object_by_id(self, obj_id: int) -> Object: return list(filter(lambda obj: obj.id == obj_id, self.objects))[0] @abstractmethod + def remove_object_from_simulator(self, obj: Object) -> None: + """ + Removes an object from the physics simulator. + :param obj: The object to be removed. + """ + pass + def remove_object(self, obj: Object) -> None: """ - Remove an object from the world. + Removes this object from the current world. + For the object to be removed it has to be detached from all objects it + is currently attached to. After this is done a call to world remove object is done + to remove this Object from the simulation/world. :param obj: The object to be removed. """ - pass + obj.detach_all() + + self.objects.remove(obj) + + # This means the current world of the object is not the prospection world, since it + # has a reference to the prospection world + if self.prospection_world is not None: + self.world_sync.remove_obj_queue.put(self) + self.world_sync.remove_obj_queue.join() + + self.remove_object_from_simulator(obj) + + if World.robot == self: + World.robot = None def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_parent_transform: Transform) -> int: """ @@ -508,19 +530,21 @@ def get_link_color(self, link: Link) -> Color: """ pass - def get_color_of_object(self, obj: Object) -> Union[Color, Dict[str, Color]]: + def get_object_color(self, obj: Object) -> Union[Color, Dict[str, Color]]: """ This method returns the rgba_color of this object. The return is either: 1. A Color object with RGBA values, this is the case if the object only has one link (this happens for example if the object is spawned from a .obj or .stl file) 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. - Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which the - object is spawned. + Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which + the object is spawned. :param obj: The object for which the rgba_color should be returned. + :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and + the rgba_color as value. """ - link_to_color_dict = self.get_colors_of_all_links_of_object(obj) + link_to_color_dict = self.get_colors_of_object_links(obj) if len(link_to_color_dict) == 1: return list(link_to_color_dict.values())[0] @@ -528,7 +552,7 @@ def get_color_of_object(self, obj: Object) -> Union[Color, Dict[str, Color]]: return link_to_color_dict @abstractmethod - def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: + def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. @@ -538,7 +562,7 @@ def get_colors_of_all_links_of_object(self, obj: Object) -> Dict[str, Color]: pass @abstractmethod - def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: + def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. @@ -549,7 +573,7 @@ def get_object_aabb(self, obj: Object) -> AxisAlignedBoundingBox: pass @abstractmethod - def get_object_link_aabb(self, obj_id: int, link_id: int) -> AxisAlignedBoundingBox: + def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -630,6 +654,7 @@ def robot_is_set() -> bool: def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: """ Closes the World as well as the prospection world, also collects any other thread that is running. + :param wait_time_before_exit_in_secs: The time to wait before exiting the world in seconds. """ if wait_time_before_exit_in_secs is not None: time.sleep(wait_time_before_exit_in_secs) @@ -640,6 +665,9 @@ def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: self.join_threads() def exit_prospection_world_if_exists(self): + """ + Exits the prospection world if it exists. + """ if self.prospection_world: self.terminate_world_sync() self.prospection_world.exit() @@ -652,10 +680,16 @@ def disconnect_from_physics_server(self): pass def reset_current_world(self): + """ + Resets the current world to None if this is the current world. + """ if World.current_world == self: World.current_world = None def reset_robot(self): + """ + Sets the robot class variable to None. + """ self.set_robot(None) @abstractmethod @@ -666,13 +700,16 @@ def join_threads(self): pass def terminate_world_sync(self): + """ + Terminates the world sync thread. + """ self.world_sync.terminate = True self.world_sync.join() def save_state(self) -> int: """ - Returns the id of the saved state of the World. The saved state contains the position, orientation and joint - position of every Object in the World, the objects attachments and the constraint ids. + Returns the id of the saved state of the World. The saved state contains the states of all the objects and + the state of the physics simulator. :return: A unique id of the state """ @@ -682,16 +719,21 @@ def save_state(self) -> int: return state_id def save_objects_state(self, state_id: int): + """ + Saves the state of all objects in the World according to the given state using the unique state id. + :param state_id: The unique id representing the state. + """ for obj in self.objects: obj.save_state(state_id) def restore_state(self, state_id) -> None: """ - Restores the state of the World according to the given state using the unique state id. This includes position, - orientation, and joint states. However, restore can not respawn objects if there are objects that were deleted - between creation of the state and restoring, they will be skipped. + Restores the state of the World according to the given state using the unique state id. This includes the state + of the physics simulator and the state of all objects. + However, restore can not respawn objects if there are objects that were deleted between creation of the state + and restoring, they will be skipped. - :param state_id: The unique id representing the state, as returned by :func:`~save_state` + :param state_id: The unique id representing the state. """ self.restore_physics_simulator_state(state_id) self.restore_objects_states(state_id) @@ -700,6 +742,7 @@ def restore_state(self, state_id) -> None: def save_physics_simulator_state(self) -> int: """ Saves the state of the physics simulator and returns the unique id of the state. + :return: The unique id representing the state. """ pass @@ -707,6 +750,7 @@ def save_physics_simulator_state(self) -> int: def remove_physics_simulator_state(self, state_id: int): """ Removes the state of the physics simulator with the given id. + :param state_id: The unique id representing the state. """ pass @@ -715,10 +759,15 @@ def restore_physics_simulator_state(self, state_id: int): """ Restores the objects and environment state in the physics simulator according to the given state using the unique state id. + :param state_id: The unique id representing the state. """ pass def restore_objects_states(self, state_id: int): + """ + Restores the state of all objects in the World according to the given state using the unique state id. + :param state_id: The unique id representing the state. + """ for obj in self.objects: obj.restore_state(state_id) @@ -733,30 +782,13 @@ def get_images_for_target(self, 2. A depth image 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. - :param cam_pose: The pose of the camera - :param target_pose: The pose to which the camera should point to - :param size: The height and width of the images in pixel + :param target_pose: The pose to which the camera should point. + :param cam_pose: The pose of the camera. + :param size: The height and width of the images in pixels. :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. """ pass - def _copy(self) -> World: - """ - Copies this World into another and returns it. The other World - will be in Direct mode. The prospection world should always be preferred instead of creating a new World. - This method should only be used if necessary since there can be unforeseen problems. - - :return: The reference to the new World - """ - world = World(WorldMode.DIRECT, False, World.simulation_frequency) - for obj in self.objects: - obj_pose = Pose(obj.get_position_as_list(), obj.get_orientation_as_list()) - o = Object(obj.name, obj.obj_type, obj.path, obj_pose, world, - obj.color) - for joint in obj.joint_name_to_id: - o.set_joint_position(joint, obj.get_joint_position(joint)) - return world - def register_two_objects_collision_callbacks(self, object_a: Object, object_b: Object, @@ -784,7 +816,7 @@ def add_resource_path(cls, path: str) -> None: """ cls.data_directory.append(path) - def get_prospection_object_from_object(self, obj: Object) -> Object: + def get_prospection_object_for_object(self, obj: Object) -> Object: """ Returns the corresponding object from the prospection world for a given object in the main world. If the given Object is already in the prospection world, it is returned. @@ -804,7 +836,7 @@ def get_prospection_object_from_object(self, obj: Object) -> Object: f" the object isn't anymore in the main (graphical) World" f" or if the given object is already a prospection object. ") - def get_object_from_prospection_object(self, prospection_object: Object) -> Object: + def get_object_for_prospection_object(self, prospection_object: Object) -> Object: """ Returns the corresponding object from the main World for a given object in the prospection world. If the given object is not in the prospection @@ -825,6 +857,7 @@ def reset_world(self, remove_saved_states=True) -> None: All attached objects will be detached, all joints will be set to the default position of 0 and all objects will be set to the position and orientation in which they were spawned. + :param remove_saved_states: If the saved states should be removed. """ if remove_saved_states: @@ -834,6 +867,9 @@ def reset_world(self, remove_saved_states=True) -> None: obj.reset(remove_saved_states) def remove_saved_states(self): + """ + Removes all saved states of the World. + """ for state_id in self.saved_states: self.remove_physics_simulator_state(state_id) self.saved_states = [] @@ -850,9 +886,9 @@ def update_transforms_for_objects_in_current_world(self) -> None: def ray_test(self, from_position: List[float], to_position: List[float]) -> int: """ Cast a ray and return the first object hit, if any. - param from_position: The starting position of the ray in Cartesian world coordinates. - param to_position: The ending position of the ray in Cartesian world coordinates. - return: The object id of the first object hit, or -1 if no object was hit. + :param from_position: The starting position of the ray in Cartesian world coordinates. + :param to_position: The ending position of the ray in Cartesian world coordinates. + :return: The object id of the first object hit, or -1 if no object was hit. """ pass @@ -864,34 +900,81 @@ def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[L to compute the ray intersections for the batch. Specify 0 to let simulator decide, 1 (default) for single core execution, 2 or more to select the number of threads to use. - param from_positions: The starting positions of the rays in Cartesian world coordinates. - param to_positions: The ending positions of the rays in Cartesian world coordinates. - param num_threads: The number of threads to use to compute the ray intersections for the batch. + :param from_positions: The starting positions of the rays in Cartesian world coordinates. + :param to_positions: The ending positions of the rays in Cartesian world coordinates. + :param num_threads: The number of threads to use to compute the ray intersections for the batch. """ pass def create_visual_shape(self, visual_shape: VisualShape) -> int: + """ + Creates a visual shape in the physics simulator and returns the unique id of the created shape. + :param visual_shape: The visual shape to be created, uses the VisualShape dataclass defined in world_dataclasses + :return: The unique id of the created shape. + """ raise NotImplementedError def create_multi_body(self, multi_body: MultiBody) -> int: + """ + Creates a multi body in the physics simulator and returns the unique id of the created multi body. The multibody + is created by joining multiple links/shapes together with joints. + :param multi_body: The multi body to be created, uses the MultiBody dataclass defined in world_dataclasses. + :return: The unique id of the created multi body. + """ raise NotImplementedError def create_box_visual_shape(self, shape_data: BoxVisualShape) -> int: + """ + Creates a box visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the box visual shape to be created, + uses the BoxVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError def create_cylinder_visual_shape(self, shape_data: CylinderVisualShape) -> int: + """ + Creates a cylinder visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the cylinder visual shape to be created, + uses the CylinderVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError def create_sphere_visual_shape(self, shape_data: SphereVisualShape) -> int: + """ + Creates a sphere visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the sphere visual shape to be created, + uses the SphereVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError def create_capsule_visual_shape(self, shape_data: CapsuleVisualShape) -> int: + """ + Creates a capsule visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the capsule visual shape to be created, + uses the CapsuleVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError def create_plane_visual_shape(self, shape_data: PlaneVisualShape) -> int: + """ + Creates a plane visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the plane visual shape to be created, + uses the PlaneVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError def create_mesh_visual_shape(self, shape_data: MeshVisualShape) -> int: + """ + Creates a mesh visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the mesh visual shape to be created, + uses the MeshVisualShape dataclass defined in world_dataclasses. + :return: The unique id of the created shape. + """ raise NotImplementedError @@ -907,8 +990,12 @@ class UseProspectionWorld: def __init__(self): self.prev_world: Optional[World] = None + # The previous world is saved to restore it after the with block is exited. def __enter__(self): + """ + This method is called when entering the with block, it will set the current world to the prospection world + """ if not World.current_world.is_prospection_world: time.sleep(20 * World.current_world.simulation_time_step) # blocks until the adding queue is ready @@ -919,6 +1006,9 @@ def __enter__(self): World.current_world = World.current_world.prospection_world def __exit__(self, *args): + """ + This method is called when exiting the with block, it will restore the previous world to be the current world. + """ if self.prev_world is not None: World.current_world = self.prev_world World.current_world.world_sync.pause_sync = False @@ -1014,41 +1104,48 @@ def check_for_equal(self) -> None: self.equal_states = eql -@dataclass -class LinkState: - constraint_ids: Dict[Link, int] - - class Link: - + """ + Represents a link of an Object in the World. + """ def __init__(self, _id: int, urdf_link: urdf_parser_py.urdf.Link, obj: Object): - self.id = _id - self.urdf_link = urdf_link - self.object = obj - self.world = obj.world - self.local_transformer = LocalTransformer() + self.id: int = _id + self.urdf_link: urdf_parser_py.urdf.Link = urdf_link + self.object: Object = obj + self.world: World = obj.world + self.local_transformer: LocalTransformer = LocalTransformer() self.constraint_ids: Dict[Link, int] = {} self.saved_states: Dict[int, LinkState] = {} def save_state(self, state_id: int) -> None: """ - Saves the state of this link, this includes the pose of the link. + Saves the state of this link. + :param state_id: The unique id of the state. """ self.saved_states[state_id] = self.get_current_state() def restore_state(self, state_id: int) -> None: """ - Restores the state of this link, this includes the pose of the link. + Restores the state of this link. + :param state_id: The unique id of the state. """ self.constraint_ids = self.saved_states[state_id].constraint_ids def get_current_state(self): + """ + :return: The current state of this link as a LinkState object. + """ return LinkState(self.constraint_ids.copy()) def add_fixed_constraint_with_link(self, child_link: Link) -> int: + """ + Adds a fixed constraint between this link and the given link, used to create attachments for example. + :param child_link: The child link to which a fixed constraint should be added. + :return: The unique id of the constraint. + """ constraint_id = self.world.add_fixed_constraint(self, child_link, child_link.get_transform_from_link(self)) @@ -1057,125 +1154,217 @@ def add_fixed_constraint_with_link(self, child_link: Link) -> int: return constraint_id def remove_constraint_with_link(self, child_link: Link) -> None: + """ + Removes the constraint between this link and the given link. + :param child_link: The child link of the constraint that should be removed. + """ self.world.remove_constraint(self.constraint_ids[child_link]) del self.constraint_ids[child_link] del child_link.constraint_ids[self] def get_object_id(self) -> int: + """ + Returns the id of the object to which this link belongs. + :return: The integer id of the object to which this link belongs. + """ return self.object.id @property def tf_frame(self) -> str: + """ + Returns the tf frame of this link. + :return: The tf frame of this link as a string. + """ return f"{self.object.tf_frame}/{self.urdf_link.name}" @property def is_root(self) -> bool: + """ + Returns whether this link is the root link of the object. + :return: True if this link is the root link, False otherwise. + """ return self.object.get_root_link_id() == self.id def update_transform(self, transform_time: Optional[rospy.Time] = None): + """ + Updates the transformation of this link at the given time. + :param transform_time: The time at which the transformation should be updated. + """ self.local_transformer.update_transforms([self.transform], transform_time) @property def transform(self) -> Transform: """ The transformation from the world frame to this link frame. + :return: A Transform object with the transformation from the world frame to this link frame. """ return self.pose.to_transform(self.tf_frame) - def get_transform_to_link(self, link: Link): + def get_transform_to_link(self, link: Link) -> Transform: + """ + Returns the transformation from this link to the given link. + :param link: The link to which the transformation should be returned. + :return: A Transform object with the transformation from this link to the given link. + """ return link.get_transform_from_link(self) def get_transform_from_link(self, link: Link) -> Transform: + """ + Returns the transformation from the given link to this link. + :param link: The link from which the transformation should be returned. + :return: A Transform object with the transformation from the given link to this link. + """ return self.get_pose_wrt_link(link).to_transform(self.tf_frame) def get_pose_wrt_link(self, link: Link) -> Pose: + """ + Returns the pose of this link with respect to the given link. + :param link: The link with respect to which the pose should be returned. + :return: A Pose object with the pose of this link with respect to the given link. + """ return self.local_transformer.transform_pose(self.pose, link.tf_frame) - def get_aabb(self) -> AxisAlignedBoundingBox: - return self.world.get_object_link_aabb(self.object.id, self.id) + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + Returns the axis aligned bounding box of this link. + :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. + """ + return self.world.get_link_axis_aligned_bounding_box(self) @property - def position(self) -> Pose.position: + def position(self) -> Point: + """ + The getter for the position of the link relative to the world frame. + :return: A Point object containing the position of the link relative to the world frame. + """ return self.pose.position @property def position_as_list(self) -> List[float]: + """ + The getter for the position of the link relative to the world frame as a list. + :return: A list containing the position of the link relative to the world frame. + """ return self.pose.position_as_list() @property def orientation(self) -> Quaternion: + """ + The getter for the orientation of the link relative to the world frame. + :return: A Quaternion object containing the orientation of the link relative to the world frame. + """ return self.pose.orientation @property def orientation_as_list(self) -> List[float]: + """ + The getter for the orientation of the link relative to the world frame as a list. + :return: A list containing the orientation of the link relative to the world frame. + """ return self.pose.orientation_as_list() @property def pose(self) -> Pose: """ The pose of the link relative to the world frame. + :return: A Pose object containing the pose of the link relative to the world frame. """ return self.world.get_link_pose(self) @property def pose_as_list(self) -> List[List[float]]: + """ + The pose of the link relative to the world frame as a list. + :return: A list containing the position and orientation of the link relative to the world frame. + """ return self.pose.to_list() @property def name(self) -> str: + """ + The name of the link as defined in the URDF. + :return: The name of the link as a string. + """ return self.urdf_link.name def get_geometry(self) -> GeometricType: + """ + Returns the geometry type of the URDF collision element of this link. + """ return None if not self.collision else self.collision.geometry - def get_origin_transform(self): + def get_origin_transform(self) -> Transform: + """ + Returns the transformation between the link frame and the origin frame of this link. + """ return Transform(self.origin.xyz, list(quaternion_from_euler(*self.origin.rpy))) @property - def origin(self): + def origin(self) -> urdf_parser_py.urdf.Pose: + """ + The URDF origin pose of this link. + :return: A '~urdf_parser_py.urdf.Pose' object containing the origin pose of this link. + """ return self.collision.origin @property def collision(self) -> Collision: + """ + The URDF collision element of this link which has a geometry, and origin. + :return: A '~urdf_parser_py.urdf.Collision' object containing the collision element of this link. + """ return self.urdf_link.collision @property def color(self) -> Color: + """ + The getter for the rgba_color of this link. + :return: A Color object containing the rgba_color of this link. + """ return self.world.get_link_color(self) @color.setter def color(self, color: List[float]) -> None: - self.world.set_link_color(self, Color.from_rgba(color)) + """ + The setter for the color of this link, could be rgb or rgba. + :param color: The color as a list of floats, either rgb or rgba. + """ + self.world.set_link_color(self, Color.from_list(color)) class RootLink(Link): - + """ + Represents the root link of an Object in the World. + It differs from the normal Link class in that the pose ande the tf_frame is the same as that of the object. + """ def __init__(self, obj: Object): super().__init__(obj.get_root_link_id(), obj.get_root_urdf_link(), obj) @property def tf_frame(self) -> str: + """ + Returns the tf frame of the root link, which is the same as the tf frame of the object. + :return: A string containing the tf frame of the root link. + """ return self.object.tf_frame @property def pose(self) -> Pose: + """ + Returns the pose of the root link, which is the same as the pose of the object. + :return: A Pose object containing the pose of the root link. + """ return self.object.get_pose() -@dataclass -class ObjectState: - state_id: int - attachments: Dict[Object, Attachment] - - class Object: """ Represents a spawned Object in the World. """ - def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, - pose: Pose = None, - world: World = None, + def __init__(self, name: str, obj_type: ObjectType, path: str, + pose: Optional[Pose] = None, + world: Optional[World] = None, color: Optional[Color] = Color(), ignore_cached_files: Optional[bool] = False): """ @@ -1185,7 +1374,7 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object - :param obj_type: The type of the object + :param obj_type: The type of the object as an ObjectType enum. :param path: The path to the source file, if only a filename is provided then the resourcer directories will be searched :param pose: The pose at which the Object should be spawned @@ -1201,44 +1390,143 @@ def __init__(self, name: str, obj_type: Union[str, ObjectType], path: str, self.world: World = world if world is not None else World.current_world self.name: str = name - self.obj_type: Union[str, ObjectType] = obj_type + self.obj_type: ObjectType = obj_type self.color: Color = color self.local_transformer = LocalTransformer() self.original_pose = self.local_transformer.transform_pose(pose, "map") - position, orientation = self.original_pose.to_list() - self.id, self.path = _load_object(name, path, position, orientation, self.world, color, ignore_cached_files) self._current_pose = self.original_pose - self.joint_name_to_id: Dict[str, int] = self._get_joint_name_to_id_map() - self.link_name_to_id: Dict[str, int] = self._get_link_name_to_id_map() - self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) + self.id, self.path = self._load_object(path, ignore_cached_files) + + self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) + + self._init_urdf_object() + if self.urdf_object.name == robot_description.name: + self.world.set_robot_if_not_set(self) + + self._init_joint_name_and_id_map() + + self._init_link_name_and_id_map() + + self._init_links() + self.update_link_transforms() self.attachments: Dict[Object, Attachment] = {} self.saved_states: Dict[int, ObjectState] = {} # takes the state id as key and returns the attachments of the object at that state - self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) - if not self.world.is_prospection_world: - self.world.world_sync.add_obj_queue.put( - [name, obj_type, path, position, orientation, self.world.prospection_world, color, self]) + self._add_to_world_sync_obj_queue(path) + self._init_current_positions_of_joint() + + self.world.objects.append(self) + + def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: + """ + Loads an object to the given World with the given position and orientation. The rgba_color will only be + used when an .obj or .stl file is given. + If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created + and this URDf file will be loaded instead. + When spawning a URDf file a new file will be created in the cache directory, if there exists none. + This new file will have resolved mesh file paths, meaning there will be no references + to ROS packges instead there will be absolute file paths. + + :param path: The path to the source file or the name on the ROS parameter server + :param ignore_cached_files: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path to the file used for spawning + """ + pa = pathlib.Path(path) + extension = pa.suffix + if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): + for data_dir in World.data_directory: + path = get_path_from_data_dir(path, data_dir) + if path: + break + + if not path: + raise FileNotFoundError( + f"File {pa.name} could not be found in the resource directory {World.data_directory}") + # rospack = rospkg.RosPack() + # cach_dir = rospack.get_path('pycram') + '/resources/cached/' + cach_dir = World.data_directory[0] + '/cached/' + if not pathlib.Path(cach_dir).exists(): + os.mkdir(cach_dir) + + # if file is not yet cached corrcet the urdf and save if in the cache directory + if not _is_cached(path, self.name, cach_dir) or ignore_cached_files: + if extension == ".obj" or extension == ".stl": + path = _generate_urdf_file(self.name, path, self.color, cach_dir) + elif extension == ".urdf": + with open(path, mode="r") as f: + urdf_string = fix_missing_inertial(f.read()) + urdf_string = remove_error_tags(urdf_string) + urdf_string = fix_link_attributes(urdf_string) + try: + urdf_string = _correct_urdf_string(urdf_string) + except rospkg.ResourceNotFound as e: + rospy.logerr(f"Could not find resource package linked in this URDF") + raise e + path = cach_dir + pa.name + with open(path, mode="w") as f: + f.write(urdf_string) + else: # Using the urdf from the parameter server + urdf_string = rospy.get_param(path) + path = cach_dir + self.name + ".urdf" + with open(path, mode="w") as f: + f.write(_correct_urdf_string(urdf_string)) + # save correct path in case the file is already in the cache directory + elif extension == ".obj" or extension == ".stl": + path = cach_dir + pa.stem + ".urdf" + elif extension == ".urdf": + path = cach_dir + pa.name + else: + path = cach_dir + self.name + ".urdf" + + try: + obj_id = self.world.load_urdf_and_get_object_id(path, Pose(self.get_position_as_list(), + self.get_orientation_as_list())) + return obj_id, path + except Exception as e: + logging.error( + "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" + " the name of an URDF string on the parameter server.") + os.remove(path) + raise (e) + + def _init_urdf_object(self): + """ + Initializes the URDF object from the URDF file. + """ with open(self.path) as f: self.urdf_object = URDF.from_xml_string(f.read()) - if self.urdf_object.name == robot_description.name: - self.world.set_robot_if_not_set(self) - self.link_name_to_id[self.urdf_object.get_root()] = -1 - self.link_id_to_name[-1] = self.urdf_object.get_root() - self.links: Dict[str, Link] = self._init_links() - self.update_link_transforms() - self._current_joints_positions = {} - self._init_current_positions_of_joint() + def _init_joint_name_and_id_map(self) -> None: + """ + Creates a dictionary which maps the joint names to their unique ids and vice versa. + """ + joint_names = self.world.get_joint_names(self) + n_joints = len(joint_names) + self.joint_name_to_id = dict(zip(joint_names, range(n_joints))) + self.joint_id_to_name = dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys())) - self.world.objects.append(self) + def _init_link_name_and_id_map(self) -> None: + """ + Creates a dictionary which maps the link names to their unique ids and vice versa. + """ + link_names = self.world.get_link_names(self) + n_links = len(link_names) + self.link_name_to_id: Dict[str, int] = dict(zip(link_names, range(n_links))) + self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) + self.link_name_to_id[self.urdf_object.get_root()] = -1 + self.link_id_to_name[-1] = self.urdf_object.get_root() def _init_links(self): + """ + Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the + corresponding link objects. + """ links = {} for urdf_link in self.urdf_object.links: link_name = urdf_link.name @@ -1247,12 +1535,21 @@ def _init_links(self): links[link_name] = RootLink(self) else: links[link_name] = Link(link_id, urdf_link, self) - return links + self.links = links + + def _add_to_world_sync_obj_queue(self, path: str): + """ + Adds this object to the objects queue of the WorldSync object of the World. + """ + self.world.world_sync.add_obj_queue.put( + [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), + self.world.prospection_world, self.color, self]) def _init_current_positions_of_joint(self) -> None: """ Initialize the cached joint position for each joint. """ + self._current_joints_positions = {} for joint_name in self.joint_name_to_id.keys(): self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) @@ -1260,6 +1557,7 @@ def _init_current_positions_of_joint(self) -> None: def base_origin_shift(self) -> np.ndarray: """ The shift between the base of the object and the origin of the object. + :return: A numpy array with the shift between the base of the object and the origin of the object. """ return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) @@ -1275,21 +1573,8 @@ def remove(self) -> None: is currently attached to. After this is done a call to world remove object is done to remove this Object from the simulation/world. """ - self.detach_all() - - self.world.objects.remove(self) - - # This means the current world of the object is not the prospection world, since it - # has a reference to the prospection world - if self.world.prospection_world is not None: - self.world.world_sync.remove_obj_queue.put(self) - self.world.world_sync.remove_obj_queue.join() - self.world.remove_object(self) - if World.robot == self: - World.robot = None - def reset(self, remove_saved_states=True) -> None: """ Resets the Object to the state it was first spawned in. @@ -1520,22 +1805,6 @@ def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: pose.pose.orientation = target_orientation self.set_pose(pose) - def _get_joint_name_to_id_map(self) -> Dict[str, int]: - """ - Creates a dictionary which maps the joint names to their unique ids. - """ - joint_names = self.world.get_joint_names(self) - n_joints = len(joint_names) - return dict(zip(joint_names, range(n_joints))) - - def _get_link_name_to_id_map(self) -> Dict[str, int]: - """ - Creates a dictionary which maps the link names to their unique ids. - """ - link_names = self.world.get_link_names(self) - n_links = len(link_names) - return dict(zip(link_names, range(n_links))) - def get_joint_id(self, name: str) -> int: """ Returns the unique id for a joint name. As used by the world/simulator. @@ -1700,10 +1969,10 @@ def set_color(self, color: Color) -> None: self.world.set_object_color(self, color) def get_color(self) -> Union[Color, Dict[str, Color]]: - return self.world.get_color_of_object(self) + return self.world.get_object_color(self) def get_aabb(self) -> AxisAlignedBoundingBox: - return self.world.get_object_aabb(self) + return self.world.get_object_axis_aligned_bounding_box(self) def get_base_origin(self) -> Pose: """ @@ -1711,7 +1980,7 @@ def get_base_origin(self) -> Pose: :return: The position of the bottom of this Object """ - aabb = self.get_link_by_id(-1).get_aabb() + aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() base_width = np.absolute(aabb.min_x - aabb.max_x) base_length = np.absolute(aabb.min_y - aabb.max_y) return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], @@ -1896,88 +2165,6 @@ def __del__(self): self.remove_constraint_if_exists() -def _load_object(name: str, - path: str, - position: List[float], - orientation: List[float], - world: World, - color: Color, - ignore_cached_files: bool) -> Tuple[int, str]: - """ - Loads an object to the given World with the given position and orientation. The rgba_color will only be - used when an .obj or .stl file is given. - If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created - and this URDf file will be loaded instead. - When spawning a URDf file a new file will be created in the cache directory, if there exists none. - This new file will have resolved mesh file paths, meaning there will be no references - to ROS packges instead there will be absolute file paths. - - :param name: The name of the object which should be spawned - :param path: The path to the source file or the name on the ROS parameter server - :param position: The position in which the object should be spawned - :param orientation: The orientation in which the object should be spawned - :param world: The World to which the Object should be spawned - :param color: The rgba_color of the object, only used when .obj or .stl file is given - :param ignore_cached_files: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path to the file used for spawning - """ - pa = pathlib.Path(path) - extension = pa.suffix - world, world_id = _world_and_id(world) - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for dir in world.data_directory: - path = get_path_from_data_dir(path, dir) - if path: break - - if not path: - raise FileNotFoundError( - f"File {pa.name} could not be found in the resource directory {world.data_directory}") - # rospack = rospkg.RosPack() - # cach_dir = rospack.get_path('pycram') + '/resources/cached/' - cach_dir = world.data_directory[0] + '/cached/' - if not pathlib.Path(cach_dir).exists(): - os.mkdir(cach_dir) - - # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path, name, cach_dir) or ignore_cached_files: - if extension == ".obj" or extension == ".stl": - path = _generate_urdf_file(name, path, color, cach_dir) - elif extension == ".urdf": - with open(path, mode="r") as f: - urdf_string = fix_missing_inertial(f.read()) - urdf_string = remove_error_tags(urdf_string) - urdf_string = fix_link_attributes(urdf_string) - try: - urdf_string = _correct_urdf_string(urdf_string) - except rospkg.ResourceNotFound as e: - rospy.logerr(f"Could not find resource package linked in this URDF") - raise e - path = cach_dir + pa.name - with open(path, mode="w") as f: - f.write(urdf_string) - else: # Using the urdf from the parameter server - urdf_string = rospy.get_param(path) - path = cach_dir + name + ".urdf" - with open(path, mode="w") as f: - f.write(_correct_urdf_string(urdf_string)) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = cach_dir + pa.stem + ".urdf" - elif extension == ".urdf": - path = cach_dir + pa.name - else: - path = cach_dir + name + ".urdf" - - try: - obj = world.load_urdf_and_get_object_id(path, Pose(position, orientation)) - return obj, path - except Exception as e: - logging.error( - "The File could not be loaded. Plese note that the path has to be either a URDF, stl or obj file or the name of an URDF string on the parameter server.") - os.remove(path) - raise (e) - - def _is_cached(path: str, name: str, cach_dir: str) -> bool: """ Checks if the file in the given path is already cached or if diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 474c6f86d..6eff03e2a 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,5 +1,5 @@ from dataclasses import dataclass -from typing import List, Optional, Tuple, Callable +from typing_extensions import List, Optional, Tuple, Callable, Dict from .enums import JointType, Shape @@ -7,12 +7,37 @@ class Color: """ Dataclass for storing rgba_color as an RGBA value. + The values are stored as floats between 0 and 1. + The default rgba_color is white. 'A' stands for the opacity. """ R: float = 1 G: float = 1 B: float = 1 A: float = 1 + @classmethod + def from_list(cls, color: List[float]): + """ + Sets the rgba_color from a list of RGBA values. + + :param color: The list of RGBA values + """ + if len(color) == 3: + return cls.from_rgb(color) + elif len(color) == 4: + return cls.from_rgba(color) + else: + raise ValueError("Color list must have 3 or 4 elements") + + @classmethod + def from_rgb(cls, rgb: List[float]): + """ + Sets the rgba_color from a list of RGB values. + + :param rgb: The list of RGB values + """ + return cls(rgb[0], rgb[1], rgb[2], 1) + @classmethod def from_rgba(cls, rgba: List[float]): """ @@ -235,3 +260,14 @@ class MeshVisualShape(VisualShape): class PlaneVisualShape(VisualShape): shape_data: PlaneShapeData visual_geometry_type = Shape.PLANE + + +@dataclass +class LinkState: + constraint_ids: Dict['Link', int] + + +@dataclass +class ObjectState: + state_id: int + attachments: Dict['Object', 'Attachment'] diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 35fca3d44..f9fc06319 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -29,7 +29,7 @@ def stable(obj: Object) -> bool: :param obj: The object which should be checked :return: True if the given object is stable in the world False else """ - prospection_obj = World.current_world.get_prospection_object_from_object(obj) + prospection_obj = World.current_world.get_prospection_object_for_object(obj) with UseProspectionWorld(): coords_prev = prospection_obj.get_position_as_list() World.current_world.set_gravity([0, 0, -9.8]) @@ -58,8 +58,8 @@ def contact( """ with UseProspectionWorld(): - prospection_obj1 = World.current_world.get_prospection_object_from_object(object1) - prospection_obj2 = World.current_world.get_prospection_object_from_object(object2) + prospection_obj1 = World.current_world.get_prospection_object_for_object(object1) + prospection_obj2 = World.current_world.get_prospection_object_for_object(object2) World.current_world.perform_collision_detection() con_points = World.current_world.get_contact_points_between_two_objects(prospection_obj1, prospection_obj2) @@ -108,9 +108,9 @@ def visible( :return: True if the object is visible from the camera_position False if not """ with UseProspectionWorld(): - prospection_obj = World.current_world.get_prospection_object_from_object(obj) + prospection_obj = World.current_world.get_prospection_object_for_object(obj) if World.robot: - prospection_robot = World.current_world.get_prospection_object_from_object(World.robot) + prospection_robot = World.current_world.get_prospection_object_for_object(World.robot) state_id = World.current_world.save_state() for obj in World.current_world.objects: @@ -176,7 +176,7 @@ def occluding( occluding_obj_ids.append(seg_mask[c[0]][c[1]]) occ_objects = list(set(map(World.current_world.get_object_by_id, occluding_obj_ids))) - occ_objects = list(map(World.current_world.get_object_from_prospection_object, occ_objects)) + occ_objects = list(map(World.current_world.get_object_for_prospection_object, occ_objects)) return occ_objects @@ -198,7 +198,7 @@ def reachable( :return: True if the end effector is closer than the threshold to the target position, False in every other case """ - prospection_robot = World.current_world.get_prospection_object_from_object(robot) + prospection_robot = World.current_world.get_prospection_object_for_object(robot) with UseProspectionWorld(): target_pose = try_to_reach(pose_or_object, prospection_robot, gripper_name) @@ -230,7 +230,7 @@ def blocking( or object is not reachable. """ - prospection_robot = World.current_world.get_prospection_object_from_object(robot) + prospection_robot = World.current_world.get_prospection_object_for_object(robot) with UseProspectionWorld(): if grasp: try_to_reach_with_grasp(pose_or_object, prospection_robot, gripper_name, grasp) @@ -240,7 +240,7 @@ def blocking( block = [] for obj in World.current_world.objects: if contact(prospection_robot, obj): - block.append(World.current_world.get_object_from_prospection_object(obj)) + block.append(World.current_world.get_object_for_prospection_object(obj)) return block @@ -272,7 +272,7 @@ def link_pose_for_joint_config( :param link_name: Name of the link for which the pose should be returned :return: The pose of the link after applying the joint configuration """ - prospection_object = World.current_world.get_prospection_object_from_object(obj) + prospection_object = World.current_world.get_prospection_object_for_object(obj) with UseProspectionWorld(): for joint, pose in joint_config.items(): prospection_object.set_joint_position(joint, pose) From 5e32afdb9ba57a9d6befec2c78087fee1f5e5d9b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Mon, 29 Jan 2024 16:34:45 +0100 Subject: [PATCH 064/195] [designator] removed deprecated motions --- src/pycram/designators/motion_designator.py | 62 --------------- .../process_modules/boxy_process_modules.py | 59 -------------- .../default_process_modules.py | 52 ------------- .../process_modules/pr2_process_modules.py | 77 ------------------- 4 files changed, 250 deletions(-) diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 44b131aa5..31c163e0f 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -118,68 +118,6 @@ def insert(self, session, *args, **kwargs) -> ORMMoveMotion: return motion -@dataclass -class PickUpMotion(BaseMotion): - """ - Lets the robot pick up a specific object - """ - - object_desig: ObjectDesignatorDescription.Object - """ - Object designator describing the object to be picked up - """ - arm: str - """ - Arm that should be used for picking up the object - """ - grasp: str - """ - From which direction the object should be grasped, e.g. 'left', 'front', etc. - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.pick_up().execute(self) - - def to_sql(self) -> ORMMotionDesignator: - pass - - def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: - pass - - -@dataclass -class PlaceMotion(BaseMotion): - """ - Lets the robot place an object that was picked up - """ - - object: ObjectDesignatorDescription.Object - """ - Object designator of the object to be placed - """ - target: Pose - """ - Pose at which the object should be placed - """ - arm: str - """ - Arm that is currently holding the object - """ - - @with_tree - def perform(self): - pm_manager = ProcessModuleManager.get_manager() - return pm_manager.place().execute(self) - - def to_sql(self) -> ORMMotionDesignator: - pass - - def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: - pass - - @dataclass class MoveTCPMotion(BaseMotion): """ diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index a455e6743..9ecd818f0 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -37,55 +37,6 @@ def _execute(self, desig: MoveMotion): robot.set_pose(desig.target) -class BoxyPickUp(ProcessModule): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - - def _execute(self, desig: PickUpMotion): - object = desig.object_desig.bullet_world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - arm = desig.arm - - _move_arm_tcp(target, robot, arm) - tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) - - -class BoxyPlace(ProcessModule): - """ - This process module places an object at the given position in world coordinate frame. - """ - - def _execute(self, desig: PlaceMotion): - """ - - :param desig: A PlaceMotion - :return: - """ - object = desig.object.bullet_world_object - robot = BulletWorld.robot - arm = desig.arm - - # Transformations such that the target position is the position of the object and not the tcp - object_pose = object.get_pose() - local_tf = LocalTransformer() - tcp_to_object = local_tf.transform_pose(object_pose, - robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) - target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() - - _move_arm_tcp(target_diff, robot, arm) - robot.detach(object) - - class BoxyOpen(ProcessModule): """ Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. @@ -251,8 +202,6 @@ class BoxyManager(ProcessModuleManager): def __init__(self): super().__init__("boxy") self._navigate_lock = Lock() - self._pick_up_lock = Lock() - self._place_lock = Lock() self._looking_lock = Lock() self._detecting_lock = Lock() self._move_tcp_lock = Lock() @@ -267,14 +216,6 @@ def navigate(self): if ProcessModuleManager.execution_type == "simulated": return BoxyNavigation(self._navigate_lock) - def pick_up(self): - if ProcessModuleManager.execution_type == "simulated": - return BoxyPickUp(self._pick_up_lock) - - def place(self): - if ProcessModuleManager.execution_type == "simulated": - return BoxyPlace(self._place_lock) - def looking(self): if ProcessModuleManager.execution_type == "simulated": return BoxyMoveHead(self._looking_lock) diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 9705722a4..87bea5cb8 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -23,48 +23,6 @@ def _execute(self, desig: MoveMotion): robot.set_pose(desig.target) -class DefaultPickUp(ProcessModule): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - - def _execute(self, desig: PickUpMotion): - object = desig.object_desig.bullet_world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - arm = desig.arm - - _move_arm_tcp(target, robot, arm) - tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) - - -class DefaultPlace(ProcessModule): - """ - This process module places an object at the given position in world coordinate frame. - """ - - def _execute(self, desig: PlaceMotion): - """ - - :param desig: A PlaceMotion - :return: - """ - object = desig.object.bullet_world_object - robot = BulletWorld.robot - arm = desig.arm - - _move_arm_tcp(desig.target, robot, arm) - robot.detach(object) - - class DefaultMoveHead(ProcessModule): """ This process module moves the head to look at a specific point in the world coordinate frame. @@ -228,8 +186,6 @@ class DefaultManager(ProcessModuleManager): def __init__(self): super().__init__("default") self._navigate_lock = Lock() - self._pick_up_lock = Lock() - self._place_lock = Lock() self._looking_lock = Lock() self._detecting_lock = Lock() self._move_tcp_lock = Lock() @@ -244,14 +200,6 @@ def navigate(self): if ProcessModuleManager.execution_type == "simulated": return DefaultNavigation(self._navigate_lock) - def pick_up(self): - if ProcessModuleManager.execution_type == "simulated": - return DefaultPickUp(self._pick_up_lock) - - def place(self): - if ProcessModuleManager.execution_type == "simulated": - return DefaultPlace(self._place_lock) - def looking(self): if ProcessModuleManager.execution_type == "simulated": return DefaultMoveHead(self._looking_lock) diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 6bdc8d3df..77cc067eb 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -55,54 +55,6 @@ def _execute(self, desig: MoveMotion): robot.set_pose(desig.target) -class Pr2PickUp(ProcessModule): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - - def _execute(self, desig: PickUpMotion): - object = desig.object_desig.bullet_world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - arm = desig.arm - - _move_arm_tcp(target, robot, arm) - tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) - - -class Pr2Place(ProcessModule): - """ - This process module places an object at the given position in world coordinate frame. - """ - - def _execute(self, desig: PlaceMotion): - """ - - :param desig: A PlaceMotion - :return: - """ - object = desig.object.bullet_world_object - robot = BulletWorld.robot - arm = desig.arm - - # Transformations such that the target position is the position of the object and not the tcp - object_pose = object.get_pose() - local_tf = LocalTransformer() - tcp_to_object = local_tf.transform_pose(object_pose, robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) - target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() - - _move_arm_tcp(target_diff, robot, arm) - robot.detach(object) - - class Pr2MoveHead(ProcessModule): """ This process module moves the head to look at a specific point in the world coordinate frame. @@ -271,18 +223,6 @@ def _execute(self, designator: MoveMotion) -> Any: giskard.achieve_cartesian_goal(designator.target, robot_description.base_link, "map") -class Pr2PickUpReal(ProcessModule): - - def _execute(self, designator: PickUpMotion) -> Any: - pass - - -class Pr2PlaceReal(ProcessModule): - - def _execute(self, designator: BaseMotion) -> Any: - pass - - class Pr2MoveHeadReal(ProcessModule): """ Process module for the real robot to move that such that it looks at the given position. Uses the same calculation @@ -339,9 +279,6 @@ def _execute(self, designator: DetectingMotion) -> Any: return bullet_obj[0] - - - class Pr2MoveTCPReal(ProcessModule): """ Moves the tool center point of the real PR2 while avoiding all collisions @@ -434,8 +371,6 @@ class Pr2Manager(ProcessModuleManager): def __init__(self): super().__init__("pr2") self._navigate_lock = Lock() - self._pick_up_lock = Lock() - self._place_lock = Lock() self._looking_lock = Lock() self._detecting_lock = Lock() self._move_tcp_lock = Lock() @@ -452,18 +387,6 @@ def navigate(self): elif ProcessModuleManager.execution_type == "real": return Pr2NavigationReal(self._navigate_lock) - def pick_up(self): - if ProcessModuleManager.execution_type == "simulated": - return Pr2PickUp(self._pick_up_lock) - elif ProcessModuleManager.execution_type == "real": - return Pr2PickUpReal(self._pick_up_lock) - - def place(self): - if ProcessModuleManager.execution_type == "simulated": - return Pr2Place(self._place_lock) - elif ProcessModuleManager.execution_type == "real": - return Pr2PlaceReal(self._place_lock) - def looking(self): if ProcessModuleManager.execution_type == "simulated": return Pr2MoveHead(self._looking_lock) From eace428cd55f1ba1049af6889b13e73d11e5a426 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 30 Jan 2024 17:26:01 +0100 Subject: [PATCH 065/195] [Abstract World] Cleaned Object constructor, added more internal methods to Object class. --- src/pycram/world.py | 209 ++++++++++++++++++++------------------------ 1 file changed, 95 insertions(+), 114 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 6ca2bd4bc..94ac24184 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -67,6 +67,11 @@ class World(ABC): Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ + cach_dir = data_directory[0] + '/cached/' + """ + Global reference for the cache directory, this is used to cache the URDF files of the robot and the objects. + """ + def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequency: float): """ Creates a new simulation, the mode decides if the simulation should be a rendered window or just run in the @@ -390,26 +395,6 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> """ pass - def get_joint_ranges(self) -> Tuple[List, List, List, List, List]: - """ - Calculates the lower and upper limits, the joint ranges and the joint damping. For a given robot Object. - Fixed joints will be skipped because they don't have limits or ranges. - - :return: The lists for the upper and lower limits, joint ranges, rest poses and joint damping - """ - ll, ul, jr, rp, jd = [], [], [], [], [] - joint_names = self.get_joint_names(self.robot) - for name in joint_names: - joint_type = self.get_object_joint_type(self.robot, name) - if joint_type != JointType.FIXED: - ll.append(self.get_object_joint_lower_limit(self.robot, name)) - ul.append(self.get_object_joint_upper_limit(self.robot, name)) - jr.append(ul[-1] - ll[-1]) - rp.append(self.get_joint_rest_pose(self.robot, name)) - jd.append(self.get_joint_damping(self.robot, name)) - - return ll, ul, jr, rp, jd - def get_joint_rest_pose(self, obj: Object, joint_name: str) -> float: """ Get the rest pose of a joint of an articulated object @@ -664,7 +649,7 @@ def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: self.reset_robot() self.join_threads() - def exit_prospection_world_if_exists(self): + def exit_prospection_world_if_exists(self) -> None: """ Exits the prospection world if it exists. """ @@ -673,33 +658,33 @@ def exit_prospection_world_if_exists(self): self.prospection_world.exit() @abstractmethod - def disconnect_from_physics_server(self): + def disconnect_from_physics_server(self) -> None: """ Disconnects the world from the physics server. """ pass - def reset_current_world(self): + def reset_current_world(self) -> None: """ Resets the current world to None if this is the current world. """ if World.current_world == self: World.current_world = None - def reset_robot(self): + def reset_robot(self) -> None: """ Sets the robot class variable to None. """ self.set_robot(None) @abstractmethod - def join_threads(self): + def join_threads(self) -> None: """ Join any running threads. Useful for example when exiting the world. """ pass - def terminate_world_sync(self): + def terminate_world_sync(self) -> None: """ Terminates the world sync thread. """ @@ -718,7 +703,7 @@ def save_state(self) -> int: self.saved_states.append(state_id) return state_id - def save_objects_state(self, state_id: int): + def save_objects_state(self, state_id: int) -> None: """ Saves the state of all objects in the World according to the given state using the unique state id. :param state_id: The unique id representing the state. @@ -747,7 +732,7 @@ def save_physics_simulator_state(self) -> int: pass @abstractmethod - def remove_physics_simulator_state(self, state_id: int): + def remove_physics_simulator_state(self, state_id: int) -> None: """ Removes the state of the physics simulator with the given id. :param state_id: The unique id representing the state. @@ -755,7 +740,7 @@ def remove_physics_simulator_state(self, state_id: int): pass @abstractmethod - def restore_physics_simulator_state(self, state_id: int): + def restore_physics_simulator_state(self, state_id: int) -> None: """ Restores the objects and environment state in the physics simulator according to the given state using the unique state id. @@ -763,7 +748,7 @@ def restore_physics_simulator_state(self, state_id: int): """ pass - def restore_objects_states(self, state_id: int): + def restore_objects_states(self, state_id: int) -> None: """ Restores the state of all objects in the World according to the given state using the unique state id. :param state_id: The unique id representing the state. @@ -866,7 +851,7 @@ def reset_world(self, remove_saved_states=True) -> None: for obj in self.objects: obj.reset(remove_saved_states) - def remove_saved_states(self): + def remove_saved_states(self) -> None: """ Removes all saved states of the World. """ @@ -1134,7 +1119,7 @@ def restore_state(self, state_id: int) -> None: """ self.constraint_ids = self.saved_states[state_id].constraint_ids - def get_current_state(self): + def get_current_state(self) -> LinkState: """ :return: The current state of this link as a LinkState object. """ @@ -1185,7 +1170,7 @@ def is_root(self) -> bool: """ return self.object.get_root_link_id() == self.id - def update_transform(self, transform_time: Optional[rospy.Time] = None): + def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: """ Updates the transformation of this link at the given time. :param transform_time: The time at which the transformation should be updated. @@ -1393,15 +1378,14 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.obj_type: ObjectType = obj_type self.color: Color = color - self.local_transformer = LocalTransformer() - self.original_pose = self.local_transformer.transform_pose(pose, "map") - self._current_pose = self.original_pose + self._init_local_transformer_and_pose(pose) - self.id, self.path = self._load_object(path, ignore_cached_files) + self._load_object_and_set_id_and_path(path, ignore_cached_files) self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) self._init_urdf_object() + if self.urdf_object.name == robot_description.name: self.world.set_robot_if_not_set(self) @@ -1423,7 +1407,16 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.objects.append(self) - def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: + def _init_local_transformer_and_pose(self, pose: Pose) -> None: + """ + Initializes the local transformer and the pose of this object at the given pose and transforms it to the map + frame. + """ + self.local_transformer = LocalTransformer() + self.original_pose = self.local_transformer.transform_pose(pose, "map") + self._current_pose = self.original_pose + + def _load_object_and_set_id_and_path(self, path, ignore_cached_files: bool) -> None: """ Loads an object to the given World with the given position and orientation. The rgba_color will only be used when an .obj or .stl file is given. @@ -1433,9 +1426,7 @@ def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: This new file will have resolved mesh file paths, meaning there will be no references to ROS packges instead there will be absolute file paths. - :param path: The path to the source file or the name on the ROS parameter server :param ignore_cached_files: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path to the file used for spawning """ pa = pathlib.Path(path) extension = pa.suffix @@ -1448,16 +1439,13 @@ def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: if not path: raise FileNotFoundError( f"File {pa.name} could not be found in the resource directory {World.data_directory}") - # rospack = rospkg.RosPack() - # cach_dir = rospack.get_path('pycram') + '/resources/cached/' - cach_dir = World.data_directory[0] + '/cached/' - if not pathlib.Path(cach_dir).exists(): - os.mkdir(cach_dir) + if not pathlib.Path(World.cach_dir).exists(): + os.mkdir(World.cach_dir) # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path, self.name, cach_dir) or ignore_cached_files: + if not _is_cached(path) or ignore_cached_files: if extension == ".obj" or extension == ".stl": - path = _generate_urdf_file(self.name, path, self.color, cach_dir) + path = self._generate_urdf_file(path) elif extension == ".urdf": with open(path, mode="r") as f: urdf_string = fix_missing_inertial(f.read()) @@ -1468,26 +1456,27 @@ def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: except rospkg.ResourceNotFound as e: rospy.logerr(f"Could not find resource package linked in this URDF") raise e - path = cach_dir + pa.name + path = World.cach_dir + pa.name with open(path, mode="w") as f: f.write(urdf_string) else: # Using the urdf from the parameter server urdf_string = rospy.get_param(path) - path = cach_dir + self.name + ".urdf" + path = World.cach_dir + self.name + ".urdf" with open(path, mode="w") as f: f.write(_correct_urdf_string(urdf_string)) # save correct path in case the file is already in the cache directory elif extension == ".obj" or extension == ".stl": - path = cach_dir + pa.stem + ".urdf" + path = World.cach_dir + pa.stem + ".urdf" elif extension == ".urdf": - path = cach_dir + pa.name + path = World.cach_dir + pa.name else: - path = cach_dir + self.name + ".urdf" + path = World.cach_dir + self.name + ".urdf" try: obj_id = self.world.load_urdf_and_get_object_id(path, Pose(self.get_position_as_list(), self.get_orientation_as_list())) - return obj_id, path + self.id = obj_id + self.path = path except Exception as e: logging.error( "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" @@ -1495,7 +1484,42 @@ def _load_object(self, path: str, ignore_cached_files: bool) -> Tuple[int, str]: os.remove(path) raise (e) - def _init_urdf_object(self): + def _generate_urdf_file(self, path) -> str: + """ + Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be + used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with + the name as filename. + + :return: The absolute path of the created file + """ + urdf_template = ' \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + ' + urdf_template = fix_missing_inertial(urdf_template) + rgb = " ".join(list(map(str, self.color.get_rgba()))) + pathlib_obj = pathlib.Path(path) + path = str(pathlib_obj.resolve()) + content = urdf_template.replace("~a", self.name).replace("~b", path).replace("~c", rgb) + with open(World.cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: + file.write(content) + return World.cach_dir + pathlib_obj.stem + ".urdf" + + def _init_urdf_object(self) -> None: """ Initializes the URDF object from the URDF file. """ @@ -1522,7 +1546,7 @@ def _init_link_name_and_id_map(self) -> None: self.link_name_to_id[self.urdf_object.get_root()] = -1 self.link_id_to_name[-1] = self.urdf_object.get_root() - def _init_links(self): + def _init_links(self) -> None: """ Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the corresponding link objects. @@ -2165,29 +2189,6 @@ def __del__(self): self.remove_constraint_if_exists() -def _is_cached(path: str, name: str, cach_dir: str) -> bool: - """ - Checks if the file in the given path is already cached or if - there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from - the parameter server is used. - - :param path: The path given by the user to the source file. - :param name: The name for this object. - :param cach_dir: The absolute path the cach directory in the pycram package. - :return: True if there already exists a chached file, False in any other case. - """ - file_name = pathlib.Path(path).name - full_path = pathlib.Path(cach_dir + file_name) - if full_path.exists(): - return True - # Returns filename without the filetype, e.g. returns "test" for "test.txt" - file_stem = pathlib.Path(path).stem - full_path = pathlib.Path(cach_dir + file_stem + ".urdf") - if full_path.exists(): - return True - return False - - def _correct_urdf_string(urdf_string: str) -> str: """ Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legac) @@ -2273,44 +2274,24 @@ def fix_link_attributes(urdf_string: str) -> str: return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') -def _generate_urdf_file(name: str, path: str, color: Color, cach_dir: str) -> str: +def _is_cached(path) -> bool: """ - Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be - used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with the name - as filename. - - :param name: The name of the object - :param path: The path to the .obj or .stl file - :param color: The rgba_color which should be used for the material tag - :param cach_dir The absolute file path to the cach directory in the pycram package - :return: The absolute path of the created file + Checks if the file in the given path is already cached or if + there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from + the parameter server is used. + + :return: True if there already exists a cached file, False in any other case. """ - urdf_template = ' \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - ' - urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, color.get_rgba()))) - pathlib_obj = pathlib.Path(path) - path = str(pathlib_obj.resolve()) - content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) - with open(cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: - file.write(content) - return cach_dir + pathlib_obj.stem + ".urdf" + file_name = pathlib.Path(path).name + full_path = pathlib.Path(World.cach_dir + file_name) + if full_path.exists(): + return True + # Returns filename without the filetype, e.g. returns "test" for "test.txt" + file_stem = pathlib.Path(path).stem + full_path = pathlib.Path(World.cach_dir + file_stem + ".urdf") + if full_path.exists(): + return True + return False def _world_and_id(world: World) -> Tuple[World, int]: From 2a8d4fa1c9d55525569657e10dbdc6dfcafa44b0 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 31 Jan 2024 10:26:44 +0100 Subject: [PATCH 066/195] [Abstract World] Documented internal functions. --- src/pycram/designators/location_designator.py | 2 +- src/pycram/world.py | 150 +++++++++++++----- 2 files changed, 111 insertions(+), 41 deletions(-) diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 6060d0205..f525593bd 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -336,7 +336,7 @@ def __iter__(self): sem_costmap = SemanticCostmap(self.part_of.world_object, self.urdf_link_name) height_offset = 0 if self.for_object: - min_p, max_p = self.for_object.world_object.get_aabb().get_min_max_points() + min_p, max_p = self.for_object.world_object.get_axis_aligned_bounding_box().get_min_max_points() height_offset = (max_p.z - min_p.z) / 2 for maybe_pose in pose_generator(sem_costmap): maybe_pose.position.z += height_offset diff --git a/src/pycram/world.py b/src/pycram/world.py index 94ac24184..0a859b2a7 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1378,7 +1378,9 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.obj_type: ObjectType = obj_type self.color: Color = color - self._init_local_transformer_and_pose(pose) + self.local_transformer = LocalTransformer() + self.original_pose = self.local_transformer.transform_pose(pose, "map") + self._current_pose = self.original_pose self._load_object_and_set_id_and_path(path, ignore_cached_files) @@ -1407,14 +1409,6 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.objects.append(self) - def _init_local_transformer_and_pose(self, pose: Pose) -> None: - """ - Initializes the local transformer and the pose of this object at the given pose and transforms it to the map - frame. - """ - self.local_transformer = LocalTransformer() - self.original_pose = self.local_transformer.transform_pose(pose, "map") - self._current_pose = self.original_pose def _load_object_and_set_id_and_path(self, path, ignore_cached_files: bool) -> None: """ @@ -1561,9 +1555,10 @@ def _init_links(self) -> None: links[link_name] = Link(link_id, urdf_link, self) self.links = links - def _add_to_world_sync_obj_queue(self, path: str): + def _add_to_world_sync_obj_queue(self, path: str) -> None: """ Adds this object to the objects queue of the WorldSync object of the World. + :param path: The path of the URDF file of this object. """ self.world.world_sync.add_obj_queue.put( [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), @@ -1605,6 +1600,7 @@ def reset(self, remove_saved_states=True) -> None: All attached objects will be detached, all joints will be set to the default position of 0 and the object will be set to the position and orientation in which it was spawned. + :param remove_saved_states: If True the saved states will be removed. """ self.detach_all() self.reset_all_joints_positions() @@ -1734,26 +1730,49 @@ def move_base_to_origin_pos(self) -> None: """ self.set_pose(self.get_pose(), base=True) - def save_state(self, state_id): + def save_state(self, state_id) -> None: + """ + Saves the state of this object by saving the state of all links and attachments. + :param state_id: The unique id of the state. + """ self.save_links_states(state_id) self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) - def save_links_states(self, state_id: int): + def save_links_states(self, state_id: int) -> None: + """ + Saves the state of all links of this object. + :param state_id: The unique id of the state. + """ for link in self.links.values(): link.save_state(state_id) - def restore_state(self, state_id: int): + def restore_state(self, state_id: int) -> None: + """ + Restores the state of this object by restoring the state of all links and attachments. + :param state_id: The unique id of the state. + """ self.restore_links_states(state_id) self.restore_attachments(state_id) - def restore_attachments(self, state_id): + def restore_attachments(self, state_id) -> None: + """ + Restores the attachments of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ self.attachments = self.saved_states[state_id].attachments - def restore_links_states(self, state_id): + def restore_links_states(self, state_id) -> None: + """ + Restores the states of all links of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ for link in self.links.values(): link.restore_state(state_id) - def remove_saved_states(self): + def remove_saved_states(self) -> None: + """ + Removes all saved states of this object. + """ self.saved_states = {} for link in self.links.values(): link.saved_states = {} @@ -1766,7 +1785,8 @@ def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Objec After this the _set_attached_objects method of all attached objects will be called. - :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent loops in the update. + :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent + loops in the update. """ if already_moved_objects is None: @@ -1841,6 +1861,7 @@ def get_joint_id(self, name: str) -> int: def get_root_urdf_link(self) -> urdf_parser_py.urdf.Link: """ Returns the root link of the URDF of this object. + :return: The root link as defined in the URDF of this object. """ link_name = self.urdf_object.get_root() for link in self.urdf_object.links: @@ -1850,15 +1871,22 @@ def get_root_urdf_link(self) -> urdf_parser_py.urdf.Link: def get_root_link(self) -> Link: """ Returns the root link of this object. + :return: The root link of this object. """ return self.links[self.urdf_object.get_root()] def get_root_link_id(self) -> int: + """ + Returns the unique id of the root link of this object. + :return: The unique id of the root link of this object. + """ return self.get_link_id(self.urdf_object.get_root()) def get_link_id(self, link_name: str) -> int: """ Returns a unique id for a link name. + :param link_name: The name of the link. + :return: The unique id of the link. """ assert link_name is not None return self.link_name_to_id[link_name] @@ -1866,6 +1894,8 @@ def get_link_id(self, link_name: str) -> int: def get_link_by_id(self, link_id: int) -> Link: """ Returns the link for a given unique link id + :param link_id: The unique id of the link. + :return: The link object. """ return self.links[self.link_id_to_name[link_id]] @@ -1892,7 +1922,6 @@ def set_positions_of_all_joints(self, joint_poses: dict) -> None: multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. :param joint_poses: - :return: """ for joint_name, joint_position in joint_poses.items(): self.world.reset_joint_position(self, joint_name, joint_position) @@ -1993,16 +2022,20 @@ def set_color(self, color: Color) -> None: self.world.set_object_color(self, color) def get_color(self) -> Union[Color, Dict[str, Color]]: + """ + :return: The rgba_color of this object or a dictionary of link names and their colors. + """ return self.world.get_object_color(self) - def get_aabb(self) -> AxisAlignedBoundingBox: + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis aligned bounding box of this object. + """ return self.world.get_object_axis_aligned_bounding_box(self) def get_base_origin(self) -> Pose: """ - Returns the origin of the base/bottom of an object - - :return: The position of the bottom of this Object + :return: the origin of the base/bottom of this object. """ aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() base_width = np.absolute(aabb.min_x - aabb.max_x) @@ -2070,7 +2103,10 @@ def get_positions_of_all_joints(self) -> Dict[str: float]: """ return self._current_joints_positions - def update_link_transforms(self, transform_time: Optional[rospy.Time] = None): + def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: + """ + Updates the transforms of all links of this object using time 'transform_time' or the current ros time. + """ for link in self.links.values(): link.update_transform(transform_time) @@ -2124,44 +2160,71 @@ def __init__(self, parent_to_child_transform: Optional[Transform] = None, constraint_id: Optional[int] = None): """ - Creates an attachment between the parent object and the child object. + Creates an attachment between the parent object link and the child object link. + This could be a bidirectional attachment, meaning that both objects will move when one moves. + :param parent_link: The parent object link. + :param child_link: The child object link. + :param bidirectional: If true, both objects will move when one moves. + :param parent_to_child_transform: The transform from the parent link to the child object link. + :param constraint_id: The id of the constraint in the simulator. """ - self.parent_link = parent_link - self.child_link = child_link - self.bidirectional = bidirectional - self._loose = False and not bidirectional + self.parent_link: Link = parent_link + self.child_link: Link = child_link + self.bidirectional: bool = bidirectional + self._loose: bool = False and not bidirectional - self.parent_to_child_transform = parent_to_child_transform + self.parent_to_child_transform: Transform = parent_to_child_transform if self.parent_to_child_transform is None: self.update_transform() - self.constraint_id = constraint_id + self.constraint_id: int = constraint_id if self.constraint_id is None: self.add_fixed_constraint() - def update_transform_and_constraint(self): + def update_transform_and_constraint(self) -> None: + """ + Updates the transform and constraint of this attachment. + """ self.update_transform() self.update_constraint() - def update_transform(self): + def update_transform(self) -> None: + """ + Updates the transform of this attachment by calculating the transform from the parent link to the child link. + """ self.parent_to_child_transform = self.calculate_transform() - def update_constraint(self): + def update_constraint(self) -> None: + """ + Updates the constraint of this attachment by removing the old constraint if one exists and adding a new one. + """ self.remove_constraint_if_exists() self.add_fixed_constraint() - def add_fixed_constraint(self): + def add_fixed_constraint(self) -> None: + """ + Adds a fixed constraint between the parent link and the child link. + """ cid = self.parent_link.add_fixed_constraint_with_link(self.child_link) self.constraint_id = cid - def calculate_transform(self): + def calculate_transform(self) -> Transform: + """ + Calculates the transform from the parent link to the child link. + """ return self.parent_link.get_transform_to_link(self.child_link) - def remove_constraint_if_exists(self): + def remove_constraint_if_exists(self) -> None: + """ + Removes the constraint between the parent and the child links if one exists. + """ if self.child_link in self.parent_link.constraint_ids: self.parent_link.remove_constraint_with_link(self.child_link) - def get_inverse(self): + def get_inverse(self) -> Attachment: + """ + :return: A new Attachment object with the parent and child links swapped. + """ attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, constraint_id=self.constraint_id) attachment.loose = False if self.loose else True @@ -2175,17 +2238,24 @@ def loose(self) -> bool: return self._loose @loose.setter - def loose(self, loose: bool): + def loose(self, loose: bool) -> None: + """ + Sets the loose property of this attachment. + :param loose: If true, then the child object will not move when parent moves. + """ self._loose = loose and not self.bidirectional @property def is_reversed(self) -> bool: """ - If true means that when child moves, parent moves not the other way around. + :return: True if the parent and child links are swapped. """ return self.loose - def __del__(self): + def __del__(self) -> None: + """ + Removes the constraint between the parent and the child links if one exists when the attachment is deleted. + """ self.remove_constraint_if_exists() From efdf22a2599268c98b8eb07722e288a2abbd10da Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 31 Jan 2024 19:40:36 +0100 Subject: [PATCH 067/195] [Abstract World] Removed all mentions and dependencies of bullet world and pybullet from all places except bullet_world.py Applied some cleaning and removed duplications. Added extra functionallity to World class like force torque sensor. --- src/pycram/bullet_world.py | 2 +- src/pycram/costmaps.py | 50 ++-- src/pycram/designator.py | 44 ++-- src/pycram/designators/action_designator.py | 2 +- src/pycram/designators/location_designator.py | 2 +- src/pycram/designators/motion_designator.py | 50 ++-- src/pycram/designators/object_designator.py | 4 +- src/pycram/event.py | 2 +- src/pycram/external_interfaces/giskard.py | 47 ++-- src/pycram/external_interfaces/ik.py | 22 +- src/pycram/external_interfaces/knowrob.py | 2 +- src/pycram/external_interfaces/robokudo.py | 8 +- src/pycram/fluent.py | 2 +- src/pycram/helper.py | 4 +- src/pycram/language.py | 2 +- src/pycram/local_transformer.py | 6 +- src/pycram/orm/action_designator.py | 2 +- src/pycram/orm/base.py | 3 +- src/pycram/orm/motion_designator.py | 2 +- src/pycram/orm/task.py | 2 +- src/pycram/pose.py | 4 +- src/pycram/pose_generator_and_validator.py | 45 ++-- src/pycram/process_module.py | 53 +++-- .../process_modules/boxy_process_modules.py | 215 ++---------------- .../default_process_modules.py | 194 ++-------------- .../process_modules/donbot_process_modules.py | 103 +++------ .../process_modules/hsr_process_modules.py | 9 +- .../process_modules/pr2_process_modules.py | 153 +++++++------ .../resolver/location/giskard_location.py | 8 +- src/pycram/resolver/location/jpt_location.py | 52 ++--- src/pycram/robot_description.py | 2 +- src/pycram/ros/force_torque_sensor.py | 15 +- src/pycram/ros/joint_state_publisher.py | 15 +- src/pycram/ros/robot_state_updater.py | 28 +-- src/pycram/ros/tf_broadcaster.py | 12 +- src/pycram/ros/viz_marker_publisher.py | 9 +- src/pycram/task.py | 18 +- src/pycram/world.py | 121 ++++++++-- src/pycram/world_dataclasses.py | 64 ++---- src/pycram/world_reasoning.py | 11 +- 40 files changed, 529 insertions(+), 860 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 82e57c3b8..d268d37f4 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -3,7 +3,7 @@ import threading import time -from typing import List, Optional, Dict, Tuple +from typing_extensions import List, Optional, Dict, Tuple import numpy as np import pybullet as p diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index c56812631..aac666802 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -1,7 +1,7 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations -from typing import Tuple, List, Optional +from typing_extensions import Tuple, List, Optional import matplotlib.pyplot as plt import numpy as np @@ -14,7 +14,7 @@ from .local_transformer import LocalTransformer from .pose import Pose, Transform from .world import World -from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, BoxShapeData, MultiBody, Color, JointType +from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color class Costmap: @@ -54,8 +54,7 @@ def __init__(self, resolution: float, def visualize(self) -> None: """ Visualizes a costmap in the World, the visualisation works by - subdividing the costmap in rectangles which are then visualized as pybullet - visual shapes. + subdividing the costmap in rectangles which are then visualized as world visual shapes. """ if self.vis_ids: return @@ -75,43 +74,26 @@ def visualize(self) -> None: map[i:i + curr_height, j:j + curr_width] = 0 cells = [] # Creation of the visual shapes, for documentation of the visual shapes - # please look here: https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.q1gn7v6o58bf + # please look here: + # https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.q1gn7v6o58bf for box in boxes: - box_shape_data = BoxShapeData([(box[1] * self.resolution) / 2, (box[2] * self.resolution) / 2, 0.001]) - visual_frame_position = [(box[0][0] + box[1] / 2) * self.resolution, - (box[0][1] + box[2] / 2) * self.resolution, 0.] - visual_shape = BoxVisualShape(Color(1, 0, 0, 0.6), visual_frame_position, box_shape_data) + visual_shape = BoxVisualShape(Color(1, 0, 0, 0.6), + visual_frame_position=[(box[0][0] + box[1] / 2) * self.resolution, + (box[0][1] + box[2] / 2) * self.resolution, 0.], + half_extents=[(box[1] * self.resolution) / 2, + (box[2] * self.resolution) / 2, 0.001]) visual = self.world.create_visual_shape(visual_shape) cells.append(visual) # Set to 127 for since this is the maximal amount of links in a multibody for cell_parts in self._chunks(cells, 127): - # Dummy paramater since these are needed to spawn visual shapes as a - # multibody. - link_poses = [[0, 0, 0] for c in cell_parts] - link_orientations = [[0, 0, 0, 1] for c in cell_parts] - link_masses = [1.0 for c in cell_parts] - link_parent = [0 for c in cell_parts] - link_joints = [JointType.FIXED for c in cell_parts] - link_collision = [-1 for c in cell_parts] - link_joint_axis = [[1, 0, 0] for c in cell_parts] - offset = Transform([-self.height / 2 * self.resolution, -self.width / 2 * self.resolution, 0.05], [0, 0, 0, 1]) origin = Transform(self.origin.position_as_list(), self.origin.orientation_as_list()) new_transform = origin * offset new_pose = new_transform.to_pose().to_list() - multi_body = MultiBody(base_visual_shape_index=-1, base_position=new_pose[0], base_orientation=new_pose[1], - link_visual_shape_indices=cell_parts, link_positions=link_poses, - link_orientations=link_orientations, link_masses=link_masses, - link_inertial_frame_positions=link_poses, - link_inertial_frame_orientations=link_orientations, - link_parent_indices=link_parent, link_joint_types=link_joints, - link_joint_axis=link_joint_axis, - link_collision_shape_indices=link_collision) - - map_obj = self.world.create_multi_body(multi_body) + map_obj = self.world.create_multi_body_from_visual_shapes(cell_parts, Pose(*new_pose)) self.vis_ids.append(map_obj) def _chunks(self, lst: List, n: int) -> List: @@ -130,7 +112,7 @@ def close_visualization(self) -> None: Removes the visualization from the World. """ for v_id in self.vis_ids: - self.world.remove_object(v_id) + self.world.remove_object(self.world.get_object_by_id(v_id)) self.vis_ids = [] def _find_consectuive_line(self, start: Tuple[int, int], map: np.ndarray) -> int: @@ -266,7 +248,7 @@ def __init__(self, distance_to_obstacle: float, self.origin = Pose() if not origin else origin self.resolution = resolution self.distance_obstacle = max(int(distance_to_obstacle / self.resolution), 1) - self.map = self._create_from_bullet(size, resolution) + self.map = self._create_from_world(size, resolution) Costmap.__init__(self, resolution, size, size, self.origin, self.map) def _calculate_diff_origin(self, height: int, width: int) -> Pose: @@ -361,7 +343,7 @@ def create_sub_map(self, sub_origin: Pose, size: int) -> Costmap: sub_map = np.rot90(np.flip(self._convert_map(sub_map), 0)) return Costmap(self.resolution, size, size, Pose(list(sub_origin * -1)), sub_map) - def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: + def _create_from_world(self, size: int, resolution: float) -> np.ndarray: """ Creates an Occupancy Costmap for the specified World. This map marks every position as valid that has no object above it. After @@ -382,7 +364,7 @@ def _create_from_bullet(self, size: int, resolution: float) -> np.ndarray: rays = np.dstack(np.dstack((indices_0, indices_10))).T res = np.zeros(len(rays)) - # Using the PyBullet rayTest to check if there is an object above the position + # Using the World rayTest to check if there is an object above the position # if there is no object the position is marked as valid # 16383 is the maximal number of rays that can be processed in a batch i = 0 @@ -520,7 +502,7 @@ def _create_images(self) -> List[np.ndarray]: def _depth_buffer_to_meter(self, buffer: np.ndarray) -> np.ndarray: """ - Converts the depth images generated by PyBullet to represent + Converts the depth images generated by the World to represent each position in metre. :return: The depth image in metre diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 8f5c70a8a..a22f51a74 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -12,12 +12,13 @@ from .helper import GeneratorList, bcolors from threading import Lock from time import time -from typing import List, Dict, Any, Type, Optional, Union, get_type_hints, Callable, Tuple, Iterable +from typing_extensions import List, Dict, Any, Optional, Union, get_type_hints, Callable, Iterable from .local_transformer import LocalTransformer from .language import Language from .pose import Pose from .robot_descriptions import robot_description +from .enums import ObjectType import logging @@ -25,7 +26,7 @@ from .orm.object_designator import (Object as ORMObjectDesignator) from .orm.motion_designator import (Motion as ORMMotionDesignator) -from .orm.base import Quaternion, Position, Base, RobotState, ProcessMetaData +from .orm.base import RobotState, ProcessMetaData from .task import with_tree @@ -72,11 +73,11 @@ class Designator(ABC): argument and return a list of solutions. A solution can also be a generator. """ - def __init__(self, description: Type[DesignatorDescription], parent: Optional[Designator] = None): + def __init__(self, description: DesignatorDescription, parent: Optional[Designator] = None): """Create a new desginator. Arguments: - :param properties: A list of tuples (key-value pairs) describing this designator. + :param description: A list of tuples (key-value pairs) describing this designator. :param parent: The parent to equate with (default is None). """ self._mutex: Lock = Lock() @@ -87,7 +88,7 @@ def __init__(self, description: Type[DesignatorDescription], parent: Optional[De self._solutions = None self._index: int = 0 self.timestamp = None - self._description: Type[DesignatorDescription] = description + self._description: DesignatorDescription = description if parent is not None: self.equate(parent) @@ -358,7 +359,7 @@ def get_slots(self) -> List[str]: """ return list(self.__dict__.keys()) - def copy(self) -> Type[DesignatorDescription]: + def copy(self) -> DesignatorDescription: return self @@ -432,7 +433,8 @@ def get_slots(self): """ return list(self.__dict__.keys()).remove('cmd') - def _check_properties(self, desig: str, exclude: List[str] = []) -> None: + # TODO: Not used anymore, remove? + def _check_properties(self, desig: str, exclude: List[str] = None) -> None: """ Checks the properties of this description. It will be checked if any attribute is None and if any attribute has to wrong type according to the type hints in @@ -443,6 +445,7 @@ def _check_properties(self, desig: str, exclude: List[str] = []) -> None: Exception as output. :param exclude: A list of properties which should not be checked. """ + exclude = exclude if exclude else [] right_types = get_type_hints(self.Motion) attributes = self.__dict__.copy() del attributes["resolve"] @@ -479,7 +482,7 @@ class Action: The torso height of the robot at the start of the action. """ - robot_type: str = dataclasses.field(init=False) + robot_type: ObjectType = dataclasses.field(init=False) """ The type of the robot at the start of the action. """ @@ -605,7 +608,7 @@ class Object: Name of the object """ - obj_type: str + obj_type: ObjectType """ Type of the object """ @@ -715,26 +718,7 @@ def special_knowledge_adjustment_pose(self, grasp: str, pose: Pose) -> Pose: return pose_in_object return pose - # def special_knowledge(self, grasp, pose): - # """ - # Returns t special knowledge for "grasp front". - # """ - # - # special_knowledge = [] # Initialize as an empty list - # if self.type in SPECIAL_KNOWLEDGE: - # special_knowledge = SPECIAL_KNOWLEDGE[self.type] - # - # for key, value in special_knowledge: - # if key == grasp: - # # Adjust target pose based on special knowledge - # pose.pose.position.x += value[0] - # pose.pose.position.y += value[1] - # pose.pose.position.z += value[2] - # print("Adjusted target pose based on special knowledge for grasp: ", grasp) - # return pose - # return pose - - def __init__(self, names: Optional[List[str]] = None, types: Optional[List[str]] = None, + def __init__(self, names: Optional[List[str]] = None, types: Optional[List[ObjectType]] = None, resolver: Optional[Callable] = None): """ Base of all object designator descriptions. Every object designator has the name and type of the object. @@ -744,7 +728,7 @@ def __init__(self, names: Optional[List[str]] = None, types: Optional[List[str]] :param resolver: An alternative resolver that returns an object designator for the list of names and types """ super().__init__(resolver) - self.types: Optional[List[str]] = types + self.types: Optional[List[ObjectType]] = types self.names: Optional[List[str]] = names def ground(self) -> Union[Object, bool]: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 142b21bdf..beea5f255 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -1,5 +1,5 @@ import itertools -from typing import Any, Union +from typing_extensions import Any, Union import sqlalchemy.orm diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index f525593bd..4b2a0a931 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -1,5 +1,5 @@ import dataclasses -from typing import List, Union, Iterable, Optional, Callable +from typing_extensions import List, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart from ..world import World, UseProspectionWorld diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 247f1d508..4efa64e49 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -2,20 +2,19 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..world import Object -from pycram.bullet_world import BulletWorld +from ..world import Object, World from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager from ..robot_descriptions import robot_description from ..designator import MotionDesignatorDescription -from ..orm.motion_designator import (MoveMotion as ORMMoveMotion, AccessingMotion as ORMAccessingMotion, +from ..orm.motion_designator import (MoveMotion as ORMMoveMotion, MoveTCPMotion as ORMMoveTCPMotion, LookingMotion as ORMLookingMotion, MoveGripperMotion as ORMMoveGripperMotion, DetectingMotion as ORMDetectingMotion, - WorldStateDetectingMotion as ORMWorldStateDetectingMotion, OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion) +from ..enums import ObjectType -from typing import List, Dict, Callable, Optional +from typing_extensions import List, Dict, Callable, Optional from ..pose import Pose from ..task import with_tree @@ -231,7 +230,8 @@ def __init__(self, target: Pose, arm: Optional[str] = None, :param target: Target pose for the TCP :param arm: Arm that should be moved :param resolver: Alternative resolver which returns a resolved motion designator - :param allow_gripper_collision: If the gripper should be allowed to collide with something, only used on the real robot + :param allow_gripper_collision: If the gripper should be allowed to collide with something, + only used on the real robot """ super().__init__(resolver) self.cmd: str = 'move-tcp' @@ -278,25 +278,25 @@ def insert(self, session: Session, *args, **kwargs) -> ORMLookingMotion: return motion - def __init__(self, target: Optional[Pose] = None, object: Optional[ObjectDesignatorDescription.Object] = None, + def __init__(self, target: Optional[Pose] = None, obj: Optional[ObjectDesignatorDescription.Object] = None, resolver: Optional[Callable] = None): """ Moves the head of the robot such that the camera points towards the given location. If ``target`` and ``object`` are given ``target`` will be preferred. :param target: Position and orientation of the target - :param object: An Object in the BulletWorld + :param obj: An Object in the World :param resolver: Alternative resolver that returns a resolved motion designator for parameter """ super().__init__(resolver) self.cmd: str = 'looking' self.target: Optional[Pose] = target - self.object: Object = object.world_object if object else object + self.object: Object = obj.world_object if obj else obj def ground(self) -> Motion: """ - Default resolver for looking, chooses which pose to take if ``target`` and ``object`` are given. If both are given - ``target`` will be preferred. + Default resolver for looking, chooses which pose to take if ``target`` and ``object`` are given. + If both are given ``target`` will be preferred. :return: A resolved motion designator """ @@ -373,7 +373,7 @@ class DetectingMotion(MotionDesignatorDescription): @dataclasses.dataclass class Motion(MotionDesignatorDescription.Motion): # cmd: str - object_type: str + object_type: ObjectType """ Type of the object that should be detected """ @@ -381,16 +381,16 @@ class Motion(MotionDesignatorDescription.Motion): @with_tree def perform(self): pm_manager = ProcessModuleManager.get_manager() - bullet_world_object = pm_manager.detecting().execute(self) - if not bullet_world_object: + world_object = pm_manager.detecting().execute(self) + if not world_object: raise PerceptionObjectNotFound( f"Could not find an object with the type {self.object_type} in the FOV of the robot") if ProcessModuleManager.execution_type == "real": - return RealObject.Object(bullet_world_object.name, bullet_world_object.obj_type, - bullet_world_object, bullet_world_object.get_pose()) + return RealObject.Object(world_object.name, world_object.obj_type, + world_object, world_object.get_pose()) - return ObjectDesignatorDescription.Object(bullet_world_object.name, bullet_world_object.obj_type, - bullet_world_object) + return ObjectDesignatorDescription.Object(world_object.name, world_object.obj_type, + world_object) def to_sql(self) -> ORMDetectingMotion: return ORMDetectingMotion(self.object_type) @@ -401,7 +401,7 @@ def insert(self, session: Session, *args, **kwargs) -> ORMDetectingMotion: session.commit() return motion - def __init__(self, object_type: str, resolver: Optional[Callable] = None): + def __init__(self, object_type: ObjectType, resolver: Optional[Callable] = None): """ Checks for every object in the FOV of the robot if it fits the given object type. If the types match an object designator describing the object will be returned. @@ -411,7 +411,7 @@ def __init__(self, object_type: str, resolver: Optional[Callable] = None): """ super().__init__(resolver) self.cmd: str = 'detecting' - self.object_type: str = object_type + self.object_type: ObjectType = object_type def ground(self) -> Motion: """ @@ -504,7 +504,7 @@ def perform(self): def __init__(self, object_type: str, resolver: Optional[Callable] = None): """ - Tries to find an object using the belief state (BulletWorld), if there is an object in the belief state matching + Tries to find an object using the belief state (World), if there is an object in the belief state matching the given object type an object designator will be returned. :param object_type: The object type which should be detected @@ -568,10 +568,11 @@ def ground(self) -> Motion: if len(self.names) != len(self.positions): raise DesignatorError("[Motion Designator][Move Joints] The length of names and positions does not match") for i in range(len(self.names)): - lower, upper = BulletWorld.robot.get_joint_limits(self.names[i]) + lower, upper = World.robot.get_joint_limits(self.names[i]) if self.positions[i] < lower or self.positions[i] > upper: raise DesignatorError( - f"[Motion Designator][Move Joints] The given configuration for the Joint {self.names[i]} violates its limits") + f"[Motion Designator][Move Joints] The given configuration for the Joint {self.names[i]}" + f" violates its limits") return self.Motion(self.cmd, self.names, self.positions) @@ -672,7 +673,8 @@ def insert(self, session: Session, *args, **kwargs) -> ORMClosingMotion: def __init__(self, object_part: ObjectPart.Object, arm: str, resolver: Optional[Callable] = None): """ - Lets the robot close a container specified by the given parameter. This assumes that the handle is already grasped + Lets the robot close a container specified by the given parameter. This assumes that the handle is already + grasped. :param object_part: Object designator describing the handle of the drawer :param arm: Arm that should be used diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index d7d28507a..e52be0235 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,7 +1,7 @@ import dataclasses -from typing import List, Optional, Callable +from typing_extensions import List, Optional, Callable import sqlalchemy.orm -from pycram.world import World, Object as WorldObject +from ..world import World, Object as WorldObject from ..designator import ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) diff --git a/src/pycram/event.py b/src/pycram/event.py index 7b52b4a44..462e3180f 100644 --- a/src/pycram/event.py +++ b/src/pycram/event.py @@ -1,7 +1,7 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations -from typing import Callable, List, Optional, Any +from typing_extensions import Callable, List, Optional, Any class Event: diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index a5d921de5..25e9bc833 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -11,11 +11,10 @@ from ..pose import Pose from ..robot_descriptions import robot_description -from ..bullet_world import BulletWorld -from pycram.world import Object +from ..world import World, Object from ..robot_description import ManipulatorDescription -from typing import List, Tuple, Dict, Callable, Optional +from typing_extensions import List, Tuple, Dict, Callable, Optional from geometry_msgs.msg import PoseStamped, PointStamped, QuaternionStamped, Vector3Stamped from threading import Lock, RLock @@ -96,11 +95,11 @@ def wrapper(*args, **kwargs): @init_giskard_interface def initial_adding_objects() -> None: """ - Adds object that are loaded in the BulletWorld to the Giskard belief state, if they are not present at the moment. + Adds object that are loaded in the World to the Giskard belief state, if they are not present at the moment. """ groups = giskard_wrapper.get_group_names() - for obj in BulletWorld.current_world.objects: - if obj is BulletWorld.robot: + for obj in World.current_world.objects: + if obj is World.robot: continue name = obj.name + "_" + str(obj.id) if name not in groups: @@ -110,11 +109,11 @@ def initial_adding_objects() -> None: @init_giskard_interface def removing_of_objects() -> None: """ - Removes objects that are present in the Giskard belief state but not in the BulletWorld from the Giskard belief state. + Removes objects that are present in the Giskard belief state but not in the World from the Giskard belief state. """ groups = giskard_wrapper.get_group_names() object_names = list( - map(lambda obj: object_names.name + "_" + str(obj.id), BulletWorld.current_world.objects)) + map(lambda obj: object_names.name + "_" + str(obj.id), World.current_world.objects)) diff = list(set(groups) - set(object_names)) for grp in diff: giskard_wrapper.remove_group(grp) @@ -123,19 +122,19 @@ def removing_of_objects() -> None: @init_giskard_interface def sync_worlds() -> None: """ - Synchronizes the BulletWorld and the Giskard belief state, this includes adding and removing objects to the Giskard - belief state such that it matches the objects present in the BulletWorld and moving the robot to the position it is - currently at in the BulletWorld. + Synchronizes the World and the Giskard belief state, this includes adding and removing objects to the Giskard + belief state such that it matches the objects present in the World and moving the robot to the position it is + currently at in the World. """ add_gripper_groups() - bullet_object_names = set() - for obj in BulletWorld.current_world.objects: + world_object_names = set() + for obj in World.current_world.objects: if obj.name != robot_description.name and len(obj.link_name_to_id) != 1: - bullet_object_names.add(obj.name + "_" + str(obj.id)) + world_object_names.add(obj.name + "_" + str(obj.id)) giskard_object_names = set(giskard_wrapper.get_group_names()) robot_name = {robot_description.name} - if not bullet_object_names.union(robot_name).issubset(giskard_object_names): + if not world_object_names.union(robot_name).issubset(giskard_object_names): giskard_wrapper.clear_world() initial_adding_objects() @@ -155,9 +154,9 @@ def update_pose(object: Object) -> 'UpdateWorldResponse': @init_giskard_interface def spawn_object(object: Object) -> None: """ - Spawns a BulletWorld Object in the giskard belief state. + Spawns a World Object in the giskard belief state. - :param object: BulletWorld object that should be spawned + :param object: World object that should be spawned """ if len(object.link_name_to_id) == 1: geometry = object.urdf_object.link_map[object.urdf_object.get_root()].collision.geometry @@ -173,7 +172,7 @@ def remove_object(object: Object) -> 'UpdateWorldResponse': """ Removes an object from the giskard belief state. - :param object: The BulletWorld Object that should be removed + :param object: The World Object that should be removed """ return giskard_wrapper.remove_group(object.name + "_" + str(object.id)) @@ -240,7 +239,7 @@ def _manage_par_motion_goals(goal_func, *args) -> Optional['MoveResult']: if "tip_link" in par_value_pair.keys() and "root_link" in par_value_pair.keys(): if par_value_pair["tip_link"] == robot_description.base_link: continue - chain = BulletWorld.robot.urdf_object.get_chain(par_value_pair["root_link"], + chain = World.robot.urdf_object.get_chain(par_value_pair["root_link"], par_value_pair["tip_link"]) if set(chain).intersection(used_joints) != set(): giskard_wrapper.cmd_seq = tmp @@ -530,8 +529,8 @@ def avoid_collisions(object1: Object, object2: Object) -> None: """ Will avoid collision between the two objects for the next goal. - :param object1: The first BulletWorld Object - :param object2: The second BulletWorld Object + :param object1: The first World Object + :param object2: The second World Object """ giskard_wrapper.avoid_collision(-1, object1.name + "_" + str(object1.id), object2.name + "_" + str(object2.id)) @@ -541,10 +540,10 @@ def avoid_collisions(object1: Object, object2: Object) -> None: @init_giskard_interface def make_world_body(object: Object) -> 'WorldBody': """ - Creates a WorldBody message for a BulletWorld Object. The WorldBody will contain the URDF of the BulletWorld Object + Creates a WorldBody message for a World Object. The WorldBody will contain the URDF of the World Object - :param object: The BulletWorld Object - :return: A WorldBody message for the BulletWorld Object + :param object: The World Object + :return: A WorldBody message for the World Object """ urdf_string = "" with open(object.path) as f: diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index b7d1fb50b..48657fa97 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -1,6 +1,5 @@ -from typing import List, Union +from typing_extensions import List, Union -import pybullet as p import rospy from moveit_msgs.msg import PositionIKRequest from moveit_msgs.msg import RobotState @@ -10,26 +9,11 @@ from ..world import Object from ..helper import calculate_wrist_tool_offset, _apply_ik from ..local_transformer import LocalTransformer -from ..pose import Pose, Transform +from ..pose import Pose from ..robot_descriptions import robot_description from ..plan_failures import IKError -def _get_position_for_joints(robot, joints): - """ - Returns a list with all joint positions for the joint names specified in - the joints parameter - - :param robot: The robot the joint states should be taken from - :param joints: The list of joint names that should be in the output - :return: A list of joint states according and in the same order as the joint - names in the joints parameter - """ - return list( - map(lambda x: p.getJointState(robot.id, robot.get_joint_id(x), physicsClientId=robot.world.client_id)[0], - joints)) - - def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_object: Object, joints: List[str]) -> PositionIKRequest: """ @@ -50,7 +34,7 @@ def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_ob robot_state = RobotState() joint_state = JointState() joint_state.name = joints - joint_state.position = _get_position_for_joints(robot_object, joints) + joint_state.position = [robot_object.get_joint_position(joint) for joint in joints] # joint_state.velocity = [0.0 for x in range(len(joints))] # joint_state.effort = [0.0 for x in range(len(joints))] robot_state.joint_state = joint_state diff --git a/src/pycram/external_interfaces/knowrob.py b/src/pycram/external_interfaces/knowrob.py index 3b9372b1b..9bd5055b6 100644 --- a/src/pycram/external_interfaces/knowrob.py +++ b/src/pycram/external_interfaces/knowrob.py @@ -3,7 +3,7 @@ import sys import rosservice -from typing import Dict, List, Union +from typing_extensions import Dict, List, Union SCRIPT_DIR = os.path.abspath(os.path.dirname(__file__)) sys.path.append(os.path.join(SCRIPT_DIR, os.pardir, os.pardir, "neem-interface", "src")) diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index fbfad9b5a..4ecc35085 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -1,5 +1,5 @@ import sys -from typing import Callable +from typing_extensions import Callable import rosnode import rospy @@ -9,7 +9,7 @@ from ..designator import ObjectDesignatorDescription from ..pose import Pose from ..local_transformer import LocalTransformer -from ..bullet_world import BulletWorld +from ..world import World from ..enums import ObjectType try: @@ -99,7 +99,7 @@ def make_query_goal_msg(obj_desc: ObjectDesignatorDescription) -> 'QueryGoal': """ goal_msg = QueryGoal() goal_msg.obj.uid = str(id(obj_desc)) - goal_msg.obj.obj_type = str(obj_desc.types[0].name) # For testing purposes + goal_msg.obj.obj_type = str(obj_desc.types[0].name) # For testing purposes if ObjectType.JEROEN_CUP == obj_desc.types[0]: goal_msg.obj.color.append("blue") elif ObjectType.BOWL == obj_desc.types[0]: @@ -125,7 +125,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti for i in range(0, len(query_result.res[0].pose)): pose = Pose.from_pose_stamped(query_result.res[0].pose[i]) - pose.frame = BulletWorld.current_world.robot.links[pose.frame].tf_frame # TODO: pose.frame is a link name? + pose.frame = World.current_world.robot.links[pose.frame].tf_frame # TODO: pose.frame is a link name? source = query_result.res[0].poseSource[i] lt = LocalTransformer() diff --git a/src/pycram/fluent.py b/src/pycram/fluent.py index a8f2f3ef2..89706e3c8 100644 --- a/src/pycram/fluent.py +++ b/src/pycram/fluent.py @@ -16,7 +16,7 @@ from enum import Enum from threading import Condition, Lock from uuid import uuid4 -from typing import Any, Optional, List, Callable +from typing_extensions import Any, Optional, List, Callable class Behavior(Enum): diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 0ade114bc..61ab85e59 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -7,15 +7,13 @@ GeneratorList -- implementation of generator list wrappers. """ from inspect import isgeneratorfunction -from typing import List -from typing import Tuple, Callable +from typing_extensions import List, Tuple, Callable import numpy as np from pytransform3d.rotations import quaternion_wxyz_from_xyzw, quaternion_xyzw_from_wxyz from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform from .world import Object as WorldObject -from .local_transformer import LocalTransformer from .pose import Transform, Pose import math diff --git a/src/pycram/language.py b/src/pycram/language.py index 081ba0cbe..80948cc8d 100644 --- a/src/pycram/language.py +++ b/src/pycram/language.py @@ -2,7 +2,7 @@ from __future__ import annotations import time -from typing import Iterable, Optional, Callable, Dict, Any, List, Union +from typing_extensions import Iterable, Optional, Callable, Dict, Any, List, Union from anytree import NodeMixin, Node, PreOrderIter, RenderTree from .enums import State diff --git a/src/pycram/local_transformer.py b/src/pycram/local_transformer.py index ebbe4e64d..3ea74dea2 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -10,7 +10,7 @@ from geometry_msgs.msg import TransformStamped from .pose import Pose, Transform -from typing import List, Optional, Union, Iterable +from typing_extensions import List, Optional, Union, Iterable class LocalTransformer(TransformerROS): @@ -22,7 +22,7 @@ class LocalTransformer(TransformerROS): This class uses the robots (currently only one! supported) URDF file to initialize the tfs for the robot. Moreover, the function update_local_transformer_from_btr - updates these tfs by copying the tfs state from the pybullet world. + updates these tfs by copying the tfs state from the world. This class extends the TransformerRos, you can find documentation for TransformerROS here: `TFDoc `_ @@ -47,7 +47,7 @@ def __init__(self): self.tf_stampeds: List[TransformStamped] = [] self.static_tf_stampeds: List[TransformStamped] = [] - # Since this file can't import world.py this holds the reference to the current_bullet_world + # Since this file can't import world.py this holds the reference to the current_world self.world = None # TODO: Ask Jonas if this is still needed self.prospection_world = None diff --git a/src/pycram/orm/action_designator.py b/src/pycram/orm/action_designator.py index 48b4197a3..d27642cf7 100644 --- a/src/pycram/orm/action_designator.py +++ b/src/pycram/orm/action_designator.py @@ -1,4 +1,4 @@ -from typing import Optional +from typing_extensions import Optional from .base import RobotState, Designator, MapperArgsMixin, PoseMixin from .object_designator import ObjectMixin diff --git a/src/pycram/orm/base.py b/src/pycram/orm/base.py index cc6356d5e..407270a17 100644 --- a/src/pycram/orm/base.py +++ b/src/pycram/orm/base.py @@ -1,8 +1,7 @@ """Implementation of base classes for orm modelling.""" import datetime import getpass -import os -from typing import Optional +from typing_extensions import Optional import git import rospkg diff --git a/src/pycram/orm/motion_designator.py b/src/pycram/orm/motion_designator.py index fb2e5d322..44624d33d 100644 --- a/src/pycram/orm/motion_designator.py +++ b/src/pycram/orm/motion_designator.py @@ -5,7 +5,7 @@ The MotionDesignator class is the base class that defines the polymorphic behavior of all other motion designator classes. """ -from typing import Optional +from typing_extensions import Optional from .base import MapperArgsMixin, Designator, PoseMixin from .object_designator import Object, ObjectMixin diff --git a/src/pycram/orm/task.py b/src/pycram/orm/task.py index 5d2152c1f..333bd5d8e 100644 --- a/src/pycram/orm/task.py +++ b/src/pycram/orm/task.py @@ -1,5 +1,5 @@ """Implementation of ORM classes associated with pycram.task.""" -from typing import Optional +from typing_extensions import Optional from sqlalchemy import ForeignKey from sqlalchemy.orm import MappedAsDataclass, Mapped, mapped_column, relationship from .action_designator import Action diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 8cdd39d11..08987ae90 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -1,17 +1,15 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations -import copy import math import datetime -from typing import List, Union, Optional +from typing_extensions import List, Union, Optional import numpy as np import rospy import sqlalchemy.orm from geometry_msgs.msg import PoseStamped, TransformStamped, Vector3, Point from geometry_msgs.msg import (Pose as GeoPose, Quaternion as GeoQuaternion) -from std_msgs.msg import Header from tf import transformations from .orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 131d87124..6f14c7a46 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -1,8 +1,7 @@ import tf import numpy as np -from .world import Object -from .bullet_world import World +from .world import Object, World from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform @@ -10,7 +9,7 @@ from .external_interfaces.ik import request_ik from .plan_failures import IKError from .helper import _apply_ik -from typing import Tuple, List, Union, Dict, Iterable +from typing_extensions import Tuple, List, Union, Dict, Iterable def pose_generator(costmap: Costmap, number_of_samples=100, orientation_generator=None) -> Iterable: @@ -110,6 +109,28 @@ def visibility_validator(pose: Pose, return res +def _in_contact(robot: Object, obj: Object, allowed_collision: Dict[Object, List[str]], + allowed_robot_links: List[str]) -> bool: + """ + This method checks if a given robot is in contact with a given object. + :param robot: The robot object that should be checked for contact. + :param obj: The object that should be checked for contact with the robot. + :param allowed_collision: A dictionary that contains the allowed collisions for links of each object in the world. + :param allowed_robot_links: A list of links of the robot that are allowed to be in contact with the object. + :return: True if the robot is in contact with the object and False otherwise. + """ + in_contact, contact_links = contact(robot, obj, return_links=True) + allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] + + if in_contact: + for link in contact_links: + if link[0].name in allowed_robot_links or link[1].name in allowed_links: + in_contact = False + # TODO: in_contact is never set to True after it was set to False is that correct? + # TODO: If it is correct, then this loop should break after the first contact is found + return in_contact + + def reachability_validator(pose: Pose, robot: Object, target: Union[Object, Pose], @@ -150,7 +171,7 @@ def reachability_validator(pose: Pose, if robot in allowed_collision.keys(): allowed_robot_links = allowed_collision[robot] - joint_state_before_ik=robot._current_joints_positions + joint_state_before_ik = robot._current_joints_positions try: # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) resp = request_ik(target, robot, left_joints, left_gripper) @@ -159,13 +180,7 @@ def reachability_validator(pose: Pose, for obj in World.current_world.objects: if obj.name == "floor": continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - - if in_contact: - for link in contact_links: - if link[0].name in allowed_robot_links or link[1].name in allowed_links: - in_contact = False + in_contact = _in_contact(robot, obj, allowed_collision, allowed_robot_links) if not in_contact: arms.append("left") @@ -183,13 +198,7 @@ def reachability_validator(pose: Pose, for obj in World.current_world.objects: if obj.name == "floor": continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - - if in_contact: - for link in contact_links: - if link[0].name in allowed_robot_links or link[1].name in allowed_links: - in_contact = False + in_contact = _in_contact(robot, obj, allowed_collision, allowed_robot_links) if not in_contact: arms.append("right") diff --git a/src/pycram/process_module.py b/src/pycram/process_module.py index 351798350..a9626bb05 100644 --- a/src/pycram/process_module.py +++ b/src/pycram/process_module.py @@ -10,21 +10,19 @@ import threading import time from abc import ABC -from threading import Lock +from typing_extensions import Callable, Type, Any, Union import rospy from .designator import MotionDesignatorDescription -from .fluent import Fluent -from typing import Callable, List, Type, Any, Union from .language import Language - from .robot_descriptions import robot_description class ProcessModule: """ - Implementation of process modules. Process modules are the part that communicate with the outer world to execute designators. + Implementation of process modules. Process modules are the part that communicate with the outer world to execute + designators. """ execution_delay = True """ @@ -78,6 +76,7 @@ class RealRobot: with real_robot: some designators """ + def __init__(self): self.pre: str = "" @@ -89,7 +88,7 @@ def __enter__(self): self.pre = ProcessModuleManager.execution_type ProcessModuleManager.execution_type = "real" - def __exit__(self, type, value, traceback): + def __exit__(self, _type, value, traceback): """ Exit method for the 'with' scope, sets the :py:attr:`~ProcessModuleManager.execution_type` to the previously used one. @@ -102,8 +101,8 @@ def __call__(self): class SimulatedRobot: """ - Management class for executing designators on the simulated robot. This is intended to be used in a with environment. - When importing this class an instance is imported instead. + Management class for executing designators on the simulated robot. This is intended to be used in + a with environment. When importing this class an instance is imported instead. Example: @@ -112,6 +111,7 @@ class SimulatedRobot: with simulated_robot: some designators """ + def __init__(self): self.pre: str = "" @@ -123,7 +123,7 @@ def __enter__(self): self.pre = ProcessModuleManager.execution_type ProcessModuleManager.execution_type = "simulated" - def __exit__(self, type, value, traceback): + def __exit__(self, _type, value, traceback): """ Exit method for the 'with' scope, sets the :py:attr:`~ProcessModuleManager.execution_type` to the previously used one. @@ -149,6 +149,7 @@ def plan(): :param func: Function this decorator is annotating :return: The decorated function wrapped into the decorator """ + def wrapper(*args, **kwargs): pre = ProcessModuleManager.execution_type ProcessModuleManager.execution_type = "real" @@ -174,6 +175,7 @@ def plan(): :param func: Function this decorator is annotating :return: The decorated function wrapped into the decorator """ + def wrapper(*args, **kwargs): pre = ProcessModuleManager.execution_type ProcessModuleManager.execution_type = "simulated" @@ -237,6 +239,7 @@ def get_manager() -> Union[ProcessModuleManager, None]: :return: ProcessModuleManager instance of the current robot """ manager = None + _default_manager = None if not ProcessModuleManager.execution_type: rospy.logerr( f"No execution_type is set, did you use the with_simulated_robot or with_real_robot decorator?") @@ -246,17 +249,23 @@ def get_manager() -> Union[ProcessModuleManager, None]: if pm_manager.robot_name == robot_description.name: manager = pm_manager if pm_manager.robot_name == "default": - default_manager = pm_manager + _default_manager = pm_manager if manager: return manager + elif _default_manager: + rospy.logwarn_once(f"No Process Module Manager found for robot: '{robot_description.name}'" + f", using default process modules") + return _default_manager else: - rospy.logwarn_once(f"No Process Module Manager found for robot: '{robot_description.name}', using default process modules") - return default_manager + rospy.logerr(f"No Process Module Manager found for robot: '{robot_description.name}'" + f", and no default process modules available") + return None def navigate(self) -> Type[ProcessModule]: """ - Returns the Process Module for navigating the robot with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for navigating the robot with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for navigating """ @@ -283,7 +292,8 @@ def place(self) -> Type[ProcessModule]: def looking(self) -> Type[ProcessModule]: """ - Returns the Process Module for looking at a point with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for looking at a point with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for looking at a specific point """ @@ -292,7 +302,8 @@ def looking(self) -> Type[ProcessModule]: def detecting(self) -> Type[ProcessModule]: """ - Returns the Process Module for detecting an object with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for detecting an object with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for detecting an object """ @@ -301,7 +312,8 @@ def detecting(self) -> Type[ProcessModule]: def move_tcp(self) -> Type[ProcessModule]: """ - Returns the Process Module for moving the Tool Center Point with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for moving the Tool Center Point with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for moving the TCP """ @@ -340,7 +352,8 @@ def move_joints(self) -> Type[ProcessModule]: def move_gripper(self) -> Type[ProcessModule]: """ - Returns the Process Module for moving the gripper with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for moving the gripper with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for moving the gripper """ @@ -349,7 +362,8 @@ def move_gripper(self) -> Type[ProcessModule]: def open(self) -> Type[ProcessModule]: """ - Returns the Process Module for opening drawers with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for opening drawers with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for opening drawers """ @@ -358,7 +372,8 @@ def open(self) -> Type[ProcessModule]: def close(self) -> Type[ProcessModule]: """ - Returns the Process Module for closing drawers with respect to the :py:attr:`~ProcessModuleManager.execution_type` + Returns the Process Module for closing drawers with respect to + the :py:attr:`~ProcessModuleManager.execution_type` :return: The Process Module for closing drawers """ diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index a8185b760..eafdd360c 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -1,78 +1,17 @@ -import time from threading import Lock -from typing import Tuple, List import numpy as np -import pybullet as p - -import pycram.world_reasoning as btr -import pycram.helper as helper -from ..bullet_world import BulletWorld, Object as BulletWorldObject -from ..designators.motion_designator import * -from ..enums import JointType -from ..external_interfaces.ik import request_ik -from ..local_transformer import LocalTransformer as local_tf, LocalTransformer + +from ..world import World +from ..designators.motion_designator import PlaceMotion +from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description -from tf.transformations import euler_from_quaternion, quaternion_from_euler - - -def _transform_to_torso(pose_and_rotation: Tuple[List[float], List[float]], robot: BulletWorldObject) -> Tuple[ - List[float], List[float]]: - map_T_torso = robot.links[robot_description.torso_link].pose_as_list - torso_T_map = p.invertTransform(map_T_torso[0], map_T_torso[1]) - map_T_target = pose_and_rotation - torso_T_target = p.multiplyTransforms(torso_T_map[0], torso_T_map[1], map_T_target[0], map_T_target[1]) - return torso_T_target - - -def _park_arms(arm): - """ - Defines the joint poses for the parking positions of the arms of Boxy and applies them to the - in the BulletWorld defined robot. - :return: None - """ - - robot = BulletWorld.robot - if arm == "right": - for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - robot.set_joint_position(joint, pose) - if arm == "left": - for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): - robot.set_joint_position(joint, pose) - - -class BoxyNavigation(ProcessModule): - """ - The process module to move the robot from one position to another. - """ - - def _execute(self, desig: MoveMotion.Motion): - robot = BulletWorld.robot - robot.set_pose(desig.target) - - -class BoxyPickUp(ProcessModule): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - - def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - arm = desig.arm - - _move_arm_tcp(target, robot, arm) - tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) +from ..process_modules.pr2_process_modules import (_park_arms, Pr2Navigation as BoxyNavigation, + Pr2PickUp as BoxyPickUp, Pr2Open as BoxyOpen, + Pr2Close as BoxyClose, Pr2Detecting as BoxyDetecting, + Pr2MoveTCP as BoxyMoveTCP, Pr2MoveArmJoints as BoxyMoveArmJoints, + Pr2WorldStateDetecting as BoxyWorldStateDetecting, _move_arm_tcp) class BoxyPlace(ProcessModule): @@ -86,58 +25,19 @@ def _execute(self, desig: PlaceMotion.Motion): :param desig: A PlaceMotion :return: """ - object = desig.object.world_object - robot = BulletWorld.robot + obj = desig.object.world_object + robot = World.robot arm = desig.arm # Transformations such that the target position is the position of the object and not the tcp - object_pose = object.get_pose() + object_pose = obj.get_pose() local_tf = LocalTransformer() tcp_to_object = local_tf.transform_pose(object_pose, - robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) + robot.links[robot_description.get_tool_frame(arm)].tf_frame) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) - robot.detach(object) - - -class BoxyOpen(ProcessModule): - """ - Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. - """ - - def _execute(self, desig: OpeningMotion.Motion): - part_of_object = desig.object_part.world_object - - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - - goal_pose = btr.link_pose_for_joint_config(part_of_object, { - container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - - desig.object_part.world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( - container_joint)[1]) - - -class BoxyClose(ProcessModule): - """ - Low-level implementation that lets the robot close a grasped container, in simulation - """ - def _execute(self, desig: ClosingMotion.Motion): - part_of_object = desig.object_part.world_object - - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - - goal_pose = btr.link_pose_for_joint_config(part_of_object, { - container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - - desig.object_part.world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( - container_joint)[0]) + robot.detach(obj) class BoxyParkArms(ProcessModule): @@ -160,26 +60,27 @@ class BoxyMoveHead(ProcessModule): def _execute(self, desig): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() - pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("neck_shoulder_link")) + pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): - robot.set_joint_states(robot_description.get_static_joint_chain("neck", "front")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "front")) if pose_in_shoulder.position.y >= 0 and pose_in_shoulder.position.y >= abs(pose_in_shoulder.position.x): - robot.set_joint_states(robot_description.get_static_joint_chain("neck", "neck_right")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "neck_right")) if pose_in_shoulder.position.x <= 0 and abs(pose_in_shoulder.position.x) > abs(pose_in_shoulder.position.y): - robot.set_joint_states(robot_description.get_static_joint_chain("neck", "back")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "back")) if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): - robot.set_joint_states(robot_description.get_static_joint_chain("neck", "neck_left")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "neck_left")) - pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("neck_shoulder_link")) + pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) new_pan = np.arctan2(pose_in_shoulder.position.y, pose_in_shoulder.position.x) - robot.set_joint_state("neck_shoulder_pan_joint", new_pan + robot.get_joint_state("neck_shoulder_pan_joint")) + robot.set_joint_position("neck_shoulder_pan_joint", + new_pan + robot.get_joint_position("neck_shoulder_pan_joint")) class BoxyMoveGripper(ProcessModule): @@ -189,76 +90,10 @@ class BoxyMoveGripper(ProcessModule): """ def _execute(self, desig): - robot = BulletWorld.robot + robot = World.robot gripper = desig.gripper motion = desig.motion - robot.set_joint_states(robot_description.get_static_gripper_chain(gripper, motion)) - - -class BoxyDetecting(ProcessModule): - """ - This process module tries to detect an object with the given type. To be detected the object has to be in - the field of view of the robot. - """ - - def _execute(self, desig): - robot = BulletWorld.robot - object_type = desig.object_type - # Should be "wide_stereo_optical_frame" - cam_frame_name = robot_description.get_camera_frame() - # should be [0, 0, 1] - front_facing_axis = robot_description.front_facing_axis - - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) - for obj in objects: - if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): - return obj - - -class BoxyMoveTCP(ProcessModule): - """ - This process moves the tool center point of either the right or the left arm. - """ - - def _execute(self, desig: MoveTCPMotion.Motion): - target = desig.target - robot = BulletWorld.robot - - _move_arm_tcp(target, robot, desig.arm) - - -class BoxyMoveArmJoints(ProcessModule): - """ - This process modules moves the joints of either the right or the left arm. The joint states can be given as - list that should be applied or a pre-defined position can be used, such as "parking" - """ - - def _execute(self, desig: MoveArmJointsMotion.Motion): - - robot = BulletWorld.robot - if desig.right_arm_poses: - robot.set_joint_states(desig.right_arm_poses) - if desig.left_arm_poses: - robot.set_joint_states(desig.left_arm_poses) - - -class BoxyWorldStateDetecting(ProcessModule): - """ - This process module detectes an object even if it is not in the field of view of the robot. - """ - - def _execute(self, desig: WorldStateDetectingMotion.Motion): - obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] - - -def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: - gripper = robot_description.get_tool_frame(arm) - - joints = robot_description.chains[arm].joints - - inv = request_ik(target, robot, joints, gripper) - helper._apply_ik(robot, inv, joints) + robot.set_positions_of_all_joints(robot_description.get_static_gripper_chain(gripper, motion)) class BoxyManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 84567c3b9..ba763b7c7 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -1,68 +1,16 @@ from threading import Lock -import pycram.bullet_world_reasoning as btr import numpy as np -from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld -from ..external_interfaces.ik import request_ik, IKError -from ..helper import _apply_ik +from ..process_modules.pr2_process_modules import Pr2Navigation as DefaultNavigation, Pr2PickUp as DefaultPickUp, \ + Pr2Place as DefaultPlace, Pr2WorldStateDetecting as DefaultWorldStateDetecting, Pr2Open as DefaultOpen, \ + Pr2Close as DefaultClose, Pr2MoveGripper as DefaultMoveGripper, Pr2Detecting as DefaultDetecting, \ + Pr2MoveTCP as DefaultMoveTCP +from ..robot_descriptions import robot_description +from ..world import World from ..local_transformer import LocalTransformer -from ..designators.motion_designator import * -from ..enums import JointType - - -class DefaultNavigation(ProcessModule): - """ - The process module to move the robot from one position to another. - """ - - def _execute(self, desig: MoveMotion.Motion): - robot = BulletWorld.robot - robot.set_pose(desig.target) - - -class DefaultPickUp(ProcessModule): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - - def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - arm = desig.arm - - _move_arm_tcp(target, robot, arm) - tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) - - -class DefaultPlace(ProcessModule): - """ - This process module places an object at the given position in world coordinate frame. - """ - - def _execute(self, desig: PlaceMotion.Motion): - """ - - :param desig: A PlaceMotion - :return: - """ - object = desig.object.world_object - robot = BulletWorld.robot - arm = desig.arm - - _move_arm_tcp(desig.target, robot, arm) - robot.detach(object) +from ..designators.motion_designator import LookingMotion, MoveArmJointsMotion, MoveJointsMotion class DefaultMoveHead(ProcessModule): @@ -73,7 +21,7 @@ class DefaultMoveHead(ProcessModule): def _execute(self, desig: LookingMotion.Motion): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() @@ -82,63 +30,17 @@ def _execute(self, desig: LookingMotion.Motion): pan_joint = robot_description.chains["neck"].joints[0] tilt_joint = robot_description.chains["neck"].joints[1] - pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame(pan_link)) - pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame(tilt_link)) + pose_in_pan = local_transformer.transform_pose(target, robot.links[pan_link].tf_frame) + pose_in_tilt = local_transformer.transform_pose(target, robot.links[tilt_link].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = robot.get_joint_state(pan_joint) - current_tilt = robot.get_joint_state(tilt_joint) - - robot.set_joint_state(pan_joint, new_pan + current_pan) - robot.set_joint_state(tilt_joint, new_tilt + current_tilt) - - -class DefaultMoveGripper(ProcessModule): - """ - This process module controls the gripper of the robot. They can either be opened or closed. - Furthermore, it can only moved one gripper at a time. - """ - - def _execute(self, desig: MoveGripperMotion.Motion): - robot = BulletWorld.robot - gripper = desig.gripper - motion = desig.motion - for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): - robot.set_joint_state(joint, state) - - -class DefaultDetecting(ProcessModule): - """ - This process module tries to detect an object with the given type. To be detected the object has to be in - the field of view of the robot. - """ + current_pan = robot.get_joint_position(pan_joint) + current_tilt = robot.get_joint_position(tilt_joint) - def _execute(self, desig: DetectingMotion.Motion): - robot = BulletWorld.robot - object_type = desig.object_type - # Should be "wide_stereo_optical_frame" - cam_frame_name = robot_description.get_camera_frame() - # should be [0, 0, 1] - front_facing_axis = robot_description.front_facing_axis - - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) - for obj in objects: - if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): - return obj - - -class DefaultMoveTCP(ProcessModule): - """ - This process moves the tool center point of either the right or the left arm. - """ - - def _execute(self, desig: MoveTCPMotion.Motion): - target = desig.target - robot = BulletWorld.robot - - _move_arm_tcp(target, robot, desig.arm) + robot.set_joint_position(pan_joint, new_pan + current_pan) + robot.set_joint_position(tilt_joint, new_tilt + current_tilt) class DefaultMoveArmJoints(ProcessModule): @@ -149,78 +51,20 @@ class DefaultMoveArmJoints(ProcessModule): def _execute(self, desig: MoveArmJointsMotion.Motion): - robot = BulletWorld.robot + robot = World.robot if desig.right_arm_poses: for joint, pose in desig.right_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) if desig.left_arm_poses: for joint, pose in desig.left_arm_poses.items(): - robot.set_joint_state(joint, pose) + robot.set_joint_position(joint, pose) class DefaultMoveJoints(ProcessModule): def _execute(self, desig: MoveJointsMotion.Motion): - robot = BulletWorld.robot + robot = World.robot for joint, pose in zip(desig.names, desig.positions): - robot.set_joint_state(joint, pose) - - -class DefaultWorldStateDetecting(ProcessModule): - """ - This process module detectes an object even if it is not in the field of view of the robot. - """ - - def _execute(self, desig: WorldStateDetectingMotion.Motion): - obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] - - -class DefaultOpen(ProcessModule): - """ - Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. - """ - - def _execute(self, desig: OpeningMotion.Motion): - part_of_object = desig.object_part.world_object - - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - - goal_pose = btr.link_pose_for_joint_config(part_of_object, { - container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - - desig.object_part.world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( - container_joint)[1]) - - -class DefaultClose(ProcessModule): - """ - Low-level implementation that lets the robot close a grasped container, in simulation - """ - def _execute(self, desig: ClosingMotion.Motion): - part_of_object = desig.object_part.world_object - - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - - goal_pose = btr.link_pose_for_joint_config(part_of_object, { - container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) - - desig.object_part.world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( - container_joint)[0]) - - -def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: - gripper = robot_description.get_tool_frame(arm) - - joints = robot_description.chains[arm].joints - - inv = request_ik(target, robot, joints, gripper) - _apply_ik(robot, inv, joints) + robot.set_joint_position(joint, pose) class DefaultManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 45cf31899..936c5c57e 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -1,29 +1,24 @@ -import time from threading import Lock import numpy as np -import pybullet as p +from typing_extensions import Optional -import pycram.world_reasoning as btr -import pycram.helper as helper -from ..bullet_world import BulletWorld, Object +from ..bullet_world import World from ..designators.motion_designator import MoveArmJointsMotion, WorldStateDetectingMotion -from ..external_interfaces.ik import request_ik from ..local_transformer import LocalTransformer -from ..pose import Pose from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description -from tf.transformations import euler_from_quaternion, quaternion_from_euler +from ..process_modules.pr2_process_modules import Pr2PickUp, Pr2Detecting as DonbotDetecting, _move_arm_tcp def _park_arms(arm): """ Defines the joint poses for the parking positions of the arm of Donbot and applies them to the - in the BulletWorld defined robot. + in the World defined robot. :return: None """ - robot = BulletWorld.robot + robot = World.robot if arm == "left": for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): robot.set_joint_position(joint, pose) @@ -35,28 +30,17 @@ class DonbotNavigation(ProcessModule): """ def _execute(self, desig): - robot = BulletWorld.robot + robot = World.robot robot.set_pose(desig.target) -class DonbotPickUp(ProcessModule): + +class DonbotPickUp(Pr2PickUp): """ This process module is for picking up a given object. The object has to be reachable for this process module to succeed. """ - - def _execute(self, desig): - object = desig.object_desig.world_object - robot = BulletWorld.robot - grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() - target.orientation.x = grasp[0] - target.orientation.y = grasp[1] - target.orientation.z = grasp[2] - target.orientation.w = grasp[3] - - _move_arm_tcp(target, robot, "left") - tool_frame = robot_description.get_tool_frame("left") - robot.attach(object, tool_frame) + def _execute(self, desig, used_arm: Optional[str] = "left"): + super()._execute(desig, "left") class DonbotPlace(ProcessModule): @@ -65,19 +49,18 @@ class DonbotPlace(ProcessModule): """ def _execute(self, desig): - object = desig.object.world_object - robot = BulletWorld.robot + obj = desig.object.world_object + robot = World.robot # Transformations such that the target position is the position of the object and not the tcp - object_pose = object.get_pose() + object_pose = obj.get_pose() local_tf = LocalTransformer() tcp_to_object = local_tf.transform_pose(object_pose, - robot.get_link_tf_frame(robot_description.get_tool_frame("left"))) + robot.links[robot_description.get_tool_frame("left")].tf_frame) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, "left") - robot.detach(object) - + robot.detach(obj) class DonbotMoveHead(ProcessModule): @@ -88,26 +71,26 @@ class DonbotMoveHead(ProcessModule): def _execute(self, desig): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() - pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("ur5_shoulder_link")) + pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): - robot.set_joint_states(robot_description.get_static_joint_chain("left", "front")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "front")) if pose_in_shoulder.position.y >= 0 and pose_in_shoulder.position.y >= abs(pose_in_shoulder.position.x): - robot.set_joint_states(robot_description.get_static_joint_chain("left", "arm_right")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "arm_right")) if pose_in_shoulder.position.x <= 0 and abs(pose_in_shoulder.position.x) > abs(pose_in_shoulder.position.y): - robot.set_joint_states(robot_description.get_static_joint_chain("left", "back")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "back")) if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): - robot.set_joint_states(robot_description.get_static_joint_chain("left", "arm_left")) + robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "arm_left")) - pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("ur5_shoulder_link")) + pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) new_pan = np.arctan2(pose_in_shoulder.position.y, pose_in_shoulder.position.x) - robot.set_joint_state("ur5_shoulder_pan_joint", new_pan + robot.get_joint_state("ur5_shoulder_pan_joint")) + robot.set_joint_position("ur5_shoulder_pan_joint", new_pan + robot.get_joint_position("ur5_shoulder_pan_joint")) class DonbotMoveGripper(ProcessModule): @@ -117,30 +100,10 @@ class DonbotMoveGripper(ProcessModule): """ def _execute(self, desig): - robot = BulletWorld.robot + robot = World.robot gripper = desig.gripper motion = desig.motion - robot.set_joint_states(robot_description.get_static_gripper_chain(gripper, motion)) - - -class DonbotDetecting(ProcessModule): - """ - This process module tries to detect an object with the given type. To be detected the object has to be in - the field of view of the robot. - """ - - def _execute(self, desig): - robot = BulletWorld.robot - object_type = desig.object_type - # Should be "wide_stereo_optical_frame" - cam_frame_name = robot_description.get_camera_frame() - # should be [0, 0, 1] - front_facing_axis = robot_description.front_facing_axis - - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) - for obj in objects: - if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): - return obj + robot.set_positions_of_all_joints(robot_description.get_static_gripper_chain(gripper, motion)) class DonbotMoveTCP(ProcessModule): @@ -150,7 +113,7 @@ class DonbotMoveTCP(ProcessModule): def _execute(self, desig): target = desig.target - robot = BulletWorld.robot + robot = World.robot _move_arm_tcp(target, robot, desig.arm) @@ -162,9 +125,9 @@ class DonbotMoveJoints(ProcessModule): """ def _execute(self, desig: MoveArmJointsMotion.Motion): - robot = BulletWorld.robot + robot = World.robot if desig.left_arm_poses: - robot.set_joint_states(desig.left_arm_poses) + robot.set_positions_of_all_joints(desig.left_arm_poses) class DonbotWorldStateDetecting(ProcessModule): @@ -174,15 +137,7 @@ class DonbotWorldStateDetecting(ProcessModule): def _execute(self, desig: WorldStateDetectingMotion.Motion): obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] - -def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: - gripper = robot_description.get_tool_frame(arm) - - joints = robot_description.chains[arm].joints - - inv = request_ik(target, robot, joints, gripper) - helper._apply_ik(robot, inv, joints) + return list(filter(lambda obj: obj.type == obj_type, World.current_world.objects))[0] class DonbotManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 5bd04c89e..2467f522e 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -1,13 +1,13 @@ from threading import Lock -from typing import Optional +from typing_extensions import Optional from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager from ..world import World from ..pose import Pose, Point from ..helper import _apply_ik +from ..external_interfaces.ik import request_ik import pycram.world_reasoning as btr -import pybullet as p import logging import time @@ -16,10 +16,11 @@ def calculate_and_apply_ik(robot, gripper: str, target_position: Point, max_iter """ Calculates the inverse kinematics for the given target pose and applies it to the robot. """ - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), target_position, - maxNumIterations=max_iterations) + target_position_l = [target_position.x, target_position.y, target_position.z] # TODO: Check if this is correct (getting the arm and using its joints), previously joints was not provided. arm = "right" if gripper == robot_description.get_tool_frame("right") else "left" + inv = request_ik(Pose(target_position_l, [0, 0, 0, 1]), + robot, robot_description.chains[arm].joints, gripper) joints = robot_description.chains[arm].joints _apply_ik(robot, inv, joints) diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 88b5a1b6d..b8db116cc 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -1,18 +1,25 @@ from threading import Lock -from typing import Any +from typing_extensions import Any, Optional, Tuple +from abc import abstractmethod import actionlib -import pycram.world_reasoning as btr +from .. import world_reasoning as btr import numpy as np import rospy -from ..process_module import ProcessModule +from ..process_module import ProcessModule, ProcessModuleManager from ..external_interfaces.ik import request_ik from ..helper import _apply_ik from ..local_transformer import LocalTransformer -from ..designators.motion_designator import * +from ..designators.object_designator import ObjectDesignatorDescription +from ..designators.motion_designator import MoveMotion, PickUpMotion, PlaceMotion, LookingMotion, \ + DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ + MoveGripperMotion, OpeningMotion, ClosingMotion, MotionDesignatorDescription +from ..robot_descriptions import robot_description +from ..world import World, Object +from ..pose import Pose from ..enums import JointType, ObjectType from ..external_interfaces import giskard from ..external_interfaces.robokudo import query @@ -26,11 +33,11 @@ def _park_arms(arm): """ Defines the joint poses for the parking positions of the arms of PR2 and applies them to the - in the BulletWorld defined robot. + in the World defined robot. :return: None """ - robot = BulletWorld.robot + robot = World.robot if arm == "right": for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): robot.set_joint_position(joint, pose) @@ -45,7 +52,7 @@ class Pr2Navigation(ProcessModule): """ def _execute(self, desig: MoveMotion.Motion): - robot = BulletWorld.robot + robot = World.robot robot.set_pose(desig.target) @@ -55,21 +62,21 @@ class Pr2PickUp(ProcessModule): The object has to be reachable for this process module to succeed. """ - def _execute(self, desig: PickUpMotion.Motion): - object = desig.object_desig.world_object - robot = BulletWorld.robot + def _execute(self, desig: PickUpMotion.Motion, used_arm: Optional[str] = None): + obj = desig.object_desig.world_object + robot = World.robot grasp = robot_description.grasps.get_orientation_for_grasp(desig.grasp) - target = object.get_pose() + target = obj.get_pose() target.orientation.x = grasp[0] target.orientation.y = grasp[1] target.orientation.z = grasp[2] target.orientation.w = grasp[3] - arm = desig.arm + arm = desig.arm if used_arm is None else used_arm _move_arm_tcp(target, robot, arm) tool_frame = robot_description.get_tool_frame(arm) - robot.attach(object, tool_frame) + robot.attach(obj, tool_frame) class Pr2Place(ProcessModule): @@ -83,43 +90,69 @@ def _execute(self, desig: PlaceMotion.Motion): :param desig: A PlaceMotion :return: """ - object = desig.object.world_object - robot = BulletWorld.robot + obj = desig.object.world_object + robot = World.robot arm = desig.arm # Transformations such that the target position is the position of the object and not the tcp - object_pose = object.get_pose() + object_pose = obj.get_pose() local_tf = LocalTransformer() tool_name = robot_description.get_tool_frame(arm) tcp_to_object = local_tf.transform_pose(object_pose, robot.links[tool_name].tf_frame) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) - robot.detach(object) + robot.detach(obj) -class Pr2MoveHead(ProcessModule): - """ - This process module moves the head to look at a specific point in the world coordinate frame. - This point can either be a position or an object. +class _Pr2MoveHead(ProcessModule): """ + This process module moves the head to look at a specific point in the world coordinate frame. + This point can either be a position or an object. + """ + def __init__(self, lock: Lock): + super().__init__(lock) + self.robot: Object = World.robot - def _execute(self, desig: LookingMotion.Motion): + def get_pan_and_tilt_goals(self, desig: LookingMotion.Motion) -> Tuple[float, float]: + """ + Calculates the pan and tilt angles to achieve the desired looking motion. + :param desig: The looking motion designator + :return: The pan and tilt angles + """ target = desig.target - robot = BulletWorld.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, robot.links["head_pan_link"].tf_frame) - pose_in_tilt = local_transformer.transform_pose(target, robot.links["head_tilt_link"].tf_frame) + pose_in_pan = local_transformer.transform_pose(target, self.robot.links["head_pan_link"].tf_frame) + pose_in_tilt = local_transformer.transform_pose(target, self.robot.links["head_tilt_link"].tf_frame) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = robot.get_joint_position("head_pan_joint") - current_tilt = robot.get_joint_position("head_tilt_joint") + current_pan = self.robot.get_joint_position("head_pan_joint") + current_tilt = self.robot.get_joint_position("head_tilt_joint") - robot.set_joint_position("head_pan_joint", new_pan + current_pan) - robot.set_joint_position("head_tilt_joint", new_tilt + current_tilt) + return new_pan + current_pan, new_tilt + current_tilt + + @abstractmethod + def _execute(self, designator: LookingMotion.Motion) -> None: + pass + + +class Pr2MoveHead(_Pr2MoveHead): + """ + This process module moves the head to look at a specific point in the world coordinate frame. + This point can either be a position or an object. + """ + + def _execute(self, desig: LookingMotion.Motion): + """ + Moves the head to look at the given position. + :param desig: The looking motion designator + """ + pan_goal, tilt_goal = self.get_pan_and_tilt_goals(desig) + self.robot.set_joint_position("head_pan_joint", pan_goal) + self.robot.set_joint_position("head_tilt_joint", tilt_goal) class Pr2MoveGripper(ProcessModule): @@ -129,7 +162,7 @@ class Pr2MoveGripper(ProcessModule): """ def _execute(self, desig: MoveGripperMotion.Motion): - robot = BulletWorld.robot + robot = World.robot gripper = desig.gripper motion = desig.motion for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): @@ -143,14 +176,14 @@ class Pr2Detecting(ProcessModule): """ def _execute(self, desig: DetectingMotion.Motion): - robot = BulletWorld.robot + robot = World.robot object_type = desig.object_type # Should be "wide_stereo_optical_frame" cam_frame_name = robot_description.get_camera_frame() # should be [0, 0, 1] front_facing_axis = robot_description.front_facing_axis - objects = BulletWorld.current_world.get_objects_by_type(object_type) + objects = World.current_world.get_objects_by_type(object_type) for obj in objects: if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis): return obj @@ -163,7 +196,7 @@ class Pr2MoveTCP(ProcessModule): def _execute(self, desig: MoveTCPMotion.Motion): target = desig.target - robot = BulletWorld.robot + robot = World.robot _move_arm_tcp(target, robot, desig.arm) @@ -176,7 +209,7 @@ class Pr2MoveArmJoints(ProcessModule): def _execute(self, desig: MoveArmJointsMotion.Motion): - robot = BulletWorld.robot + robot = World.robot if desig.right_arm_poses: robot.set_positions_of_all_joints(desig.right_arm_poses) if desig.left_arm_poses: @@ -188,7 +221,7 @@ class PR2MoveJoints(ProcessModule): Process Module for generic joint movements, is not confined to the arms but can move any joint of the robot """ def _execute(self, desig: MoveJointsMotion.Motion): - robot = BulletWorld.robot + robot = World.robot robot.set_positions_of_all_joints(dict(zip(desig.names, desig.positions))) @@ -199,7 +232,7 @@ class Pr2WorldStateDetecting(ProcessModule): def _execute(self, desig: WorldStateDetectingMotion.Motion): obj_type = desig.object_type - return list(filter(lambda obj: obj.obj_type == obj_type, BulletWorld.current_world.objects))[0] + return list(filter(lambda obj: obj.obj_type == obj_type, World.current_world.objects))[0] class Pr2Open(ProcessModule): @@ -215,7 +248,7 @@ def _execute(self, desig: OpeningMotion.Motion): goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits( @@ -235,7 +268,7 @@ def _execute(self, desig: ClosingMotion.Motion): goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits( @@ -278,29 +311,22 @@ def _execute(self, designator: MotionDesignatorDescription.Motion) -> Any: pass -class Pr2MoveHeadReal(ProcessModule): +class Pr2MoveHeadReal(_Pr2MoveHead): """ Process module for the real robot to move that such that it looks at the given position. Uses the same calculation as the simulated one """ def _execute(self, desig: LookingMotion.Motion): - target = desig.target - robot = BulletWorld.robot - - local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, robot.links["head_pan_link"].tf_frame) - pose_in_tilt = local_transformer.transform_pose(target, robot.links["head_tilt_link"].tf_frame) - - new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) - new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - - current_pan = robot.get_joint_position("head_pan_joint") - current_tilt = robot.get_joint_position("head_tilt_joint") + """ + Moves the head to look at the given position. + :param desig: The looking motion designator + """ + pan_goal, tilt_goal = self.get_pan_and_tilt_goals(desig) giskard.avoid_all_collisions() - giskard.achieve_joint_goal({"head_pan_joint": new_pan + current_pan, - "head_tilt_joint": new_tilt + current_tilt}) + giskard.achieve_joint_goal({"head_pan_joint": pan_goal, + "head_tilt_joint": tilt_goal}) class Pr2DetectingReal(ProcessModule): @@ -315,14 +341,14 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose(obj_pose, BulletWorld.robot.links["torso_lift_link"].tf_frame) + obj_pose = lt.transform_pose(obj_pose, World.robot.links["torso_lift_link"].tf_frame) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 - bullet_obj = BulletWorld.current_world.get_objects_by_type(designator.object_type) - if bullet_obj: - bullet_obj[0].set_pose(obj_pose) - return bullet_obj[0] + world_obj = World.current_world.get_objects_by_type(designator.object_type) + if world_obj: + world_obj[0].set_pose(obj_pose) + return world_obj[0] elif designator.object_type == ObjectType.JEROEN_CUP: cup = Object("cup", ObjectType.JEROEN_CUP, "jeroen_cup.stl", pose=obj_pose) return cup @@ -330,11 +356,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=obj_pose) return bowl - - return bullet_obj[0] - - - + return world_obj[0] class Pr2MoveTCPReal(ProcessModule): @@ -396,7 +418,10 @@ def feedback_callback(msg): goal = Pr2GripperCommandGoal() goal.command.position = 0.0 if designator.motion == "close" else 0.1 goal.command.max_effort = 50.0 - controller_topic = "r_gripper_controller/gripper_action" if designator.gripper == "right" else "l_gripper_controller/gripper_action" + if designator.gripper == "right": + controller_topic = "r_gripper_controller/gripper_action" + else: + controller_topic = "l_gripper_controller/gripper_action" client = actionlib.SimpleActionClient(controller_topic, Pr2GripperCommandAction) rospy.loginfo("Waiting for action server") client.wait_for_server() diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 9d6122aa2..7285f3107 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,14 +1,12 @@ from pycram.external_interfaces.giskard import achieve_cartesian_goal from pycram.designators.location_designator import CostmapLocation -from pycram.world import UseProspectionWorld, BulletWorld -from pycram.helper import _apply_ik +from ...world import UseProspectionWorld, World from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.pose_generator_and_validator import reachability_validator -from typing import Tuple, Dict +from typing_extensions import Tuple, Dict import tf -import numpy as np class GiskardLocation(CostmapLocation): @@ -28,7 +26,7 @@ def __iter__(self) -> CostmapLocation.Location: pose_left, end_config_left = self._get_reachable_pose_for_arm(self.target, robot_description.get_tool_frame("left")) - test_robot = BulletWorld.current_world.get_prospection_object_for_object(BulletWorld.robot) + test_robot = World.current_world.get_prospection_object_for_object(World.robot) with UseProspectionWorld(): valid, arms = reachability_validator(pose_right, test_robot, self.target, {}) if valid: diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index b9de0ccb2..5161ee014 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -1,22 +1,18 @@ import dataclasses -import time -from typing import Optional, List, Tuple +from typing_extensions import Optional, List import jpt import numpy as np -import pybullet import tf -import pycram.designators.location_designator -import pycram.task -from ...costmaps import OccupancyCostmap, plot_grid -from ...plan_failures import PlanFailure +from ...designators import location_designator +from ...costmaps import OccupancyCostmap from ...pose import Pose -from pycram.bullet_world import BulletWorld -from pycram.world import Object +from ...world import Object, World +from ...world_dataclasses import BoxVisualShape, Color -class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): +class JPTCostmapLocation(location_designator.CostmapLocation): """Costmap Locations using Joint Probability Trees (JPTs). JPT costmaps are trained to model the dependency with a robot position relative to the object, the robots type, the objects type, the robot torso height, and the grasp parameters. @@ -24,7 +20,7 @@ class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation) """ @dataclasses.dataclass - class Location(pycram.designators.location_designator.LocationDesignatorDescription.Location): + class Location(location_designator.LocationDesignatorDescription.Location): pose: Pose reachable_arm: str torso_height: float @@ -187,7 +183,7 @@ def __iter__(self): def visualize(self): """ - Plot the possible areas to stand in the BulletWorld. The opacity is the probability of success. + Plot the possible areas to stand in the World. The opacity is the probability of success. """ @@ -210,23 +206,14 @@ def visualize(self): center = np.array([sum(x_range) / 2, sum(y_range) / 2]) - visual = pybullet.createVisualShape(pybullet.GEOM_BOX, - halfExtents=[(x_range[1] - x_range[0]) / 2, - (y_range[1] - y_range[0]) / 2, 0.001], - rgbaColor=[1, 0, 0, success], - visualFramePosition=[*center, 0]) + box_visual_shape = BoxVisualShape(Color(1, 0, 0, success), [*center, 0], + half_extents=[(x_range[1] - x_range[0]) / 2, + (y_range[1] - y_range[0]) / 2, 0.001]) + visual = World.current_world.create_visual_shape(box_visual_shape) self.visual_ids.append(visual) for id_list in np.array_split(np.array(self.visual_ids), np.ceil(len(self.visual_ids) / 127)): - # Dummy paramater since these are needed to spawn visual shapes as a multibody. - link_poses = [[0, 0, 0] for c in id_list] - link_orientations = [[0, 0, 0, 1] for c in id_list] - link_masses = [1.0 for c in id_list] - link_parent = [0 for c in id_list] - link_joints = [pybullet.JOINT_FIXED for c in id_list] - link_collision = [-1 for c in id_list] - link_joint_axis = [[1, 0, 0] for c in id_list] # The position at which the multibody will be spawned. Offset such that # the origin referes to the centre of the costmap. @@ -234,15 +221,8 @@ def visualize(self): base_position = list(origin_pose[0]) base_position[2] = 0 - map_obj = pybullet.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=id_list, - basePosition=base_position, baseOrientation=origin_pose[1], - linkPositions=link_poses, - linkMasses=link_masses, linkOrientations=link_orientations, - linkInertialFramePositions=link_poses, - linkInertialFrameOrientations=link_orientations, - linkParentIndices=link_parent, - linkJointTypes=link_joints, linkJointAxis=link_joint_axis, - linkCollisionShapeIndices=link_collision) + map_obj = World.current_world.create_multi_body_from_visual_shapes(id_list.tolist(), Pose(base_position, + origin_pose[1])) self.visual_ids.append(map_obj) def close_visualization(self) -> None: @@ -250,6 +230,6 @@ def close_visualization(self) -> None: Close all plotted objects. """ - for id in self.visual_ids: - pybullet.removeBody(id) + for _id in self.visual_ids: + World.current_world.remove_object(World.current_world.get_object_by_id(_id)) self.visual_ids = [] diff --git a/src/pycram/robot_description.py b/src/pycram/robot_description.py index ab896d1e1..795330b90 100644 --- a/src/pycram/robot_description.py +++ b/src/pycram/robot_description.py @@ -3,7 +3,7 @@ import rospkg from copy import deepcopy from numbers import Number -from typing import List, Optional, Dict, Union, Type +from typing_extensions import List, Optional, Dict, Union, Type from urdf_parser_py.urdf import URDF from . import utils diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index 3b9b21af4..ed68a1a86 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -3,11 +3,10 @@ import threading import rospy -import pybullet as pb from geometry_msgs.msg import WrenchStamped from std_msgs.msg import Header -from..bullet_world import BulletWorld +from ..world import World class ForceTorqueSensor: @@ -18,21 +17,22 @@ class ForceTorqueSensor: """ def __init__(self, joint_name, fts_topic="/pycram/fts", interval=0.1): """ - The given joint_name has to be part of :py:attr:`~pycram.world.BulletWorld.robot` otherwise a + The given joint_name has to be part of :py:attr:`~pycram.world.World.robot` otherwise a RuntimeError will be raised. :param joint_name: Name of the joint for which force-torque should be simulated :param fts_topic: Name of the ROS topic to which should be published :param interval: Interval at which the messages should be published, in seconds """ - self.world = BulletWorld.current_world + self.world = World.current_world self.fts_joint_idx = None self.joint_name = joint_name if joint_name in self.world.robot.joint_name_to_id.keys(): self.fts_joint_idx = self.world.robot.joint_name_to_id[joint_name] else: - raise RuntimeError(f"Could not register ForceTorqueSensor: Joint {joint_name} does not exist in robot object") - pb.enableJointForceTorqueSensor(self.world.robot.id, self.fts_joint_idx, enableSensor=1) + raise RuntimeError(f"Could not register ForceTorqueSensor: Joint {joint_name}" + f" does not exist in robot object") + self.world.enable_joint_force_torque_sensor(self.world.robot, self.fts_joint_idx) self.fts_pub = rospy.Publisher(fts_topic, WrenchStamped, queue_size=10) self.interval = interval @@ -50,8 +50,7 @@ def _publish(self) -> None: """ seq = 0 while not self.kill_event.is_set(): - current_joint_state = pb.getJointState(self.world.robot.id, self.fts_joint_idx) - joint_ft = current_joint_state[2] + joint_ft = self.world.get_joint_force_torque(self.world.robot, self.fts_joint_idx) h = Header() h.seq = seq h.stamp = rospy.Time.now() diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index fb7682e19..75e4c084c 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -6,22 +6,22 @@ from sensor_msgs.msg import JointState from std_msgs.msg import Header -from ..bullet_world import BulletWorld +from ..world import World class JointStatePublisher: """ - Joint state publisher for the robot currently loaded in the BulletWorld + Joint state publisher for the robot currently loaded in the World """ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): """ - Robot object is from :py:attr:`~pycram.world.BulletWorld.robot` and current joint states are published to + Robot object is from :py:attr:`~pycram.world.World.robot` and current joint states are published to the given joint_state_topic as a JointState message. :param joint_state_topic: Topic name to which the joint states should be published :param interval: Interval at which the joint states should be published, in seconds """ - self.world = BulletWorld.current_world + self.world = World.current_world self.joint_state_pub = rospy.Publisher(joint_state_topic, JointState, queue_size=10) self.interval = interval @@ -33,10 +33,11 @@ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): def _publish(self) -> None: """ - Publishes the current joint states of the :py:attr:`~pycram.world.BulletWorld.robot` in an infinite loop. - The joint states are published as long as the kill_event is not set by :py:meth:`~JointStatePublisher._stop_publishing` + Publishes the current joint states of the :py:attr:`~pycram.world.World.robot` in an infinite loop. + The joint states are published as long as the kill_event is not set + by :py:meth:`~JointStatePublisher._stop_publishing` """ - robot = BulletWorld.robot + robot = World.robot joint_names = [joint_name for joint_name in robot.joint_name_to_id.keys()] seq = 0 diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index f8f8bab82..93ab7ecce 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -1,19 +1,18 @@ import rospy -import threading import atexit import tf import time from geometry_msgs.msg import TransformStamped from sensor_msgs.msg import JointState -from pycram.bullet_world import BulletWorld -from pycram.robot_descriptions import robot_description -from pycram.pose import Transform, Pose +from ..world import World +from ..robot_descriptions import robot_description +from ..pose import Pose class RobotStateUpdater: """ - Updates the robot in the Bullet World with information of the real robot published to ROS topics. + Updates the robot in the World with information of the real robot published to ROS topics. Infos used to update the robot are: * The current pose of the robot * The current joint state of the robot @@ -31,10 +30,8 @@ def __init__(self, tf_topic: str, joint_state_topic: str): self.tf_topic = tf_topic self.joint_state_topic = joint_state_topic - self.tf_timer = rospy.Timer(rospy.Duration(0.1), self._subscribe_tf) - self.joint_state_timer = rospy.Timer(rospy.Duration(0.1), self._subscribe_joint_state) - - + self.tf_timer = rospy.Timer(rospy.Duration.from_sec(0.1), self._subscribe_tf) + self.joint_state_timer = rospy.Timer(rospy.Duration.from_sec(0.1), self._subscribe_joint_state) atexit.register(self._stop_subscription) @@ -45,27 +42,26 @@ def _subscribe_tf(self, msg: TransformStamped) -> None: :param msg: TransformStamped message published to the topic """ trans, rot = self.tf_listener.lookupTransform("/map", robot_description.base_frame, rospy.Time(0)) - BulletWorld.robot.set_pose(Pose(trans, rot)) + World.robot.set_pose(Pose(trans, rot)) def _subscribe_joint_state(self, msg: JointState) -> None: """ - Sets the current joint configuration of the robot in the bullet world to the configuration published on the topic. - Since this uses rospy.wait_for_message which can have errors when used with threads there might be an attribute error - in the rospy implementation. + Sets the current joint configuration of the robot in the world to the configuration published on the + topic. Since this uses rospy.wait_for_message which can have errors when used with threads there might be an + attribute error in the rospy implementation. :param msg: JointState message published to the topic. """ try: msg = rospy.wait_for_message(self.joint_state_topic, JointState) for name, position in zip(msg.name, msg.position): - BulletWorld.robot.set_joint_position(name, position) + World.robot.set_joint_position(name, position) except AttributeError: pass - def _stop_subscription(self) -> None: """ - Stops the Timer for TF and joint states and therefore the updating of the robot in the bullet world. + Stops the Timer for TF and joint states and therefore the updating of the robot in the world. """ self.tf_timer.shutdown() self.joint_state_timer.shutdown() diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index 5d6930522..e3be3bc6d 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -4,13 +4,13 @@ import atexit from ..pose import Pose -from ..bullet_world import BulletWorld +from ..world import World from tf2_msgs.msg import TFMessage class TFBroadcaster: """ - Broadcaster that publishes TF frames for every object in the BulletWorld. + Broadcaster that publishes TF frames for every object in the World. """ def __init__(self, projection_namespace="simulated", odom_frame="odom", interval=0.1): """ @@ -21,7 +21,7 @@ def __init__(self, projection_namespace="simulated", odom_frame="odom", interval :param odom_frame: Name of the statically published odom frame :param interval: Interval at which the TFs should be published, in seconds """ - self.world = BulletWorld.current_world + self.world = World.current_world self.tf_static_publisher = rospy.Publisher("/tf_static", TFMessage, queue_size=10) self.tf_publisher = rospy.Publisher("/tf", TFMessage, queue_size=10) @@ -39,7 +39,7 @@ def __init__(self, projection_namespace="simulated", odom_frame="odom", interval def update(self): """ - Updates the TFs for the static odom frame and all objects currently in the BulletWorld. + Updates the TFs for the static odom frame and all objects currently in the World. """ # Update static odom self._update_static_odom() @@ -48,7 +48,7 @@ def update(self): def _update_objects(self) -> None: """ - Publishes the current pose of all objects in the BulletWorld. As well as the poses of all links of these objects. + Publishes the current pose of all objects in the World. As well as the poses of all links of these objects. """ for obj in self.world.objects: pose = obj.get_pose() @@ -89,7 +89,7 @@ def _publish_pose(self, child_frame_id: str, pose: Pose, static=False) -> None: def _publish(self) -> None: """ - Constantly publishes the positions of all objects in the BulletWorld. + Constantly publishes the positions of all objects in the World. """ while not self.kill_event.is_set(): self.update() diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 0eb2cb5b2..d47279a90 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -5,22 +5,21 @@ from geometry_msgs.msg import Vector3 from std_msgs.msg import ColorRGBA -from pycram.bullet_world import BulletWorld +from ..world import World from visualization_msgs.msg import MarkerArray, Marker import rospy import urdf_parser_py -from tf.transformations import quaternion_from_euler from pycram.pose import Transform class VizMarkerPublisher: """ - Publishes an Array of visualization marker which represent the situation in the Bullet World + Publishes an Array of visualization marker which represent the situation in the World """ def __init__(self, topic_name="/pycram/viz_marker", interval=0.1): """ - The Publisher creates an Array of Visualization marker with a Marker for each link of each Object in the Bullet + The Publisher creates an Array of Visualization marker with a Marker for each link of each Object in the World. This Array is published with a rate of interval. :param topic_name: The name of the topic to which the Visualization Marker should be published. @@ -56,7 +55,7 @@ def _make_marker_array(self) -> MarkerArray: :return: An Array of Visualization Marker """ marker_array = MarkerArray() - for obj in BulletWorld.current_world.objects: + for obj in World.current_world.objects: if obj.name == "floor": continue for link in obj.link_name_to_id.keys(): diff --git a/src/pycram/task.py b/src/pycram/task.py index 8bc63d246..b8baacbe0 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -7,19 +7,19 @@ import inspect import json import logging -from typing import List, Dict, Optional, Callable, Any +from typing_extensions import List, Dict, Optional, Callable import anytree -import pybullet import sqlalchemy.orm.session import tqdm -from .bullet_world import BulletWorld +from .world import World from .orm.task import (Code as ORMCode, TaskTreeNode as ORMTaskTreeNode) from .orm.base import ProcessMetaData from .plan_failures import PlanFailure from .language import Code from .enums import TaskStatus +from .world_dataclasses import Color class TaskCode(Code): @@ -215,18 +215,18 @@ class SimulatedTaskTree: """TaskTree for execution in a 'new' simulation.""" def __enter__(self): - """At the beginning of a with statement the current task tree and bullet world will be suspended and remembered. + """At the beginning of a with statement the current task tree and world will be suspended and remembered. Fresh structures are then available inside the with statement.""" global task_tree def simulation(): return None self.suspended_tree = task_tree - self.world_state = BulletWorld.current_world.save_state() + self.world_state = World.current_world.save_state() self.simulated_root = TaskTreeNode(code=TaskCode(simulation)) task_tree = self.simulated_root - pybullet.addUserDebugText("Simulating...", [0, 0, 1.75], textColorRGB=[0, 0, 0], - parentObjectUniqueId=1, lifeTime=0) + World.current_world.add_text("Simulating...", [0, 0, 1.75], color=Color.from_rgb([0, 0, 0]), + parent_object_id=1) return self def __exit__(self, exc_type, exc_val, exc_tb): @@ -235,8 +235,8 @@ def __exit__(self, exc_type, exc_val, exc_tb): """ global task_tree task_tree = self.suspended_tree - BulletWorld.current_world.restore_state(self.world_state) - pybullet.removeAllUserDebugItems() + World.current_world.restore_state(self.world_state) + World.current_world.remove_text() task_tree: Optional[TaskTreeNode] = None diff --git a/src/pycram/world.py b/src/pycram/world.py index 0a859b2a7..b520779b9 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -58,8 +58,8 @@ class World(ABC): robot: Optional[Object] = None """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the - URDF with the name of the URDF on the parameter server. + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in + the URDF with the name of the URDF on the parameter server. """ data_directory: List[str] = [os.path.join(os.path.dirname(__file__), '..', '..', 'resources')] @@ -170,6 +170,7 @@ def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: """ pass + # TODO: This is not used anywhere, should it be removed? def get_objects_by_name(self, name: str) -> List[Object]: """ Returns a list of all Objects in this World with the same name as the given one. @@ -179,7 +180,7 @@ def get_objects_by_name(self, name: str) -> List[Object]: """ return list(filter(lambda obj: obj.name == name, self.objects)) - def get_objects_by_type(self, obj_type: str) -> List[Object]: + def get_objects_by_type(self, obj_type: ObjectType) -> List[Object]: """ Returns a list of all Objects which have the type 'obj_type'. @@ -357,6 +358,7 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: :param real_time: If the simulation should happen in real time or faster. """ for i in range(0, int(seconds * self.simulation_frequency)): + curr_time = rospy.Time.now() self.step() for objects, callbacks in self.coll_callbacks.items(): contact_points = self.get_contact_points_between_two_objects(objects[0], objects[1]) @@ -365,7 +367,8 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: elif callbacks.no_collision_cb is not None: callbacks.no_collision_cb() if real_time: - time.sleep(self.simulation_time_step) + loop_time = rospy.Time.now() - curr_time + time.sleep(max(0, self.simulation_time_step - loop_time.to_sec())) @abstractmethod def perform_collision_detection(self) -> None: @@ -433,7 +436,6 @@ def get_link_names(self, obj: Object) -> List[str]: """ pass - @abstractmethod def get_number_of_joints(self, obj: Object) -> int: """ Get the number of joints of an articulated object @@ -899,6 +901,36 @@ def create_visual_shape(self, visual_shape: VisualShape) -> int: """ raise NotImplementedError + def create_multi_body_from_visual_shapes(self, visual_shape_ids: List[int], pose: Pose) -> int: + """ + Creates a multi body from visual shapes in the physics simulator and returns the unique id of the created + multi body. + :param visual_shape_ids: The ids of the visual shapes that should be used to create the multi body. + :param pose: The pose of the origin of the multi body relative to the world frame. + :return: The unique id of the created multi body. + """ + # Dummy paramater since these are needed to spawn visual shapes as a + # multibody. + num_of_shapes = len(visual_shape_ids) + link_poses = [[0, 0, 0] for _ in range(num_of_shapes)] + link_orientations = [[0, 0, 0, 1] for _ in range(num_of_shapes)] + link_masses = [1.0 for _ in range(num_of_shapes)] + link_parent = [0 for _ in range(num_of_shapes)] + link_joints = [JointType.FIXED for _ in range(num_of_shapes)] + link_collision = [-1 for _ in range(num_of_shapes)] + link_joint_axis = [[1, 0, 0] for _ in range(num_of_shapes)] + + multi_body = MultiBody(base_visual_shape_index=-1, base_position=pose.position_as_list(), + base_orientation=pose.orientation_as_list(), + link_visual_shape_indices=visual_shape_ids, link_positions=link_poses, + link_orientations=link_orientations, link_masses=link_masses, + link_inertial_frame_positions=link_poses, + link_inertial_frame_orientations=link_orientations, + link_parent_indices=link_parent, link_joint_types=link_joints, + link_joint_axis=link_joint_axis, + link_collision_shape_indices=link_collision) + return self.create_multi_body(multi_body) + def create_multi_body(self, multi_body: MultiBody) -> int: """ Creates a multi body in the physics simulator and returns the unique id of the created multi body. The multibody @@ -962,6 +994,69 @@ def create_mesh_visual_shape(self, shape_data: MeshVisualShape) -> int: """ raise NotImplementedError + def add_text(self, text: str, position: List[float], orientation: Optional[List[float]] = None, size: float = 0.1, + color: Optional[Color] = Color(), life_time: Optional[float] = 0, + parent_object_id: Optional[int] = None) -> None: + """ + Adds text to the world. + :param text: The text to be added. + :param position: The position of the text in the world. + :param orientation: By default, debug text will always face the camera, + automatically rotation. By specifying a text orientation (quaternion), the orientation will be fixed in + world space or local space (when parent is specified). + :param size: The size of the text. + :param color: The color of the text. + :param life_time: The lifetime in seconds of the text to remain in the world, if 0 the text will remain + in the world until it is removed manually. + :param parent_object_id: The id of the object to which the text should be attached. + """ + raise NotImplementedError + + def remove_text(self, text_id: Optional[int] = None) -> None: + """ + Removes text from the world using the given id. if no id is given all text will be removed. + :param text_id: The id of the text to be removed. + """ + raise NotImplementedError + + def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: + """ + You can enable a joint force/torque sensor in each joint. Once enabled, if you perform + a simulation step, the get_joint_force_torque will report the joint reaction forces in the fixed degrees of + freedom: a fixed joint will measure all 6DOF joint forces/torques. A revolute/hinge joint + force/torque sensor will measure 5DOF reaction forces along all axis except the hinge axis. The + applied force by a joint motor is available through get_applied_joint_motor_torque. + :param obj: The object in which the joint is located. + :param fts_joint_idx: The index of the joint for which the force torque sensor should be enabled. + """ + raise NotImplementedError + + def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: + """ + Disables the force torque sensor of a joint. + :param obj: The object in which the joint is located. + :param joint_id: The id of the joint for which the force torque sensor should be disabled. + """ + raise NotImplementedError + + def get_joint_force_torque(self, obj: Object, joint_id: int) -> List[float]: + """ + Returns the joint reaction forces and torques of the specified joint. + :param obj: The object in which the joint is located. + :param joint_id: The id of the joint for which the force torque should be returned. + :return: The joint reaction forces and torques of the specified joint. + """ + raise NotImplementedError + + def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: + """ + Returns the applied torque by a joint motor. + :param obj: The object in which the joint is located. + :param joint_id: The id of the joint for which the applied motor torque should be returned. + :return: The applied torque by a joint motor. + """ + raise NotImplementedError + class UseProspectionWorld: """ @@ -1030,8 +1125,8 @@ def run(self): terminate flag is set. While this loop runs it continuously checks the cartesian and joint position of every object in the World and updates the corresponding object in the - prospection world. When there are entries in the adding or removing queue the corresponding objects will be added - or removed in the same iteration. + prospection world. When there are entries in the adding or removing queue the corresponding objects will + be added or removed in the same iteration. """ while not self.terminate: self.check_for_pause() @@ -1382,7 +1477,7 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.original_pose = self.local_transformer.transform_pose(pose, "map") self._current_pose = self.original_pose - self._load_object_and_set_id_and_path(path, ignore_cached_files) + self.id, self.path = self._load_object_and_get_id(path, ignore_cached_files) self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) @@ -1409,8 +1504,7 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.objects.append(self) - - def _load_object_and_set_id_and_path(self, path, ignore_cached_files: bool) -> None: + def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: """ Loads an object to the given World with the given position and orientation. The rgba_color will only be used when an .obj or .stl file is given. @@ -1421,6 +1515,7 @@ def _load_object_and_set_id_and_path(self, path, ignore_cached_files: bool) -> N to ROS packges instead there will be absolute file paths. :param ignore_cached_files: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path of the file that was loaded. """ pa = pathlib.Path(path) extension = pa.suffix @@ -1469,8 +1564,7 @@ def _load_object_and_set_id_and_path(self, path, ignore_cached_files: bool) -> N try: obj_id = self.world.load_urdf_and_get_object_id(path, Pose(self.get_position_as_list(), self.get_orientation_as_list())) - self.id = obj_id - self.path = path + return obj_id, path except Exception as e: logging.error( "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" @@ -1983,7 +2077,8 @@ def contact_points_simulated(self) -> List: def update_joints_from_topic(self, topic_name: str) -> None: """ Updates the joints of this object with positions obtained from a topic with the message type JointState. - Joint names on the topic have to correspond to the joints of this object otherwise an error message will be logged. + Joint names on the topic have to correspond to the joints of this object otherwise an error message will be + logged. :param topic_name: Name of the topic with the joint states """ diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 6eff03e2a..40d4d8db2 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -183,83 +183,47 @@ class MultiBody: link_collision_shape_indices: List[int] -@dataclass -class ShapeData: - pass - - -@dataclass -class BoxShapeData(ShapeData): - half_extents: List[float] - - -@dataclass -class SphereShapeData(ShapeData): - radius: float - - -@dataclass -class CapsuleShapeData(SphereShapeData): - length: float - - -@dataclass -class CylinderShapeData(CapsuleShapeData): - pass - - -@dataclass -class MeshShapeData(ShapeData): - mesh_scale: List[float] - mesh_file_name: str - - -@dataclass -class PlaneShapeData(ShapeData): - normal: List[float] - - @dataclass class VisualShape: rgba_color: Color visual_frame_position: List[float] - shape_data: ShapeData - visual_geometry_type: Shape @dataclass class BoxVisualShape(VisualShape): - shape_data: BoxShapeData - visual_geometry_type = Shape.BOX + half_extents: List[float] + visual_geometry_type: Optional[Shape] = Shape.BOX @dataclass class SphereVisualShape(VisualShape): - shape_data: SphereShapeData - visual_geometry_type = Shape.SPHERE + radius: float + visual_geometry_type: Optional[Shape] = Shape.SPHERE @dataclass -class CapsuleVisualShape(SphereVisualShape): - shape_data: CapsuleShapeData - visual_geometry_type = Shape.CAPSULE +class CapsuleVisualShape(VisualShape): + radius: float + length: float + visual_geometry_type: Optional[Shape] = Shape.CAPSULE @dataclass class CylinderVisualShape(CapsuleVisualShape): - visual_geometry_type = Shape.CYLINDER + visual_geometry_type: Optional[Shape] = Shape.CYLINDER @dataclass class MeshVisualShape(VisualShape): - visual_geometry_type = Shape.MESH - shape_data: MeshShapeData + mesh_scale: List[float] + mesh_file_name: str + visual_geometry_type: Optional[Shape] = Shape.MESH @dataclass class PlaneVisualShape(VisualShape): - shape_data: PlaneShapeData - visual_geometry_type = Shape.PLANE + normal: List[float] + visual_geometry_type: Optional[Shape] = Shape.PLANE @dataclass diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index f9fc06319..01d9709a8 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -1,5 +1,5 @@ import itertools -from typing import List, Tuple, Optional, Union, Dict +from typing_extensions import List, Tuple, Optional, Union, Dict import numpy as np @@ -23,7 +23,7 @@ def __init__(*args, **kwargs): def stable(obj: Object) -> bool: """ Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating - physics in the BulletWorld. This will be done by simulating the world for 10 seconds and compare + physics in the World. This will be done by simulating the world for 10 seconds and compare the previous coordinates with the coordinates after the simulation. :param obj: The object which should be checked @@ -78,6 +78,13 @@ def contact( def get_visible_objects( camera_pose: Pose, front_facing_axis: Optional[List[float]] = None) -> Tuple[np.ndarray, Pose]: + """ + Returns a segmentation mask of the objects that are visible from the given camera pose and the front facing axis. + :param camera_pose: The pose of the camera in world coordinate frame. + :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz + :return: A segmentation mask of the objects that are visible and the pose of the point at exactly 2 meters in front + of the camera in the direction of the front facing axis with respect to the world coordinate frame. + """ front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis world_to_cam = camera_pose.to_transform("camera") From c9328d5e41e58d874ce356973e89013702560122 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Thu, 1 Feb 2024 15:58:43 +0100 Subject: [PATCH 068/195] [doc] updated orm querying, motions and actions in documentation --- doc/source/designators.rst | 2 +- doc/source/index.rst | 48 +- examples/cram_plan_tutorial.ipynb | 18 +- examples/custom_resolver.ipynb | 70 +- examples/intro.ipynb | 2265 +++++++++++++------------- examples/local_transformer.ipynb | 97 +- examples/migrate_neems.ipynb | 4 +- examples/motion_designator.ipynb | 296 ++-- examples/orm_example.ipynb | 206 ++- examples/orm_querying_examples.ipynb | 57 +- 10 files changed, 1582 insertions(+), 1481 deletions(-) diff --git a/doc/source/designators.rst b/doc/source/designators.rst index d07af0a5e..08ec4d8f4 100644 --- a/doc/source/designators.rst +++ b/doc/source/designators.rst @@ -45,7 +45,7 @@ action looks like this: .. code-block:: python - NavigateAction.Action(robot_position=((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0)), target_location=[[1, 0, 0], [0, 0, 0, 1]]) + NavigateActionPerformable(robot_position=((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0)), target_location=[[1, 0, 0], [0, 0, 0, 1]]) A visual representation of the whole idea of designator and designator descriptions can be diff --git a/doc/source/index.rst b/doc/source/index.rst index c8ab43941..fb1161d2d 100644 --- a/doc/source/index.rst +++ b/doc/source/index.rst @@ -52,30 +52,48 @@ The code for this plan can be seen below. .. code-block:: python - @with_simulated_robot - def plan(): - MotionDesignator(MoveArmJointsMotionDescription(left_arm_config='park', - right_arm_config='park')).perform() + from pycram.bullet_world import BulletWorld, Object + from pycram.process_module import simulated_robot + from pycram.designators.motion_designator import * + from pycram.designators.location_designator import * + from pycram.designators.action_designator import * + from pycram.designators.object_designator import * + from pycram.enums import ObjectType - MotionDesignator(MoveMotionDescription(target=moving_targets[robot_name]["sink"][0], - orientation=moving_targets[robot_name]["sink"][1])).perform() + world = BulletWorld() + kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") + robot = Object("pr2", ObjectType.ROBOT, "pr2.urdf") + cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", position=[1.4, 1, 0.95]) - det_obj = MotionDesignator(DetectingMotionDescription(object_type="milk")).perform() + cereal_desig = ObjectDesignatorDescription(names=["cereal"]) + kitchen_desig = ObjectDesignatorDescription(names=["kitchen"]) + robot_desig = ObjectDesignatorDescription(names=["pr2"]).resolve() - MotionDesignator(PickUpMotionDescription(object=milk, arm="left", grasp="front")).perform() + with simulated_robot: + ParkArmsAction([Arms.BOTH]).resolve().perform() + MoveTorsoAction([0.3]).resolve().perform() - MotionDesignator(MoveMotionDescription(target=moving_targets[robot_name]["island"][0], - orientation=moving_targets[robot_name]["island"][1])).perform() + pickup_pose = CostmapLocation(target=cereal_desig.resolve(), reachable_for=robot_desig).resolve() + pickup_arm = pickup_pose.reachable_arms[0] - MotionDesignator(PlaceMotionDescription(object=milk, target=[-0.9, 1, 0.93], arm="left")).perform() + NavigateAction(target_locations=[pickup_pose.pose]).resolve().perform() - MotionDesignator(MoveArmJointsMotionDescription(left_arm_config='park', - right_arm_config='park')).perform() + PickUpAction(object_designator_description=cereal_desig, arms=[pickup_arm], grasps=["front"]).resolve().perform() - MotionDesignator(MoveMotionDescription(target=[0.0, 0.0, 0], - orientation=[0, 0, 0, 1])).perform() + ParkArmsAction([Arms.BOTH]).resolve().perform() + place_island = SemanticCostmapLocation("kitchen_island_surface", kitchen_desig.resolve(), cereal_desig.resolve()).resolve() + + place_stand = CostmapLocation(place_island.pose, reachable_for=robot_desig, reachable_arm=pickup_arm).resolve() + + NavigateAction(target_locations=[place_stand.pose]).resolve().perform() + + PlaceAction(cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform() + + ParkArmsAction([Arms.BOTH]).resolve().perform() + + world.exit() Tutorials --------- diff --git a/examples/cram_plan_tutorial.ipynb b/examples/cram_plan_tutorial.ipynb index a7fd04383..a26cd5b88 100644 --- a/examples/cram_plan_tutorial.ipynb +++ b/examples/cram_plan_tutorial.ipynb @@ -287,30 +287,30 @@ "def plan(obj, obj_desig, torso=0.2, place=\"countertop\"):\n", " world.reset_bullet_world()\n", " with simulated_robot:\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", "\n", - " MoveTorsoAction.Action(torso).perform()\n", + " MoveTorsoActionPerformable(torso).perform()\n", " location = CostmapLocation(target=obj_desig, reachable_for=robot_desig)\n", " pose = location.resolve()\n", " print()\n", - " NavigateAction.Action(pose.pose).perform()\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " NavigateActionPerformable(pose.pose).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", " good_torsos.append(torso)\n", " picked_up_arm = pose.reachable_arms[0]\n", - " PickUpAction.Action(object_designator=obj_desig, arm=pose.reachable_arms[0], grasp=\"front\").perform()\n", + " PickUpActionPerformable(object_designator=obj_desig, arm=pose.reachable_arms[0], grasp=\"front\").perform()\n", "\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", " scm = SemanticCostmapLocation(place, apartment_desig, obj_desig)\n", " pose_island = scm.resolve()\n", "\n", " place_location = CostmapLocation(target=pose_island.pose, reachable_for=robot_desig, reachable_arm=picked_up_arm)\n", " pose = place_location.resolve()\n", "\n", - " NavigateAction.Action(pose.pose).perform()\n", + " NavigateActionPerformable(pose.pose).perform()\n", "\n", - " PlaceAction.Action(object_designator=obj_desig, target_location=pose_island.pose, arm=picked_up_arm).perform()\n", + " PlaceActionPerformable(object_designator=obj_desig, target_location=pose_island.pose, arm=picked_up_arm).perform()\n", "\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", "\n", "good_torsos = []\n", "for obj_name in object_names:\n", diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb index 21e1bf7cc..ef4413897 100644 --- a/examples/custom_resolver.ipynb +++ b/examples/custom_resolver.ipynb @@ -23,8 +23,8 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:35.037185202Z", - "start_time": "2024-01-05T11:39:32.842006673Z" + "end_time": "2024-01-29T16:05:37.443271489Z", + "start_time": "2024-01-29T16:05:35.328010988Z" } }, "outputs": [ @@ -32,22 +32,15 @@ "name": "stdout", "output_type": "stream", "text": [ - "Collecting probabilistic_model\r\n", - " Using cached probabilistic_model-1.5.18-py3-none-any.whl (30 kB)\r\n", - "Requirement already satisfied, skipping upgrade: portion>=2.4.1 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.4.1)\r\n", + "Requirement already up-to-date: probabilistic_model in /home/dprueser/.local/lib/python3.8/site-packages (1.6.20)\r\n", "Requirement already satisfied, skipping upgrade: random-events>=1.2.5 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", - "Requirement already satisfied, skipping upgrade: plotly>=5.18.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (5.18.0)\r\n", "Requirement already satisfied, skipping upgrade: anytree>=2.9.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.9.0)\r\n", + "Requirement already satisfied, skipping upgrade: portion>=2.4.1 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.4.1)\r\n", + "Requirement already satisfied, skipping upgrade: plotly>=5.18.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (5.18.0)\r\n", + "Requirement already satisfied, skipping upgrade: six in /usr/local/lib/python3.8/dist-packages (from anytree>=2.9.0->probabilistic_model) (1.16.0)\r\n", "Requirement already satisfied, skipping upgrade: sortedcontainers~=2.2 in /home/dprueser/.local/lib/python3.8/site-packages (from portion>=2.4.1->probabilistic_model) (2.4.0)\r\n", "Requirement already satisfied, skipping upgrade: tenacity>=6.2.0 in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (8.2.3)\r\n", - "Requirement already satisfied, skipping upgrade: packaging in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (23.2)\r\n", - "Requirement already satisfied, skipping upgrade: six in /usr/lib/python3/dist-packages (from anytree>=2.9.0->probabilistic_model) (1.14.0)\r\n", - "Installing collected packages: probabilistic-model\r\n", - " Attempting uninstall: probabilistic-model\r\n", - " Found existing installation: probabilistic-model 1.5.17\r\n", - " Uninstalling probabilistic-model-1.5.17:\r\n", - " Successfully uninstalled probabilistic-model-1.5.17\r\n", - "Successfully installed probabilistic-model-1.5.18\r\n" + "Requirement already satisfied, skipping upgrade: packaging in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (23.2)\r\n" ] } ], @@ -60,8 +53,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:36.023993906Z", - "start_time": "2024-01-05T11:39:35.047597162Z" + "end_time": "2024-01-29T16:05:38.648889392Z", + "start_time": "2024-01-29T16:05:37.442437872Z" } }, "outputs": [ @@ -74,8 +67,8 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1704454775.649694]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1704454775.654652]: Failed to import Giskard messages\n" + "[WARN] [1706544338.060994]: Failed to import Giskard messages\n", + "[WARN] [1706544338.065403]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -249,8 +242,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-01-05T11:41:21.098968043Z", - "start_time": "2024-01-05T11:39:36.024974459Z" + "end_time": "2024-01-29T16:07:21.351710589Z", + "start_time": "2024-01-29T16:05:38.643086881Z" } }, "outputs": [ @@ -270,9 +263,9 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - " 38%|███▊ | 369/960 [00:40<01:06, 8.92it/s, success_rate=0.0867]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/l_gripper_motor_screw_link (parent map) at time 1704454816.991220 according to authority default_authority\n", + " 96%|█████████▌| 923/960 [01:38<00:03, 9.52it/s, success_rate=0.0845]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame spoon_2 (parent map) at time 1706544437.280444 according to authority default_authority\n", " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", - "100%|██████████| 960/960 [01:44<00:00, 9.47it/s, success_rate=0.0854]" + "100%|██████████| 960/960 [01:42<00:00, 10.12it/s, success_rate=0.0854]" ] } ], @@ -298,8 +291,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:41:21.193149641Z", - "start_time": "2024-01-05T11:41:21.142076887Z" + "end_time": "2024-01-29T16:07:21.445516208Z", + "start_time": "2024-01-29T16:07:21.396046276Z" } }, "outputs": [], @@ -325,8 +318,8 @@ "metadata": { "scrolled": true, "ExecuteTime": { - "end_time": "2024-01-05T11:41:21.278910069Z", - "start_time": "2024-01-05T11:41:21.194743363Z" + "end_time": "2024-01-29T16:07:21.541375696Z", + "start_time": "2024-01-29T16:07:21.448402324Z" } }, "outputs": [], @@ -365,8 +358,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-01-05T11:41:21.326300043Z", - "start_time": "2024-01-05T11:41:21.284443546Z" + "end_time": "2024-01-29T16:07:21.605599589Z", + "start_time": "2024-01-29T16:07:21.552928567Z" } }, "outputs": [ @@ -374,7 +367,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "SELECT \"TaskTreeNode\".status AS \"TaskTreeNode_status\", \"Object\".type AS \"Object_type\", \"PickUpAction\".arm AS \"PickUpAction_arm\", \"PickUpAction\".grasp AS \"PickUpAction_grasp\", \"Position_1\".z - \"RobotState\".torso_height AS \"relative torso height\", \"Position_2\".x - \"Position_1\".x AS x, \"Position_2\".y - \"Position_1\".y AS y \n", + "SELECT \"TaskTreeNode\".status, \"Object\".type, \"PickUpAction\".arm, \"PickUpAction\".grasp, \"Position_1\".z - \"RobotState\".torso_height AS \"relative torso height\", \"Position_2\".x - \"Position_1\".x AS x, \"Position_2\".y - \"Position_1\".y AS y \n", "FROM \"TaskTreeNode\" JOIN \"Code\" ON \"Code\".id = \"TaskTreeNode\".code_id JOIN (\"Designator\" JOIN \"Action\" ON \"Designator\".id = \"Action\".id JOIN \"PickUpAction\" ON \"Action\".id = \"PickUpAction\".id) ON \"Designator\".id = \"Code\".designator_id JOIN \"RobotState\" ON \"RobotState\".id = \"Action\".robot_state_id JOIN \"Pose\" AS \"Pose_1\" ON \"Pose_1\".id = \"RobotState\".pose_id JOIN \"Position\" AS \"Position_2\" ON \"Position_2\".id = \"Pose_1\".position_id JOIN \"Object\" ON \"Object\".id = \"PickUpAction\".object_id JOIN \"Pose\" AS \"Pose_2\" ON \"Pose_2\".id = \"Object\".pose_id JOIN \"Position\" AS \"Position_1\" ON \"Position_1\".id = \"Pose_2\".position_id\n", " status type arm grasp \\\n", "0 FAILED ObjectType.BREAKFAST_CEREAL left left \n", @@ -407,6 +400,7 @@ } ], "source": [ + "from sqlalchemy import select\n", "from pycram.orm.base import Pose as ORMPose\n", "\n", "robot_pose = sqlalchemy.orm.aliased(ORMPose)\n", @@ -414,7 +408,7 @@ "robot_pos = sqlalchemy.orm.aliased(Position)\n", "object_pos = sqlalchemy.orm.aliased(Position)\n", "\n", - "query = (session.query(TaskTreeNode.status, Object.type, ORMPickUpAction.arm, ORMPickUpAction.grasp,\n", + "query = (select(TaskTreeNode.status, Object.type, ORMPickUpAction.arm, ORMPickUpAction.grasp,\n", " sqlalchemy.label(\"relative torso height\", object_pos.z - RobotState.torso_height),\n", " sqlalchemy.label(\"x\", robot_pos.x - object_pos.x), \n", " sqlalchemy.label(\"y\", robot_pos.y - object_pos.y))\n", @@ -428,7 +422,7 @@ " .join(object_pos, object_pose.position))\n", "print(query)\n", "\n", - "df = pd.read_sql(query.statement, session.get_bind())\n", + "df = pd.read_sql(query, session.get_bind())\n", "df[\"status\"] = df[\"status\"].apply(lambda x: str(x.name))\n", "print(df)" ] @@ -445,8 +439,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:41:21.658478914Z", - "start_time": "2024-01-05T11:41:21.326092672Z" + "end_time": "2024-01-29T16:07:21.939517021Z", + "start_time": "2024-01-29T16:07:21.601075366Z" } }, "outputs": [ @@ -454,7 +448,7 @@ "name": "stderr", "output_type": "stream", "text": [ - "100%|██████████| 960/960 [01:45<00:00, 9.11it/s, success_rate=0.0854]\n" + "100%|██████████| 960/960 [01:43<00:00, 9.32it/s, success_rate=0.0854]\n" ] }, { @@ -487,8 +481,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:46:59.969239637Z", - "start_time": "2024-01-05T11:41:21.659115424Z" + "end_time": "2024-01-29T16:13:01.579305735Z", + "start_time": "2024-01-29T16:07:21.942920319Z" } }, "outputs": [ @@ -499,11 +493,11 @@ "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", diff --git a/examples/intro.ipynb b/examples/intro.ipynb index d0247e613..9096f380c 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -12,8 +12,8 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:17.693331699Z", - "start_time": "2024-01-05T11:38:17.084580161Z" + "end_time": "2024-01-29T16:14:50.953932170Z", + "start_time": "2024-01-29T16:14:50.284068023Z" } }, "outputs": [ @@ -26,8 +26,8 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1704454697.683303]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1704454697.688683]: Failed to import Giskard messages\n" + "[WARN] [1706544890.889466]: Failed to import Giskard messages\n", + "[WARN] [1706544890.894063]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -53,8 +53,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:18.005042043Z", - "start_time": "2024-01-05T11:38:17.754902302Z" + "end_time": "2024-01-29T16:14:51.215354072Z", + "start_time": "2024-01-29T16:14:50.980844838Z" } }, "outputs": [ @@ -92,19 +92,11 @@ "execution_count": 3, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:18.052419130Z", - "start_time": "2024-01-05T11:38:18.021916002Z" + "end_time": "2024-01-29T16:14:51.251936758Z", + "start_time": "2024-01-29T16:14:51.234948638Z" } }, "outputs": [ - { - "data": { - "text/plain": "[array([[[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n ...,\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]]], dtype=uint8),\n array([[0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n ...,\n [0.80473447, 0.80473447, 0.80473447, ..., 0.80473447, 0.80473447,\n 0.80473447],\n [0.8031688 , 0.8031688 , 0.8031688 , ..., 0.8031688 , 0.8031688 ,\n 0.8031688 ],\n [0.80160314, 0.80160314, 0.80160314, ..., 0.80160314, 0.80160314,\n 0.80160314]], dtype=float32),\n array([[-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n ...,\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1]], dtype=int32)]" - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - }, { "name": "stderr", "output_type": "stream", @@ -112,6 +104,14 @@ "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" ] + }, + { + "data": { + "text/plain": "[array([[[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n [[255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n ...,\n [255, 255, 255, 255],\n [255, 255, 255, 255],\n [255, 255, 255, 255]],\n \n ...,\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]],\n \n [[239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n ...,\n [239, 239, 239, 255],\n [239, 239, 239, 255],\n [239, 239, 239, 255]]], dtype=uint8),\n array([[0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n [0.99999994, 0.99999994, 0.99999994, ..., 0.99999994, 0.99999994,\n 0.99999994],\n ...,\n [0.80473447, 0.80473447, 0.80473447, ..., 0.80473447, 0.80473447,\n 0.80473447],\n [0.8031688 , 0.8031688 , 0.8031688 , ..., 0.8031688 , 0.8031688 ,\n 0.8031688 ],\n [0.80160314, 0.80160314, 0.80160314, ..., 0.80160314, 0.80160314,\n 0.80160314]], dtype=float32),\n array([[-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n [-1, -1, -1, ..., -1, -1, -1],\n ...,\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1],\n [ 1, 1, 1, ..., 1, 1, 1]], dtype=int32)]" + }, + "execution_count": 3, + "metadata": {}, + "output_type": "execute_result" } ], "source": [ @@ -149,8 +149,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:18.094930935Z", - "start_time": "2024-01-05T11:38:18.028522514Z" + "end_time": "2024-01-29T16:14:51.319150211Z", + "start_time": "2024-01-29T16:14:51.238519616Z" } }, "outputs": [], @@ -172,8 +172,8 @@ "execution_count": 5, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:18.097339564Z", - "start_time": "2024-01-05T11:38:18.096109982Z" + "end_time": "2024-01-29T16:14:51.361155485Z", + "start_time": "2024-01-29T16:14:51.360054431Z" } }, "outputs": [], @@ -193,8 +193,8 @@ "execution_count": 6, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:18.142227637Z", - "start_time": "2024-01-05T11:38:18.099015288Z" + "end_time": "2024-01-29T16:14:51.404210573Z", + "start_time": "2024-01-29T16:14:51.360232825Z" } }, "outputs": [], @@ -214,8 +214,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:21.716481380Z", - "start_time": "2024-01-05T11:38:18.142151725Z" + "end_time": "2024-01-29T16:14:54.380977290Z", + "start_time": "2024-01-29T16:14:51.404113811Z" } }, "outputs": [ @@ -261,8 +261,8 @@ "execution_count": 8, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:22.274205765Z", - "start_time": "2024-01-05T11:38:21.717433092Z" + "end_time": "2024-01-29T16:14:54.951307507Z", + "start_time": "2024-01-29T16:14:54.380864026Z" } }, "outputs": [], @@ -276,8 +276,8 @@ "execution_count": 9, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:30.651191441Z", - "start_time": "2024-01-05T11:38:30.646880498Z" + "end_time": "2024-01-29T16:15:01.756580723Z", + "start_time": "2024-01-29T16:14:54.961615686Z" } }, "outputs": [], @@ -290,8 +290,8 @@ "execution_count": 10, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:33.983967866Z", - "start_time": "2024-01-05T11:38:30.649221674Z" + "end_time": "2024-01-29T16:15:05.092885577Z", + "start_time": "2024-01-29T16:15:05.091325419Z" } }, "outputs": [], @@ -312,8 +312,8 @@ "execution_count": 11, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:34.747939331Z", - "start_time": "2024-01-05T11:38:33.985076157Z" + "end_time": "2024-01-29T16:15:05.847569295Z", + "start_time": "2024-01-29T16:15:05.093669437Z" } }, "outputs": [], @@ -326,8 +326,8 @@ "execution_count": 12, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:34.845540496Z", - "start_time": "2024-01-05T11:38:34.749095455Z" + "end_time": "2024-01-29T16:15:05.944506368Z", + "start_time": "2024-01-29T16:15:05.849514274Z" } }, "outputs": [], @@ -350,8 +350,8 @@ "execution_count": 13, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:35.719367991Z", - "start_time": "2024-01-05T11:38:34.846943933Z" + "end_time": "2024-01-29T16:15:06.810575822Z", + "start_time": "2024-01-29T16:15:05.955432369Z" } }, "outputs": [], @@ -364,8 +364,8 @@ "execution_count": 14, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:36.074271101Z", - "start_time": "2024-01-05T11:38:36.067925005Z" + "end_time": "2024-01-29T16:15:07.161867271Z", + "start_time": "2024-01-29T16:15:07.159806241Z" } }, "outputs": [], @@ -385,8 +385,8 @@ "execution_count": 15, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:36.075213164Z", - "start_time": "2024-01-05T11:38:36.070266632Z" + "end_time": "2024-01-29T16:15:07.193879719Z", + "start_time": "2024-01-29T16:15:07.161787791Z" } }, "outputs": [], @@ -399,8 +399,8 @@ "execution_count": 16, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:38.237916925Z", - "start_time": "2024-01-05T11:38:36.073992561Z" + "end_time": "2024-01-29T16:15:09.283523209Z", + "start_time": "2024-01-29T16:15:07.188128850Z" } }, "outputs": [], @@ -413,8 +413,8 @@ "execution_count": 17, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:39.305574111Z", - "start_time": "2024-01-05T11:38:38.238541874Z" + "end_time": "2024-01-29T16:15:10.347228575Z", + "start_time": "2024-01-29T16:15:09.280179794Z" } }, "outputs": [], @@ -444,8 +444,8 @@ "execution_count": 18, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:41.970422232Z", - "start_time": "2024-01-05T11:38:39.305851886Z" + "end_time": "2024-01-29T16:15:12.961385558Z", + "start_time": "2024-01-29T16:15:10.347682457Z" } }, "outputs": [ @@ -453,6 +453,10 @@ "name": "stderr", "output_type": "stream", "text": [ + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", @@ -479,21 +483,11 @@ "metadata": { "scrolled": true, "ExecuteTime": { - "end_time": "2024-01-05T11:38:42.271284276Z", - "start_time": "2024-01-05T11:38:41.989603716Z" + "end_time": "2024-01-29T16:15:13.246942739Z", + "start_time": "2024-01-29T16:15:12.963076402Z" } }, "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" - ] - }, { "name": "stdout", "output_type": "stream", @@ -513,8 +507,8 @@ "execution_count": 20, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:42.355865055Z", - "start_time": "2024-01-05T11:38:42.270253375Z" + "end_time": "2024-01-29T16:15:13.334740244Z", + "start_time": "2024-01-29T16:15:13.249042978Z" } }, "outputs": [ @@ -539,8 +533,8 @@ "execution_count": 21, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:42.450970248Z", - "start_time": "2024-01-05T11:38:42.358883797Z" + "end_time": "2024-01-29T16:15:13.430296220Z", + "start_time": "2024-01-29T16:15:13.334507309Z" } }, "outputs": [ @@ -586,8 +580,8 @@ "execution_count": 22, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:42.957994018Z", - "start_time": "2024-01-05T11:38:42.494000112Z" + "end_time": "2024-01-29T16:15:13.939910370Z", + "start_time": "2024-01-29T16:15:13.437727375Z" } }, "outputs": [], @@ -598,7 +592,7 @@ "description = MoveMotion(target=Pose([1, 0, 0], [0, 0, 0, 1]))\n", "\n", "with simulated_robot:\n", - " description.resolve().perform()\n", + " description.perform()\n", " \n" ] }, @@ -608,8 +602,8 @@ "metadata": { "scrolled": true, "ExecuteTime": { - "end_time": "2024-01-05T11:38:43.465280115Z", - "start_time": "2024-01-05T11:38:42.966741953Z" + "end_time": "2024-01-29T16:15:14.446281217Z", + "start_time": "2024-01-29T16:15:13.948689644Z" } }, "outputs": [], @@ -618,7 +612,7 @@ "\n", "@with_simulated_robot\n", "def move():\n", - " MoveMotion(target=Pose([0, 0, 0], [0, 0, 0, 1])).resolve().perform()\n", + " MoveMotion(target=Pose([0, 0, 0], [0, 0, 0, 1])).perform()\n", "\n", "move()" ] @@ -628,8 +622,6 @@ "metadata": {}, "source": [ "Other implemented Motion Designator descriptions are:\n", - "* Pick up\n", - "* Place\n", "* Accessing\n", "* Move TCP\n", "* Looking\n", @@ -653,14 +645,14 @@ "execution_count": 24, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:43.472245439Z", - "start_time": "2024-01-05T11:38:43.467689247Z" + "end_time": "2024-01-29T16:15:14.453344058Z", + "start_time": "2024-01-29T16:15:14.448819583Z" } }, "outputs": [ { "data": { - "text/plain": "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1704454719\n nsecs: 314873933\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1704454722\n nsecs: 356852293\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...), _pose=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1704454719\n nsecs: 314873933\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1704454722\n nsecs: 356852293\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...)>)" + "text/plain": "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1706544910\n nsecs: 372853994\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1706544913\n nsecs: 335583925\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...), _pose=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1706544910\n nsecs: 372853994\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1706544913\n nsecs: 335583925\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...)>)" }, "execution_count": 24, "metadata": {}, @@ -688,8 +680,43 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-01-05T11:38:50.957195391Z", - "start_time": "2024-01-05T11:38:43.471315489Z" + "end_time": "2024-01-29T16:15:14.493010865Z", + "start_time": "2024-01-29T16:15:14.451251059Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": "BelieveObject.Object(name='Milk', type=, bullet_world_object=Object(world=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1706544910\n nsecs: 372853994\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1706544913\n nsecs: 335583925\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...), _pose=, \nlocal_transformer=, \nname=Milk, \ntype=ObjectType.MILK, \ncolor=[1, 1, 1, 1], \nid=4, \npath=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \njoints: ..., \nlinks: ..., \nattachments: ..., \ncids: ..., \noriginal_pose=header: \n seq: 0\n stamp: \n secs: 1706544910\n nsecs: 372853994\n frame_id: \"map\"\npose: \n position: \n x: 1.0\n y: 0.0\n z: 1.0\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \ntf_frame=Milk_4, \nurdf_object: ..., \n_current_pose=header: \n seq: 0\n stamp: \n secs: 1706544913\n nsecs: 335583925\n frame_id: \"map\"\npose: \n position: \n x: 0.6\n y: -0.5\n z: 0.7\n orientation: \n x: 0.0\n y: 0.0\n z: 0.0\n w: 1.0, \n_current_link_poses: ..., \n_current_link_transforms: ..., \n_current_joint_states={}, \nbase_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \nlink_to_geometry: ...)>)" + }, + "execution_count": 25, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "from pycram.designators.object_designator import *\n", + "\n", + "milk_desig = BelieveObject(names=[\"Milk\"])\n", + "milk_desig.resolve()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Location Designators\n", + "Location Designators can create a position in cartesian space from a symbolic description." + ] + }, + { + "cell_type": "code", + "execution_count": 26, + "metadata": { + "scrolled": false, + "ExecuteTime": { + "end_time": "2024-01-29T16:15:22.177685226Z", + "start_time": "2024-01-29T16:15:14.482072615Z" } }, "outputs": [ @@ -700,8 +727,8 @@ "Resolved: CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 189191341\n", + " secs: 1706544915\n", + " nsecs: 201824188\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -716,8 +743,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 901956796\n", + " secs: 1706544915\n", + " nsecs: 927674055\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -732,8 +759,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 911677598\n", + " secs: 1706544915\n", + " nsecs: 938544273\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -748,8 +775,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 921111106\n", + " secs: 1706544915\n", + " nsecs: 949182987\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -764,8 +791,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 930423736\n", + " secs: 1706544915\n", + " nsecs: 959582567\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -780,8 +807,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 939850091\n", + " secs: 1706544915\n", + " nsecs: 969888687\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -796,8 +823,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 949112415\n", + " secs: 1706544915\n", + " nsecs: 979798555\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -812,8 +839,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 958681583\n", + " secs: 1706544915\n", + " nsecs: 994071245\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -828,8 +855,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 968044519\n", + " secs: 1706544916\n", + " nsecs: 9548187\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -844,8 +871,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 977337121\n", + " secs: 1706544916\n", + " nsecs: 24910449\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -860,8 +887,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454724\n", - " nsecs: 986764192\n", + " secs: 1706544916\n", + " nsecs: 40581226\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -876,8 +903,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 5548715\n", + " secs: 1706544916\n", + " nsecs: 71025371\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -892,8 +919,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 24160146\n", + " secs: 1706544916\n", + " nsecs: 103567123\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -908,8 +935,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 33551692\n", + " secs: 1706544916\n", + " nsecs: 120177507\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -924,8 +951,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 43041944\n", + " secs: 1706544916\n", + " nsecs: 135888099\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -940,8 +967,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 52456855\n", + " secs: 1706544916\n", + " nsecs: 147926568\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -956,8 +983,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 61823606\n", + " secs: 1706544916\n", + " nsecs: 158867120\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -972,8 +999,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 71311473\n", + " secs: 1706544916\n", + " nsecs: 171792984\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -988,8 +1015,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 80672740\n", + " secs: 1706544916\n", + " nsecs: 183446645\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1004,8 +1031,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 90170145\n", + " secs: 1706544916\n", + " nsecs: 195348024\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1020,8 +1047,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 118748664\n", + " secs: 1706544916\n", + " nsecs: 225474596\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1036,8 +1063,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 128309965\n", + " secs: 1706544916\n", + " nsecs: 235300779\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1052,8 +1079,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 137932062\n", + " secs: 1706544916\n", + " nsecs: 246283054\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1068,8 +1095,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 147601604\n", + " secs: 1706544916\n", + " nsecs: 255914211\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1084,8 +1111,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 157281398\n", + " secs: 1706544916\n", + " nsecs: 265790700\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1100,8 +1127,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 166773319\n", + " secs: 1706544916\n", + " nsecs: 276698589\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1116,8 +1143,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 176612615\n", + " secs: 1706544916\n", + " nsecs: 289893150\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1132,8 +1159,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 186205387\n", + " secs: 1706544916\n", + " nsecs: 303444147\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1148,8 +1175,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 196010589\n", + " secs: 1706544916\n", + " nsecs: 314954519\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1164,8 +1191,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 205993652\n", + " secs: 1706544916\n", + " nsecs: 332621335\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1180,8 +1207,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 215711593\n", + " secs: 1706544916\n", + " nsecs: 348136901\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1196,8 +1223,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 225684404\n", + " secs: 1706544916\n", + " nsecs: 359711885\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1212,8 +1239,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 235526561\n", + " secs: 1706544916\n", + " nsecs: 370139122\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1228,8 +1255,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 255168437\n", + " secs: 1706544916\n", + " nsecs: 395307302\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1244,8 +1271,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 264625310\n", + " secs: 1706544916\n", + " nsecs: 405689239\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1260,8 +1287,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 274528026\n", + " secs: 1706544916\n", + " nsecs: 416645288\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1276,8 +1303,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 293281793\n", + " secs: 1706544916\n", + " nsecs: 437982320\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1292,8 +1319,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 302706003\n", + " secs: 1706544916\n", + " nsecs: 448891639\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1308,8 +1335,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 321676969\n", + " secs: 1706544916\n", + " nsecs: 469527959\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1324,8 +1351,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 331218719\n", + " secs: 1706544916\n", + " nsecs: 480023622\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1340,8 +1367,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 341029405\n", + " secs: 1706544916\n", + " nsecs: 490493774\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1356,8 +1383,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 350405693\n", + " secs: 1706544916\n", + " nsecs: 501381158\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1372,8 +1399,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 360239028\n", + " secs: 1706544916\n", + " nsecs: 511650800\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1388,8 +1415,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 369774341\n", + " secs: 1706544916\n", + " nsecs: 521751880\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1404,8 +1431,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 379291534\n", + " secs: 1706544916\n", + " nsecs: 532479286\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1420,8 +1447,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 408546209\n", + " secs: 1706544916\n", + " nsecs: 561986207\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1436,8 +1463,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 418382167\n", + " secs: 1706544916\n", + " nsecs: 571810960\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1452,8 +1479,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 428440093\n", + " secs: 1706544916\n", + " nsecs: 581784725\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1468,8 +1495,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 448060989\n", + " secs: 1706544916\n", + " nsecs: 601855516\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1484,8 +1511,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 458268404\n", + " secs: 1706544916\n", + " nsecs: 611686706\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1500,8 +1527,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 468119144\n", + " secs: 1706544916\n", + " nsecs: 622118949\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1516,8 +1543,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 477586746\n", + " secs: 1706544916\n", + " nsecs: 632574319\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1532,8 +1559,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 487447023\n", + " secs: 1706544916\n", + " nsecs: 643788337\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1548,8 +1575,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 496778726\n", + " secs: 1706544916\n", + " nsecs: 654880285\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1564,8 +1591,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 515697717\n", + " secs: 1706544916\n", + " nsecs: 675857067\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1580,8 +1607,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 535202741\n", + " secs: 1706544916\n", + " nsecs: 696542024\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1596,8 +1623,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 562966585\n", + " secs: 1706544916\n", + " nsecs: 728210210\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1612,8 +1639,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 603397607\n", + " secs: 1706544916\n", + " nsecs: 769653797\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1628,8 +1655,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 613683938\n", + " secs: 1706544916\n", + " nsecs: 779698371\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1644,8 +1671,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 623685836\n", + " secs: 1706544916\n", + " nsecs: 790320158\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1660,8 +1687,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 635320425\n", + " secs: 1706544916\n", + " nsecs: 800973892\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1676,8 +1703,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 645336151\n", + " secs: 1706544916\n", + " nsecs: 811413764\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1692,8 +1719,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 665030956\n", + " secs: 1706544916\n", + " nsecs: 832077503\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1708,8 +1735,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 684486150\n", + " secs: 1706544916\n", + " nsecs: 853376865\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1724,8 +1751,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 694182634\n", + " secs: 1706544916\n", + " nsecs: 865315675\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1740,8 +1767,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 703764915\n", + " secs: 1706544916\n", + " nsecs: 875989675\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1756,8 +1783,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 722873687\n", + " secs: 1706544916\n", + " nsecs: 896036386\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1772,8 +1799,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 732309579\n", + " secs: 1706544916\n", + " nsecs: 906243562\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1788,8 +1815,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 742166519\n", + " secs: 1706544916\n", + " nsecs: 916708469\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1804,8 +1831,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 752015113\n", + " secs: 1706544916\n", + " nsecs: 927308559\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1820,8 +1847,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 762117147\n", + " secs: 1706544916\n", + " nsecs: 937535762\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1836,8 +1863,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 772179365\n", + " secs: 1706544916\n", + " nsecs: 947962045\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1852,8 +1879,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 781810283\n", + " secs: 1706544916\n", + " nsecs: 958276748\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1868,8 +1895,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 792211532\n", + " secs: 1706544916\n", + " nsecs: 969069242\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1884,8 +1911,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 802207708\n", + " secs: 1706544916\n", + " nsecs: 980567216\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1900,8 +1927,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 811917543\n", + " secs: 1706544916\n", + " nsecs: 992730140\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1916,8 +1943,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 822474241\n", + " secs: 1706544917\n", + " nsecs: 3598690\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1932,8 +1959,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 832451105\n", + " secs: 1706544917\n", + " nsecs: 14332056\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1948,8 +1975,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 842451095\n", + " secs: 1706544917\n", + " nsecs: 24833202\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1964,8 +1991,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 864063024\n", + " secs: 1706544917\n", + " nsecs: 44901132\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1980,8 +2007,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 874287605\n", + " secs: 1706544917\n", + " nsecs: 55425643\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -1996,8 +2023,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 884132862\n", + " secs: 1706544917\n", + " nsecs: 66057682\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2012,8 +2039,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 893823862\n", + " secs: 1706544917\n", + " nsecs: 78454971\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2028,8 +2055,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 913730621\n", + " secs: 1706544917\n", + " nsecs: 98734617\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2044,8 +2071,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 923520088\n", + " secs: 1706544917\n", + " nsecs: 108744382\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2060,8 +2087,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 932972908\n", + " secs: 1706544917\n", + " nsecs: 119309425\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2076,8 +2103,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 942650079\n", + " secs: 1706544917\n", + " nsecs: 129229784\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2092,8 +2119,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 952360153\n", + " secs: 1706544917\n", + " nsecs: 139137268\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2108,8 +2135,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 962044715\n", + " secs: 1706544917\n", + " nsecs: 149181365\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2124,8 +2151,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454725\n", - " nsecs: 972100019\n", + " secs: 1706544917\n", + " nsecs: 159062862\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2140,8 +2167,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 10155916\n", + " secs: 1706544917\n", + " nsecs: 197809934\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2156,8 +2183,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 19874572\n", + " secs: 1706544917\n", + " nsecs: 207918167\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2172,8 +2199,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 39346933\n", + " secs: 1706544917\n", + " nsecs: 227355718\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2188,8 +2215,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 48823833\n", + " secs: 1706544917\n", + " nsecs: 237487077\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2204,8 +2231,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 58706760\n", + " secs: 1706544917\n", + " nsecs: 247480630\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2220,8 +2247,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 68709850\n", + " secs: 1706544917\n", + " nsecs: 257900953\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2236,8 +2263,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 87986469\n", + " secs: 1706544917\n", + " nsecs: 278165102\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2252,8 +2279,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 97659826\n", + " secs: 1706544917\n", + " nsecs: 288398027\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2268,8 +2295,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 107616424\n", + " secs: 1706544917\n", + " nsecs: 298751831\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2284,8 +2311,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 117786407\n", + " secs: 1706544917\n", + " nsecs: 308977603\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2300,8 +2327,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 127777814\n", + " secs: 1706544917\n", + " nsecs: 319071054\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2316,8 +2343,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 138854026\n", + " secs: 1706544917\n", + " nsecs: 329062938\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2332,8 +2359,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 149201869\n", + " secs: 1706544917\n", + " nsecs: 339415788\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2348,8 +2375,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 159495592\n", + " secs: 1706544917\n", + " nsecs: 349754333\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2364,8 +2391,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 169792652\n", + " secs: 1706544917\n", + " nsecs: 359853982\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2380,8 +2407,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 179657697\n", + " secs: 1706544917\n", + " nsecs: 371557712\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2396,8 +2423,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 189663410\n", + " secs: 1706544917\n", + " nsecs: 381916522\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2412,8 +2439,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 199556350\n", + " secs: 1706544917\n", + " nsecs: 391955852\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2428,8 +2455,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 209797859\n", + " secs: 1706544917\n", + " nsecs: 401677608\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2444,8 +2471,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 219633102\n", + " secs: 1706544917\n", + " nsecs: 411783218\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2460,8 +2487,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 229408979\n", + " secs: 1706544917\n", + " nsecs: 421791553\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2476,8 +2503,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 239880800\n", + " secs: 1706544917\n", + " nsecs: 432043552\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2492,8 +2519,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 250423669\n", + " secs: 1706544917\n", + " nsecs: 442192077\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2508,8 +2535,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 260511398\n", + " secs: 1706544917\n", + " nsecs: 452643394\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2524,8 +2551,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 280463457\n", + " secs: 1706544917\n", + " nsecs: 474348306\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2540,8 +2567,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 291324138\n", + " secs: 1706544917\n", + " nsecs: 484361648\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2556,8 +2583,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 313117504\n", + " secs: 1706544917\n", + " nsecs: 504082441\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2572,8 +2599,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 323770761\n", + " secs: 1706544917\n", + " nsecs: 514279603\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2588,8 +2615,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 334040164\n", + " secs: 1706544917\n", + " nsecs: 524206399\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2604,8 +2631,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 344825744\n", + " secs: 1706544917\n", + " nsecs: 534056901\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2620,8 +2647,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 355269432\n", + " secs: 1706544917\n", + " nsecs: 544548749\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2636,8 +2663,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 365238666\n", + " secs: 1706544917\n", + " nsecs: 554365396\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2652,8 +2679,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 376126766\n", + " secs: 1706544917\n", + " nsecs: 564265251\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2668,8 +2695,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 387210607\n", + " secs: 1706544917\n", + " nsecs: 574109077\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2684,8 +2711,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 408796787\n", + " secs: 1706544917\n", + " nsecs: 593857049\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2700,8 +2727,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 419713258\n", + " secs: 1706544917\n", + " nsecs: 604115009\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2716,8 +2743,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 439749002\n", + " secs: 1706544917\n", + " nsecs: 626145839\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2732,8 +2759,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 449327468\n", + " secs: 1706544917\n", + " nsecs: 636278867\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2748,8 +2775,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 470635890\n", + " secs: 1706544917\n", + " nsecs: 657084703\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2764,8 +2791,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 480293035\n", + " secs: 1706544917\n", + " nsecs: 667837142\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2780,8 +2807,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 500214099\n", + " secs: 1706544917\n", + " nsecs: 689748287\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2796,8 +2823,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 520314931\n", + " secs: 1706544917\n", + " nsecs: 709959506\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2812,8 +2839,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 530125856\n", + " secs: 1706544917\n", + " nsecs: 720077991\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2828,8 +2855,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 540076732\n", + " secs: 1706544917\n", + " nsecs: 729877233\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2844,8 +2871,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 549759149\n", + " secs: 1706544917\n", + " nsecs: 740610361\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2860,8 +2887,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 569632768\n", + " secs: 1706544917\n", + " nsecs: 760720729\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2876,8 +2903,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 589303016\n", + " secs: 1706544917\n", + " nsecs: 780767917\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2892,8 +2919,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 599044799\n", + " secs: 1706544917\n", + " nsecs: 791338205\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2908,8 +2935,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 609395503\n", + " secs: 1706544917\n", + " nsecs: 803500652\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2924,8 +2951,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 619220018\n", + " secs: 1706544917\n", + " nsecs: 816298246\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2940,8 +2967,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 629041433\n", + " secs: 1706544917\n", + " nsecs: 826271057\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2956,8 +2983,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 639055252\n", + " secs: 1706544917\n", + " nsecs: 836186170\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2972,8 +2999,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 648601055\n", + " secs: 1706544917\n", + " nsecs: 846061468\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -2988,8 +3015,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 668470382\n", + " secs: 1706544917\n", + " nsecs: 866801500\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3004,8 +3031,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 678457498\n", + " secs: 1706544917\n", + " nsecs: 879305124\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3020,8 +3047,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 688319921\n", + " secs: 1706544917\n", + " nsecs: 889095067\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3036,8 +3063,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 697925806\n", + " secs: 1706544917\n", + " nsecs: 899603128\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3052,8 +3079,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 708099126\n", + " secs: 1706544917\n", + " nsecs: 909643411\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3068,8 +3095,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 717890977\n", + " secs: 1706544917\n", + " nsecs: 919872760\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3084,8 +3111,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 727897167\n", + " secs: 1706544917\n", + " nsecs: 930837392\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3100,8 +3127,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 737935304\n", + " secs: 1706544917\n", + " nsecs: 940669298\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3116,8 +3143,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 747606992\n", + " secs: 1706544917\n", + " nsecs: 950444221\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3132,8 +3159,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 761164903\n", + " secs: 1706544917\n", + " nsecs: 960928440\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3148,8 +3175,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 772180557\n", + " secs: 1706544917\n", + " nsecs: 971531629\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3164,8 +3191,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 786565303\n", + " secs: 1706544917\n", + " nsecs: 981504678\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3180,8 +3207,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 800817966\n", + " secs: 1706544917\n", + " nsecs: 991544485\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3196,8 +3223,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 811119318\n", + " secs: 1706544918\n", + " nsecs: 1651048\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3212,8 +3239,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 821317911\n", + " secs: 1706544918\n", + " nsecs: 11669158\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3228,8 +3255,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 831474781\n", + " secs: 1706544918\n", + " nsecs: 21538734\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3244,8 +3271,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 851423263\n", + " secs: 1706544918\n", + " nsecs: 41085720\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3260,8 +3287,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 861536979\n", + " secs: 1706544918\n", + " nsecs: 50888299\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3276,8 +3303,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 871807813\n", + " secs: 1706544918\n", + " nsecs: 60572385\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3292,8 +3319,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 891721963\n", + " secs: 1706544918\n", + " nsecs: 79907894\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3308,8 +3335,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 901814699\n", + " secs: 1706544918\n", + " nsecs: 92547893\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3324,8 +3351,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 915273189\n", + " secs: 1706544918\n", + " nsecs: 102537870\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3340,8 +3367,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 926554679\n", + " secs: 1706544918\n", + " nsecs: 112884759\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3356,8 +3383,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 940182209\n", + " secs: 1706544918\n", + " nsecs: 123359680\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3372,8 +3399,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 965167760\n", + " secs: 1706544918\n", + " nsecs: 144013881\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3388,8 +3415,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 975308895\n", + " secs: 1706544918\n", + " nsecs: 153965234\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3404,8 +3431,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454726\n", - " nsecs: 985270500\n", + " secs: 1706544918\n", + " nsecs: 164059638\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3420,8 +3447,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 14838933\n", + " secs: 1706544918\n", + " nsecs: 194094181\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3436,8 +3463,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 24997949\n", + " secs: 1706544918\n", + " nsecs: 203748703\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3452,8 +3479,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 34455060\n", + " secs: 1706544918\n", + " nsecs: 213503837\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3468,8 +3495,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 44534921\n", + " secs: 1706544918\n", + " nsecs: 224017381\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3484,8 +3511,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 54246187\n", + " secs: 1706544918\n", + " nsecs: 233902931\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3500,8 +3527,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 83569049\n", + " secs: 1706544918\n", + " nsecs: 263562440\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3516,8 +3543,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 93582630\n", + " secs: 1706544918\n", + " nsecs: 273334980\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3532,8 +3559,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 112976551\n", + " secs: 1706544918\n", + " nsecs: 294827461\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3548,8 +3575,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 123248338\n", + " secs: 1706544918\n", + " nsecs: 304959297\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3564,8 +3591,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 132923603\n", + " secs: 1706544918\n", + " nsecs: 314709424\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3580,8 +3607,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 142979860\n", + " secs: 1706544918\n", + " nsecs: 325293064\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3596,8 +3623,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 152651309\n", + " secs: 1706544918\n", + " nsecs: 335991859\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3612,8 +3639,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 163275718\n", + " secs: 1706544918\n", + " nsecs: 346140861\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3628,8 +3655,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 173099279\n", + " secs: 1706544918\n", + " nsecs: 356065750\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3644,8 +3671,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 199396848\n", + " secs: 1706544918\n", + " nsecs: 377432346\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3660,8 +3687,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 220230817\n", + " secs: 1706544918\n", + " nsecs: 397984027\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3676,8 +3703,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 230001449\n", + " secs: 1706544918\n", + " nsecs: 408214569\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3692,8 +3719,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 240165948\n", + " secs: 1706544918\n", + " nsecs: 418574810\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3708,8 +3735,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 249710559\n", + " secs: 1706544918\n", + " nsecs: 428881645\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3724,8 +3751,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 260489702\n", + " secs: 1706544918\n", + " nsecs: 438925266\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3740,8 +3767,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 270841121\n", + " secs: 1706544918\n", + " nsecs: 449546337\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3756,8 +3783,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 280830144\n", + " secs: 1706544918\n", + " nsecs: 459606885\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3772,8 +3799,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 290997505\n", + " secs: 1706544918\n", + " nsecs: 469818115\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3788,8 +3815,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 300702810\n", + " secs: 1706544918\n", + " nsecs: 480182886\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3804,8 +3831,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 310925006\n", + " secs: 1706544918\n", + " nsecs: 490321397\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3820,8 +3847,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 320628404\n", + " secs: 1706544918\n", + " nsecs: 501243829\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3836,8 +3863,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 330796957\n", + " secs: 1706544918\n", + " nsecs: 511368751\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3852,8 +3879,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 350512981\n", + " secs: 1706544918\n", + " nsecs: 531534433\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3868,8 +3895,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 360772371\n", + " secs: 1706544918\n", + " nsecs: 542391061\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3884,8 +3911,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 370627880\n", + " secs: 1706544918\n", + " nsecs: 552552223\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3900,8 +3927,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 380810976\n", + " secs: 1706544918\n", + " nsecs: 562627077\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3916,8 +3943,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 390733242\n", + " secs: 1706544918\n", + " nsecs: 572496891\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3932,8 +3959,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 401291370\n", + " secs: 1706544918\n", + " nsecs: 582713603\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3948,8 +3975,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 411706209\n", + " secs: 1706544918\n", + " nsecs: 593607664\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3964,8 +3991,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 421663045\n", + " secs: 1706544918\n", + " nsecs: 604231595\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3980,8 +4007,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 431575298\n", + " secs: 1706544918\n", + " nsecs: 615185499\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -3996,8 +4023,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 442079544\n", + " secs: 1706544918\n", + " nsecs: 626099348\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4012,8 +4039,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 451843976\n", + " secs: 1706544918\n", + " nsecs: 635951280\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4028,8 +4055,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 471526861\n", + " secs: 1706544918\n", + " nsecs: 656157970\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4044,8 +4071,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 481531858\n", + " secs: 1706544918\n", + " nsecs: 666541576\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4060,8 +4087,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 510531187\n", + " secs: 1706544918\n", + " nsecs: 696901559\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4076,8 +4103,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 520304441\n", + " secs: 1706544918\n", + " nsecs: 706899642\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4092,8 +4119,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 529991149\n", + " secs: 1706544918\n", + " nsecs: 717074871\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4108,8 +4135,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 539878845\n", + " secs: 1706544918\n", + " nsecs: 727422475\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4124,8 +4151,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 549521207\n", + " secs: 1706544918\n", + " nsecs: 737593412\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4140,8 +4167,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 559333324\n", + " secs: 1706544918\n", + " nsecs: 748543024\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4156,8 +4183,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 568988084\n", + " secs: 1706544918\n", + " nsecs: 759326457\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4172,8 +4199,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 588930606\n", + " secs: 1706544918\n", + " nsecs: 780078649\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4188,8 +4215,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 598807811\n", + " secs: 1706544918\n", + " nsecs: 790158510\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4204,8 +4231,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 619289398\n", + " secs: 1706544918\n", + " nsecs: 812283277\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4220,8 +4247,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 629359006\n", + " secs: 1706544918\n", + " nsecs: 822262287\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4236,8 +4263,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 639499425\n", + " secs: 1706544918\n", + " nsecs: 832731246\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4252,8 +4279,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 649319171\n", + " secs: 1706544918\n", + " nsecs: 842995643\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4268,8 +4295,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 659330844\n", + " secs: 1706544918\n", + " nsecs: 853036403\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4284,8 +4311,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 669612884\n", + " secs: 1706544918\n", + " nsecs: 863647460\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4300,8 +4327,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 679676771\n", + " secs: 1706544918\n", + " nsecs: 873960256\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4316,8 +4343,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 689470529\n", + " secs: 1706544918\n", + " nsecs: 884471654\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4332,8 +4359,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 699056148\n", + " secs: 1706544918\n", + " nsecs: 895127058\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4348,8 +4375,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 708853006\n", + " secs: 1706544918\n", + " nsecs: 906480073\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4364,8 +4391,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 718634128\n", + " secs: 1706544918\n", + " nsecs: 917049169\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4380,8 +4407,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 728414297\n", + " secs: 1706544918\n", + " nsecs: 927591085\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4396,8 +4423,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 749159097\n", + " secs: 1706544918\n", + " nsecs: 947772502\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4412,8 +4439,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 759160280\n", + " secs: 1706544918\n", + " nsecs: 957824230\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4428,8 +4455,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 769248008\n", + " secs: 1706544918\n", + " nsecs: 968458414\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4444,8 +4471,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 779141187\n", + " secs: 1706544918\n", + " nsecs: 979157924\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4460,8 +4487,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 789060115\n", + " secs: 1706544918\n", + " nsecs: 989204168\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4476,8 +4503,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 818681716\n", + " secs: 1706544919\n", + " nsecs: 20420312\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4492,8 +4519,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 829430341\n", + " secs: 1706544919\n", + " nsecs: 31285047\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4508,8 +4535,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 839163064\n", + " secs: 1706544919\n", + " nsecs: 41488409\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4524,8 +4551,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 848954200\n", + " secs: 1706544919\n", + " nsecs: 51862955\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4540,8 +4567,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 859354734\n", + " secs: 1706544919\n", + " nsecs: 62264919\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4556,8 +4583,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 879795551\n", + " secs: 1706544919\n", + " nsecs: 82359075\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4572,8 +4599,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 899379730\n", + " secs: 1706544919\n", + " nsecs: 103036642\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4588,8 +4615,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 909643888\n", + " secs: 1706544919\n", + " nsecs: 113466262\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4604,8 +4631,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 929649591\n", + " secs: 1706544919\n", + " nsecs: 133843421\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4620,8 +4647,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 939815521\n", + " secs: 1706544919\n", + " nsecs: 144020557\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4636,8 +4663,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 959586143\n", + " secs: 1706544919\n", + " nsecs: 163890361\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4652,8 +4679,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 969409227\n", + " secs: 1706544919\n", + " nsecs: 173745393\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4668,8 +4695,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 979031085\n", + " secs: 1706544919\n", + " nsecs: 183910846\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4684,8 +4711,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 988930702\n", + " secs: 1706544919\n", + " nsecs: 194156885\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4700,8 +4727,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454727\n", - " nsecs: 999084234\n", + " secs: 1706544919\n", + " nsecs: 204169988\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4716,8 +4743,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 8918762\n", + " secs: 1706544919\n", + " nsecs: 214705228\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4732,8 +4759,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 28315067\n", + " secs: 1706544919\n", + " nsecs: 235476016\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4748,8 +4775,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 37947177\n", + " secs: 1706544919\n", + " nsecs: 245808124\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4764,8 +4791,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 47890901\n", + " secs: 1706544919\n", + " nsecs: 255650997\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4780,8 +4807,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 57522058\n", + " secs: 1706544919\n", + " nsecs: 265812635\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4796,8 +4823,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 67149162\n", + " secs: 1706544919\n", + " nsecs: 275789737\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4812,8 +4839,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 76910734\n", + " secs: 1706544919\n", + " nsecs: 286756038\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4828,8 +4855,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 87213277\n", + " secs: 1706544919\n", + " nsecs: 298326969\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4844,8 +4871,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 97060918\n", + " secs: 1706544919\n", + " nsecs: 308969020\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4860,8 +4887,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 108145713\n", + " secs: 1706544919\n", + " nsecs: 319038152\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4876,8 +4903,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 118573904\n", + " secs: 1706544919\n", + " nsecs: 329315423\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4892,8 +4919,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 128924608\n", + " secs: 1706544919\n", + " nsecs: 339347362\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4908,8 +4935,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 139441013\n", + " secs: 1706544919\n", + " nsecs: 349482059\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4924,8 +4951,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 149400472\n", + " secs: 1706544919\n", + " nsecs: 359558582\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4940,8 +4967,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 159833192\n", + " secs: 1706544919\n", + " nsecs: 369482517\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4956,8 +4983,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 169833660\n", + " secs: 1706544919\n", + " nsecs: 379415988\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4972,8 +4999,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 179687261\n", + " secs: 1706544919\n", + " nsecs: 389329671\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -4988,8 +5015,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 189734935\n", + " secs: 1706544919\n", + " nsecs: 399363040\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5004,8 +5031,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 199295997\n", + " secs: 1706544919\n", + " nsecs: 409301280\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5020,8 +5047,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 209303140\n", + " secs: 1706544919\n", + " nsecs: 419255733\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5036,8 +5063,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 219341278\n", + " secs: 1706544919\n", + " nsecs: 429352521\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5052,8 +5079,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 229027032\n", + " secs: 1706544919\n", + " nsecs: 439219951\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5068,8 +5095,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 238579750\n", + " secs: 1706544919\n", + " nsecs: 449213981\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5084,8 +5111,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 248189449\n", + " secs: 1706544919\n", + " nsecs: 459560871\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5100,8 +5127,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 258103370\n", + " secs: 1706544919\n", + " nsecs: 469874858\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5116,8 +5143,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 268151521\n", + " secs: 1706544919\n", + " nsecs: 479789495\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5132,8 +5159,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 278077602\n", + " secs: 1706544919\n", + " nsecs: 489479780\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5148,8 +5175,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 288434267\n", + " secs: 1706544919\n", + " nsecs: 499516248\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5164,8 +5191,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 298222303\n", + " secs: 1706544919\n", + " nsecs: 509546995\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5180,8 +5207,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 308148384\n", + " secs: 1706544919\n", + " nsecs: 519337415\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5196,8 +5223,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 329452991\n", + " secs: 1706544919\n", + " nsecs: 539964437\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5212,8 +5239,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 339732646\n", + " secs: 1706544919\n", + " nsecs: 550527572\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5228,8 +5255,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 349679470\n", + " secs: 1706544919\n", + " nsecs: 560472249\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5244,8 +5271,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 372056722\n", + " secs: 1706544919\n", + " nsecs: 580207109\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5260,8 +5287,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 382091522\n", + " secs: 1706544919\n", + " nsecs: 590407609\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5276,8 +5303,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 412238359\n", + " secs: 1706544919\n", + " nsecs: 621572971\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5292,8 +5319,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 422187566\n", + " secs: 1706544919\n", + " nsecs: 631641149\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5308,8 +5335,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 431981563\n", + " secs: 1706544919\n", + " nsecs: 641553401\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5324,8 +5351,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 441920280\n", + " secs: 1706544919\n", + " nsecs: 653319358\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5340,8 +5367,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 451804637\n", + " secs: 1706544919\n", + " nsecs: 663541078\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5356,8 +5383,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 475440740\n", + " secs: 1706544919\n", + " nsecs: 683467149\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5372,8 +5399,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 485437870\n", + " secs: 1706544919\n", + " nsecs: 693924903\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5388,8 +5415,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 495399475\n", + " secs: 1706544919\n", + " nsecs: 704140663\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5404,8 +5431,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 505185365\n", + " secs: 1706544919\n", + " nsecs: 713812112\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5420,8 +5447,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 515660047\n", + " secs: 1706544919\n", + " nsecs: 723740100\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5436,8 +5463,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 525471210\n", + " secs: 1706544919\n", + " nsecs: 733844518\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5452,8 +5479,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 536112785\n", + " secs: 1706544919\n", + " nsecs: 744749307\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5468,8 +5495,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 570803880\n", + " secs: 1706544919\n", + " nsecs: 774046421\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5484,8 +5511,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 580623388\n", + " secs: 1706544919\n", + " nsecs: 783934116\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5500,8 +5527,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 590690374\n", + " secs: 1706544919\n", + " nsecs: 794060468\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5516,8 +5543,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 600275516\n", + " secs: 1706544919\n", + " nsecs: 804785490\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5532,8 +5559,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 620325326\n", + " secs: 1706544919\n", + " nsecs: 825284957\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5548,8 +5575,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 639937162\n", + " secs: 1706544919\n", + " nsecs: 845585823\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5564,8 +5591,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 649961471\n", + " secs: 1706544919\n", + " nsecs: 856135606\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5580,8 +5607,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 669656515\n", + " secs: 1706544919\n", + " nsecs: 876502752\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5596,8 +5623,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 679559946\n", + " secs: 1706544919\n", + " nsecs: 886613845\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5612,8 +5639,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 689200401\n", + " secs: 1706544919\n", + " nsecs: 896639585\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5628,8 +5655,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 699025630\n", + " secs: 1706544919\n", + " nsecs: 907559156\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5644,8 +5671,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 718453407\n", + " secs: 1706544919\n", + " nsecs: 927424430\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5660,8 +5687,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 728411674\n", + " secs: 1706544919\n", + " nsecs: 937479496\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5676,8 +5703,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 747882127\n", + " secs: 1706544919\n", + " nsecs: 957934379\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5692,8 +5719,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 767148971\n", + " secs: 1706544919\n", + " nsecs: 977858066\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5708,8 +5735,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 777645587\n", + " secs: 1706544919\n", + " nsecs: 987823247\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5724,8 +5751,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 788507223\n", + " secs: 1706544919\n", + " nsecs: 997573375\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5740,8 +5767,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 798871278\n", + " secs: 1706544920\n", + " nsecs: 7592201\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5756,8 +5783,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 823041200\n", + " secs: 1706544920\n", + " nsecs: 27238607\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5772,8 +5799,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 833983421\n", + " secs: 1706544920\n", + " nsecs: 37187337\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5788,8 +5815,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 853881120\n", + " secs: 1706544920\n", + " nsecs: 57217121\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5804,8 +5831,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 863618850\n", + " secs: 1706544920\n", + " nsecs: 67085981\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5820,8 +5847,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 873755455\n", + " secs: 1706544920\n", + " nsecs: 77337503\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5836,8 +5863,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 883673667\n", + " secs: 1706544920\n", + " nsecs: 87342262\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5852,8 +5879,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 893738508\n", + " secs: 1706544920\n", + " nsecs: 97246408\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5868,8 +5895,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 903726816\n", + " secs: 1706544920\n", + " nsecs: 107070446\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5884,8 +5911,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 914144754\n", + " secs: 1706544920\n", + " nsecs: 117566823\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5900,8 +5927,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 924309968\n", + " secs: 1706544920\n", + " nsecs: 127794265\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5916,8 +5943,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 934568881\n", + " secs: 1706544920\n", + " nsecs: 137711286\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5932,8 +5959,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 944923162\n", + " secs: 1706544920\n", + " nsecs: 150225162\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5948,8 +5975,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 954938173\n", + " secs: 1706544920\n", + " nsecs: 160764455\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5964,8 +5991,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 964920282\n", + " secs: 1706544920\n", + " nsecs: 170743227\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5980,8 +6007,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 974496364\n", + " secs: 1706544920\n", + " nsecs: 180782556\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -5996,8 +6023,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454728\n", - " nsecs: 994848012\n", + " secs: 1706544920\n", + " nsecs: 201177597\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6012,8 +6039,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 5209684\n", + " secs: 1706544920\n", + " nsecs: 213806390\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6028,8 +6055,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 15120983\n", + " secs: 1706544920\n", + " nsecs: 223469972\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6044,8 +6071,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 34841537\n", + " secs: 1706544920\n", + " nsecs: 243908166\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6060,8 +6087,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 54306030\n", + " secs: 1706544920\n", + " nsecs: 263970375\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6076,8 +6103,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 63890218\n", + " secs: 1706544920\n", + " nsecs: 273994445\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6092,8 +6119,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 73581933\n", + " secs: 1706544920\n", + " nsecs: 284109830\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6108,8 +6135,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 83770036\n", + " secs: 1706544920\n", + " nsecs: 294022321\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6124,8 +6151,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 114562034\n", + " secs: 1706544920\n", + " nsecs: 326006412\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6140,8 +6167,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 128451824\n", + " secs: 1706544920\n", + " nsecs: 337008714\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6156,8 +6183,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 140075445\n", + " secs: 1706544920\n", + " nsecs: 347310543\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6172,8 +6199,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 149988651\n", + " secs: 1706544920\n", + " nsecs: 358036518\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6188,8 +6215,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 160300254\n", + " secs: 1706544920\n", + " nsecs: 370610475\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6204,8 +6231,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 170534372\n", + " secs: 1706544920\n", + " nsecs: 381522893\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6220,8 +6247,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 180233716\n", + " secs: 1706544920\n", + " nsecs: 391707181\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6236,8 +6263,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 190173625\n", + " secs: 1706544920\n", + " nsecs: 402300357\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6252,8 +6279,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 199840784\n", + " secs: 1706544920\n", + " nsecs: 412396192\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6268,8 +6295,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 209982872\n", + " secs: 1706544920\n", + " nsecs: 422230243\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6284,8 +6311,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 220086812\n", + " secs: 1706544920\n", + " nsecs: 432636737\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6300,8 +6327,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 230565071\n", + " secs: 1706544920\n", + " nsecs: 442850828\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6316,8 +6343,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 262809038\n", + " secs: 1706544920\n", + " nsecs: 473550319\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6332,8 +6359,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 274945259\n", + " secs: 1706544920\n", + " nsecs: 483459949\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6348,8 +6375,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 284489154\n", + " secs: 1706544920\n", + " nsecs: 493614435\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6364,8 +6391,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 294175386\n", + " secs: 1706544920\n", + " nsecs: 504096269\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6380,8 +6407,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 303731441\n", + " secs: 1706544920\n", + " nsecs: 513952732\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6396,8 +6423,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 313288927\n", + " secs: 1706544920\n", + " nsecs: 523840188\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6412,8 +6439,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 322869777\n", + " secs: 1706544920\n", + " nsecs: 533734798\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6428,8 +6455,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 332524299\n", + " secs: 1706544920\n", + " nsecs: 544054985\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6444,8 +6471,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 342247724\n", + " secs: 1706544920\n", + " nsecs: 553883552\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6460,8 +6487,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 351795196\n", + " secs: 1706544920\n", + " nsecs: 563676357\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6476,8 +6503,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 361424207\n", + " secs: 1706544920\n", + " nsecs: 573505640\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6492,8 +6519,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 371025085\n", + " secs: 1706544920\n", + " nsecs: 583408832\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6508,8 +6535,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 380615949\n", + " secs: 1706544920\n", + " nsecs: 593615531\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6524,8 +6551,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 399971723\n", + " secs: 1706544920\n", + " nsecs: 612910509\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6540,8 +6567,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 410209894\n", + " secs: 1706544920\n", + " nsecs: 622579574\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6556,8 +6583,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 420065879\n", + " secs: 1706544920\n", + " nsecs: 632315635\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6572,8 +6599,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 429817914\n", + " secs: 1706544920\n", + " nsecs: 642050027\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6588,8 +6615,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 439763307\n", + " secs: 1706544920\n", + " nsecs: 651688337\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6604,8 +6631,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 449737310\n", + " secs: 1706544920\n", + " nsecs: 661351203\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6620,8 +6647,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 459516048\n", + " secs: 1706544920\n", + " nsecs: 671063661\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6636,8 +6663,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 469855308\n", + " secs: 1706544920\n", + " nsecs: 680626392\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6652,8 +6679,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 480250120\n", + " secs: 1706544920\n", + " nsecs: 690305233\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6668,8 +6695,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 489985704\n", + " secs: 1706544920\n", + " nsecs: 699806213\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6684,8 +6711,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 514060497\n", + " secs: 1706544920\n", + " nsecs: 719159364\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6700,8 +6727,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 524521827\n", + " secs: 1706544920\n", + " nsecs: 728794574\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6716,8 +6743,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 534343481\n", + " secs: 1706544920\n", + " nsecs: 739019632\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6732,8 +6759,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 553424119\n", + " secs: 1706544920\n", + " nsecs: 758497953\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6748,8 +6775,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 563100337\n", + " secs: 1706544920\n", + " nsecs: 768382310\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6764,8 +6791,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 572806596\n", + " secs: 1706544920\n", + " nsecs: 778136730\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6780,8 +6807,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 592219591\n", + " secs: 1706544920\n", + " nsecs: 797852516\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6796,8 +6823,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 602131605\n", + " secs: 1706544920\n", + " nsecs: 807753801\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6812,8 +6839,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 612154722\n", + " secs: 1706544920\n", + " nsecs: 817374706\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6828,8 +6855,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 621884822\n", + " secs: 1706544920\n", + " nsecs: 827094316\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6844,8 +6871,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 631433486\n", + " secs: 1706544920\n", + " nsecs: 837395668\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6860,8 +6887,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 640997409\n", + " secs: 1706544920\n", + " nsecs: 848101377\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6876,8 +6903,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 689654350\n", + " secs: 1706544920\n", + " nsecs: 897163629\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6892,8 +6919,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 699763059\n", + " secs: 1706544920\n", + " nsecs: 907011747\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6908,8 +6935,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 709666728\n", + " secs: 1706544920\n", + " nsecs: 916730880\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6924,8 +6951,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 719478130\n", + " secs: 1706544920\n", + " nsecs: 926568746\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6940,8 +6967,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 729162454\n", + " secs: 1706544920\n", + " nsecs: 937285184\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6956,8 +6983,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 739078283\n", + " secs: 1706544920\n", + " nsecs: 947034358\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6972,8 +6999,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 748747825\n", + " secs: 1706544920\n", + " nsecs: 957026481\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -6988,8 +7015,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 758508443\n", + " secs: 1706544920\n", + " nsecs: 967617511\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7004,8 +7031,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 768118619\n", + " secs: 1706544920\n", + " nsecs: 977944612\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7020,8 +7047,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 778162002\n", + " secs: 1706544920\n", + " nsecs: 988276481\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7036,8 +7063,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 788316965\n", + " secs: 1706544920\n", + " nsecs: 998299598\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7052,8 +7079,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 798148393\n", + " secs: 1706544921\n", + " nsecs: 8562088\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7068,8 +7095,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 808482408\n", + " secs: 1706544921\n", + " nsecs: 18221139\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7084,8 +7111,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 818536281\n", + " secs: 1706544921\n", + " nsecs: 28006315\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7100,8 +7127,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 828765153\n", + " secs: 1706544921\n", + " nsecs: 37898063\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7116,8 +7143,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 848044395\n", + " secs: 1706544921\n", + " nsecs: 57746171\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7132,8 +7159,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 858117818\n", + " secs: 1706544921\n", + " nsecs: 67290544\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7148,8 +7175,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 867625951\n", + " secs: 1706544921\n", + " nsecs: 77006340\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7164,8 +7191,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 877413272\n", + " secs: 1706544921\n", + " nsecs: 86667060\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7180,8 +7207,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 887440681\n", + " secs: 1706544921\n", + " nsecs: 96265316\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7196,8 +7223,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 897084951\n", + " secs: 1706544921\n", + " nsecs: 105965852\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7212,8 +7239,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 907503843\n", + " secs: 1706544921\n", + " nsecs: 115576744\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7228,8 +7255,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 917495489\n", + " secs: 1706544921\n", + " nsecs: 125284671\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7244,8 +7271,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 927219152\n", + " secs: 1706544921\n", + " nsecs: 135140895\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7260,8 +7287,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 937005519\n", + " secs: 1706544921\n", + " nsecs: 144938230\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7276,8 +7303,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 946638345\n", + " secs: 1706544921\n", + " nsecs: 154725313\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7292,8 +7319,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 975183248\n", + " secs: 1706544921\n", + " nsecs: 183697938\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7308,8 +7335,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 984693288\n", + " secs: 1706544921\n", + " nsecs: 194594383\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7324,8 +7351,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454729\n", - " nsecs: 994870901\n", + " secs: 1706544921\n", + " nsecs: 204714298\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7340,8 +7367,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 4707336\n", + " secs: 1706544921\n", + " nsecs: 214483737\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7356,8 +7383,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 34533977\n", + " secs: 1706544921\n", + " nsecs: 244819402\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7372,8 +7399,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 44676065\n", + " secs: 1706544921\n", + " nsecs: 255036592\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7388,8 +7415,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 54926156\n", + " secs: 1706544921\n", + " nsecs: 265106439\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7404,8 +7431,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 64422369\n", + " secs: 1706544921\n", + " nsecs: 275486230\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7420,8 +7447,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 74395179\n", + " secs: 1706544921\n", + " nsecs: 285556316\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7436,8 +7463,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 83957433\n", + " secs: 1706544921\n", + " nsecs: 295557022\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7452,8 +7479,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 93839406\n", + " secs: 1706544921\n", + " nsecs: 305361986\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7468,8 +7495,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 103564739\n", + " secs: 1706544921\n", + " nsecs: 314964056\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7484,8 +7511,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 113248825\n", + " secs: 1706544921\n", + " nsecs: 324617624\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7500,8 +7527,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 123576402\n", + " secs: 1706544921\n", + " nsecs: 334374666\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7516,8 +7543,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 133637905\n", + " secs: 1706544921\n", + " nsecs: 344164848\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7532,8 +7559,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 143495321\n", + " secs: 1706544921\n", + " nsecs: 353968620\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7548,8 +7575,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 153331756\n", + " secs: 1706544921\n", + " nsecs: 363894939\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7564,8 +7591,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 163374900\n", + " secs: 1706544921\n", + " nsecs: 373680114\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7580,8 +7607,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 174808502\n", + " secs: 1706544921\n", + " nsecs: 383259534\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7596,8 +7623,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 185347795\n", + " secs: 1706544921\n", + " nsecs: 393896102\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7612,8 +7639,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 196193218\n", + " secs: 1706544921\n", + " nsecs: 403790950\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7628,8 +7655,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 206784486\n", + " secs: 1706544921\n", + " nsecs: 413312673\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7644,8 +7671,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 217048168\n", + " secs: 1706544921\n", + " nsecs: 422859430\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7660,8 +7687,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 227622985\n", + " secs: 1706544921\n", + " nsecs: 432488441\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7676,8 +7703,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 237950801\n", + " secs: 1706544921\n", + " nsecs: 442560195\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7692,8 +7719,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 248067378\n", + " secs: 1706544921\n", + " nsecs: 452620267\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7708,8 +7735,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 258363723\n", + " secs: 1706544921\n", + " nsecs: 462723493\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7724,8 +7751,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 268745660\n", + " secs: 1706544921\n", + " nsecs: 472694635\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7740,8 +7767,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 278952360\n", + " secs: 1706544921\n", + " nsecs: 482583999\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7756,8 +7783,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 289012908\n", + " secs: 1706544921\n", + " nsecs: 492875099\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7772,8 +7799,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 299065113\n", + " secs: 1706544921\n", + " nsecs: 503608465\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7788,8 +7815,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 339966058\n", + " secs: 1706544921\n", + " nsecs: 545543432\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7804,8 +7831,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 351265430\n", + " secs: 1706544921\n", + " nsecs: 556905508\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7820,8 +7847,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 383670091\n", + " secs: 1706544921\n", + " nsecs: 579474687\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7836,8 +7863,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 401098966\n", + " secs: 1706544921\n", + " nsecs: 590476512\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7852,8 +7879,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 414599180\n", + " secs: 1706544921\n", + " nsecs: 600560188\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7868,8 +7895,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 425669193\n", + " secs: 1706544921\n", + " nsecs: 611992359\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7884,8 +7911,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 436941385\n", + " secs: 1706544921\n", + " nsecs: 623099565\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7900,8 +7927,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 447655439\n", + " secs: 1706544921\n", + " nsecs: 633123397\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7916,8 +7943,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 470032453\n", + " secs: 1706544921\n", + " nsecs: 655219793\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7932,8 +7959,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 480431079\n", + " secs: 1706544921\n", + " nsecs: 665919780\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7948,8 +7975,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 490664720\n", + " secs: 1706544921\n", + " nsecs: 676297664\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7964,8 +7991,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 501055717\n", + " secs: 1706544921\n", + " nsecs: 686551332\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7980,8 +8007,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 511538267\n", + " secs: 1706544921\n", + " nsecs: 697294473\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -7996,8 +8023,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 521835565\n", + " secs: 1706544921\n", + " nsecs: 707584142\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8012,8 +8039,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 531538486\n", + " secs: 1706544921\n", + " nsecs: 717669010\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8028,8 +8055,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 540988683\n", + " secs: 1706544921\n", + " nsecs: 729904651\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8044,8 +8071,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 559922933\n", + " secs: 1706544921\n", + " nsecs: 755266666\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8060,8 +8087,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 569701671\n", + " secs: 1706544921\n", + " nsecs: 765379905\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8076,8 +8103,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 579053401\n", + " secs: 1706544921\n", + " nsecs: 775438785\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8092,8 +8119,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 588583230\n", + " secs: 1706544921\n", + " nsecs: 785464763\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8108,8 +8135,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 598399162\n", + " secs: 1706544921\n", + " nsecs: 797777175\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8124,8 +8151,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 608730077\n", + " secs: 1706544921\n", + " nsecs: 810024023\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8140,8 +8167,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 618813991\n", + " secs: 1706544921\n", + " nsecs: 821498632\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8156,8 +8183,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 628623723\n", + " secs: 1706544921\n", + " nsecs: 832209587\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8172,8 +8199,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 638496398\n", + " secs: 1706544921\n", + " nsecs: 842942476\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8188,8 +8215,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 648101329\n", + " secs: 1706544921\n", + " nsecs: 854440927\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8204,8 +8231,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 657718896\n", + " secs: 1706544921\n", + " nsecs: 864692211\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8220,8 +8247,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 667537689\n", + " secs: 1706544921\n", + " nsecs: 874951601\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8236,8 +8263,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 677129745\n", + " secs: 1706544921\n", + " nsecs: 885563135\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8252,8 +8279,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 686960220\n", + " secs: 1706544921\n", + " nsecs: 897155761\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8268,8 +8295,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 696655988\n", + " secs: 1706544921\n", + " nsecs: 907792329\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8284,8 +8311,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 706870079\n", + " secs: 1706544921\n", + " nsecs: 917936801\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8300,8 +8327,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 716971874\n", + " secs: 1706544921\n", + " nsecs: 928446054\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8316,8 +8343,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 746616125\n", + " secs: 1706544921\n", + " nsecs: 961369752\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8332,8 +8359,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 756603956\n", + " secs: 1706544921\n", + " nsecs: 973284721\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8348,8 +8375,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 766701936\n", + " secs: 1706544921\n", + " nsecs: 987850427\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8364,8 +8391,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 776644468\n", + " secs: 1706544921\n", + " nsecs: 998610258\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8380,8 +8407,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 786627054\n", + " secs: 1706544922\n", + " nsecs: 8282661\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8396,8 +8423,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 806035041\n", + " secs: 1706544922\n", + " nsecs: 27345895\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8412,8 +8439,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 815665483\n", + " secs: 1706544922\n", + " nsecs: 37099599\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8428,8 +8455,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 845581769\n", + " secs: 1706544922\n", + " nsecs: 67073106\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8444,8 +8471,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 865120410\n", + " secs: 1706544922\n", + " nsecs: 86748838\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8460,8 +8487,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 884716749\n", + " secs: 1706544922\n", + " nsecs: 105825424\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8476,8 +8503,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 894847631\n", + " secs: 1706544922\n", + " nsecs: 115547418\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8492,8 +8519,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 914685487\n", + " secs: 1706544922\n", + " nsecs: 134811162\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8508,8 +8535,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 924642562\n", + " secs: 1706544922\n", + " nsecs: 144512414\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8524,8 +8551,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 934620380\n", + " secs: 1706544922\n", + " nsecs: 154634714\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8540,8 +8567,8 @@ "CostmapLocation.Location(pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1704454730\n", - " nsecs: 944352626\n", + " secs: 1706544922\n", + " nsecs: 164654016\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -8556,28 +8583,6 @@ ] } ], - "source": [ - "from pycram.designators.object_designator import *\n", - "\n", - "milk_desig = BelieveObject(names=[\"Milk\"])\n", - "milk_desig.resolve()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Location Designators\n", - "Location Designators can create a position in cartesian space from a symbolic description." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "scrolled": false - }, - "outputs": [], "source": [ "from pycram.designators.location_designator import *\n", "from pycram.designators.object_designator import *\n", @@ -8604,11 +8609,11 @@ }, { "cell_type": "code", - "execution_count": 26, + "execution_count": 27, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:51.471552922Z", - "start_time": "2024-01-05T11:38:50.957762794Z" + "end_time": "2024-01-29T16:15:22.690059907Z", + "start_time": "2024-01-29T16:15:22.178420266Z" } }, "outputs": [], @@ -8630,11 +8635,11 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": 28, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:38:51.532465685Z", - "start_time": "2024-01-05T11:38:51.473570735Z" + "end_time": "2024-01-29T16:15:22.784167007Z", + "start_time": "2024-01-29T16:15:22.739698077Z" } }, "outputs": [], @@ -8645,11 +8650,11 @@ }, { "cell_type": "code", - "execution_count": 28, + "execution_count": 29, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.490830292Z", - "start_time": "2024-01-05T11:38:51.542100060Z" + "end_time": "2024-01-29T16:15:37.008203353Z", + "start_time": "2024-01-29T16:15:22.784090487Z" } }, "outputs": [], @@ -8695,11 +8700,11 @@ }, { "cell_type": "code", - "execution_count": 29, + "execution_count": 30, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.494121167Z", - "start_time": "2024-01-05T11:39:03.491538560Z" + "end_time": "2024-01-29T16:15:37.015721112Z", + "start_time": "2024-01-29T16:15:37.010004750Z" } }, "outputs": [ @@ -8708,26 +8713,26 @@ "output_type": "stream", "text": [ "no_operation()\n", - "├── perform(Motion)\n", - "├── perform(Motion)\n", + "├── perform(MoveMotion)\n", + "├── perform(MoveMotion)\n", "├── perform(ParkArmsActionPerformable)\n", "├── perform(ParkArmsActionPerformable)\n", "├── perform(MoveTorsoActionPerformable)\n", "├── perform(NavigateActionPerformable)\n", - "│ └── perform(Motion)\n", + "│ └── perform(MoveMotion)\n", "├── perform(PickUpActionPerformable)\n", - "│ ├── perform(Motion)\n", - "│ ├── perform(Motion)\n", - "│ ├── perform(Motion)\n", - "│ ├── perform(Motion)\n", - "│ └── perform(Motion)\n", + "│ ├── perform(MoveTCPMotion)\n", + "│ ├── perform(MoveGripperMotion)\n", + "│ ├── perform(MoveTCPMotion)\n", + "│ ├── perform(MoveGripperMotion)\n", + "│ └── perform(MoveTCPMotion)\n", "├── perform(ParkArmsActionPerformable)\n", "├── perform(NavigateActionPerformable)\n", - "│ └── perform(Motion)\n", + "│ └── perform(MoveMotion)\n", "├── perform(PlaceActionPerformable)\n", - "│ ├── perform(Motion)\n", - "│ ├── perform(Motion)\n", - "│ └── perform(Motion)\n", + "│ ├── perform(MoveTCPMotion)\n", + "│ ├── perform(MoveGripperMotion)\n", + "│ └── perform(MoveTCPMotion)\n", "└── perform(ParkArmsActionPerformable)\n" ] } @@ -8741,11 +8746,11 @@ }, { "cell_type": "code", - "execution_count": 30, + "execution_count": 31, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.669289460Z", - "start_time": "2024-01-05T11:39:03.494369670Z" + "end_time": "2024-01-29T16:15:37.200246997Z", + "start_time": "2024-01-29T16:15:37.012295886Z" } }, "outputs": [], @@ -8763,11 +8768,11 @@ }, { "cell_type": "code", - "execution_count": 31, + "execution_count": 32, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.922190909Z", - "start_time": "2024-01-05T11:39:03.675069105Z" + "end_time": "2024-01-29T16:15:37.447175714Z", + "start_time": "2024-01-29T16:15:37.236464380Z" } }, "outputs": [ @@ -8775,14 +8780,14 @@ "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 22/22 [00:00<00:00, 116.49it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 22/22 [00:00<00:00, 119.33it/s]\n" ] }, { "data": { - "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 38, 17, 681423), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" + "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 14, 50, 893086), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" }, - "execution_count": 31, + "execution_count": 32, "metadata": {}, "output_type": "execute_result" } @@ -8806,11 +8811,11 @@ }, { "cell_type": "code", - "execution_count": 32, + "execution_count": 33, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.966372243Z", - "start_time": "2024-01-05T11:39:03.922350989Z" + "end_time": "2024-01-29T16:15:37.488726709Z", + "start_time": "2024-01-29T16:15:37.444290355Z" } }, "outputs": [ @@ -8824,17 +8829,19 @@ } ], "source": [ - "navigations = session.query(pycram.orm.action_designator.NavigateAction).all()\n", + "from sqlalchemy import select\n", + "\n", + "navigations = session.scalars(select(pycram.orm.action_designator.NavigateAction)).all()\n", "print(*navigations, sep=\"\\n\")" ] }, { "cell_type": "code", - "execution_count": 33, + "execution_count": 34, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:39:03.967890749Z", - "start_time": "2024-01-05T11:39:03.966131716Z" + "end_time": "2024-01-29T16:15:37.489720308Z", + "start_time": "2024-01-29T16:15:37.488078620Z" } }, "outputs": [ @@ -8842,18 +8849,16 @@ "name": "stdout", "output_type": "stream", "text": [ - "(NavigateAction(id=6, process_metadata_id=1, dtype='NavigateAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), pose_id=7), Position(id=7, x=0.5799999999999998, y=1.28, z=0.0, process_metadata_id=1), Quaternion(id=7, x=0.0, y=0.0, z=0.16378361324016077, w=-0.9864962889104031, process_metadata_id=1))\n", - "(NavigateAction(id=15, process_metadata_id=1, dtype='NavigateAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), pose_id=16), Position(id=16, x=-1.9074999952316287, y=0.779200015068054, z=0.0, process_metadata_id=1), Quaternion(id=16, x=0.0, y=0.0, z=0.16439898730535735, w=0.9863939238321437, process_metadata_id=1))\n" + "NavigateAction(id=6, process_metadata_id=1, dtype='NavigateAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), pose_id=7)\n", + "NavigateAction(id=15, process_metadata_id=1, dtype='NavigateAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), pose_id=16)\n" ] } ], "source": [ - "navigations = (session.query(pycram.orm.action_designator.NavigateAction, \n", - " pycram.orm.base.Position, \n", - " pycram.orm.base.Quaternion).\n", - " join(pycram.orm.action_designator.NavigateAction.pose).\n", - " join(pycram.orm.base.Pose.position).\n", - " join(pycram.orm.base.Pose.orientation).all())\n", + "navigations = (session.scalars(select(pycram.orm.action_designator.NavigateAction, pycram.orm.base.Position, pycram.orm.base.Quaternion).\n", + " join(pycram.orm.action_designator.NavigateAction.pose).\n", + " join(pycram.orm.base.Pose.position).\n", + " join(pycram.orm.base.Pose.orientation)).all())\n", "print(*navigations, sep=\"\\n\")" ] }, @@ -8868,7 +8873,7 @@ }, { "cell_type": "code", - "execution_count": 34, + "execution_count": 35, "outputs": [], "source": [ "world.exit()" @@ -8876,8 +8881,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:39:04.199668442Z", - "start_time": "2024-01-05T11:39:03.966287501Z" + "end_time": "2024-01-29T16:15:37.732405944Z", + "start_time": "2024-01-29T16:15:37.488193658Z" } } } diff --git a/examples/local_transformer.ipynb b/examples/local_transformer.ipynb index 2d4d41c03..8a6352cde 100644 --- a/examples/local_transformer.ipynb +++ b/examples/local_transformer.ipynb @@ -17,14 +17,28 @@ "id": "615cb805", "metadata": { "ExecuteTime": { - "end_time": "2023-09-08T16:51:08.901104329Z", - "start_time": "2023-09-08T16:51:08.139879012Z" + "end_time": "2024-01-29T16:28:32.010116177Z", + "start_time": "2024-01-29T16:28:31.439191974Z" } }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "pybullet build time: May 20 2022 19:44:17\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1706545711.997153]: Failed to import Giskard messages\n", + "[WARN] [1706545712.001630]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + ] + } + ], "source": [ "from pycram.bullet_world import BulletWorld, Object\n", - "from pycram.pose import Transform\n", + "from pycram.pose import Transform, Pose\n", "from pycram.local_transformer import LocalTransformer" ] }, @@ -46,8 +60,8 @@ "id": "7a3222c2", "metadata": { "ExecuteTime": { - "end_time": "2023-09-08T16:51:11.202198685Z", - "start_time": "2023-09-08T16:51:10.916529902Z" + "end_time": "2024-01-29T16:28:32.323570586Z", + "start_time": "2024-01-29T16:28:32.085550201Z" } }, "outputs": [ @@ -55,8 +69,6 @@ "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" ] @@ -77,9 +89,14 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 3, "id": "c019c259", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:28:32.326842316Z", + "start_time": "2024-01-29T16:28:32.324154465Z" + } + }, "outputs": [], "source": [ "world.exit()" @@ -100,12 +117,12 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 4, "id": "14494539", "metadata": { "ExecuteTime": { - "end_time": "2023-09-08T16:51:38.439962987Z", - "start_time": "2023-09-08T16:51:33.675944073Z" + "end_time": "2024-01-29T16:28:35.474604282Z", + "start_time": "2024-01-29T16:28:32.329041645Z" } }, "outputs": [ @@ -113,6 +130,8 @@ "name": "stderr", "output_type": "stream", "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Scalar element defined multiple times: limit\n", @@ -144,16 +163,21 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 5, "id": "708606eb", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:28:35.481284612Z", + "start_time": "2024-01-29T16:28:35.472994214Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "\n", - "\n" + "\n", + "\n" ] } ], @@ -178,12 +202,12 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 6, "id": "988ffda1", "metadata": { "ExecuteTime": { - "end_time": "2023-09-08T16:42:15.478051994Z", - "start_time": "2023-09-08T16:42:15.472743693Z" + "end_time": "2024-01-29T16:28:35.509096003Z", + "start_time": "2024-01-29T16:28:35.483520847Z" } }, "outputs": [ @@ -194,8 +218,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448290\n", - " nsecs: 552922010\n", + " secs: 1706545715\n", + " nsecs: 495329141\n", " frame_id: \"milk_4\"\n", "pose: \n", " position: \n", @@ -210,8 +234,8 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448290\n", - " nsecs: 553559541\n", + " secs: 1706545715\n", + " nsecs: 496921062\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -228,7 +252,6 @@ ], "source": [ "from pycram.local_transformer import LocalTransformer\n", - "from pycram.pose import Pose\n", "\n", "l = LocalTransformer()\n", "test_pose = Pose([1, 1, 1], [0, 0, 0, 1], \"map\")\n", @@ -251,9 +274,14 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 7, "id": "dd2bafc5", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:28:35.509520802Z", + "start_time": "2024-01-29T16:28:35.500190623Z" + } + }, "outputs": [], "source": [ "from pycram.pose import Transform\n", @@ -274,12 +302,12 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 8, "id": "6b23f540", "metadata": { "ExecuteTime": { - "end_time": "2023-09-08T16:47:16.375950749Z", - "start_time": "2023-09-08T16:47:16.332420624Z" + "end_time": "2024-01-29T16:28:35.509787045Z", + "start_time": "2024-01-29T16:28:35.504069535Z" } }, "outputs": [], @@ -303,9 +331,14 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 9, "id": "bd619710", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:28:35.552242116Z", + "start_time": "2024-01-29T16:28:35.508694526Z" + } + }, "outputs": [ { "name": "stdout", diff --git a/examples/migrate_neems.ipynb b/examples/migrate_neems.ipynb index db3baabe5..8f8064c0d 100644 --- a/examples/migrate_neems.ipynb +++ b/examples/migrate_neems.ipynb @@ -128,7 +128,7 @@ " @with_tree\n", " def pick_and_place_plan(self):\n", " with simulated_robot:\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n", + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n", " MoveTorsoAction([0.3]).resolve().perform()\n", " pickup_pose = CostmapLocation(target=self.cereal_desig.resolve(), reachable_for=self.robot_desig).resolve()\n", " pickup_arm = pickup_pose.reachable_arms[0]\n", @@ -147,7 +147,7 @@ "\n", " PlaceAction(self.cereal_desig, target_locations=[place_island.pose], arms=[pickup_arm]).resolve().perform()\n", "\n", - " ParkArmsAction.Action(Arms.BOTH).perform()\n" + " ParkArmsAction([Arms.BOTH]).resolve().perform()\n" ] }, { diff --git a/examples/motion_designator.ipynb b/examples/motion_designator.ipynb index 9b0dbb8b6..2a0b256de 100644 --- a/examples/motion_designator.ipynb +++ b/examples/motion_designator.ipynb @@ -15,23 +15,35 @@ "cell_type": "code", "execution_count": 1, "id": "7f7c74ae", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:00.051126267Z", + "start_time": "2024-01-29T16:46:56.312023994Z" + } + }, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "pybullet build time: May 20 2022 19:44:17\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1706546816.907019]: Failed to import Giskard messages\n", + "[WARN] [1706546816.911886]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" ] } @@ -54,9 +66,14 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 2, "id": "cc2e1bcd", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:00.051774984Z", + "start_time": "2024-01-29T16:47:00.048239557Z" + } + }, "outputs": [], "source": [ "world.exit()" @@ -73,27 +90,36 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 3, "id": "ad9c75e3", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:00.576314628Z", + "start_time": "2024-01-29T16:47:00.051456576Z" + } + }, "outputs": [], "source": [ + "from pycram.pose import Pose\n", "from pycram.designators.motion_designator import MoveMotion\n", "from pycram.process_module import simulated_robot\n", "\n", "with simulated_robot:\n", " motion_description = MoveMotion(target=Pose([1, 0, 0], [0, 0, 0, 1]))\n", " \n", - " motion_desig = motion_description.resolve()\n", - " \n", - " motion_desig.perform()" + " motion_description.perform()" ] }, { "cell_type": "code", "execution_count": 4, "id": "ac9f7766", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:00.594527954Z", + "start_time": "2024-01-29T16:47:00.591545638Z" + } + }, "outputs": [], "source": [ "world.reset_bullet_world()" @@ -112,7 +138,12 @@ "cell_type": "code", "execution_count": 5, "id": "52aa961d", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:01.122650746Z", + "start_time": "2024-01-29T16:47:00.593841452Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import MoveTCPMotion\n", @@ -121,7 +152,7 @@ "with simulated_robot:\n", " motion_description = MoveTCPMotion(target=Pose([0.5, 0.6, 0.6], [0, 0, 0, 1]), arm=\"left\")\n", " \n", - " motion_description.resolve().perform()" + " motion_description.perform()" ] }, { @@ -137,7 +168,12 @@ "cell_type": "code", "execution_count": 6, "id": "84ffcf03", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:01.633288773Z", + "start_time": "2024-01-29T16:47:01.135133088Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import LookingMotion\n", @@ -146,7 +182,7 @@ "with simulated_robot:\n", " motion_description = LookingMotion(target=Pose([1, 1, 1], [0, 0, 0, 1]))\n", " \n", - " motion_description.resolve().perform()" + " motion_description.perform()" ] }, { @@ -162,7 +198,12 @@ "cell_type": "code", "execution_count": 7, "id": "f90adb34", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:02.149528442Z", + "start_time": "2024-01-29T16:47:01.647168572Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import MoveGripperMotion\n", @@ -171,7 +212,7 @@ "with simulated_robot:\n", " motion_description = MoveGripperMotion(motion=\"open\", gripper=\"left\")\n", " \n", - " motion_description.resolve().perform()" + " motion_description.perform()" ] }, { @@ -189,7 +230,12 @@ "cell_type": "code", "execution_count": 8, "id": "4c9f3e27", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:02.199992775Z", + "start_time": "2024-01-29T16:47:02.150827945Z" + } + }, "outputs": [], "source": [ "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([1.5, 0, 1]))" @@ -197,21 +243,26 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 9, "id": "27eae08a", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:03.473751479Z", + "start_time": "2024-01-29T16:47:02.201339779Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "ObjectDesignatorDescription.Object(name=milk, type=ObjectType.MILK, bullet_world_object=Object(world=, \n", - "local_transformer=, \n", + "ObjectDesignatorDescription.Object(name=milk, type=ObjectType.MILK, bullet_world_object=Object(world=, \n", + "local_transformer=, \n", "name=milk, \n", "type=ObjectType.MILK, \n", "color=[1, 1, 1, 1], \n", "id=3, \n", - "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", + "path=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \n", "joints: ..., \n", "links: ..., \n", "attachments: ..., \n", @@ -219,8 +270,8 @@ "original_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -237,8 +288,8 @@ "_current_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -250,48 +301,17 @@ " y: 0.0\n", " z: 0.0\n", " w: 1.0, \n", - "_current_link_poses={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_link_transforms={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448598\n", - " nsecs: 510938167\n", - " frame_id: \"map\"\n", - "child_frame_id: \"milk_3\"\n", - "transform: \n", - " translation: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " rotation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", + "_current_link_poses: ..., \n", + "_current_link_transforms: ..., \n", "_current_joint_states={}, \n", "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", - "link_to_geometry={'milk_main': }), _pose=, \n", - "local_transformer=, \n", + "link_to_geometry: ...), _pose=, \n", + "local_transformer=, \n", "name=milk, \n", "type=ObjectType.MILK, \n", "color=[1, 1, 1, 1], \n", "id=3, \n", - "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", + "path=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \n", "joints: ..., \n", "links: ..., \n", "attachments: ..., \n", @@ -299,8 +319,8 @@ "original_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -317,8 +337,8 @@ "_current_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -330,46 +350,15 @@ " y: 0.0\n", " z: 0.0\n", " w: 1.0, \n", - "_current_link_poses={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_link_transforms={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448598\n", - " nsecs: 510938167\n", - " frame_id: \"map\"\n", - "child_frame_id: \"milk_3\"\n", - "transform: \n", - " translation: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " rotation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", + "_current_link_poses: ..., \n", + "_current_link_transforms: ..., \n", "_current_joint_states={}, \n", "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", - "link_to_geometry={'milk_main': })>, pose=header: \n", + "link_to_geometry: ...)>, pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -389,11 +378,11 @@ "from pycram.process_module import simulated_robot\n", "\n", "with simulated_robot:\n", - " LookingMotion(target=Pose([1.5, 0, 1], [0, 0, 0, 1])).resolve().perform()\n", + " LookingMotion(target=Pose([1.5, 0, 1], [0, 0, 0, 1])).perform()\n", " \n", " motion_description = DetectingMotion(object_type=ObjectType.MILK)\n", " \n", - " obj = motion_description.resolve().perform()\n", + " obj = motion_description.perform()\n", " \n", " print(obj)" ] @@ -404,23 +393,28 @@ "metadata": {}, "source": [ "## Move Arm Joints\n", - "This motion designator moves one or both arms. Movement targets can either be a dictionary with joint name as key and target pose as value or a pre-defined configuration like 'park'." + "This motion designator moves one or both arms. Movement targets are a dictionary with joint name as key and target pose as value. " ] }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 10, "id": "ce7655c1", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:03.979196754Z", + "start_time": "2024-01-29T16:47:03.482859314Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import MoveArmJointsMotion\n", "from pycram.process_module import simulated_robot\n", "\n", "with simulated_robot:\n", - " motion_description = MoveArmJointsMotion(left_arm_config=\"park\", right_arm_poses={\"r_shoulder_pan_joint\": -0.7})\n", + " motion_description = MoveArmJointsMotion(right_arm_poses={\"r_shoulder_pan_joint\": -0.7})\n", " \n", - " motion_description.resolve().perform()" + " motion_description.perform()" ] }, { @@ -436,9 +430,14 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 11, "id": "0f9f0ca8", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:04.035948673Z", + "start_time": "2024-01-29T16:47:03.980202995Z" + } + }, "outputs": [], "source": [ "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([-1, 0, 1]))" @@ -446,21 +445,26 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 12, "id": "4382bfa3", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:04.540918323Z", + "start_time": "2024-01-29T16:47:04.035986657Z" + } + }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Object(world=, \n", - "local_transformer=, \n", + "Object(world=, \n", + "local_transformer=, \n", "name=milk, \n", "type=ObjectType.MILK, \n", "color=[1, 1, 1, 1], \n", "id=3, \n", - "path=/home/jdech/workspace/ros/src/pycram-1/src/pycram/../../resources/cached/milk.urdf, \n", + "path=/home/dprueser/workspace/ros/src/pycram/src/pycram/../../resources/cached/milk.urdf, \n", "joints: ..., \n", "links: ..., \n", "attachments: ..., \n", @@ -468,8 +472,8 @@ "original_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -486,8 +490,8 @@ "_current_pose=header: \n", " seq: 0\n", " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", + " secs: 1706546822\n", + " nsecs: 149801731\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -499,42 +503,11 @@ " y: 0.0\n", " z: 0.0\n", " w: 1.0, \n", - "_current_link_poses={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448584\n", - " nsecs: 433914899\n", - " frame_id: \"map\"\n", - "pose: \n", - " position: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " orientation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", - "_current_link_transforms={'milk_main': header: \n", - " seq: 0\n", - " stamp: \n", - " secs: 1699448598\n", - " nsecs: 510938167\n", - " frame_id: \"map\"\n", - "child_frame_id: \"milk_3\"\n", - "transform: \n", - " translation: \n", - " x: 1.5\n", - " y: 0.0\n", - " z: 1.0\n", - " rotation: \n", - " x: 0.0\n", - " y: 0.0\n", - " z: 0.0\n", - " w: 1.0}, \n", + "_current_link_poses: ..., \n", + "_current_link_transforms: ..., \n", "_current_joint_states={}, \n", "base_origin_shift=[ 4.15300950e-04 -6.29518181e-05 8.96554102e-02], \n", - "link_to_geometry={'milk_main': })\n" + "link_to_geometry: ...)\n" ] } ], @@ -545,7 +518,7 @@ "with simulated_robot:\n", " motion_description = WorldStateDetectingMotion(object_type=ObjectType.MILK)\n", " \n", - " obj = motion_description.resolve().perform()\n", + " obj = motion_description.perform()\n", " \n", " print(obj)" ] @@ -561,9 +534,14 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": 13, "id": "1e0191c8", - "metadata": {}, + "metadata": { + "ExecuteTime": { + "end_time": "2024-01-29T16:47:05.046180891Z", + "start_time": "2024-01-29T16:47:04.548113629Z" + } + }, "outputs": [], "source": [ "from pycram.designators.motion_designator import MoveJointsMotion\n", @@ -572,7 +550,7 @@ "with simulated_robot:\n", " motion_description = MoveJointsMotion(names=[\"torso_lift_joint\", \"r_shoulder_pan_joint\"], positions=[0.2, -1.2])\n", " \n", - " motion_description.resolve().perform()" + " motion_description.perform()" ] } ], diff --git a/examples/orm_example.ipynb b/examples/orm_example.ipynb index dc0b3e711..26e810c9c 100644 --- a/examples/orm_example.ipynb +++ b/examples/orm_example.ipynb @@ -15,14 +15,14 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:06.779230216Z", - "start_time": "2024-01-05T11:48:06.588261981Z" + "end_time": "2024-01-29T16:51:09.128875369Z", + "start_time": "2024-01-29T16:51:08.956260897Z" } }, "outputs": [ { "data": { - "text/plain": "" + "text/plain": "" }, "execution_count": 1, "metadata": {}, @@ -50,8 +50,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:07.264463765Z", - "start_time": "2024-01-05T11:48:06.770051795Z" + "end_time": "2024-01-29T16:51:09.568683265Z", + "start_time": "2024-01-29T16:51:09.124071834Z" } }, "outputs": [ @@ -64,8 +64,8 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1704455287.243634]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1704455287.248237]: Failed to import Giskard messages\n" + "[WARN] [1706547069.541495]: Failed to import Giskard messages\n", + "[WARN] [1706547069.546682]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -88,8 +88,8 @@ "execution_count": 3, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.697221588Z", - "start_time": "2024-01-05T11:48:07.267874656Z" + "end_time": "2024-01-29T16:51:35.305706324Z", + "start_time": "2024-01-29T16:51:09.568597034Z" } }, "outputs": [ @@ -105,14 +105,62 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Scalar element defined multiple times: limit\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Scalar element defined multiple times: limit\n", "Scalar element defined multiple times: limit\n" ] }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "argc=2\n", + "argv[0] = --unused\n", + "argv[1] = --start_demo_name=Physics Server\n", + "ExampleBrowserThreadFunc started\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "X11 functions dynamically loaded using dlopen/dlsym OK!\n", + "Creating context\n", + "Created GL 3.3 context\n", + "Direct GLX rendering context obtained\n", + "Making context current\n", + "GL_VENDOR=AMD\n", + "GL_RENDERER=AMD Radeon RX 6700 XT (NAVY_FLOUNDER, DRM 3.42.0, 5.15.0-89-generic, LLVM 12.0.0)\n", + "GL_VERSION=4.6 (Core Profile) Mesa 21.2.6\n", + "GL_SHADING_LANGUAGE_VERSION=4.60\n", + "pthread_getconcurrency()=0\n", + "Version = 4.6 (Core Profile) Mesa 21.2.6\n", + "Vendor = AMD\n", + "Renderer = AMD Radeon RX 6700 XT (NAVY_FLOUNDER, DRM 3.42.0, 5.15.0-89-generic, LLVM 12.0.0)\n", + "b3Printf: Selected demo: Physics Server\n", + "startThreads creating 1 threads.\n", + "starting thread 0\n", + "started thread 0 \n", + "MotionThreadFunc thread started\n", + "ven = AMD\n", + "ven = AMD\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/r_gripper_r_finger_tip_link (parent map) at time 1706547087.197074 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + "Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/r_gripper_palm_link (parent map) at time 1706547087.480158 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + "Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/projector_wg6802418_child_frame (parent map) at time 1706547089.689294 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + "Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame shadow/pr2_1/l_shoulder_pan_link (parent map) at time 1706547092.019791 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n" + ] + }, { "name": "stdout", "output_type": "stream", @@ -122,20 +170,20 @@ " ├── perform(ParkArmsActionPerformable)\n", " ├── perform(MoveTorsoActionPerformable)\n", " ├── perform(NavigateActionPerformable)\n", - " │ └── perform(Motion)\n", + " │ └── perform(MoveMotion)\n", " ├── perform(PickUpActionPerformable)\n", - " │ ├── perform(Motion)\n", - " │ ├── perform(Motion)\n", - " │ ├── perform(Motion)\n", - " │ ├── perform(Motion)\n", - " │ └── perform(Motion)\n", + " │ ├── perform(MoveTCPMotion)\n", + " │ ├── perform(MoveGripperMotion)\n", + " │ ├── perform(MoveTCPMotion)\n", + " │ ├── perform(MoveGripperMotion)\n", + " │ └── perform(MoveTCPMotion)\n", " ├── perform(ParkArmsActionPerformable)\n", " ├── perform(NavigateActionPerformable)\n", - " │ └── perform(Motion)\n", + " │ └── perform(MoveMotion)\n", " ├── perform(PlaceActionPerformable)\n", - " │ ├── perform(Motion)\n", - " │ ├── perform(Motion)\n", - " │ └── perform(Motion)\n", + " │ ├── perform(MoveTCPMotion)\n", + " │ ├── perform(MoveGripperMotion)\n", + " │ └── perform(MoveTCPMotion)\n", " └── perform(ParkArmsActionPerformable)\n" ] } @@ -204,8 +252,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.882423457Z", - "start_time": "2024-01-05T11:48:27.695892994Z" + "end_time": "2024-01-29T16:51:35.505074180Z", + "start_time": "2024-01-29T16:51:35.307461245Z" } }, "outputs": [ @@ -213,12 +261,12 @@ "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 20/20 [00:00<00:00, 112.65it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 20/20 [00:00<00:00, 105.04it/s]\n" ] }, { "data": { - "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" + "text/plain": "TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" }, "execution_count": 4, "metadata": {}, @@ -241,8 +289,8 @@ "execution_count": 5, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.887896771Z", - "start_time": "2024-01-05T11:48:27.883057209Z" + "end_time": "2024-01-29T16:51:35.508649071Z", + "start_time": "2024-01-29T16:51:35.506023628Z" } }, "outputs": [ @@ -250,12 +298,14 @@ "name": "stdout", "output_type": "stream", "text": [ - "ProcessMetaData(id=1, created_at=datetime.datetime(2024, 1, 5, 11, 48, 27), created_by='dprueser', description='Tutorial for getting familiar with the ORM.', pycram_version='be748996363cb497af6784f6f2aaeffcb2fb1c42')\n" + "ProcessMetaData(id=1, created_at=datetime.datetime(2024, 1, 29, 16, 51, 35), created_by='dprueser', description='Tutorial for getting familiar with the ORM.', pycram_version='5e32afdb9ba57a9d6befec2c78087fee1f5e5d9b')\n" ] } ], "source": [ - "print(*session.query(pycram.orm.base.ProcessMetaData).all())" + "from sqlalchemy import select\n", + "\n", + "print(*session.scalars(select(pycram.orm.base.ProcessMetaData)).all())" ] }, { @@ -271,8 +321,8 @@ "execution_count": 6, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.933255911Z", - "start_time": "2024-01-05T11:48:27.886082312Z" + "end_time": "2024-01-29T16:51:35.520518056Z", + "start_time": "2024-01-29T16:51:35.508477111Z" } }, "outputs": [ @@ -286,7 +336,7 @@ } ], "source": [ - "navigations = session.query(pycram.orm.action_designator.NavigateAction).all()\n", + "navigations = session.scalars(select(pycram.orm.action_designator.NavigateAction)).all()\n", "print(*navigations, sep=\"\\n\")" ] }, @@ -302,8 +352,8 @@ "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.933794333Z", - "start_time": "2024-01-05T11:48:27.930158041Z" + "end_time": "2024-01-29T16:51:35.560192686Z", + "start_time": "2024-01-29T16:51:35.520628950Z" } }, "outputs": [ @@ -323,7 +373,7 @@ } ], "source": [ - "actions = session.query(pycram.orm.action_designator.Action).all()\n", + "actions = session.scalars(select(pycram.orm.action_designator.Action)).all()\n", "print(*actions, sep=\"\\n\")" ] }, @@ -339,8 +389,8 @@ "execution_count": 8, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.934174898Z", - "start_time": "2024-01-05T11:48:27.930328964Z" + "end_time": "2024-01-29T16:51:35.561234983Z", + "start_time": "2024-01-29T16:51:35.535162323Z" } }, "outputs": [ @@ -348,14 +398,14 @@ "name": "stdout", "output_type": "stream", "text": [ - "Pose(id=7, time=datetime.datetime(2024, 1, 5, 11, 48, 13, 104805), frame='map', position_id=7, orientation_id=7, process_metadata_id=1)\n" + "Pose(id=7, time=datetime.datetime(2024, 1, 29, 16, 51, 15, 804838), frame='map', position_id=7, orientation_id=7, process_metadata_id=1)\n" ] } ], "source": [ - "object_actions = (session.query(pycram.orm.base.Pose)\n", + "object_actions = (session.scalars(select(pycram.orm.base.Pose)\n", " .join(pycram.orm.action_designator.PickUpAction.object)\n", - " .join(pycram.orm.object_designator.Object.pose)\n", + " .join(pycram.orm.object_designator.Object.pose))\n", " .all())\n", "print(*object_actions, sep=\"\\n\")\n" ] @@ -384,8 +434,8 @@ "execution_count": 9, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.992321580Z", - "start_time": "2024-01-05T11:48:27.930434353Z" + "end_time": "2024-01-29T16:51:35.600701170Z", + "start_time": "2024-01-29T16:51:35.539887927Z" } }, "outputs": [ @@ -393,30 +443,30 @@ "name": "stdout", "output_type": "stream", "text": [ - "TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=3, code_id=3, code=Code(id=3, function='perform', designator_id=1, designator=ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=, pose_id=1, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167962), end_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 674674), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=4, code_id=4, code=Code(id=4, function='perform', designator_id=2, designator=MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=, pose_id=2, process_metadata_id=1), position=0.3), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 674769), end_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 177846), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742815), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288620), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=6, code_id=6, code=Code(id=6, function='perform', designator_id=4, designator=MoveMotion(id=4, process_metadata_id=1, dtype='MoveMotion', pose_id=5), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742855), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288611), status=, reason=None, parent_id=5, parent=TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 14, 742815), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288620), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=8, code_id=8, code=Code(id=8, function='perform', designator_id=6, designator=MoveTCPMotion(id=6, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=8), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 417504), end_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 929845), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=9, code_id=9, code=Code(id=9, function='perform', designator_id=7, designator=MoveGripperMotion(id=7, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 929939), end_time=datetime.datetime(2024, 1, 5, 12, 48, 16, 435586), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=10, code_id=10, code=Code(id=10, function='perform', designator_id=8, designator=MoveTCPMotion(id=8, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=9), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 16, 568469), end_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 76882), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=11, code_id=11, code=Code(id=11, function='perform', designator_id=9, designator=MoveGripperMotion(id=9, process_metadata_id=1, dtype='MoveGripperMotion', motion='close', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 77011), end_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 589849), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=12, code_id=12, code=Code(id=12, function='perform', designator_id=10, designator=MoveTCPMotion(id=10, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=10), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 17, 720082), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 228417), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 15, 288722), end_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 519955), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=13, code_id=13, code=Code(id=13, function='perform', designator_id=11, designator=ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=, pose_id=11, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 18, 520072), end_time=datetime.datetime(2024, 1, 5, 12, 48, 19, 27331), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115462), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625686), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=15, code_id=15, code=Code(id=15, function='perform', designator_id=13, designator=MoveMotion(id=13, process_metadata_id=1, dtype='MoveMotion', pose_id=14), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115512), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625678), status=, reason=None, parent_id=14, parent=TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 115462), end_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625686), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=17, code_id=17, code=Code(id=17, function='perform', designator_id=15, designator=MoveTCPMotion(id=15, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=18), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 626977), end_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 135284), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=18, code_id=18, code=Code(id=18, function='perform', designator_id=16, designator=MoveGripperMotion(id=16, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 135369), end_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 642910), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=19, code_id=19, code=Code(id=19, function='perform', designator_id=17, designator=MoveTCPMotion(id=17, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=19), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 26, 643067), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153860), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 25, 625795), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153873), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", - "TaskTreeNode(id=20, code_id=20, code=Code(id=20, function='perform', designator_id=18, designator=ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=, pose_id=20, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 153953), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660007), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 13, 167898), end_time=datetime.datetime(2024, 1, 5, 12, 48, 27, 660020), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 5, 12, 48, 7, 241508), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n" + "TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=3, code_id=3, code=Code(id=3, function='perform', designator_id=1, designator=ParkArmsAction(id=1, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=1, robot_state=RobotState(id=1, torso_height=0.0, type=, pose_id=1, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872243), end_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 378193), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=4, code_id=4, code=Code(id=4, function='perform', designator_id=2, designator=MoveTorsoAction(id=2, process_metadata_id=1, dtype='MoveTorsoAction', robot_state_id=2, robot_state=RobotState(id=2, torso_height=0.0, type=, pose_id=2, process_metadata_id=1), position=0.3), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 378288), end_time=datetime.datetime(2024, 1, 29, 17, 51, 16, 881639), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459617), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970219), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=6, code_id=6, code=Code(id=6, function='perform', designator_id=4, designator=MoveMotion(id=4, process_metadata_id=1, dtype='MoveMotion', pose_id=5), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459689), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970208), status=, reason=None, parent_id=5, parent=TaskTreeNode(id=5, code_id=5, code=Code(id=5, function='perform', designator_id=3, designator=NavigateAction(id=3, process_metadata_id=1, dtype='NavigateAction', robot_state_id=3, robot_state=RobotState(id=3, torso_height=0.3, type=, pose_id=3, process_metadata_id=1), pose_id=4), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 459617), end_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970219), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=8, code_id=8, code=Code(id=8, function='perform', designator_id=6, designator=MoveTCPMotion(id=6, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=8), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 122271), end_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 631460), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=9, code_id=9, code=Code(id=9, function='perform', designator_id=7, designator=MoveGripperMotion(id=7, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 18, 631582), end_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 141918), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=10, code_id=10, code=Code(id=10, function='perform', designator_id=8, designator=MoveTCPMotion(id=8, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=9), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 273490), end_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 783950), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=11, code_id=11, code=Code(id=11, function='perform', designator_id=9, designator=MoveGripperMotion(id=9, process_metadata_id=1, dtype='MoveGripperMotion', motion='close', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 19, 784120), end_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 298210), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=12, code_id=12, code=Code(id=12, function='perform', designator_id=10, designator=MoveTCPMotion(id=10, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=10), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 457629), end_time=datetime.datetime(2024, 1, 29, 17, 51, 20, 974496), status=, reason=None, parent_id=7, parent=TaskTreeNode(id=7, code_id=7, code=Code(id=7, function='perform', designator_id=5, designator=PickUpAction(id=5, process_metadata_id=1, dtype='PickUpAction', robot_state_id=4, robot_state=RobotState(id=4, torso_height=0.3, type=, pose_id=6, process_metadata_id=1), arm='left', grasp='front', object_id=1), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 17, 970355), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274534), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=13, code_id=13, code=Code(id=13, function='perform', designator_id=11, designator=ParkArmsAction(id=11, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=5, robot_state=RobotState(id=5, torso_height=0.3, type=, pose_id=11, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 274678), end_time=datetime.datetime(2024, 1, 29, 17, 51, 21, 782383), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 702999), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209586), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=15, code_id=15, code=Code(id=15, function='perform', designator_id=13, designator=MoveMotion(id=13, process_metadata_id=1, dtype='MoveMotion', pose_id=14), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 703060), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209577), status=, reason=None, parent_id=14, parent=TaskTreeNode(id=14, code_id=14, code=Code(id=14, function='perform', designator_id=12, designator=NavigateAction(id=12, process_metadata_id=1, dtype='NavigateAction', robot_state_id=6, robot_state=RobotState(id=6, torso_height=0.3, type=, pose_id=12, process_metadata_id=1), pose_id=13), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 32, 702999), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209586), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=17, code_id=17, code=Code(id=17, function='perform', designator_id=15, designator=MoveTCPMotion(id=15, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=18), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 210786), end_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 721856), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=18, code_id=18, code=Code(id=18, function='perform', designator_id=16, designator=MoveGripperMotion(id=16, process_metadata_id=1, dtype='MoveGripperMotion', motion='open', gripper='left', allow_gripper_collision=None), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 722026), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 239587), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=19, code_id=19, code=Code(id=19, function='perform', designator_id=17, designator=MoveTCPMotion(id=17, process_metadata_id=1, dtype='MoveTCPMotion', arm='left', allow_gripper_collision=None, pose_id=19), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 241042), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751946), status=, reason=None, parent_id=16, parent=TaskTreeNode(id=16, code_id=16, code=Code(id=16, function='perform', designator_id=14, designator=PlaceAction(id=14, process_metadata_id=1, dtype='PlaceAction', robot_state_id=7, robot_state=RobotState(id=7, torso_height=0.3, type=, pose_id=15, process_metadata_id=1), arm='left', pose_id=17, object_id=2), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 33, 209685), end_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 751975), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n", + "TaskTreeNode(id=20, code_id=20, code=Code(id=20, function='perform', designator_id=18, designator=ParkArmsAction(id=18, process_metadata_id=1, dtype='ParkArmsAction', robot_state_id=8, robot_state=RobotState(id=8, torso_height=0.3, type=, pose_id=20, process_metadata_id=1), arm=), process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 34, 752094), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265524), status=, reason=None, parent_id=2, parent=TaskTreeNode(id=2, code_id=2, code=Code(id=2, function='plan', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 15, 872198), end_time=datetime.datetime(2024, 1, 29, 17, 51, 35, 265539), status=, reason=None, parent_id=1, parent=TaskTreeNode(id=1, code_id=1, code=Code(id=1, function='no_operation', designator_id=None, designator=None, process_metadata_id=1), start_time=datetime.datetime(2024, 1, 29, 17, 51, 9, 545708), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1), process_metadata_id=1), process_metadata_id=1)\n" ] } ], "source": [ - "successful_tasks = session.query(pycram.orm.task.TaskTreeNode).filter(pycram.orm.task.TaskTreeNode.status == \"SUCCEEDED\")\n", + "successful_tasks = session.scalars(select(pycram.orm.task.TaskTreeNode).where(pycram.orm.task.TaskTreeNode.status == \"SUCCEEDED\"))\n", "print(*successful_tasks, sep=\"\\n\")" ] }, @@ -434,13 +484,13 @@ "execution_count": 10, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.993029221Z", - "start_time": "2024-01-05T11:48:27.956265531Z" + "end_time": "2024-01-29T16:51:35.601121928Z", + "start_time": "2024-01-29T16:51:35.600085428Z" } }, "outputs": [], "source": [ - "from sqlalchemy.orm import Mapped, mapped_column\n", + "from sqlalchemy.orm import Mapped, mapped_column, Session\n", "from pycram.orm.action_designator import Action\n", "from dataclasses import dataclass\n", "\n", @@ -485,8 +535,8 @@ "execution_count": 11, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:27.993997340Z", - "start_time": "2024-01-05T11:48:27.956444747Z" + "end_time": "2024-01-29T16:51:35.601417935Z", + "start_time": "2024-01-29T16:51:35.600240790Z" } }, "outputs": [], @@ -506,8 +556,8 @@ "execution_count": 12, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:28.491240632Z", - "start_time": "2024-01-05T11:48:27.965003339Z" + "end_time": "2024-01-29T16:51:36.020873055Z", + "start_time": "2024-01-29T16:51:35.600296911Z" } }, "outputs": [ @@ -522,7 +572,7 @@ "name": "stderr", "output_type": "stream", "text": [ - "Inserting TaskTree into database: 100%|██████████| 21/21 [00:00<00:00, 77.00it/s]\n" + "Inserting TaskTree into database: 100%|██████████| 21/21 [00:00<00:00, 116.25it/s]\n" ] } ], @@ -545,11 +595,11 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 14, "metadata": { "ExecuteTime": { - "end_time": "2024-01-05T11:48:28.526329436Z", - "start_time": "2024-01-05T11:48:28.478332427Z" + "end_time": "2024-01-29T16:52:32.021378099Z", + "start_time": "2024-01-29T16:52:31.976674160Z" } }, "outputs": [ @@ -557,14 +607,22 @@ "data": { "text/plain": "[ORMSaying(id=37, process_metadata_id=1, dtype='ORMSaying', robot_state_id=17, robot_state=RobotState(id=17, torso_height=0.3, type=, pose_id=41, process_metadata_id=1), text='Patchie, Patchie; Where is my Patchie?')]" }, - "execution_count": 13, + "execution_count": 14, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "session.query(ORMSaying).all()" + "session.scalars(select(ORMSaying)).all()" ] + }, + { + "cell_type": "code", + "outputs": [], + "source": [], + "metadata": { + "collapsed": false + } } ], "metadata": { diff --git a/examples/orm_querying_examples.ipynb b/examples/orm_querying_examples.ipynb index 64f78edb4..12adedfe1 100644 --- a/examples/orm_querying_examples.ipynb +++ b/examples/orm_querying_examples.ipynb @@ -36,8 +36,8 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1704455774.294953]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "[WARN] [1704455774.300327]: Failed to import Giskard messages\n" + "[WARN] [1706547279.009069]: Failed to import Giskard messages\n", + "[WARN] [1706547279.013875]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -206,8 +206,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:56:14.747051902Z", - "start_time": "2024-01-05T11:56:13.637965477Z" + "end_time": "2024-01-29T16:54:39.452156158Z", + "start_time": "2024-01-29T16:54:38.500054294Z" } }, "id": "dc0c9e6f15f126a3" @@ -243,9 +243,23 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - " 74%|███████▍ | 708/960 [01:31<00:29, 8.48it/s, success_rate=0.0819]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/r_gripper_palm_link (parent map) at time 1704455865.925491 according to authority default_authority\n", + " 7%|▋ | 69/960 [00:10<01:47, 8.33it/s, success_rate=0.058] Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame floor_0 (parent map) at time 1706547289.526924 according to authority default_authority\n", " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", - "100%|██████████| 960/960 [02:03<00:00, 7.85it/s, success_rate=0.0854]" + " 28%|██▊ | 269/960 [00:38<01:37, 7.08it/s, success_rate=0.0929]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/narrow_stereo_l_stereo_camera_frame (parent map) at time 1706547317.808086 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 33%|███▎ | 314/960 [00:44<01:35, 6.79it/s, success_rate=0.0955]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame floor_0 (parent map) at time 1706547323.909252 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 52%|█████▏ | 502/960 [01:10<01:07, 6.76it/s, success_rate=0.0837]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/narrow_stereo_l_stereo_camera_frame (parent map) at time 1706547349.562933 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 57%|█████▋ | 543/960 [01:16<01:02, 6.65it/s, success_rate=0.081] Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/narrow_stereo_l_stereo_camera_optical_frame (parent map) at time 1706547355.536726 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 78%|███████▊ | 749/960 [01:44<00:28, 7.28it/s, success_rate=0.0814]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/torso_lift_motor_screw_link (parent map) at time 1706547384.042323 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 81%|████████▏ | 782/960 [01:48<00:22, 7.94it/s, success_rate=0.0831]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/l_torso_lift_side_plate_link (parent map) at time 1706547388.456061 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + " 86%|████████▌ | 826/960 [01:55<00:18, 7.12it/s, success_rate=0.0835]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame pr2_1/r_shoulder_lift_link (parent map) at time 1706547394.924536 according to authority default_authority\n", + " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", + "100%|██████████| 960/960 [02:13<00:00, 7.74it/s, success_rate=0.0854]" ] } ], @@ -261,8 +275,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:58:18.210175597Z", - "start_time": "2024-01-05T11:56:14.749214037Z" + "end_time": "2024-01-29T16:56:53.360247565Z", + "start_time": "2024-01-29T16:54:39.452769369Z" } }, "id": "f2dcacd942218899" @@ -296,9 +310,9 @@ "name": "stdout", "output_type": "stream", "text": [ - "SELECT \"PickUpAction\".arm AS \"PickUpAction_arm\", \"PickUpAction\".grasp AS \"PickUpAction_grasp\", \"RobotState\".torso_height AS \"RobotState_torso_height\", \"Position\".x AS \"Position_x\", \"Position\".y AS \"Position_y\" \n", + "SELECT \"PickUpAction\".arm, \"PickUpAction\".grasp, \"RobotState\".torso_height, \"Position\".x, \"Position\".y \n", "FROM \"TaskTreeNode\" JOIN \"Code\" ON \"Code\".id = \"TaskTreeNode\".code_id JOIN (\"Designator\" JOIN \"Action\" ON \"Designator\".id = \"Action\".id JOIN \"PickUpAction\" ON \"Action\".id = \"PickUpAction\".id) ON \"Designator\".id = \"Code\".designator_id JOIN \"RobotState\" ON \"RobotState\".id = \"Action\".robot_state_id JOIN \"Pose\" ON \"Pose\".id = \"RobotState\".pose_id JOIN \"Position\" ON \"Position\".id = \"Pose\".position_id JOIN \"Object\" ON \"Object\".id = \"PickUpAction\".object_id \n", - "WHERE \"Object\".type = ? AND \"TaskTreeNode\".status = ?\n", + "WHERE \"Object\".type = :type_1 AND \"TaskTreeNode\".status = :status_1\n", " arm grasp torso_height x y\n", "0 left left 0.198541 -0.679778 0.049746\n", "1 left left 0.092868 0.473199 0.612112\n", @@ -324,30 +338,31 @@ } ], "source": [ + "from sqlalchemy import select\n", "from pycram.enums import ObjectType\n", "\n", "milk = BulletWorldObject(\"Milk\", ObjectType.MILK, \"milk.stl\")\n", "\n", "# query all relative robot positions in regard to an objects position\n", "# make sure to order the joins() correctly\n", - "query = (session.query(ORMPickUpAction.arm, ORMPickUpAction.grasp, RobotState.torso_height, Position.x, Position.y)\n", + "query = (select(ORMPickUpAction.arm, ORMPickUpAction.grasp, RobotState.torso_height, Position.x, Position.y)\n", " .join(TaskTreeNode.code)\n", " .join(Code.designator.of_type(ORMPickUpAction))\n", " .join(ORMPickUpAction.robot_state)\n", " .join(RobotState.pose)\n", " .join(pycram.orm.base.Pose.position)\n", - " .join(ORMPickUpAction.object).filter(Object.type == milk.type)\n", - " .filter(TaskTreeNode.status == \"SUCCEEDED\"))\n", + " .join(ORMPickUpAction.object).where(Object.type == milk.type)\n", + " .where(TaskTreeNode.status == \"SUCCEEDED\"))\n", "print(query)\n", "\n", - "df = pd.read_sql_query(query.statement, session.get_bind())\n", + "df = pd.read_sql_query(query, session.get_bind())\n", "print(df)" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:58:18.210316772Z", - "start_time": "2024-01-05T11:58:18.210052650Z" + "end_time": "2024-01-29T16:56:53.362279642Z", + "start_time": "2024-01-29T16:56:53.360090447Z" } }, "id": "b17c6366f317dd7" @@ -384,7 +399,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "SELECT \"TaskTreeNode\".status AS \"TaskTreeNode_status\", \"Object\".type AS \"Object_type\", \"Position_1\".z - \"RobotState\".torso_height AS \"relative torso height\", \"Position_2\".x - \"Position_1\".x AS x, \"Position_2\".y - \"Position_1\".y AS y \n", + "SELECT \"TaskTreeNode\".status, \"Object\".type, \"Position_1\".z - \"RobotState\".torso_height AS \"relative torso height\", \"Position_2\".x - \"Position_1\".x AS x, \"Position_2\".y - \"Position_1\".y AS y \n", "FROM \"TaskTreeNode\" JOIN \"Code\" ON \"Code\".id = \"TaskTreeNode\".code_id JOIN (\"Designator\" JOIN \"Action\" ON \"Designator\".id = \"Action\".id JOIN \"PickUpAction\" ON \"Action\".id = \"PickUpAction\".id) ON \"Designator\".id = \"Code\".designator_id JOIN \"RobotState\" ON \"RobotState\".id = \"Action\".robot_state_id JOIN \"Pose\" AS \"Pose_1\" ON \"Pose_1\".id = \"RobotState\".pose_id JOIN \"Position\" AS \"Position_2\" ON \"Position_2\".id = \"Pose_1\".position_id JOIN \"Object\" ON \"Object\".id = \"PickUpAction\".object_id JOIN \"Pose\" AS \"Pose_2\" ON \"Pose_2\".id = \"Object\".pose_id JOIN \"Position\" AS \"Position_1\" ON \"Position_1\".id = \"Pose_2\".position_id\n", " status type relative torso height x \\\n", "0 FAILED ObjectType.BREAKFAST_CEREAL 0.480005 -0.737416 \n", @@ -424,7 +439,7 @@ "robot_position = sqlalchemy.orm.aliased(Position)\n", "object_position = sqlalchemy.orm.aliased(Position)\n", "\n", - "query = (session.query(TaskTreeNode.status, Object.type, \n", + "query = (select(TaskTreeNode.status, Object.type, \n", " sqlalchemy.label(\"relative torso height\", object_position.z - RobotState.torso_height),\n", " sqlalchemy.label(\"x\", robot_position.x - object_position.x),\n", " sqlalchemy.label(\"y\", robot_position.y - object_position.y))\n", @@ -438,15 +453,15 @@ " .join(object_position, object_pose.position))\n", "print(query)\n", "\n", - "df = pd.read_sql(query.statement, session.get_bind())\n", + "df = pd.read_sql(query, session.get_bind())\n", "df[\"status\"] = df[\"status\"].apply(lambda x: str(x.name))\n", "print(df)" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-01-05T11:58:18.254184939Z", - "start_time": "2024-01-05T11:58:18.210187006Z" + "end_time": "2024-01-29T16:56:53.408414208Z", + "start_time": "2024-01-29T16:56:53.408012819Z" } }, "id": "a89d1a0f2a933475" From b03c6e2559b4fda726c0f5cfd3a39ddf77c82340 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Thu, 1 Feb 2024 16:00:43 +0100 Subject: [PATCH 069/195] [orm] fixed sqlalchemy deprecation warnings --- src/pycram/orm/base.py | 21 +++++++++++---------- src/pycram/orm/object_designator.py | 7 ++++--- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/src/pycram/orm/base.py b/src/pycram/orm/base.py index cc6356d5e..6bf7f55a9 100644 --- a/src/pycram/orm/base.py +++ b/src/pycram/orm/base.py @@ -2,6 +2,7 @@ import datetime import getpass import os +from dataclasses import field from typing import Optional import git @@ -27,7 +28,7 @@ def get_pycram_version_from_git() -> Optional[str]: return repo.head.object.hexsha -class _Base(DeclarativeBase): +class _Base(DeclarativeBase, MappedAsDataclass): """Dummy class""" type_annotation_map = { str: String(255) @@ -41,7 +42,7 @@ def __tablename__(self): return self.__name__ -class Base(_Base, MappedAsDataclass): +class Base(_Base): """ Base class to add orm functionality to all pycram mappings """ @@ -59,7 +60,7 @@ def process_metadata(self): tables""" -class MapperArgsMixin: +class MapperArgsMixin(MappedAsDataclass): """ MapperArgsMixin stores __mapper_args__ information for certain subclass-tables. For information about Mixins, see https://docs.sqlalchemy.org/en/20/orm/declarative_mixins.html @@ -72,14 +73,14 @@ def __mapper_args__(self): return {"polymorphic_identity": self.__tablename__} -class PositionMixin: +class PositionMixin(MappedAsDataclass): """ PositionMixin holds a foreign key column and its relationship to the referenced table. For information about Mixins, see https://docs.sqlalchemy.org/en/20/orm/declarative_mixins.html """ __abstract__ = True - position_to_init: bool = False + position_to_init: bool = field(default=False, init=False) @declared_attr def position_id(self) -> Mapped[int]: @@ -90,14 +91,14 @@ def position(self): return relationship(Position.__tablename__, init=False) -class QuaternionMixin: +class QuaternionMixin(MappedAsDataclass): """ QuaternionMixin holds a foreign key column and its relationship to the referenced table. For information about Mixins, see https://docs.sqlalchemy.org/en/20/orm/declarative_mixins.html """ __abstract__ = True - orientation_to_init: bool = False + orientation_to_init: bool = field(default=False, init=False) @declared_attr def orientation_id(self) -> Mapped[int]: @@ -108,14 +109,14 @@ def orientation(self): return relationship(Quaternion.__tablename__, init=False) -class PoseMixin: +class PoseMixin(MappedAsDataclass): """ PoseMixin holds a foreign key column and its relationship to the referenced table. For information about Mixins, see https://docs.sqlalchemy.org/en/20/orm/declarative_mixins.html """ __abstract__ = True - pose_to_init: bool = False + pose_to_init: bool = field(default=False, init=False) @declared_attr def pose_id(self) -> Mapped[int]: @@ -126,7 +127,7 @@ def pose(self): return relationship(Pose.__tablename__, init=False) -class ProcessMetaData(MappedAsDataclass, _Base): +class ProcessMetaData(_Base): """ ProcessMetaData stores information about the context of this experiment. diff --git a/src/pycram/orm/object_designator.py b/src/pycram/orm/object_designator.py index 3f2d64205..4c2bb6c4d 100644 --- a/src/pycram/orm/object_designator.py +++ b/src/pycram/orm/object_designator.py @@ -1,19 +1,20 @@ +from dataclasses import field from typing import Optional from pycram.orm.base import Base, MapperArgsMixin, PoseMixin, Pose -from sqlalchemy.orm import Mapped, mapped_column, declared_attr, relationship +from sqlalchemy.orm import Mapped, mapped_column, declared_attr, relationship, MappedAsDataclass from sqlalchemy import ForeignKey from ..enums import ObjectType -class ObjectMixin: +class ObjectMixin(MappedAsDataclass): """ ObjectMixin holds a foreign key column and its relationship to the referenced table. For information about Mixins, see https://docs.sqlalchemy.org/en/13/orm/extensions/declarative/mixins.html """ __abstract__ = True - object_to_init: bool = False + object_to_init: bool = field(default=False, init=False) @declared_attr def object_id(self) -> Mapped[int]: From 50adda9e548cdb478f4871546abd7190b0e216b8 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 1 Feb 2024 21:11:33 +0100 Subject: [PATCH 070/195] [Abstract World] all change requests completed Update positions of objects when simulating Increasing code coverage by tests (reached 55% for bullet_world.py) (77% world.py) --- examples/bullet_world.ipynb | 57 +--- src/pycram/bullet_world.py | 312 +++++------------- src/pycram/costmaps.py | 2 +- src/pycram/helper.py | 2 +- src/pycram/plan_failures.py | 10 + src/pycram/pose.py | 7 +- src/pycram/pose_generator_and_validator.py | 4 +- .../process_modules/boxy_process_modules.py | 10 +- .../process_modules/donbot_process_modules.py | 12 +- .../process_modules/hsr_process_modules.py | 2 +- .../process_modules/pr2_process_modules.py | 6 +- .../resolver/location/giskard_location.py | 10 +- src/pycram/ros/force_torque_sensor.py | 2 +- src/pycram/world.py | 297 +++++++---------- src/pycram/world_dataclasses.py | 115 ++++--- src/pycram/world_reasoning.py | 10 - test/test_attachment.py | 4 +- test/test_bullet_world.py | 45 ++- test/test_language.py | 4 +- test/test_links.py | 4 +- test/test_object.py | 4 +- 21 files changed, 385 insertions(+), 534 deletions(-) diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index c487ec212..6a7423953 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -17,8 +17,8 @@ "id": "23bbba35", "metadata": { "ExecuteTime": { - "end_time": "2024-01-25T18:29:09.773814091Z", - "start_time": "2024-01-25T18:29:08.901441651Z" + "end_time": "2024-02-01T16:28:16.307401805Z", + "start_time": "2024-02-01T16:28:15.499235438Z" } }, "outputs": [ @@ -26,61 +26,22 @@ "name": "stderr", "output_type": "stream", "text": [ - "pybullet build time: Nov 28 2023 23:51:11\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1706207349.376331]: Failed to import Giskard messages\n", - "[WARN] [1706207349.395439]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", - "Exception in thread Thread-11:\n", - "Traceback (most recent call last):\n", - " File \"/usr/lib/python3.8/threading.py\", line 932, in _bootstrap_inner\n", - " self.run()\n", - " File \"/home/bassioun/cram_ws/src/pycram/src/pycram/bullet_world.py\", line 527, in run\n", - " keys = p.getKeyboardEvents(physicalClientId=self.world.client_id)\n", - "TypeError: 'physicalClientId' is an invalid keyword argument for this function\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "startThreads creating 1 threads.\n", - "starting thread 0\n", - "started thread 0 \n", - "argc=2\n", - "argv[0] = --unused\n", - "argv[1] = --start_demo_name=Physics Server\n", - "ExampleBrowserThreadFunc started\n", - "X11 functions dynamically loaded using dlopen/dlsym OK!\n", - "X11 functions dynamically loaded using dlopen/dlsym OK!\n", - "Creating context\n", - "Created GL 3.3 context\n", - "Direct GLX rendering context obtained\n", - "Making context current\n", - "GL_VENDOR=NVIDIA Corporation\n", - "GL_RENDERER=NVIDIA GeForce RTX 4070/PCIe/SSE2\n", - "GL_VERSION=3.3.0 NVIDIA 535.154.05\n", - "GL_SHADING_LANGUAGE_VERSION=3.30 NVIDIA via Cg compiler\n", - "pthread_getconcurrency()=0\n", - "Version = 3.3.0 NVIDIA 535.154.05\n", - "Vendor = NVIDIA Corporation\n", - "Renderer = NVIDIA GeForce RTX 4070/PCIe/SSE2\n", - "b3Printf: Selected demo: Physics Server\n", - "startThreads creating 1 threads.\n", - "starting thread 0\n", - "started thread 0 \n", - "MotionThreadFunc thread started\n" + "Failed to import Giskard messages\n", + "Could not import RoboKudo messages, RoboKudo interface could not be initialized\n", + "pybullet build time: Nov 28 2023 23:51:11\n" ] } ], "source": [ "from pycram.bullet_world import BulletWorld\n", "from pycram.pose import Pose\n", - "from pycram.enums import ObjectType\n", + "from pycram.enums import ObjectType, WorldMode\n", "\n", - "world = BulletWorld()" + "world = BulletWorld(mode=WorldMode.GUI)" ] }, { @@ -130,8 +91,8 @@ "id": "48a3aed2", "metadata": { "ExecuteTime": { - "end_time": "2024-01-25T18:29:17.841474190Z", - "start_time": "2024-01-25T18:29:17.782682388Z" + "end_time": "2024-02-01T16:14:50.629562309Z", + "start_time": "2024-02-01T16:14:50.621645448Z" } }, "outputs": [], diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index d268d37f4..68878541f 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -13,7 +13,7 @@ from .enums import JointType, ObjectType, WorldMode from .pose import Pose from .world import World, Object, Link -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape +from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape from dataclasses import asdict @@ -65,212 +65,100 @@ def remove_object_from_simulator(self, obj: Object) -> None: p.removeBody(obj.id, self.client_id) def add_constraint(self, constraint: Constraint) -> int: - """ - Add a constraint between two objects so that attachment they become attached - """ - - parent_obj = self.get_object_by_id(constraint.parent_obj_id) - parent_link_id = parent_obj.link_name_to_id[constraint.parent_link_name] - child_obj = self.get_object_by_id(constraint.child_obj_id) - child_link_id = child_obj.link_name_to_id[constraint.child_link_name] - - constraint_id = p.createConstraint(constraint.parent_obj_id, - parent_link_id, - constraint.child_obj_id, - child_link_id, + joint_axis_in_child_link_frame = [constraint.joint_axis_in_child_link_frame.x, + constraint.joint_axis_in_child_link_frame.y, + constraint.joint_axis_in_child_link_frame.z] + + constraint_id = p.createConstraint(constraint.parent_link.get_object_id(), + constraint.parent_link.id, + constraint.child_link.get_object_id(), + constraint.child_link.id, constraint.joint_type.value, - constraint.joint_axis_in_child_link_frame, - constraint.joint_frame_position_wrt_parent_origin, - constraint.joint_frame_position_wrt_child_origin, - constraint.joint_frame_orientation_wrt_parent_origin, - constraint.joint_frame_orientation_wrt_child_origin, + joint_axis_in_child_link_frame, + constraint.joint_frame_pose_wrt_parent_origin.position_as_list(), + constraint.joint_frame_pose_wrt_child_origin.position_as_list(), + constraint.joint_frame_pose_wrt_parent_origin.orientation_as_list(), + constraint.joint_frame_pose_wrt_child_origin.orientation_as_list(), physicsClientId=self.client_id) return constraint_id def remove_constraint(self, constraint_id): - print("Removing constraint with id: ", constraint_id) p.removeConstraint(constraint_id, physicsClientId=self.client_id) - def get_joint_rest_pose(self, obj: Object, joint_name: str) -> float: - """ - Get the joint rest pose of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - """ + def get_joint_rest_position(self, obj: Object, joint_name: str) -> float: return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] def get_joint_damping(self, obj: Object, joint_name: str) -> float: - """ - Get the joint damping of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - """ return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[6] - def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint upper limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint upper limit as a float. - """ + def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[8] - def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint lower limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint lower limit as a float. - """ + def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[9] - def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param obj: The object - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ + def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[13] - def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param obj: The object - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ + def get_joint_type(self, obj: Object, joint_name: str) -> JointType: joint_type = p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[2] return JointType(joint_type) - def get_object_joint_position(self, obj: Object, joint_name: str) -> float: - """ - Get the state of a joint of an articulated object - - :param obj: The object - :param joint_name: The name of the joint - """ + def get_joint_position(self, obj: Object, joint_name: str) -> float: return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] def get_link_pose(self, link: Link) -> Pose: - """ - Get the pose of a link of an articulated object with respect to the world frame. - """ return Pose(*p.getLinkState(link.get_object_id(), link.id, physicsClientId=self.client_id)[4:6]) def perform_collision_detection(self) -> None: - """ - Performs collision detection and updates the contact points. - """ p.performCollisionDetection(physicsClientId=self.client_id) def get_object_contact_points(self, obj: Object) -> List: """ - Returns a list of contact points of this Object with other Objects. For a more detailed explanation of the + For a more detailed explanation of the returned list please look at: `PyBullet Doc `_ - - :param obj: The object. - :return: A list of all contact points with other objects """ self.perform_collision_detection() return p.getContactPoints(obj.id, physicsClientId=self.client_id) def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: - """ - Returns a list of contact points between obj1 and obj2. - - :param obj1: The first object. - :param obj2: The second object. - :return: A list of all contact points between the two objects. - """ self.perform_collision_detection() return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.client_id) def get_joint_names(self, obj: Object) -> List[str]: - """ - Get the names of all joints of an articulated object. - """ num_joints = self.get_number_of_joints(obj) return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[1].decode('utf-8') for i in range(num_joints)] def get_link_names(self, obj: Object) -> List[str]: - """ - Get the names of all joints of an articulated object. - """ num_links = self.get_number_of_links(obj) return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[12].decode('utf-8') for i in range(num_links)] def get_number_of_links(self, obj: Object) -> int: - """ - Get the number of links of an articulated object - - :param obj: The object - """ return self.get_number_of_joints(obj) def get_number_of_joints(self, obj: Object) -> int: - """ - Get the number of joints of an articulated object - - :param obj: The object - """ return p.getNumJoints(obj.id, physicsClientId=self.client_id) def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: - """ - Reset the joint position instantly without physics simulation - - :param obj: The object - :param joint_name: The name of the joint - :param joint_pose: The new joint pose - """ p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.client_id) def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): - """ - Reset the world position and orientation of the base of the object instantaneously, - not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. - - :param obj: The object - :param position: The new position of the object as a vector of x,y,z - :param orientation: The new orientation of the object as a quaternion of x,y,z,w - """ p.resetBasePositionAndOrientation(obj.id, position, orientation, physicsClientId=self.client_id) def step(self): - """ - Step the world simulation using forward dynamics - """ p.stepSimulation(physicsClientId=self.client_id) - def set_link_color(self, link: Link, rgba_color: Color): - """ - Changes the rgba_color of a link of this object, the rgba_color has to be given as a 4 element list - of RGBA values. + def update_obj_pose(self, obj: Object) -> None: + obj.set_pose(Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.client_id))) - :param link: The link which should be colored. - :param rgba_color: The rgba_color as RGBA values between 0 and 1 - """ + def set_link_color(self, link: Link, rgba_color: Color): p.changeVisualShape(link.get_object_id(), link.id, rgbaColor=rgba_color, physicsClientId=self.client_id) def get_link_color(self, link: Link) -> Color: return self.get_colors_of_object_links(link.object)[link.name] def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: - """ - Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. - - :param obj: The object - :return: A dictionary with link names as keys and 4 element list with the RGBA values for each link as value. - """ visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) link_id_to_name = {v: k for k, v in obj.link_name_to_id.items()} links = list(map(lambda x: link_id_to_name[x[1]] if x[1] != -1 else "base", visual_data)) @@ -279,56 +167,23 @@ def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: return link_to_color def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: - """ - Returns the axis aligned bounding box of this object. The return of this method are two points in - world coordinate frame which define a bounding box. - - :param obj: The object for which the bounding box should be returned. - :return: AxisAlignedBoundingBox object with min and max box points. - """ return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.client_id)) def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: - """ - Returns the axis aligned bounding box of the link. The return of this method are two points in - world coordinate frame which define a bounding box. - """ return AxisAlignedBoundingBox.from_min_max(*p.getAABB(link.get_object_id(), link.id, physicsClientId=self.client_id)) def set_realtime(self, real_time: bool) -> None: - """ - Enables the real time simulation of Physic in the BulletWorld. By default, this is disabled and Physics is only - simulated to reason about it. - - :param real_time: Whether the World should simulate Physics in real time. - """ p.setRealTimeSimulation(1 if real_time else 0, physicsClientId=self.client_id) def set_gravity(self, gravity_vector: List[float]) -> None: - """ - Sets the gravity that is used in the World. By default, it is set to the gravity on earth ([0, 0, -9.8]). - Gravity is given as a vector in x,y,z. Gravity is only applied while simulating Physic. - - :param gravity_vector: The gravity vector that should be used in the World. - """ p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) - def exit(self, wait_time_before_exit_in_secs: Optional[float] = 0.1) -> None: - """ - Closes the BulletWorld as well as the shadow world, also collects any other thread that is running. This is the - preferred method to close the BulletWorld. - """ - super().exit(wait_time_before_exit_in_secs) - def disconnect_from_physics_server(self): - """ - Disconnects the world from the physics server. - """ p.disconnect(physicsClientId=self.client_id) def join_threads(self): """ - Join any running threads. Useful for example when exiting the world. + Joins the GUI thread if it exists. """ self.join_gui_thread_if_exists() @@ -337,22 +192,12 @@ def join_gui_thread_if_exists(self): self._gui_thread.join() def save_physics_simulator_state(self) -> int: - """ - Saves the state of the physics simulator and returns the unique id of the state. - """ return p.saveState(physicsClientId=self.client_id) def restore_physics_simulator_state(self, state_id): - """ - Restores the objects and environment state in the physics simulator according to - the given state using the unique state id. - """ p.restoreState(state_id, physicsClientId=self.client_id) def remove_physics_simulator_state(self, state_id: int): - """ - Removes the physics simulator state with the given unique state id. - """ p.removeState(state_id, physicsClientId=self.client_id) def add_vis_axis(self, pose: Pose, @@ -369,15 +214,14 @@ def add_vis_axis(self, pose: Pose, position, orientation = pose_in_map.to_list() - vis_x = p.createVisualShape(p.GEOM_BOX, halfExtents=[length, 0.01, 0.01], - rgbaColor=[1, 0, 0, 0.8], visualFramePosition=[length, 0.01, 0.01], - physicsClientId=self.client_id) - vis_y = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, length, 0.01], - rgbaColor=[0, 1, 0, 0.8], visualFramePosition=[0.01, length, 0.01], - physicsClientId=self.client_id) - vis_z = p.createVisualShape(p.GEOM_BOX, halfExtents=[0.01, 0.01, length], - rgbaColor=[0, 0, 1, 0.8], visualFramePosition=[0.01, 0.01, length], - physicsClientId=self.client_id) + box_vis_shape = BoxVisualShape(Color(1, 0, 0, 0.8), [length, 0.01, 0.01], [length, 0.01, 0.01]) + vis_x = self.create_visual_shape(box_vis_shape) + + box_vis_shape = BoxVisualShape(Color(0, 1, 0, 0.8), [0.01, length, 0.01], [0.01, length, 0.01]) + vis_y = self.create_visual_shape(box_vis_shape) + + box_vis_shape = BoxVisualShape(Color(0, 0, 1, 0.8), [0.01, 0.01, length], [0.01, 0.01, length]) + vis_z = self.create_visual_shape(box_vis_shape) obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], basePosition=position, baseOrientation=orientation, @@ -411,41 +255,31 @@ def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[L physicsClientId=self.client_id) def create_visual_shape(self, visual_shape: VisualShape) -> int: - return p.createVisualShape(visual_shape.visual_geometry_type, rgbaColor=visual_shape.rgba_color, + return p.createVisualShape(visual_shape.visual_geometry_type.value, rgbaColor=visual_shape.rgba_color, visualFramePosition=visual_shape.visual_frame_position, - physicsClientId=self.client_id, **asdict(visual_shape.shape_data)) + physicsClientId=self.client_id, **visual_shape.shape_data()) def create_multi_body(self, multi_body: MultiBody) -> int: return p.createMultiBody(baseVisualShapeIndex=-MultiBody.base_visual_shape_index, linkVisualShapeIndices=MultiBody.link_visual_shape_indices, - basePosition=MultiBody.base_position, baseOrientation=MultiBody.base_orientation, - linkPositions=MultiBody.link_positions, linkMasses=MultiBody.link_masses, - linkOrientations=MultiBody.link_orientations, - linkInertialFramePositions=MultiBody.link_inertial_frame_positions, - linkInertialFrameOrientations=MultiBody.link_inertial_frame_orientations, + basePosition=MultiBody.base_pose.position_as_list(), + baseOrientation=MultiBody.base_pose.orientation_as_list(), + linkPositions=[pose.position_as_list() for pose in MultiBody.link_poses], + linkMasses=MultiBody.link_masses, + linkOrientations=[pose.orientation_as_list() for pose in MultiBody.link_poses], + linkInertialFramePositions=[pose.position_as_list() + for pose in MultiBody.link_inertial_frame_poses], + linkInertialFrameOrientations=[pose.orientation_as_list() + for pose in MultiBody.link_inertial_frame_poses], linkParentIndices=MultiBody.link_parent_indices, linkJointTypes=MultiBody.link_joint_types, - linkJointAxis=MultiBody.link_joint_axis, + linkJointAxis=[[point.x, point.y, point.z] for point in MultiBody.link_joint_axis], linkCollisionShapeIndices=MultiBody.link_collision_shape_indices) def get_images_for_target(self, target_pose: Pose, cam_pose: Pose, size: Optional[int] = 256) -> List[np.ndarray]: - """ - Calculates the view and projection Matrix and returns 3 images: - - 1. An RGB image - 2. A depth image - 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. - - From the given target_pose and cam_pose only the position is used. - - :param cam_pose: The pose of the camera - :param target_pose: The pose to which the camera should point to - :param size: The height and width of the images in pixel - :return: A list containing an RGB and depth image as well as a segmentation mask, in this order. - """ # TODO: Might depend on robot cameras, if so please add these camera parameters to RobotDescription object # TODO: of your robot with a CameraDescription object. fov = 90 @@ -459,6 +293,40 @@ def get_images_for_target(self, return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=self.client_id))[2:5] + def add_text(self, text: str, position: List[float], orientation: Optional[List[float]] = None, + size: Optional[float] = None, color: Optional[Color] = Color(), life_time: Optional[float] = 0, + parent_object_id: Optional[int] = None, parent_link_id: Optional[int] = None) -> int: + args = {} + if orientation: + args["textOrientation"] = orientation + if size: + args["textSize"] = size + if life_time: + args["lifeTime"] = life_time + if parent_object_id: + args["parentObjectUniqueId"] = parent_object_id + if parent_link_id: + args["parentLinkIndex"] = parent_link_id + return p.addUserDebugText(text, position, color.get_rgb(), physicsClientId=self.client_id, **args) + + def remove_text(self, text_id: Optional[int] = None) -> None: + if text_id: + p.removeUserDebugItem(text_id, physicsClientId=self.client_id) + else: + p.removeAllUserDebugItems(physicsClientId=self.client_id) + + def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: + p.enableJointForceTorqueSensor(obj.id, fts_joint_idx, enableSensor=1, physicsClientId=self.client_id) + + def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: + p.enableJointForceTorqueSensor(obj.id, joint_id, enableSensor=0, physicsClientId=self.client_id) + + def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: + return p.getJointState(obj.id, joint_id, physicsClientId=self.client_id)[2] + + def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: + return p.getJointState(obj.id, joint_id, physicsClientId=self.client_id)[3] + class Gui(threading.Thread): """ @@ -519,18 +387,18 @@ def run(self): # Loop to update the camera position based on keyboard events while p.isConnected(self.world.client_id): # Monitor user input - keys = p.getKeyboardEvents(physicalClientId=self.world.client_id) - mouse = p.getMouseEvents(physicalClientId=self.world.client_id) + keys = p.getKeyboardEvents() + mouse = p.getMouseEvents() # Get infos about the camera - width, height, dist = (p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[0], - p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[1], - p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[10]) - cameraTargetPosition = p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[11] + width, height, dist = (p.getDebugVisualizerCamera()[0], + p.getDebugVisualizerCamera()[1], + p.getDebugVisualizerCamera()[10]) + cameraTargetPosition = p.getDebugVisualizerCamera()[11] # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera(physicalClientId=self.world.client_id)[2][i] for i in [2, 6, 10]] + xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] + yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] # Check the mouse state @@ -670,10 +538,8 @@ def run(self): dist += dist * 0.02 * speedMult p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition, - physicsClientId=self.world.client_id) + cameraTargetPosition=cameraTargetPosition) if visible == 0: cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1], - physicsClientId=self.world.client_id) + p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) time.sleep(1. / 80.) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index aac666802..db5a83a3d 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -10,7 +10,7 @@ from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData -from pycram.world import UseProspectionWorld, Object, Link +from .world import UseProspectionWorld, Object, Link from .local_transformer import LocalTransformer from .pose import Pose, Transform from .world import World diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 61ab85e59..4503e7a4d 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -49,7 +49,7 @@ def _apply_ik(robot: WorldObject, joint_poses: List[float], joints: List[str]) - # arm ="left" if gripper == robot_description.get_tool_frame("left") else "right" # ik_joints = [robot_description.torso_joint] + robot_description._safely_access_chains(arm).joints # ik_joints = robot_description._safely_access_chains(arm).joints - robot.set_positions_of_all_joints(dict(zip(joints, joint_poses))) + robot.set_joint_positions(dict(zip(joints, joint_poses))) # for i in range(0, len(joints)): # robot.set_joint_state(joints[i], joint_poses[i]) diff --git a/src/pycram/plan_failures.py b/src/pycram/plan_failures.py index 584a13e7b..dceb68013 100644 --- a/src/pycram/plan_failures.py +++ b/src/pycram/plan_failures.py @@ -385,3 +385,13 @@ class SustainedFailure(PlanFailure): def __init__(self, *args, **kwargs): super().__init__(*args, **kwargs) + + +class ReasoningError(PlanFailure): + def __init__(*args, **kwargs): + super().__init__(*args, **kwargs) + + +class CollisionError(PlanFailure): + def __init__(*args, **kwargs): + super().__init__(*args, **kwargs) diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 08987ae90..0873883aa 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -100,7 +100,6 @@ def position(self, value) -> None: """ if (not type(value) == list and not type(value) == tuple and not type(value) == GeoPose and not type(value) == Point): - print(type(value)) rospy.logwarn("Position can only be a list or geometry_msgs/Pose") return if type(value) == list or type(value) == tuple and len(value) == 3: @@ -159,7 +158,8 @@ def to_transform(self, child_frame: str) -> Transform: :param child_frame: Child frame id to which the Transform points :return: A new Transform """ - return Transform(self.position_as_list(), self.orientation_as_list(), self.frame, child_frame, self.header.stamp) + return Transform(self.position_as_list(), self.orientation_as_list(), self.frame, child_frame, + self.header.stamp) def copy(self) -> Pose: """ @@ -167,11 +167,8 @@ def copy(self) -> Pose: :return: A copy of this pose """ - if isinstance(self.position, list): - print("Position is list") p = Pose(self.position_as_list(), self.orientation_as_list(), self.frame, self.header.stamp) p.header.frame_id = self.header.frame_id - # p.header.stamp = self.header.stamp return p def position_as_list(self) -> List[float]: diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 6f14c7a46..6e28cce94 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -188,7 +188,7 @@ def reachability_validator(pose: Pose, except IKError: pass finally: - robot.set_positions_of_all_joints(joint_state_before_ik) + robot.set_joint_positions(joint_state_before_ik) try: # resp = request_ik(base_link, end_effector, target_diff, robot, right_joints) @@ -206,6 +206,6 @@ def reachability_validator(pose: Pose, except IKError: pass finally: - robot.set_positions_of_all_joints(joint_state_before_ik) + robot.set_joint_positions(joint_state_before_ik) return res, arms diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index eafdd360c..e5930b694 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -67,13 +67,13 @@ def _execute(self, desig): pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "front")) + robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "front")) if pose_in_shoulder.position.y >= 0 and pose_in_shoulder.position.y >= abs(pose_in_shoulder.position.x): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "neck_right")) + robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "neck_right")) if pose_in_shoulder.position.x <= 0 and abs(pose_in_shoulder.position.x) > abs(pose_in_shoulder.position.y): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "back")) + robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "back")) if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("neck", "neck_left")) + robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "neck_left")) pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) @@ -93,7 +93,7 @@ def _execute(self, desig): robot = World.robot gripper = desig.gripper motion = desig.motion - robot.set_positions_of_all_joints(robot_description.get_static_gripper_chain(gripper, motion)) + robot.set_joint_positions(robot_description.get_static_gripper_chain(gripper, motion)) class BoxyManager(ProcessModuleManager): diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 936c5c57e..4b9979cd5 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -78,13 +78,13 @@ def _execute(self, desig): pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "front")) + robot.set_joint_positions(robot_description.get_static_joint_chain("left", "front")) if pose_in_shoulder.position.y >= 0 and pose_in_shoulder.position.y >= abs(pose_in_shoulder.position.x): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "arm_right")) + robot.set_joint_positions(robot_description.get_static_joint_chain("left", "arm_right")) if pose_in_shoulder.position.x <= 0 and abs(pose_in_shoulder.position.x) > abs(pose_in_shoulder.position.y): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "back")) + robot.set_joint_positions(robot_description.get_static_joint_chain("left", "back")) if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): - robot.set_positions_of_all_joints(robot_description.get_static_joint_chain("left", "arm_left")) + robot.set_joint_positions(robot_description.get_static_joint_chain("left", "arm_left")) pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) @@ -103,7 +103,7 @@ def _execute(self, desig): robot = World.robot gripper = desig.gripper motion = desig.motion - robot.set_positions_of_all_joints(robot_description.get_static_gripper_chain(gripper, motion)) + robot.set_joint_positions(robot_description.get_static_gripper_chain(gripper, motion)) class DonbotMoveTCP(ProcessModule): @@ -127,7 +127,7 @@ class DonbotMoveJoints(ProcessModule): def _execute(self, desig: MoveArmJointsMotion.Motion): robot = World.robot if desig.left_arm_poses: - robot.set_positions_of_all_joints(desig.left_arm_poses) + robot.set_joint_positions(desig.left_arm_poses) class DonbotWorldStateDetecting(ProcessModule): diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 2467f522e..f0f4d7d1b 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -7,7 +7,7 @@ from ..pose import Pose, Point from ..helper import _apply_ik from ..external_interfaces.ik import request_ik -import pycram.world_reasoning as btr +from .. import world_reasoning as btr import logging import time diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index b8db116cc..e4d02d306 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -211,9 +211,9 @@ def _execute(self, desig: MoveArmJointsMotion.Motion): robot = World.robot if desig.right_arm_poses: - robot.set_positions_of_all_joints(desig.right_arm_poses) + robot.set_joint_positions(desig.right_arm_poses) if desig.left_arm_poses: - robot.set_positions_of_all_joints(desig.left_arm_poses) + robot.set_joint_positions(desig.left_arm_poses) class PR2MoveJoints(ProcessModule): @@ -222,7 +222,7 @@ class PR2MoveJoints(ProcessModule): """ def _execute(self, desig: MoveJointsMotion.Motion): robot = World.robot - robot.set_positions_of_all_joints(dict(zip(desig.names, desig.positions))) + robot.set_joint_positions(dict(zip(desig.names, desig.positions))) class Pr2WorldStateDetecting(ProcessModule): diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 7285f3107..add24a41c 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,9 +1,9 @@ -from pycram.external_interfaces.giskard import achieve_cartesian_goal -from pycram.designators.location_designator import CostmapLocation +from ...external_interfaces.giskard import achieve_cartesian_goal +from ...designators.location_designator import CostmapLocation from ...world import UseProspectionWorld, World -from pycram.pose import Pose -from pycram.robot_descriptions import robot_description -from pycram.pose_generator_and_validator import reachability_validator +from ...pose import Pose +from ...robot_descriptions import robot_description +from ...pose_generator_and_validator import reachability_validator from typing_extensions import Tuple, Dict import tf diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index ed68a1a86..b2d07b2c6 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -50,7 +50,7 @@ def _publish(self) -> None: """ seq = 0 while not self.kill_event.is_set(): - joint_ft = self.world.get_joint_force_torque(self.world.robot, self.fts_joint_idx) + joint_ft = self.world.get_joint_reaction_force_torque(self.world.robot, self.fts_joint_idx) h = Header() h.seq = seq h.stamp = rospy.Time.now() diff --git a/src/pycram/world.py b/src/pycram/world.py index b520779b9..02032afe1 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -26,7 +26,6 @@ from .robot_descriptions import robot_description from .enums import JointType, ObjectType, WorldMode from .local_transformer import LocalTransformer -from sensor_msgs.msg import JointState from .pose import Pose, Transform @@ -222,7 +221,7 @@ def remove_object(self, obj: Object) -> None: # This means the current world of the object is not the prospection world, since it # has a reference to the prospection world if self.prospection_world is not None: - self.world_sync.remove_obj_queue.put(self) + self.world_sync.remove_obj_queue.put(obj) self.world_sync.remove_obj_queue.join() self.remove_object_from_simulator(obj) @@ -242,15 +241,12 @@ def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_par :return: The unique id of the created constraint. """ - constraint = Constraint(parent_obj_id=parent_link.get_object_id(), - parent_link_name=parent_link.name, - child_obj_id=child_link.get_object_id(), - child_link_name=child_link.name, + constraint = Constraint(parent_link=parent_link, + child_link=child_link, joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=[0, 0, 0], - joint_frame_position_wrt_parent_origin=child_to_parent_transform.translation_as_list(), - joint_frame_position_wrt_child_origin=[0, 0, 0], - joint_frame_orientation_wrt_parent_origin=child_to_parent_transform.rotation_as_list(), + joint_axis_in_child_link_frame=Point(0, 0, 0), + joint_frame_pose_wrt_parent_origin=child_to_parent_transform.to_pose(), + joint_frame_pose_wrt_child_origin=Pose() ) constraint_id = self.add_constraint(constraint) return constraint_id @@ -273,7 +269,7 @@ def remove_constraint(self, constraint_id) -> None: """ pass - def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: + def get_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ Get the joint limits of an articulated object @@ -281,10 +277,10 @@ def get_object_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, :param joint_name: The name of the joint. :return: A tuple containing the upper and the lower limits of the joint respectively. """ - return self.get_object_joint_upper_limit(obj, joint_name), self.get_object_joint_lower_limit(obj, joint_name) + return self.get_joint_upper_limit(obj, joint_name), self.get_joint_lower_limit(obj, joint_name) @abstractmethod - def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: + def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: """ Get the joint upper limit of an articulated object @@ -295,7 +291,7 @@ def get_object_joint_upper_limit(self, obj: Object, joint_name: str) -> float: pass @abstractmethod - def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: + def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: """ Get the joint lower limit of an articulated object @@ -306,7 +302,7 @@ def get_object_joint_lower_limit(self, obj: Object, joint_name: str) -> float: pass @abstractmethod - def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: + def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ Returns the axis along/around which a joint is moving. The given joint_name has to be part of this object. @@ -317,7 +313,7 @@ def get_object_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: pass @abstractmethod - def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: + def get_joint_type(self, obj: Object, joint_name: str) -> JointType: """ Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. @@ -328,7 +324,7 @@ def get_object_joint_type(self, obj: Object, joint_name: str) -> JointType: pass @abstractmethod - def get_object_joint_position(self, obj: Object, joint_name: str) -> float: + def get_joint_position(self, obj: Object, joint_name: str) -> float: """ Get the position of a joint of an articulated object @@ -369,6 +365,22 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: if real_time: loop_time = rospy.Time.now() - curr_time time.sleep(max(0, self.simulation_time_step - loop_time.to_sec())) + self.update_all_objects_poses() + + def update_all_objects_poses(self) -> None: + """ + Updates the positions of all objects in the world. + """ + for obj in self.objects: + self.update_obj_pose(obj) + + @abstractmethod + def update_obj_pose(self, obj: Object) -> None: + """ + Updates the position of the given object in the world, by retrieving the position from the physics simulator. + :param obj: The object for which the position should be updated. + """ + pass @abstractmethod def perform_collision_detection(self) -> None: @@ -398,7 +410,7 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> """ pass - def get_joint_rest_pose(self, obj: Object, joint_name: str) -> float: + def get_joint_rest_position(self, obj: Object, joint_name: str) -> float: """ Get the rest pose of a joint of an articulated object @@ -638,13 +650,10 @@ def robot_is_set() -> bool: """ return World.robot is not None - def exit(self, wait_time_before_exit_in_secs: Optional[float] = None) -> None: + def exit(self) -> None: """ Closes the World as well as the prospection world, also collects any other thread that is running. - :param wait_time_before_exit_in_secs: The time to wait before exiting the world in seconds. """ - if wait_time_before_exit_in_secs is not None: - time.sleep(wait_time_before_exit_in_secs) self.exit_prospection_world_if_exists() self.disconnect_from_physics_server() self.reset_current_world() @@ -909,23 +918,20 @@ def create_multi_body_from_visual_shapes(self, visual_shape_ids: List[int], pose :param pose: The pose of the origin of the multi body relative to the world frame. :return: The unique id of the created multi body. """ - # Dummy paramater since these are needed to spawn visual shapes as a + # Dummy parameter since these are needed to spawn visual shapes as a # multibody. num_of_shapes = len(visual_shape_ids) - link_poses = [[0, 0, 0] for _ in range(num_of_shapes)] - link_orientations = [[0, 0, 0, 1] for _ in range(num_of_shapes)] + link_poses = [Pose() for _ in range(num_of_shapes)] link_masses = [1.0 for _ in range(num_of_shapes)] link_parent = [0 for _ in range(num_of_shapes)] link_joints = [JointType.FIXED for _ in range(num_of_shapes)] link_collision = [-1 for _ in range(num_of_shapes)] - link_joint_axis = [[1, 0, 0] for _ in range(num_of_shapes)] - - multi_body = MultiBody(base_visual_shape_index=-1, base_position=pose.position_as_list(), - base_orientation=pose.orientation_as_list(), - link_visual_shape_indices=visual_shape_ids, link_positions=link_poses, - link_orientations=link_orientations, link_masses=link_masses, - link_inertial_frame_positions=link_poses, - link_inertial_frame_orientations=link_orientations, + link_joint_axis = [Point(1, 0, 0) for _ in range(num_of_shapes)] + + multi_body = MultiBody(base_visual_shape_index=-1, base_pose=pose, + link_visual_shape_indices=visual_shape_ids, link_poses=link_poses, + link_masses=link_masses, + link_inertial_frame_poses=link_poses, link_parent_indices=link_parent, link_joint_types=link_joints, link_joint_axis=link_joint_axis, link_collision_shape_indices=link_collision) @@ -996,7 +1002,7 @@ def create_mesh_visual_shape(self, shape_data: MeshVisualShape) -> int: def add_text(self, text: str, position: List[float], orientation: Optional[List[float]] = None, size: float = 0.1, color: Optional[Color] = Color(), life_time: Optional[float] = 0, - parent_object_id: Optional[int] = None) -> None: + parent_object_id: Optional[int] = None, parent_link_id: Optional[int] = None) -> int: """ Adds text to the world. :param text: The text to be added. @@ -1009,6 +1015,8 @@ def add_text(self, text: str, position: List[float], orientation: Optional[List[ :param life_time: The lifetime in seconds of the text to remain in the world, if 0 the text will remain in the world until it is removed manually. :param parent_object_id: The id of the object to which the text should be attached. + :param parent_link_id: The id of the link to which the text should be attached. + :return: The id of the added text. """ raise NotImplementedError @@ -1022,10 +1030,10 @@ def remove_text(self, text_id: Optional[int] = None) -> None: def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: """ You can enable a joint force/torque sensor in each joint. Once enabled, if you perform - a simulation step, the get_joint_force_torque will report the joint reaction forces in the fixed degrees of - freedom: a fixed joint will measure all 6DOF joint forces/torques. A revolute/hinge joint - force/torque sensor will measure 5DOF reaction forces along all axis except the hinge axis. The - applied force by a joint motor is available through get_applied_joint_motor_torque. + a simulation step, the get_joint_reaction_force_torque will report the joint reaction forces in + the fixed degrees of freedom: a fixed joint will measure all 6DOF joint forces/torques. + A revolute/hinge joint force/torque sensor will measure 5DOF reaction forces along all axis except + the hinge axis. The applied force by a joint motor is available through get_applied_joint_motor_torque. :param obj: The object in which the joint is located. :param fts_joint_idx: The index of the joint for which the force torque sensor should be enabled. """ @@ -1039,7 +1047,7 @@ def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: """ raise NotImplementedError - def get_joint_force_torque(self, obj: Object, joint_id: int) -> List[float]: + def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: """ Returns the joint reaction forces and torques of the specified joint. :param obj: The object in which the joint is located. @@ -1119,7 +1127,7 @@ def __init__(self, world: World, prospection_world: World): self.object_mapping: Dict[Object, Object] = {} self.equal_states = False - def run(self): + def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): """ Main method of the synchronization, this thread runs in a loop until the terminate flag is set. @@ -1127,6 +1135,8 @@ def run(self): every object in the World and updates the corresponding object in the prospection world. When there are entries in the adding or removing queue the corresponding objects will be added or removed in the same iteration. + :param wait_time_as_n_simulation_steps: The time in simulation steps to wait between each iteration of the + syncing loop. """ while not self.terminate: self.check_for_pause() @@ -1156,12 +1166,12 @@ def run(self): if len(world_obj.joint_name_to_id) > 2: for joint_name in world_obj.joint_name_to_id.keys(): if prospection_obj.get_joint_position(joint_name) != world_obj.get_joint_position(joint_name): - prospection_obj.set_positions_of_all_joints(world_obj.get_positions_of_all_joints()) + prospection_obj.set_joint_positions(world_obj.get_positions_of_all_joints()) break self.check_for_pause() # self.check_for_equal() - time.sleep(1 / 240) + time.sleep(wait_time_as_n_simulation_steps * self.world.simulation_time_step) self.add_obj_queue.join() self.remove_obj_queue.join() @@ -1498,7 +1508,7 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, # takes the state id as key and returns the attachments of the object at that state if not self.world.is_prospection_world: - self._add_to_world_sync_obj_queue(path) + self._add_to_world_sync_obj_queue(self.path) self._init_current_positions_of_joint() @@ -1664,7 +1674,7 @@ def _init_current_positions_of_joint(self) -> None: """ self._current_joints_positions = {} for joint_name in self.joint_name_to_id.keys(): - self._current_joints_positions[joint_name] = self.world.get_object_joint_position(self, joint_name) + self._current_joints_positions[joint_name] = self.world.get_joint_position(self, joint_name) @property def base_origin_shift(self) -> np.ndarray: @@ -2008,9 +2018,9 @@ def reset_all_joints_positions(self) -> None: """ joint_names = list(self.joint_name_to_id.keys()) joint_positions = [0] * len(joint_names) - self.set_positions_of_all_joints(dict(zip(joint_names, joint_positions))) + self.set_joint_positions(dict(zip(joint_names, joint_positions))) - def set_positions_of_all_joints(self, joint_poses: dict) -> None: + def set_joint_positions(self, joint_poses: dict) -> None: """ Sets the current position of multiple joints at once, this method should be preferred when setting multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. @@ -2031,7 +2041,7 @@ def set_joint_position(self, joint_name: str, joint_position: float) -> None: :param joint_position: The target pose for this joint """ # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - up_lim, low_lim = self.world.get_object_joint_limits(self, joint_name) + up_lim, low_lim = self.world.get_joint_limits(self, joint_name) if low_lim > up_lim: low_lim, up_lim = up_lim, low_lim if not low_lim <= joint_position <= up_lim: @@ -2054,89 +2064,23 @@ def get_joint_position(self, joint_name: str) -> float: """ return self._current_joints_positions[joint_name] - def contact_points(self) -> List: - """ - Returns a list of contact points of this Object with other Objects. - - :return: A list of all contact points with other objects - """ - return self.world.get_object_contact_points(self) - - def contact_points_simulated(self) -> List: - """ - Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - - :return: A list of contact points between this Object and other Objects - """ - state_id = self.world.save_state() - self.world.step() - contact_points = self.contact_points() - self.world.restore_state(state_id) - return contact_points - - def update_joints_from_topic(self, topic_name: str) -> None: - """ - Updates the joints of this object with positions obtained from a topic with the message type JointState. - Joint names on the topic have to correspond to the joints of this object otherwise an error message will be - logged. - - :param topic_name: Name of the topic with the joint states - """ - msg = rospy.wait_for_message(topic_name, JointState) - joint_names = msg.name - joint_positions = msg.position - if set(joint_names).issubset(self.joint_name_to_id.keys()): - for i in range(len(joint_names)): - self.set_joint_position(joint_names[i], joint_positions[i]) - else: - add_joints = set(joint_names) - set(self.joint_name_to_id.keys()) - rospy.logerr(f"There are joints in the published joint state which are not in this model: /n \ - The following joint{'s' if len(add_joints) != 1 else ''}: {add_joints}") - - def update_pose_from_tf(self, frame: str) -> None: - """ - Updates the pose of this object from a TF message. + def get_joint_rest_position(self, joint_name: str) -> float: + return self.world.get_joint_rest_position(self, joint_name) - :param frame: Name of the TF frame from which the position should be taken - """ - tf_listener = tf.TransformListener() - time.sleep(0.5) - position, orientation = tf_listener.lookupTransform(frame, "map", rospy.Time(0)) - position = [position[0][0] * -1, - position[0][1] * -1, - position[0][2]] - self.set_position(Pose(position, orientation)) + def get_joint_damping(self, joint_name: str) -> float: + return self.world.get_joint_damping(self, joint_name) - def set_color(self, color: Color) -> None: - """ - Changes the rgba_color of this object, the rgba_color has to be given as a list - of RGBA values. All links of this object will be colored. - - :param color: The rgba_color as RGBA values between 0 and 1 - """ - self.world.set_object_color(self, color) + def get_joint_upper_limit(self, joint_name: str) -> float: + return self.world.get_joint_upper_limit(self, joint_name) - def get_color(self) -> Union[Color, Dict[str, Color]]: - """ - :return: The rgba_color of this object or a dictionary of link names and their colors. - """ - return self.world.get_object_color(self) + def get_joint_lower_limit(self, joint_name: str) -> float: + return self.world.get_joint_lower_limit(self, joint_name) - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: - """ - :return: The axis aligned bounding box of this object. - """ - return self.world.get_object_axis_aligned_bounding_box(self) + def get_joint_axis(self, joint_name: str) -> Tuple[float]: + return self.world.get_joint_axis(self, joint_name) - def get_base_origin(self) -> Pose: - """ - :return: the origin of the base/bottom of this object. - """ - aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() - base_width = np.absolute(aabb.min_x - aabb.max_x) - base_length = np.absolute(aabb.min_y - aabb.max_y) - return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], - self.get_pose().orientation_as_list()) + def get_joint_type(self, joint_name: str) -> JointType: + return self.world.get_joint_type(self, joint_name) def get_joint_limits(self, joint: str) -> Tuple[float, float]: """ @@ -2148,29 +2092,11 @@ def get_joint_limits(self, joint: str) -> Tuple[float, float]: """ if joint not in self.joint_name_to_id.keys(): raise KeyError(f"The given Joint: {joint} is not part of this object") - lower, upper = self.world.get_object_joint_limits(self, joint) + lower, upper = self.world.get_joint_limits(self, joint) if lower > upper: lower, upper = upper, lower return lower, upper - def get_joint_axis(self, joint_name: str) -> Tuple[float]: - """ - Returns the axis along which a joint is moving. The given joint_name has to be part of this object. - - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis a vector of xyz - """ - return self.world.get_object_joint_axis(self, joint_name) - - def get_joint_type(self, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param joint_name: Joint name for which the type should be returned - :return: The type of the joint - """ - return self.world.get_object_joint_type(self, joint_name) - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: """ Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. @@ -2205,6 +2131,57 @@ def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> for link in self.links.values(): link.update_transform(transform_time) + def contact_points(self) -> List: + """ + Returns a list of contact points of this Object with other Objects. + + :return: A list of all contact points with other objects + """ + return self.world.get_object_contact_points(self) + + def contact_points_simulated(self) -> List: + """ + Returns a list of all contact points between this Object and other Objects after stepping the simulation once. + + :return: A list of contact points between this Object and other Objects + """ + state_id = self.world.save_state() + self.world.step() + contact_points = self.contact_points() + self.world.restore_state(state_id) + return contact_points + + def set_color(self, color: Color) -> None: + """ + Changes the rgba_color of this object, the rgba_color has to be given as a list + of RGBA values. All links of this object will be colored. + + :param color: The rgba_color as RGBA values between 0 and 1 + """ + self.world.set_object_color(self, color) + + def get_color(self) -> Union[Color, Dict[str, Color]]: + """ + :return: The rgba_color of this object or a dictionary of link names and their colors. + """ + return self.world.get_object_color(self) + + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis aligned bounding box of this object. + """ + return self.world.get_object_axis_aligned_bounding_box(self) + + def get_base_origin(self) -> Pose: + """ + :return: the origin of the base/bottom of this object. + """ + aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() + base_width = np.absolute(aabb.min_x - aabb.max_x) + base_length = np.absolute(aabb.min_y - aabb.max_y) + return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], + self.get_pose().orientation_as_list()) + def filter_contact_points(contact_points, exclude_ids) -> List: """ @@ -2231,22 +2208,6 @@ def get_path_from_data_dir(file_name: str, data_directory: str) -> str: return data_directory + f"/{file_name}" -def _get_robot_name_from_urdf(urdf_string: str) -> str: - """ - Extracts the robot name from the 'robot_name' tag of a URDF. - - :param urdf_string: The URDF as string. - :return: The name of the robot described by the URDF. - """ - res = re.findall(r"robot\ *name\ *=\ *\"\ *[a-zA-Z_0-9]*\ *\"", urdf_string) - if len(res) == 1: - begin = res[0].find("\"") - end = res[0][begin + 1:].find("\"") - robot = res[0][begin + 1:begin + 1 + end].lower() - return robot - raise Exception("Robot Name not Found") - - class Attachment: def __init__(self, parent_link: Link, @@ -2266,7 +2227,7 @@ def __init__(self, self.parent_link: Link = parent_link self.child_link: Link = child_link self.bidirectional: bool = bidirectional - self._loose: bool = False and not bidirectional + self._loose: bool = False self.parent_to_child_transform: Transform = parent_to_child_transform if self.parent_to_child_transform is None: @@ -2322,7 +2283,7 @@ def get_inverse(self) -> Attachment: """ attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, constraint_id=self.constraint_id) - attachment.loose = False if self.loose else True + attachment.loose = not self._loose return attachment @property @@ -2457,15 +2418,3 @@ def _is_cached(path) -> bool: if full_path.exists(): return True return False - - -def _world_and_id(world: World) -> Tuple[World, int]: - """ - Selects the world to be used. If the given world is None the 'current_world' is used. - - :param world: The world which should be used or None if 'current_world' should be used - :return: The World object and the id of this World - """ - world = world if world is not None else World.current_world - client_id = world.client_id if world is not None else World.current_world.client_id - return world, client_id diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 40d4d8db2..1c0ee3ea0 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,6 +1,8 @@ from dataclasses import dataclass -from typing_extensions import List, Optional, Tuple, Callable, Dict +from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union from .enums import JointType, Shape +from .pose import Pose, Point +from abc import ABC, abstractmethod @dataclass @@ -55,38 +57,26 @@ def get_rgba(self) -> List[float]: """ return [self.R, self.G, self.B, self.A] + def get_rgb(self) -> List[float]: + """ + Returns the rgba_color as a list of RGB values. + + :return: The rgba_color as a list of RGB values + """ + return [self.R, self.G, self.B] + @dataclass class Constraint: """ Dataclass for storing a constraint between two objects. """ - parent_obj_id: int - parent_link_name: str - child_obj_id: int - child_link_name: str + parent_link: 'Link' + child_link: 'Link' joint_type: JointType - joint_axis_in_child_link_frame: List[int] - joint_frame_position_wrt_parent_origin: List[float] - joint_frame_position_wrt_child_origin: List[float] - joint_frame_orientation_wrt_parent_origin: Optional[List[float]] = None - joint_frame_orientation_wrt_child_origin: Optional[List[float]] = None - - -@dataclass -class Point: - x: float - y: float - z: float - - @classmethod - def from_list(cls, point: List[float]): - """ - Sets the point from a list of x, y, z values. - - :param point: The list of x, y, z values - """ - return cls(point[0], point[1], point[2]) + joint_axis_in_child_link_frame: Point + joint_frame_pose_wrt_parent_origin: Pose + joint_frame_pose_wrt_child_origin: Pose @dataclass @@ -169,61 +159,106 @@ class CollisionCallbacks: @dataclass class MultiBody: base_visual_shape_index: int - base_position: List[float] - base_orientation: List[float] + base_pose: Pose link_visual_shape_indices: List[int] - link_positions: List[List[float]] - link_orientations: List[List[float]] + link_poses: List[Pose] link_masses: List[float] - link_inertial_frame_positions: List[List[float]] - link_inertial_frame_orientations: List[List[float]] + link_inertial_frame_poses: List[Pose] link_parent_indices: List[int] link_joint_types: List[JointType] - link_joint_axis: List[List[float]] + link_joint_axis: List[Point] link_collision_shape_indices: List[int] @dataclass -class VisualShape: +class VisualShape(ABC): rgba_color: Color visual_frame_position: List[float] + @abstractmethod + def shape_data(self) -> Dict[str, Any]: + """ + Returns the shape data of the visual shape (e.g. half extents for a box, radius for a sphere). + """ + pass + + @property + @abstractmethod + def visual_geometry_type(self) -> Shape: + """ + Returns the visual geometry type of the visual shape (e.g. box, sphere). + """ + pass + @dataclass class BoxVisualShape(VisualShape): half_extents: List[float] - visual_geometry_type: Optional[Shape] = Shape.BOX + + def shape_data(self) -> Dict[str, List[float]]: + return {"halfExtents": self.half_extents} + + @property + def visual_geometry_type(self) -> Shape: + return Shape.BOX @dataclass class SphereVisualShape(VisualShape): radius: float - visual_geometry_type: Optional[Shape] = Shape.SPHERE + + def shape_data(self) -> Dict[str, float]: + return {"radius": self.radius} + + @property + def visual_geometry_type(self) -> Shape: + return Shape.SPHERE @dataclass class CapsuleVisualShape(VisualShape): radius: float length: float - visual_geometry_type: Optional[Shape] = Shape.CAPSULE + + def shape_data(self) -> Dict[str, float]: + return {"radius": self.radius, "length": self.length} + + @property + def visual_geometry_type(self) -> Shape: + return Shape.CAPSULE @dataclass class CylinderVisualShape(CapsuleVisualShape): - visual_geometry_type: Optional[Shape] = Shape.CYLINDER + + @property + def visual_geometry_type(self) -> Shape: + return Shape.CYLINDER @dataclass class MeshVisualShape(VisualShape): mesh_scale: List[float] mesh_file_name: str - visual_geometry_type: Optional[Shape] = Shape.MESH + + def shape_data(self) -> Dict[str, Union[List[float], str]]: + return {"meshScale": self.mesh_scale, "meshFileName": self.mesh_file_name} + + @property + def visual_geometry_type(self) -> Shape: + return Shape.MESH @dataclass class PlaneVisualShape(VisualShape): normal: List[float] - visual_geometry_type: Optional[Shape] = Shape.PLANE + + def shape_data(self) -> Dict[str, List[float]]: + return {"normal": self.normal} + + @property + def visual_geometry_type(self) -> Shape: + return Shape.PLANE @dataclass diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 01d9709a8..80cfa0ae9 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -10,16 +10,6 @@ from .world import World -class ReasoningError(Exception): - def __init__(*args, **kwargs): - Exception.__init__(*args, **kwargs) - - -class CollisionError(Exception): - def __init__(*args, **kwargs): - Exception.__init__(*args, **kwargs) - - def stable(obj: Object) -> bool: """ Checks if an object is stable in the world. Stable meaning that it's position will not change after simulating diff --git a/test/test_attachment.py b/test/test_attachment.py index d99cb05fc..dc1ba8869 100644 --- a/test/test_attachment.py +++ b/test/test_attachment.py @@ -1,7 +1,7 @@ -import test_bullet_world +from bullet_world_testcase import BulletWorldTestCase -class TestAttachment(test_bullet_world.BulletWorldTest): +class TestAttachment(BulletWorldTestCase): def test_attach(self): self.milk.attach(self.robot) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 91639d8ca..2387a234b 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -1,11 +1,13 @@ +import time import unittest import rospkg from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose -from pycram.world import fix_missing_inertial +from pycram.world import fix_missing_inertial, Object, ObjectType import xml.etree.ElementTree as ET +from pycram.enums import JointType class BulletWorldTest(BulletWorldTestCase): @@ -34,6 +36,47 @@ def test_save_and_restore_state(self): self.assertTrue(self.milk in self.robot.attachments) self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) + def test_remove_object(self): + time.sleep(2) + milk_id = self.milk.id + self.assertTrue(milk_id in [obj.id for obj in self.world.objects]) + self.world.remove_object(self.milk) + self.assertTrue(milk_id not in [obj.id for obj in self.world.objects]) + BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + + def test_get_joint_rest_pose(self): + self.assertEqual(self.robot.get_joint_rest_position("head_pan_joint"), 0.0) + + def test_get_joint_damping(self): + self.assertEqual(self.robot.get_joint_damping("head_pan_joint"), 0.5) + + def test_get_joint_upper_limit(self): + self.assertEqual(self.robot.get_joint_upper_limit("head_pan_joint"), -3.007) + + def test_get_joint_lower_limit(self): + self.assertEqual(self.robot.get_joint_lower_limit("head_pan_joint"), 3.007) + + def test_get_joint_axis(self): + self.assertEqual(self.robot.get_joint_axis("head_pan_joint"), (0.0, 0.0, 1.0)) + + def test_get_joint_type(self): + self.assertEqual(self.robot.get_joint_type("head_pan_joint"), JointType.REVOLUTE) + + def test_get_joint_position(self): + self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) + + def test_get_object_contact_points(self): + self.assertEqual(len(self.robot.contact_points()), 0) + self.milk.set_position(self.robot.get_position()) + self.assertTrue(len(self.robot.contact_points()) > 0) + + def test_step_simulation(self): + # TODO: kitchen explodes when stepping simulation, fix this + self.world.remove_object(self.kitchen) + self.milk.set_position(Pose([0, 0, 2])) + self.world.simulate(1) + self.assertTrue(self.milk.get_position().z < 2) + class XMLTester(unittest.TestCase): diff --git a/test/test_language.py b/test/test_language.py index 7470ed751..e4739802a 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -7,10 +7,10 @@ from pycram.pose import Pose from pycram.language import Sequential, Language, Parallel, TryAll, TryInOrder, Monitor, Repeat, Code, RenderTree from pycram.process_module import simulated_robot -import test_bullet_world +from bullet_world_testcase import BulletWorldTestCase -class LanguageTestCase(test_bullet_world.BulletWorldTest): +class LanguageTestCase(BulletWorldTestCase): def test_inheritance(self): act = NavigateAction([Pose()]) diff --git a/test/test_links.py b/test/test_links.py index 0115c8c48..a2f7f1c4f 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -1,7 +1,7 @@ -import test_bullet_world +from bullet_world_testcase import BulletWorldTestCase -class TestLinks(test_bullet_world.BulletWorldTest): +class TestLinks(BulletWorldTestCase): def test_add_constraint(self): milk_link = self.milk.get_root_link() diff --git a/test/test_object.py b/test/test_object.py index ece06cc46..409b1db9e 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -1,9 +1,9 @@ -import test_bullet_world +from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose from geometry_msgs.msg import Point -class TestObject(test_bullet_world.BulletWorldTest): +class TestObject(BulletWorldTestCase): def test_set_position_as_point(self): self.milk.set_position(Point(1, 2, 3)) From 99c675f7108b022946e162903a95faafda6519bd Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sat, 3 Feb 2024 08:59:16 +0100 Subject: [PATCH 071/195] [AbstractWorld] Added joint class to handle joint related things. Object, Link, and Joint all have cached poses. Cached poses update when World.simulate() is called. Or when the poses are set manually. --- src/pycram/bullet_world.py | 9 +- src/pycram/enums.py | 4 +- src/pycram/pose_generator_and_validator.py | 2 +- src/pycram/world.py | 443 +++++++++++++++------ src/pycram/world_dataclasses.py | 11 +- test/test_bullet_world.py | 7 +- 6 files changed, 346 insertions(+), 130 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 68878541f..0f58af09f 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -143,14 +143,15 @@ def get_number_of_joints(self, obj: Object) -> int: def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.client_id) - def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): - p.resetBasePositionAndOrientation(obj.id, position, orientation, physicsClientId=self.client_id) + def reset_object_base_pose(self, obj: Object, pose: Pose) -> None: + p.resetBasePositionAndOrientation(obj.id, pose.position_as_list(), pose.orientation_as_list(), + physicsClientId=self.client_id) def step(self): p.stepSimulation(physicsClientId=self.client_id) - def update_obj_pose(self, obj: Object) -> None: - obj.set_pose(Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.client_id))) + def get_object_pose(self, obj: Object) -> Pose: + return Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.client_id)) def set_link_color(self, link: Link, rgba_color: Color): p.changeVisualShape(link.get_object_id(), link.id, rgbaColor=rgba_color, physicsClientId=self.client_id) diff --git a/src/pycram/enums.py b/src/pycram/enums.py index 3b7280ad6..b1c1cc011 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -19,7 +19,6 @@ class TaskStatus(Enum): SUCCEEDED = 2 FAILED = 3 - class JointType(Enum): """ Enum for readable joint types. @@ -29,6 +28,9 @@ class JointType(Enum): SPHERICAL = 2 PLANAR = 3 FIXED = 4 + UNKNOWN = 5 + CONTINUOUS = 6 + FLOATING = 7 class Grasp(Enum): diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 6e28cce94..dfcc50176 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -171,7 +171,7 @@ def reachability_validator(pose: Pose, if robot in allowed_collision.keys(): allowed_robot_links = allowed_collision[robot] - joint_state_before_ik = robot._current_joints_positions + joint_state_before_ik = robot.get_positions_of_all_joints() try: # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) resp = request_ik(target, robot, left_joints, left_gripper) diff --git a/src/pycram/world.py b/src/pycram/world.py index 02032afe1..736c6a3eb 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -8,31 +8,28 @@ import threading import time import xml.etree.ElementTree +from abc import ABC, abstractmethod from queue import Queue -import tf -from tf.transformations import quaternion_from_euler -from typing_extensions import List, Optional, Dict, Tuple, Callable -from typing_extensions import Union import numpy as np import rospkg import rospy - import urdf_parser_py.urdf from geometry_msgs.msg import Quaternion, Point +from tf.transformations import quaternion_from_euler +from typing_extensions import List, Optional, Dict, Tuple, Callable +from typing_extensions import Union from urdf_parser_py.urdf import URDF, Collision, GeometricType -from .event import Event -from .robot_descriptions import robot_description from .enums import JointType, ObjectType, WorldMode +from .event import Event from .local_transformer import LocalTransformer - from .pose import Pose, Transform - -from abc import ABC, abstractmethod +from .robot_descriptions import robot_description from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks, MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, - CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, LinkState, ObjectState) + CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, + LinkState, ObjectState, JointState) class World(ABC): @@ -156,7 +153,7 @@ def simulation_time_step(self): """ The time step of the simulation in seconds. """ - return 1/World.simulation_frequency + return 1 / World.simulation_frequency @abstractmethod def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: @@ -279,7 +276,6 @@ def get_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: """ return self.get_joint_upper_limit(obj, joint_name), self.get_joint_lower_limit(obj, joint_name) - @abstractmethod def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: """ Get the joint upper limit of an articulated object @@ -288,9 +284,8 @@ def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: :param joint_name: The name of the joint. :return: The joint upper limit as a float. """ - pass + raise NotImplementedError - @abstractmethod def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: """ Get the joint lower limit of an articulated object @@ -299,9 +294,8 @@ def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: :param joint_name: The name of the joint. :return: The joint lower limit as a float. """ - pass + raise NotImplementedError - @abstractmethod def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: """ Returns the axis along/around which a joint is moving. The given joint_name has to be part of this object. @@ -310,9 +304,8 @@ def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: :param joint_name: Name of the joint for which the axis should be returned. :return: The axis which is a 3D vector of xyz values. """ - pass + raise NotImplementedError - @abstractmethod def get_joint_type(self, obj: Object, joint_name: str) -> JointType: """ Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. @@ -321,7 +314,7 @@ def get_joint_type(self, obj: Object, joint_name: str) -> JointType: :param joint_name: Joint name for which the type should be returned. :return: The type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. """ - pass + raise NotImplementedError @abstractmethod def get_joint_position(self, obj: Object, joint_name: str) -> float: @@ -372,13 +365,12 @@ def update_all_objects_poses(self) -> None: Updates the positions of all objects in the world. """ for obj in self.objects: - self.update_obj_pose(obj) + obj.update_pose() @abstractmethod - def update_obj_pose(self, obj: Object) -> None: + def get_object_pose(self, obj: Object) -> Pose: """ - Updates the position of the given object in the world, by retrieving the position from the physics simulator. - :param obj: The object for which the position should be updated. + Get the pose of an object in the world frame from the current object pose in the simulator. """ pass @@ -430,23 +422,21 @@ def get_joint_damping(self, obj: Object, joint_name: str) -> float: """ pass - @abstractmethod def get_joint_names(self, obj: Object) -> List[str]: """ Get the names of all joints of an articulated object. :param obj: The object. :return: A list of all joint names of the object. """ - pass + raise NotImplementedError - @abstractmethod def get_link_names(self, obj: Object) -> List[str]: """ Get the names of all links of an articulated object. :param obj: The object. :return: A list of all link names of the object. """ - pass + raise NotImplementedError def get_number_of_joints(self, obj: Object) -> int: """ @@ -454,7 +444,7 @@ def get_number_of_joints(self, obj: Object) -> int: :param obj: The object. :return: The number of joints of the object. """ - pass + raise NotImplementedError def get_number_of_links(self, obj: Object) -> int: """ @@ -462,7 +452,7 @@ def get_number_of_links(self, obj: Object) -> int: :param obj: The object. :return: The number of links of the object. """ - pass + raise NotImplementedError @abstractmethod def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: @@ -476,14 +466,13 @@ def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) pass @abstractmethod - def reset_object_base_pose(self, obj: Object, position: List[float], orientation: List[float]): + def reset_object_base_pose(self, obj: Object, pose: Pose): """ Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. - :param obj: The object - :param position: The new position of the object as a vector of x,y,z - :param orientation: The new orientation of the object as a quaternion of x,y,z,w + :param obj: The object. + :param pose: The new pose as a Pose object. """ pass @@ -1194,10 +1183,192 @@ def check_for_equal(self) -> None: self.equal_states = eql +class Joint: + """ + Represents a joint of an Object in the World. + """ + urdf_joint_types_mapping = {'unknown': JointType.UNKNOWN, + 'revolute': JointType.REVOLUTE, + 'continuous': JointType.CONTINUOUS, + 'prismatic': JointType.PRISMATIC, + 'floating': JointType.FLOATING, + 'planar': JointType.PLANAR, + 'fixed': JointType.FIXED} + + def __init__(self, _id: int, + urdf_joint: urdf_parser_py.urdf.Joint, + obj: Object): + self.id: int = _id + self.urdf_joint: urdf_parser_py.urdf.Joint = urdf_joint + self.object: Object = obj + self.world: World = obj.world + self.saved_states: Dict[int, JointState] = {} + self._update_position() + + def _update_position(self) -> None: + """ + Updates the current position of the joint from the physics simulator. + """ + self._current_position = self.world.get_joint_position(self.object, self.name) + + @property + def parent_link(self) -> Link: + """ + Returns the parent link of this joint. + :return: The parent link as a Link object. + """ + return self.object.links[self.urdf_joint.parent.name] + + @property + def child_link(self) -> Link: + """ + Returns the child link of this joint. + :return: The child link as a Link object. + """ + return self.object.links[self.urdf_joint.child.name] + + @property + def has_limits(self) -> bool: + """ + Checks if this joint has limits. + :return: True if the joint has limits, False otherwise. + """ + return bool(self.urdf_joint.limit) + + @property + def limits(self) -> Tuple[float, float]: + """ + Returns the lower and upper limit of a joint, if the lower limit is higher + than the upper they are swapped to ensure the lower limit is always the smaller one. + :return: A tuple with the lower and upper joint limits. + """ + lower, upper = self.lower_limit, self.upper_limit + if lower > upper: + lower, upper = upper, lower + return lower, upper + + @property + def upper_limit(self) -> float: + """ + Returns the upper joint limit of this joint. + :return: The upper joint limit as a float. + """ + return self.urdf_joint.limit.upper + + @property + def lower_limit(self) -> float: + """ + Returns the lower joint limit of this joint. + :return: The lower joint limit as a float. + """ + return self.urdf_joint.limit.lower + + @property + def axis(self) -> Point: + """ + Returns the joint axis of this joint. + :return: The joint axis as a Point object. + """ + return Point(*self.urdf_joint.axis) + + @property + def type(self) -> JointType: + """ + Returns the joint type of this joint. + :return: The joint type as a JointType object. + """ + return self.urdf_joint_types_mapping[self.urdf_joint.type] + + @property + def position(self) -> float: + return self._current_position + + @property + def rest_position(self) -> float: + return self.world.get_joint_rest_position(self.object, self.name) + + @property + def damping(self) -> float: + """ + Returns the damping of this joint. + :return: The damping as a float. + """ + return self.urdf_joint.dynamics.damping + + @property + def name(self) -> str: + """ + Returns the name of this joint. + :return: The name of this joint as a string. + """ + return self.urdf_joint.name + + def reset_position(self, position: float) -> None: + self.world.reset_joint_position(self.object, self.name, position) + self._update_position() + + def get_object_id(self) -> int: + """ + Returns the id of the object to which this joint belongs. + :return: The integer id of the object to which this joint belongs. + """ + return self.object.id + + @position.setter + def position(self, joint_position: float) -> None: + """ + Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated + in the URDF, an error will be printed. However, the joint will be set either way. + + :param joint_position: The target pose for this joint + """ + # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly + if self.has_limits: + low_lim, up_lim = self.limits + if not low_lim <= joint_position <= up_lim: + logging.error( + f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" + f" are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_position}") + # Temporarily disabled because kdl outputs values exciting joint limits + # return + self.reset_position(joint_position) + + def enable_force_torque_sensor(self) -> None: + self.world.enable_joint_force_torque_sensor(self.object, self.id) + + def disable_force_torque_sensor(self) -> None: + self.world.disable_joint_force_torque_sensor(self.object, self.id) + + def get_reaction_force_torque(self) -> List[float]: + return self.world.get_joint_reaction_force_torque(self.object, self.id) + + def get_applied_motor_torque(self) -> float: + return self.world.get_applied_joint_motor_torque(self.object, self.id) + + def save_state(self, state_id: int) -> None: + self.saved_states[state_id] = self.state + + def restore_state(self, state_id: int) -> None: + self.state = self.saved_states[state_id] + + def remove_saved_states(self) -> None: + self.saved_states = {} + + @property + def state(self) -> JointState: + return JointState(self.position) + + @state.setter + def state(self, joint_state: JointState) -> None: + self.position = joint_state.position + + class Link: """ Represents a link of an Object in the World. """ + def __init__(self, _id: int, urdf_link: urdf_parser_py.urdf.Link, @@ -1209,6 +1380,7 @@ def __init__(self, self.local_transformer: LocalTransformer = LocalTransformer() self.constraint_ids: Dict[Link, int] = {} self.saved_states: Dict[int, LinkState] = {} + self._update_pose() def save_state(self, state_id: int) -> None: """ @@ -1224,6 +1396,12 @@ def restore_state(self, state_id: int) -> None: """ self.constraint_ids = self.saved_states[state_id].constraint_ids + def remove_saved_states(self) -> None: + """ + Removes all saved states of this link. + """ + self.saved_states = {} + def get_current_state(self) -> LinkState: """ :return: The current state of this link as a LinkState object. @@ -1353,13 +1531,19 @@ def orientation_as_list(self) -> List[float]: """ return self.pose.orientation_as_list() + def _update_pose(self) -> None: + """ + Updates the current pose of this link from the world. + """ + self._current_pose = self.world.get_link_pose(self) + @property def pose(self) -> Pose: """ The pose of the link relative to the world frame. :return: A Pose object containing the pose of the link relative to the world frame. """ - return self.world.get_link_pose(self) + return self._current_pose @property def pose_as_list(self) -> List[List[float]]: @@ -1427,6 +1611,7 @@ class RootLink(Link): Represents the root link of an Object in the World. It differs from the normal Link class in that the pose ande the tf_frame is the same as that of the object. """ + def __init__(self, obj: Object): super().__init__(obj.get_root_link_id(), obj.get_root_urdf_link(), obj) @@ -1438,13 +1623,8 @@ def tf_frame(self) -> str: """ return self.object.tf_frame - @property - def pose(self) -> Pose: - """ - Returns the pose of the root link, which is the same as the pose of the object. - :return: A Pose object containing the pose of the root link. - """ - return self.object.get_pose() + def _update_pose(self) -> None: + self._current_pose = self.object.get_pose() class Object: @@ -1497,21 +1677,17 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.set_robot_if_not_set(self) self._init_joint_name_and_id_map() - self._init_link_name_and_id_map() - self._init_links() - self.update_link_transforms() + self._init_links_and_update_transforms() + self._init_joints() self.attachments: Dict[Object, Attachment] = {} self.saved_states: Dict[int, ObjectState] = {} - # takes the state id as key and returns the attachments of the object at that state if not self.world.is_prospection_world: self._add_to_world_sync_obj_queue(self.path) - self._init_current_positions_of_joint() - self.world.objects.append(self) def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: @@ -1640,24 +1816,36 @@ def _init_link_name_and_id_map(self) -> None: link_names = self.world.get_link_names(self) n_links = len(link_names) self.link_name_to_id: Dict[str, int] = dict(zip(link_names, range(n_links))) - self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) self.link_name_to_id[self.urdf_object.get_root()] = -1 - self.link_id_to_name[-1] = self.urdf_object.get_root() + self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) - def _init_links(self) -> None: + def _init_links_and_update_transforms(self) -> None: """ Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the corresponding link objects. """ - links = {} + self.links = {} for urdf_link in self.urdf_object.links: link_name = urdf_link.name link_id = self.link_name_to_id[link_name] if link_name == self.urdf_object.get_root(): - links[link_name] = RootLink(self) + self.links[link_name] = RootLink(self) else: - links[link_name] = Link(link_id, urdf_link, self) - self.links = links + self.links[link_name] = Link(link_id, urdf_link, self) + + + self.update_link_transforms() + + def _init_joints(self): + """ + Initialize the joint objects from the URDF file and creates a dictionary which mas the joint names to the + corresponding joint objects + """ + self.joints = {} + for urdf_joint in self.urdf_object.joints: + joint_name = urdf_joint.name + joint_id = self.joint_name_to_id[joint_name] + self.joints[joint_name] = Joint(joint_id, urdf_joint, self) def _add_to_world_sync_obj_queue(self, path: str) -> None: """ @@ -1668,14 +1856,6 @@ def _add_to_world_sync_obj_queue(self, path: str) -> None: [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), self.world.prospection_world, self.color, self]) - def _init_current_positions_of_joint(self) -> None: - """ - Initialize the cached joint position for each joint. - """ - self._current_joints_positions = {} - for joint_name in self.joint_name_to_id.keys(): - self._current_joints_positions[joint_name] = self.world.get_joint_position(self, joint_name) - @property def base_origin_shift(self) -> np.ndarray: """ @@ -1816,17 +1996,41 @@ def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Op :param set_attachments: Whether to set the poses of the attached objects to this object or not. """ pose_in_map = self.local_transformer.transform_pose(pose, "map") - - position, orientation = pose_in_map.to_list() if base: - position = np.array(position) + self.base_origin_shift + pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift - self.world.reset_object_base_pose(self, position, orientation) - self._current_pose = pose_in_map + self.reset_base_pose(pose_in_map) if set_attachments: self._set_attached_objects_poses() + def reset_base_pose(self, pose: Pose): + self.world.reset_object_base_pose(self, pose) + self.update_pose() + + def update_pose(self): + """ + Updates the current pose of this object from the world. + """ + self._current_pose = self.world.get_object_pose(self) + self._update_all_joints_positions() + self._update_all_links_poses() + self.update_link_transforms() + + def _update_all_joints_positions(self): + """ + Updates the posisitons of all joints by getting them from the simulator. + """ + for joint in self.joints.values(): + joint._update_position() + + def _update_all_links_poses(self): + """ + Updates the poses of all links by getting them from the simulator. + """ + for link in self.links.values(): + link._update_pose() + def move_base_to_origin_pos(self) -> None: """ Move the object such that its base will be at the current origin position. @@ -1840,6 +2044,7 @@ def save_state(self, state_id) -> None: :param state_id: The unique id of the state. """ self.save_links_states(state_id) + self.save_joints_states(state_id) self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) def save_links_states(self, state_id: int) -> None: @@ -1850,22 +2055,31 @@ def save_links_states(self, state_id: int) -> None: for link in self.links.values(): link.save_state(state_id) + def save_joints_states(self, state_id: int) -> None: + """ + Saves the state of all joints of this object. + :param state_id: The unique id of the state. + """ + for joint in self.joints.values(): + joint.save_state(state_id) + def restore_state(self, state_id: int) -> None: """ Restores the state of this object by restoring the state of all links and attachments. :param state_id: The unique id of the state. """ - self.restore_links_states(state_id) self.restore_attachments(state_id) + self.restore_links_states(state_id) + self.restore_joints_states(state_id) - def restore_attachments(self, state_id) -> None: + def restore_attachments(self, state_id: int) -> None: """ Restores the attachments of this object from a saved state using the given state id. :param state_id: The unique id of the state. """ self.attachments = self.saved_states[state_id].attachments - def restore_links_states(self, state_id) -> None: + def restore_links_states(self, state_id: int) -> None: """ Restores the states of all links of this object from a saved state using the given state id. :param state_id: The unique id of the state. @@ -1873,13 +2087,35 @@ def restore_links_states(self, state_id) -> None: for link in self.links.values(): link.restore_state(state_id) + def restore_joints_states(self, state_id: int) -> None: + """ + Restores the states of all joints of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + for joint in self.joints.values(): + joint.restore_state(state_id) + def remove_saved_states(self) -> None: """ Removes all saved states of this object. """ self.saved_states = {} + self.remove_links_saved_states() + self.remove_joints_saved_states() + + def remove_links_saved_states(self) -> None: + """ + Removes all saved states of the links of this object. + """ for link in self.links.values(): - link.saved_states = {} + link.remove_saved_states() + + def remove_joints_saved_states(self) -> None: + """ + Removes all saved states of the joints of this object. + """ + for joint in self.joints.values(): + joint.remove_saved_states() def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: """ @@ -2028,74 +2264,45 @@ def set_joint_positions(self, joint_poses: dict) -> None: :param joint_poses: """ for joint_name, joint_position in joint_poses.items(): - self.world.reset_joint_position(self, joint_name, joint_position) - self._current_joints_positions[joint_name] = joint_position + self.joints[joint_name].position = joint_position + self.update_pose() self._set_attached_objects_poses() def set_joint_position(self, joint_name: str, joint_position: float) -> None: """ - Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. + Sets the position of the given joint to the given joint pose and updates the poses of all attached objects. :param joint_name: The name of the joint :param joint_position: The target pose for this joint """ - # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - up_lim, low_lim = self.world.get_joint_limits(self, joint_name) - if low_lim > up_lim: - low_lim, up_lim = up_lim, low_lim - if not low_lim <= joint_position <= up_lim: - logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {joint_name}" - f" are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_position}") - # Temporarily disabled because kdl outputs values exciting joint limits - # return - self.world.reset_joint_position(self, joint_name, joint_position) - self._current_joints_positions[joint_name] = joint_position + self.joints[joint_name].position = joint_position + self._update_all_links_poses() + self.update_link_transforms() self._set_attached_objects_poses() def get_joint_position(self, joint_name: str) -> float: - """ - Returns the joint position for the given joint name. - - :param joint_name: The name of the joint - :return: The current pose of the joint - """ - return self._current_joints_positions[joint_name] + return self.joints[joint_name].position def get_joint_rest_position(self, joint_name: str) -> float: - return self.world.get_joint_rest_position(self, joint_name) + return self.joints[joint_name].rest_position def get_joint_damping(self, joint_name: str) -> float: - return self.world.get_joint_damping(self, joint_name) + return self.joints[joint_name].damping def get_joint_upper_limit(self, joint_name: str) -> float: - return self.world.get_joint_upper_limit(self, joint_name) + return self.joints[joint_name].upper_limit def get_joint_lower_limit(self, joint_name: str) -> float: - return self.world.get_joint_lower_limit(self, joint_name) + return self.joints[joint_name].lower_limit - def get_joint_axis(self, joint_name: str) -> Tuple[float]: - return self.world.get_joint_axis(self, joint_name) + def get_joint_axis(self, joint_name: str) -> Point: + return self.joints[joint_name].axis def get_joint_type(self, joint_name: str) -> JointType: - return self.world.get_joint_type(self, joint_name) - - def get_joint_limits(self, joint: str) -> Tuple[float, float]: - """ - Returns the lower and upper limit of a joint, if the lower limit is higher - than the upper they are swapped to ensure the lower limit is always the smaller one. + return self.joints[joint_name].type - :param joint: The name of the joint for which the limits should be found. - :return: The lower and upper limit of the joint. - """ - if joint not in self.joint_name_to_id.keys(): - raise KeyError(f"The given Joint: {joint} is not part of this object") - lower, upper = self.world.get_joint_limits(self, joint) - if lower > upper: - lower, upper = upper, lower - return lower, upper + def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: + return self.joints[joint_name].limits def find_joint_above(self, link_name: str, joint_type: JointType) -> str: """ @@ -2122,7 +2329,7 @@ def get_positions_of_all_joints(self) -> Dict[str: float]: :return: A dictionary with all joints positions'. """ - return self._current_joints_positions + return {j.name: j.position for j in self.joints.values()} def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: """ diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 1c0ee3ea0..fc96cd60e 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -261,12 +261,17 @@ def visual_geometry_type(self) -> Shape: return Shape.PLANE +@dataclass +class ObjectState: + state_id: int + attachments: Dict['Object', 'Attachment'] + + @dataclass class LinkState: constraint_ids: Dict['Link', int] @dataclass -class ObjectState: - state_id: int - attachments: Dict['Object', 'Attachment'] +class JointState: + position: float diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 2387a234b..15e46e637 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -2,6 +2,7 @@ import unittest import rospkg +from geometry_msgs.msg import Point from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose @@ -51,13 +52,13 @@ def test_get_joint_damping(self): self.assertEqual(self.robot.get_joint_damping("head_pan_joint"), 0.5) def test_get_joint_upper_limit(self): - self.assertEqual(self.robot.get_joint_upper_limit("head_pan_joint"), -3.007) + self.assertEqual(self.robot.get_joint_upper_limit("head_pan_joint"), 3.007) def test_get_joint_lower_limit(self): - self.assertEqual(self.robot.get_joint_lower_limit("head_pan_joint"), 3.007) + self.assertEqual(self.robot.get_joint_lower_limit("head_pan_joint"), -3.007) def test_get_joint_axis(self): - self.assertEqual(self.robot.get_joint_axis("head_pan_joint"), (0.0, 0.0, 1.0)) + self.assertEqual(self.robot.get_joint_axis("head_pan_joint"), Point(0.0, 0.0, 1.0)) def test_get_joint_type(self): self.assertEqual(self.robot.get_joint_type("head_pan_joint"), JointType.REVOLUTE) From 00ea8c43ea40c8a625c88aa900264777652cc42a Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 5 Feb 2024 11:08:15 +0100 Subject: [PATCH 072/195] [doc] fixed failing doc --- .github/workflows/reusable-sphinx-build.yml | 4 ++++ examples/orm_example.ipynb | 8 -------- src/pycram/designators/actions/__init__.py | 0 3 files changed, 4 insertions(+), 8 deletions(-) create mode 100644 src/pycram/designators/actions/__init__.py diff --git a/.github/workflows/reusable-sphinx-build.yml b/.github/workflows/reusable-sphinx-build.yml index d9de9b353..c6353b831 100644 --- a/.github/workflows/reusable-sphinx-build.yml +++ b/.github/workflows/reusable-sphinx-build.yml @@ -4,6 +4,10 @@ on: push: branches: - dev + pull_request: + branches: + - master + - dev # ---------------------------------------------------------------------------------------------------------------------- diff --git a/examples/orm_example.ipynb b/examples/orm_example.ipynb index 26e810c9c..6eca63f84 100644 --- a/examples/orm_example.ipynb +++ b/examples/orm_example.ipynb @@ -615,14 +615,6 @@ "source": [ "session.scalars(select(ORMSaying)).all()" ] - }, - { - "cell_type": "code", - "outputs": [], - "source": [], - "metadata": { - "collapsed": false - } } ], "metadata": { diff --git a/src/pycram/designators/actions/__init__.py b/src/pycram/designators/actions/__init__.py new file mode 100644 index 000000000..e69de29bb From a0003a8e88ab87479c1207ac080f47102e5c3807 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 5 Feb 2024 11:11:09 +0100 Subject: [PATCH 073/195] [tests] fixed deprecation warnings --- test/test_costmaps.py | 2 +- test/test_language.py | 2 +- test/test_pose.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 457bbd577..41f9567f0 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -17,7 +17,7 @@ def test_attachment_exclusion(self): self.milk.set_pose(Pose([0.5, 0, 1])) self.cereal.set_pose(Pose([50, 50, 0])) o = OccupancyCostmap(0.2, from_ros=False, size=200, resolution=0.02, origin=Pose([0, 0, 0], [0, 0, 0, 1])) - self.assertEquals(np.sum(o.map[115:135, 90:110]), 0) + self.assertEqual(np.sum(o.map[115:135, 90:110]), 0) self.robot.attach(self.milk) self.assertTrue(np.sum(o.map[80:90, 90:110]) != 0) diff --git a/test/test_language.py b/test/test_language.py index e63d5ec57..cb8746c4d 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -169,7 +169,7 @@ def test_set(param): def test_perform_parallel(self): def check_thread_id(main_id): - self.assertNotEquals(main_id, threading.get_ident()) + self.assertNotEqual(main_id, threading.get_ident()) act = Code(check_thread_id, {"main_id": threading.get_ident()}) act2 = Code(check_thread_id, {"main_id": threading.get_ident()}) act3 = Code(check_thread_id, {"main_id": threading.get_ident()}) diff --git a/test/test_pose.py b/test/test_pose.py index 97064a56d..6fbb2ef79 100644 --- a/test/test_pose.py +++ b/test/test_pose.py @@ -73,5 +73,5 @@ def test_transform_copy(self): t = Transform([1, 1, 1], [0, 0, 0, 1], "map", "test_frame") t_copy = t.copy() - self.assertEquals(t, t_copy) + self.assertEqual(t, t_copy) self.assertFalse(t is t_copy) From 3df171a0f5a1a32dd637ae8c5edd800c43ec170d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Wed, 7 Feb 2024 10:47:58 +0100 Subject: [PATCH 074/195] [process_module] added type hint --- src/pycram/process_module.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/pycram/process_module.py b/src/pycram/process_module.py index 6fa95efcf..16cf4f651 100644 --- a/src/pycram/process_module.py +++ b/src/pycram/process_module.py @@ -14,6 +14,10 @@ from .language import Language from .robot_descriptions import robot_description +from typing_extensions import TYPE_CHECKING + +if TYPE_CHECKING: + from .designators.motion_designator import BaseMotion class ProcessModule: @@ -34,14 +38,14 @@ def __init__(self, lock): """Create a new process module.""" self._lock = lock - def _execute(self, designator) -> Any: + def _execute(self, designator: BaseMotion) -> Any: """ Helper method for internal usage only. This method is to be overwritten instead of the execute method. """ pass - def execute(self, designator) -> Any: + def execute(self, designator: BaseMotion) -> Any: """ Execute the given designator. If there is already another process module of the same kind the `self._lock` will lock this thread until the execution of that process module is finished. This implicitly queues the execution of From ff0295d8e408cf4e30e6c57f74faa9274f6096b3 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 7 Feb 2024 11:16:49 +0100 Subject: [PATCH 075/195] [examples] added local transfomer to sphinx and new sym link --- doc/source/examples.rst | 5 +- doc/source/notebooks/action_designator.ipynb | 1 - doc/source/notebooks/bullet_world.ipynb | 1 - doc/source/notebooks/custom_resolver.ipynb | 1 - doc/source/notebooks/giskard.ipynb | 1 - doc/source/notebooks/intro.ipynb | 1 - doc/source/notebooks/language.ipynb | 1 - .../notebooks/location_designator.ipynb | 1 - doc/source/notebooks/migrate_neems.ipynb | 1 - doc/source/notebooks/minimal_task_tree.ipynb | 1 - doc/source/notebooks/motion_designator.ipynb | 1 - doc/source/notebooks/object_designator.ipynb | 1 - doc/source/notebooks/orm_example.ipynb | 1 - .../notebooks/orm_querying_examples.ipynb | 1 - doc/source/notebooks/pose.ipynb | 1 - doc/source/notebooks/robokudo.ipynb | 1 - .../thumbnails/action_designator.png | 1 - .../notebooks/thumbnails/bullet_world.png | 1 - doc/source/notebooks/thumbnails/default.png | 1 - .../thumbnails/location_designator.png | 1 - .../thumbnails/motion_designator.png | 1 - .../thumbnails/object_designator.png | 1 - doc/source/notebooks/thumbnails/overview.png | 1 - doc/source/notebooks/thumbnails/pose.png | 1 - doc/source/notebooks/thumbnails/tree.png | 1 - examples/local_transformer.ipynb | 121 +++++++----------- 26 files changed, 48 insertions(+), 102 deletions(-) delete mode 120000 doc/source/notebooks/action_designator.ipynb delete mode 120000 doc/source/notebooks/bullet_world.ipynb delete mode 120000 doc/source/notebooks/custom_resolver.ipynb delete mode 120000 doc/source/notebooks/giskard.ipynb delete mode 120000 doc/source/notebooks/intro.ipynb delete mode 120000 doc/source/notebooks/language.ipynb delete mode 120000 doc/source/notebooks/location_designator.ipynb delete mode 120000 doc/source/notebooks/migrate_neems.ipynb delete mode 120000 doc/source/notebooks/minimal_task_tree.ipynb delete mode 120000 doc/source/notebooks/motion_designator.ipynb delete mode 120000 doc/source/notebooks/object_designator.ipynb delete mode 120000 doc/source/notebooks/orm_example.ipynb delete mode 120000 doc/source/notebooks/orm_querying_examples.ipynb delete mode 120000 doc/source/notebooks/pose.ipynb delete mode 120000 doc/source/notebooks/robokudo.ipynb delete mode 120000 doc/source/notebooks/thumbnails/action_designator.png delete mode 120000 doc/source/notebooks/thumbnails/bullet_world.png delete mode 120000 doc/source/notebooks/thumbnails/default.png delete mode 120000 doc/source/notebooks/thumbnails/location_designator.png delete mode 120000 doc/source/notebooks/thumbnails/motion_designator.png delete mode 120000 doc/source/notebooks/thumbnails/object_designator.png delete mode 120000 doc/source/notebooks/thumbnails/overview.png delete mode 120000 doc/source/notebooks/thumbnails/pose.png delete mode 120000 doc/source/notebooks/thumbnails/tree.png diff --git a/doc/source/examples.rst b/doc/source/examples.rst index ac52e9ac0..8810ec0a9 100644 --- a/doc/source/examples.rst +++ b/doc/source/examples.rst @@ -29,13 +29,14 @@ Misc notebooks/pose notebooks/custom_resolver notebooks/language + notebooks/local_transformer Interface Examples ================== .. nbgallery:: - notebooks/giskard - notebooks/robokudo + notebooks/interface_examples/giskard + notebooks/interface_examples/robokudo Object Relational Mapping ========================= diff --git a/doc/source/notebooks/action_designator.ipynb b/doc/source/notebooks/action_designator.ipynb deleted file mode 120000 index d805f8db5..000000000 --- a/doc/source/notebooks/action_designator.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/action_designator.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb deleted file mode 120000 index bdb627d54..000000000 --- a/doc/source/notebooks/bullet_world.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/bullet_world.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/custom_resolver.ipynb b/doc/source/notebooks/custom_resolver.ipynb deleted file mode 120000 index ecd9fa1f8..000000000 --- a/doc/source/notebooks/custom_resolver.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/custom_resolver.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/giskard.ipynb b/doc/source/notebooks/giskard.ipynb deleted file mode 120000 index 6d8f4dcef..000000000 --- a/doc/source/notebooks/giskard.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/interface_examples/giskard.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/intro.ipynb b/doc/source/notebooks/intro.ipynb deleted file mode 120000 index 31a4f6830..000000000 --- a/doc/source/notebooks/intro.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/intro.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/language.ipynb b/doc/source/notebooks/language.ipynb deleted file mode 120000 index ae22ff1e9..000000000 --- a/doc/source/notebooks/language.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/language.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/location_designator.ipynb b/doc/source/notebooks/location_designator.ipynb deleted file mode 120000 index 60e30b0a0..000000000 --- a/doc/source/notebooks/location_designator.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/location_designator.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/migrate_neems.ipynb b/doc/source/notebooks/migrate_neems.ipynb deleted file mode 120000 index 031ee0a9e..000000000 --- a/doc/source/notebooks/migrate_neems.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/migrate_neems.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/minimal_task_tree.ipynb b/doc/source/notebooks/minimal_task_tree.ipynb deleted file mode 120000 index 6f3de6889..000000000 --- a/doc/source/notebooks/minimal_task_tree.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/minimal_task_tree.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/motion_designator.ipynb b/doc/source/notebooks/motion_designator.ipynb deleted file mode 120000 index 74539a9e4..000000000 --- a/doc/source/notebooks/motion_designator.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/motion_designator.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/object_designator.ipynb b/doc/source/notebooks/object_designator.ipynb deleted file mode 120000 index 065caac0b..000000000 --- a/doc/source/notebooks/object_designator.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/object_designator.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/orm_example.ipynb b/doc/source/notebooks/orm_example.ipynb deleted file mode 120000 index dd3b43ee0..000000000 --- a/doc/source/notebooks/orm_example.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/orm_example.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/orm_querying_examples.ipynb b/doc/source/notebooks/orm_querying_examples.ipynb deleted file mode 120000 index 853d8d1d2..000000000 --- a/doc/source/notebooks/orm_querying_examples.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/orm_querying_examples.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/pose.ipynb b/doc/source/notebooks/pose.ipynb deleted file mode 120000 index ca40edb56..000000000 --- a/doc/source/notebooks/pose.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/pose.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/robokudo.ipynb b/doc/source/notebooks/robokudo.ipynb deleted file mode 120000 index 97928bc1b..000000000 --- a/doc/source/notebooks/robokudo.ipynb +++ /dev/null @@ -1 +0,0 @@ -../../../examples/interface_examples/robokudo.ipynb \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/action_designator.png b/doc/source/notebooks/thumbnails/action_designator.png deleted file mode 120000 index f39b0478e..000000000 --- a/doc/source/notebooks/thumbnails/action_designator.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/action_designator.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/bullet_world.png b/doc/source/notebooks/thumbnails/bullet_world.png deleted file mode 120000 index ba0e38633..000000000 --- a/doc/source/notebooks/thumbnails/bullet_world.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/bullet_world.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/default.png b/doc/source/notebooks/thumbnails/default.png deleted file mode 120000 index 91394022f..000000000 --- a/doc/source/notebooks/thumbnails/default.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/pycram_logo.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/location_designator.png b/doc/source/notebooks/thumbnails/location_designator.png deleted file mode 120000 index bc2a3d989..000000000 --- a/doc/source/notebooks/thumbnails/location_designator.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/location_designator.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/motion_designator.png b/doc/source/notebooks/thumbnails/motion_designator.png deleted file mode 120000 index 25d82ec74..000000000 --- a/doc/source/notebooks/thumbnails/motion_designator.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/motion_designator.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/object_designator.png b/doc/source/notebooks/thumbnails/object_designator.png deleted file mode 120000 index 876198dde..000000000 --- a/doc/source/notebooks/thumbnails/object_designator.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/object_designator.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/overview.png b/doc/source/notebooks/thumbnails/overview.png deleted file mode 120000 index ec26a8933..000000000 --- a/doc/source/notebooks/thumbnails/overview.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/overview.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/pose.png b/doc/source/notebooks/thumbnails/pose.png deleted file mode 120000 index 5dcf9f1ff..000000000 --- a/doc/source/notebooks/thumbnails/pose.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/pose.png \ No newline at end of file diff --git a/doc/source/notebooks/thumbnails/tree.png b/doc/source/notebooks/thumbnails/tree.png deleted file mode 120000 index 251604eb3..000000000 --- a/doc/source/notebooks/thumbnails/tree.png +++ /dev/null @@ -1 +0,0 @@ -../../../images/thumbnails/tree.png \ No newline at end of file diff --git a/examples/local_transformer.ipynb b/examples/local_transformer.ipynb index 8a6352cde..fc039ab60 100644 --- a/examples/local_transformer.ipynb +++ b/examples/local_transformer.ipynb @@ -5,6 +5,8 @@ "id": "611b7e76", "metadata": {}, "source": [ + "# Local Transformer\n", + "The local transformer is used to handle transforms between different frames in PyCRAM. This is useful when you want to transform a pose from one frame to another, for example, from the map frame to the frame of an object. This example will introduce the Local Transformer and how to use it to transform poses between frames.\n", "\n", "## Setting up the Environment\n", "\n", @@ -17,25 +19,11 @@ "id": "615cb805", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:32.010116177Z", - "start_time": "2024-01-29T16:28:31.439191974Z" + "end_time": "2024-02-07T09:18:56.397119146Z", + "start_time": "2024-02-07T09:18:56.384091718Z" } }, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "pybullet build time: May 20 2022 19:44:17\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1706545711.997153]: Failed to import Giskard messages\n", - "[WARN] [1706545712.001630]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" - ] - } - ], + "outputs": [], "source": [ "from pycram.bullet_world import BulletWorld, Object\n", "from pycram.pose import Transform, Pose\n", @@ -51,29 +39,17 @@ "## Initializing the World\n", "\n", "Every robot simulation requires a world where it can interact. This world serves as the playground where the robot performs tasks. \n", - "Let's start by creating this world.\n" + "Let's start by creating this world.\n", + "\n", + "Since the local transformer can only transform between frames of objects which are in the world, we need to create a world first.\n" ] }, { "cell_type": "code", - "execution_count": 2, + "execution_count": null, "id": "7a3222c2", - "metadata": { - "ExecuteTime": { - "end_time": "2024-01-29T16:28:32.323570586Z", - "start_time": "2024-01-29T16:28:32.085550201Z" - } - }, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n" - ] - } - ], + "metadata": {}, + "outputs": [], "source": [ "# Create an instance of the BulletWorld\n", "world = BulletWorld()\n" @@ -89,12 +65,12 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 9, "id": "c019c259", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:32.326842316Z", - "start_time": "2024-01-29T16:28:32.324154465Z" + "end_time": "2024-02-07T09:20:31.566964425Z", + "start_time": "2024-02-07T09:20:31.309671668Z" } }, "outputs": [], @@ -112,17 +88,17 @@ "\n", "For our robot to perform meaningful tasks, we need to populate its world with objects. \n", "In this section, we'll add a variety of objects, from a simple floor plane to kitchen setups and items like milk and bowls. \n", - "These objects will be used in subsequent tasks.\n" + "These objects will be used in subsequent tasks, to provide the frames to which we will transform poses.\n" ] }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 3, "id": "14494539", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.474604282Z", - "start_time": "2024-01-29T16:28:32.329041645Z" + "end_time": "2024-02-07T09:19:12.883651520Z", + "start_time": "2024-02-07T09:19:09.027873229Z" } }, "outputs": [ @@ -130,13 +106,6 @@ "name": "stderr", "output_type": "stream", "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Scalar element defined multiple times: limit\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Scalar element defined multiple times: limit\n" ] } @@ -145,8 +114,6 @@ "from pycram.bullet_world import Object\n", "from pycram.enums import ObjectType\n", "\n", - "plane = Object(\"floor\", ObjectType.ENVIRONMENT, \"plane.urdf\", world=world)\n", - "\n", "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"kitchen.urdf\")\n", "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", Pose([0.9, 1, 0.95]))\n", "bowl = Object(\"bowl\", ObjectType.BOWL, \"bowl.stl\", Pose([1.6, 1, 0.90]))" @@ -163,12 +130,12 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 4, "id": "708606eb", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.481284612Z", - "start_time": "2024-01-29T16:28:35.472994214Z" + "end_time": "2024-02-07T09:19:17.445812011Z", + "start_time": "2024-02-07T09:19:17.433695422Z" } }, "outputs": [ @@ -176,8 +143,8 @@ "name": "stdout", "output_type": "stream", "text": [ - "\n", - "\n" + "\n", + "\n" ] } ], @@ -202,12 +169,12 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 5, "id": "988ffda1", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.509096003Z", - "start_time": "2024-01-29T16:28:35.483520847Z" + "end_time": "2024-02-07T09:19:19.412829961Z", + "start_time": "2024-02-07T09:19:19.398278560Z" } }, "outputs": [ @@ -218,9 +185,9 @@ "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1706545715\n", - " nsecs: 495329141\n", - " frame_id: \"milk_4\"\n", + " secs: 1707297559\n", + " nsecs: 407153367\n", + " frame_id: \"milk_3\"\n", "pose: \n", " position: \n", " x: 0.09999999999999998\n", @@ -231,11 +198,12 @@ " y: 0.0\n", " z: 0.0\n", " w: 1.0\n", + "-------------------\n", "header: \n", " seq: 0\n", " stamp: \n", - " secs: 1706545715\n", - " nsecs: 496921062\n", + " secs: 1707297559\n", + " nsecs: 407913208\n", " frame_id: \"map\"\n", "pose: \n", " position: \n", @@ -259,6 +227,7 @@ "transformed_pose = l.transform_to_object_frame(test_pose, milk)\n", "print(transformed_pose)\n", "\n", + "print(\"-------------------\")\n", "new_pose = l.transform_pose(transformed_pose, \"map\")\n", "print(new_pose)" ] @@ -269,17 +238,17 @@ "metadata": {}, "source": [ "In the above code, we first transformed a pose to the object frame of the milk object, and then we transformed it back to the map frame. This demonstrates how we can easily manipulate poses relative to objects in our environment.\n", - "You can also transform poses relative to other poses. by using the transform_pose method. Further u can set a Transform." + "You can also transform poses relative to other poses. by using the transform_pose method. Further you can set a Transform." ] }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 6, "id": "dd2bafc5", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.509520802Z", - "start_time": "2024-01-29T16:28:35.500190623Z" + "end_time": "2024-02-07T09:19:24.941756539Z", + "start_time": "2024-02-07T09:19:24.929728567Z" } }, "outputs": [], @@ -302,12 +271,12 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 7, "id": "6b23f540", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.509787045Z", - "start_time": "2024-01-29T16:28:35.504069535Z" + "end_time": "2024-02-07T09:19:26.995686220Z", + "start_time": "2024-02-07T09:19:26.983125610Z" } }, "outputs": [], @@ -331,12 +300,12 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 8, "id": "bd619710", "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:28:35.552242116Z", - "start_time": "2024-01-29T16:28:35.508694526Z" + "end_time": "2024-02-07T09:20:26.251771677Z", + "start_time": "2024-02-07T09:20:26.240730107Z" } }, "outputs": [ @@ -344,8 +313,8 @@ "name": "stdout", "output_type": "stream", "text": [ - "milk_4\n", - "kitchen_3/kitchen_island_surface\n" + "milk_3\n", + "kitchen_2/kitchen_island_surface\n" ] } ], From 4ebee7f361572c7bf0d1d362045ccf8229dbe5f7 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 7 Feb 2024 14:34:48 +0100 Subject: [PATCH 076/195] [doc] actually added new sym link --- doc/source/notebooks | 1 + 1 file changed, 1 insertion(+) create mode 120000 doc/source/notebooks diff --git a/doc/source/notebooks b/doc/source/notebooks new file mode 120000 index 000000000..da7b19653 --- /dev/null +++ b/doc/source/notebooks @@ -0,0 +1 @@ +../../examples/ \ No newline at end of file From a8405b2b7fc6f99f3d6c7573533c22c5d3a43013 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Fri, 9 Feb 2024 15:53:06 +0100 Subject: [PATCH 077/195] [AbstractWorld] Abstracting URDF dependency to be any type of description. Cleaning. In progress, tests are not passing. --- src/pycram/bullet_world.py | 331 ++- src/pycram/enums.py | 3 + src/pycram/external_interfaces/giskard.py | 6 +- src/pycram/urdf_interface.py | 348 +++ src/pycram/world.py | 2461 +++++++++++---------- src/pycram/world_dataclasses.py | 74 +- test/test_bullet_world.py | 22 +- test/test_links.py | 12 +- test/test_object.py | 16 + 9 files changed, 1902 insertions(+), 1371 deletions(-) create mode 100644 src/pycram/urdf_interface.py diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 0f58af09f..a4317cce4 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -3,7 +3,7 @@ import threading import time -from typing_extensions import List, Optional, Dict, Tuple +from typing_extensions import List, Optional, Dict import numpy as np import pybullet as p @@ -12,9 +12,8 @@ from .enums import JointType, ObjectType, WorldMode from .pose import Pose -from .world import World, Object, Link -from .world_dataclasses import Color, Constraint, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape -from dataclasses import asdict +from .world import World, Object, Link, Constraint +from .world_dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape class BulletWorld(World): @@ -56,62 +55,40 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo if not is_prospection_world: plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) - def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: return p.loadURDF(path, basePosition=pose.position_as_list(), - baseOrientation=pose.orientation_as_list(), physicsClientId=self.client_id) + baseOrientation=pose.orientation_as_list(), physicsClientId=self.id) def remove_object_from_simulator(self, obj: Object) -> None: - p.removeBody(obj.id, self.client_id) + p.removeBody(obj.id, self.id) def add_constraint(self, constraint: Constraint) -> int: - joint_axis_in_child_link_frame = [constraint.joint_axis_in_child_link_frame.x, - constraint.joint_axis_in_child_link_frame.y, - constraint.joint_axis_in_child_link_frame.z] - - constraint_id = p.createConstraint(constraint.parent_link.get_object_id(), - constraint.parent_link.id, - constraint.child_link.get_object_id(), - constraint.child_link.id, - constraint.joint_type.value, - joint_axis_in_child_link_frame, - constraint.joint_frame_pose_wrt_parent_origin.position_as_list(), - constraint.joint_frame_pose_wrt_child_origin.position_as_list(), - constraint.joint_frame_pose_wrt_parent_origin.orientation_as_list(), - constraint.joint_frame_pose_wrt_child_origin.orientation_as_list(), - physicsClientId=self.client_id) + + constraint_id = p.createConstraint(constraint.parent_object_id, + constraint.parent_link_id, + constraint.child_object_id, + constraint.child_link_id, + constraint.type.value, + constraint.axis_as_list, + constraint.position_wrt_parent_as_list(), + constraint.position_wrt_child_as_list(), + constraint.orientation_wrt_parent_as_list(), + constraint.orientation_wrt_child_as_list(), + physicsClientId=self.id) return constraint_id def remove_constraint(self, constraint_id): - p.removeConstraint(constraint_id, physicsClientId=self.client_id) - - def get_joint_rest_position(self, obj: Object, joint_name: str) -> float: - return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] - - def get_joint_damping(self, obj: Object, joint_name: str) -> float: - return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[6] - - def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: - return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[8] - - def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: - return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[9] - - def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: - return p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[13] - - def get_joint_type(self, obj: Object, joint_name: str) -> JointType: - joint_type = p.getJointInfo(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[2] - return JointType(joint_type) + p.removeConstraint(constraint_id, physicsClientId=self.id) def get_joint_position(self, obj: Object, joint_name: str) -> float: - return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.client_id)[0] + return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.id)[0] def get_link_pose(self, link: Link) -> Pose: - return Pose(*p.getLinkState(link.get_object_id(), link.id, physicsClientId=self.client_id)[4:6]) + return Pose(*p.getLinkState(link.object_id, link.id, physicsClientId=self.id)[4:6]) def perform_collision_detection(self) -> None: - p.performCollisionDetection(physicsClientId=self.client_id) + p.performCollisionDetection(physicsClientId=self.id) def get_object_contact_points(self, obj: Object) -> List: """ @@ -120,47 +97,33 @@ def get_object_contact_points(self, obj: Object) -> List: `PyBullet Doc `_ """ self.perform_collision_detection() - return p.getContactPoints(obj.id, physicsClientId=self.client_id) + return p.getContactPoints(obj.id, physicsClientId=self.id) def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: self.perform_collision_detection() - return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.client_id) - - def get_joint_names(self, obj: Object) -> List[str]: - num_joints = self.get_number_of_joints(obj) - return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[1].decode('utf-8') for i in range(num_joints)] - - def get_link_names(self, obj: Object) -> List[str]: - num_links = self.get_number_of_links(obj) - return [p.getJointInfo(obj.id, i, physicsClientId=self.client_id)[12].decode('utf-8') for i in range(num_links)] - - def get_number_of_links(self, obj: Object) -> int: - return self.get_number_of_joints(obj) - - def get_number_of_joints(self, obj: Object) -> int: - return p.getNumJoints(obj.id, physicsClientId=self.client_id) + return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.id) def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: - p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.client_id) + p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.id) def reset_object_base_pose(self, obj: Object, pose: Pose) -> None: p.resetBasePositionAndOrientation(obj.id, pose.position_as_list(), pose.orientation_as_list(), - physicsClientId=self.client_id) + physicsClientId=self.id) def step(self): - p.stepSimulation(physicsClientId=self.client_id) + p.stepSimulation(physicsClientId=self.id) def get_object_pose(self, obj: Object) -> Pose: - return Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.client_id)) + return Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.id)) def set_link_color(self, link: Link, rgba_color: Color): - p.changeVisualShape(link.get_object_id(), link.id, rgbaColor=rgba_color, physicsClientId=self.client_id) + p.changeVisualShape(link.object_id, link.id, rgbaColor=rgba_color, physicsClientId=self.id) def get_link_color(self, link: Link) -> Color: return self.get_colors_of_object_links(link.object)[link.name] def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: - visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.client_id) + visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.id) link_id_to_name = {v: k for k, v in obj.link_name_to_id.items()} links = list(map(lambda x: link_id_to_name[x[1]] if x[1] != -1 else "base", visual_data)) colors = list(map(lambda x: Color.from_rgba(x[7]), visual_data)) @@ -168,19 +131,19 @@ def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: return link_to_color def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: - return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.client_id)) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.id)) def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: - return AxisAlignedBoundingBox.from_min_max(*p.getAABB(link.get_object_id(), link.id, physicsClientId=self.client_id)) + return AxisAlignedBoundingBox.from_min_max(*p.getAABB(link.object_id, link.id, physicsClientId=self.id)) def set_realtime(self, real_time: bool) -> None: - p.setRealTimeSimulation(1 if real_time else 0, physicsClientId=self.client_id) + p.setRealTimeSimulation(1 if real_time else 0, physicsClientId=self.id) def set_gravity(self, gravity_vector: List[float]) -> None: - p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.client_id) + p.setGravity(gravity_vector[0], gravity_vector[1], gravity_vector[2], physicsClientId=self.id) def disconnect_from_physics_server(self): - p.disconnect(physicsClientId=self.client_id) + p.disconnect(physicsClientId=self.id) def join_threads(self): """ @@ -193,13 +156,13 @@ def join_gui_thread_if_exists(self): self._gui_thread.join() def save_physics_simulator_state(self) -> int: - return p.saveState(physicsClientId=self.client_id) + return p.saveState(physicsClientId=self.id) def restore_physics_simulator_state(self, state_id): - p.restoreState(state_id, physicsClientId=self.client_id) + p.restoreState(state_id, physicsClientId=self.id) def remove_physics_simulator_state(self, state_id: int): - p.removeState(state_id, physicsClientId=self.client_id) + p.removeState(state_id, physicsClientId=self.id) def add_vis_axis(self, pose: Pose, length: Optional[float] = 0.2) -> None: @@ -234,7 +197,7 @@ def add_vis_axis(self, pose: Pose, linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], linkCollisionShapeIndices=[-1, -1, -1], - physicsClientId=self.client_id) + physicsClientId=self.id) self.vis_axis.append(obj) @@ -243,22 +206,22 @@ def remove_vis_axis(self) -> None: Removes all spawned vis axis objects that are currently in this BulletWorld. """ for vis_id in self.vis_axis: - p.removeBody(vis_id, physicsClientId=self.client_id) + p.removeBody(vis_id, physicsClientId=self.id) self.vis_axis = [] def ray_test(self, from_position: List[float], to_position: List[float]) -> int: - res = p.rayTest(from_position, to_position, physicsClientId=self.client_id) + res = p.rayTest(from_position, to_position, physicsClientId=self.id) return res[0][0] def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[List[float]], num_threads: int = 1) -> List[int]: return p.rayTestBatch(from_positions, to_positions, numThreads=num_threads, - physicsClientId=self.client_id) + physicsClientId=self.id) def create_visual_shape(self, visual_shape: VisualShape) -> int: return p.createVisualShape(visual_shape.visual_geometry_type.value, rgbaColor=visual_shape.rgba_color, visualFramePosition=visual_shape.visual_frame_position, - physicsClientId=self.client_id, **visual_shape.shape_data()) + physicsClientId=self.id, **visual_shape.shape_data()) def create_multi_body(self, multi_body: MultiBody) -> int: return p.createMultiBody(baseVisualShapeIndex=-MultiBody.base_visual_shape_index, @@ -289,10 +252,10 @@ def get_images_for_target(self, far = 100 view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1], - physicsClientId=self.client_id) - projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far, physicsClientId=self.client_id) + physicsClientId=self.id) + projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far, physicsClientId=self.id) return list(p.getCameraImage(size, size, view_matrix, projection_matrix, - physicsClientId=self.client_id))[2:5] + physicsClientId=self.id))[2:5] def add_text(self, text: str, position: List[float], orientation: Optional[List[float]] = None, size: Optional[float] = None, color: Optional[Color] = Color(), life_time: Optional[float] = 0, @@ -308,25 +271,25 @@ def add_text(self, text: str, position: List[float], orientation: Optional[List[ args["parentObjectUniqueId"] = parent_object_id if parent_link_id: args["parentLinkIndex"] = parent_link_id - return p.addUserDebugText(text, position, color.get_rgb(), physicsClientId=self.client_id, **args) + return p.addUserDebugText(text, position, color.get_rgb(), physicsClientId=self.id, **args) def remove_text(self, text_id: Optional[int] = None) -> None: if text_id: - p.removeUserDebugItem(text_id, physicsClientId=self.client_id) + p.removeUserDebugItem(text_id, physicsClientId=self.id) else: - p.removeAllUserDebugItems(physicsClientId=self.client_id) + p.removeAllUserDebugItems(physicsClientId=self.id) def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: - p.enableJointForceTorqueSensor(obj.id, fts_joint_idx, enableSensor=1, physicsClientId=self.client_id) + p.enableJointForceTorqueSensor(obj.id, fts_joint_idx, enableSensor=1, physicsClientId=self.id) def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: - p.enableJointForceTorqueSensor(obj.id, joint_id, enableSensor=0, physicsClientId=self.client_id) + p.enableJointForceTorqueSensor(obj.id, joint_id, enableSensor=0, physicsClientId=self.id) def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: - return p.getJointState(obj.id, joint_id, physicsClientId=self.client_id)[2] + return p.getJointState(obj.id, joint_id, physicsClientId=self.id)[2] def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: - return p.getJointState(obj.id, joint_id, physicsClientId=self.client_id)[3] + return p.getJointState(obj.id, joint_id, physicsClientId=self.id)[3] class Gui(threading.Thread): @@ -348,45 +311,45 @@ def run(self): thus the thread terminates. The loop also checks for mouse and keyboard inputs to control the camera. """ if self.mode == WorldMode.DIRECT: - self.world.client_id = p.connect(p.DIRECT) + self.world.id = p.connect(p.DIRECT) else: - self.world.client_id = p.connect(p.GUI) + self.world.id = p.connect(p.GUI) # Disable the side windows of the GUI - p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0, physicsClientId=self.world.client_id) + p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0, physicsClientId=self.world.id) # Change the init camera pose p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1], physicsClientId=self.world.client_id) + cameraTargetPosition=[-2, 0, 1], physicsClientId=self.world.id) # Get the initial camera target location - cameraTargetPosition = p.getDebugVisualizerCamera(physicsClientId=self.world.client_id)[11] + camera_target_position = p.getDebugVisualizerCamera(physicsClientId=self.world.id)[11] - sphereVisualId = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1], - physicsClientId=self.world.client_id) + sphere_visual_id = p.createVisualShape(p.GEOM_SPHERE, radius=0.05, rgbaColor=[1, 0, 0, 1], + physicsClientId=self.world.id) # Create a sphere with a radius of 0.05 and a mass of 0 - sphereUid = p.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=sphereVisualId, - basePosition=cameraTargetPosition, - physicsClientId=self.world.client_id) + sphere_uid = p.createMultiBody(baseMass=0.0, + baseInertialFramePosition=[0, 0, 0], + baseVisualShapeIndex=sphere_visual_id, + basePosition=camera_target_position, + physicsClientId=self.world.id) # Define the maxSpeed, used in calculations - maxSpeed = 16 + max_speed = 16 # Set initial Camera Rotation - cameraYaw = 50 - cameraPitch = -35 + camera_yaw = 50 + camera_pitch = -35 # Keep track of the mouse state - mouseState = [0, 0, 0] - oldMouseX, oldMouseY = 0, 0 + mouse_state = [0, 0, 0] + old_mouse_x, old_mouse_y = 0, 0 # Determines if the sphere at cameraTargetPosition is visible visible = 1 # Loop to update the camera position based on keyboard events - while p.isConnected(self.world.client_id): + while p.isConnected(self.world.id): # Monitor user input keys = p.getKeyboardEvents() mouse = p.getMouseEvents() @@ -395,30 +358,30 @@ def run(self): width, height, dist = (p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], p.getDebugVisualizerCamera()[10]) - cameraTargetPosition = p.getDebugVisualizerCamera()[11] + camera_target_position = p.getDebugVisualizerCamera()[11] # Get vectors used for movement on x,y,z Vector - xVec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - yVec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] - zVec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] + x_vec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] + y_vec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + z_vec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] # Check the mouse state if mouse: for m in mouse: - mouseX = m[2] - mouseY = m[1] + mouse_x = m[2] + mouse_y = m[1] # update mouseState # Left Mouse button if m[0] == 2 and m[3] == 0: - mouseState[0] = m[4] - # Middle mouse butto (scroll wheel) + mouse_state[0] = m[4] + # Middle mouse button (scroll wheel) if m[0] == 2 and m[3] == 1: - mouseState[1] = m[4] + mouse_state[1] = m[4] # right mouse button if m[0] == 2 and m[3] == 2: - mouseState[2] = m[4] + mouse_state[2] = m[4] # change visibility by clicking the mousewheel if m[4] == 6 and m[3] == 1 and visible == 1: @@ -427,62 +390,64 @@ def run(self): visible = 1 # camera movement when the left mouse button is pressed - if mouseState[0] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < maxSpeed else maxSpeed - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < maxSpeed else maxSpeed + if mouse_state[0] == 3: + speed_x = abs(old_mouse_x - mouse_x) if (abs(old_mouse_x - mouse_x)) < max_speed\ + else max_speed + speed_y = abs(old_mouse_y - mouse_y) if (abs(old_mouse_y - mouse_y)) < max_speed\ + else max_speed # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) - if mouseX < oldMouseX: - if (cameraPitch + speedX) < 89.5: - cameraPitch += (speedX / 4) + 1 - elif mouseX > oldMouseX: - if (cameraPitch - speedX) > -89.5: - cameraPitch -= (speedX / 4) + 1 - - if mouseY < oldMouseY: - cameraYaw += (speedY / 4) + 1 - elif mouseY > oldMouseY: - cameraYaw -= (speedY / 4) + 1 - - if mouseState[1] == 3: - speedX = abs(oldMouseX - mouseX) + if mouse_x < old_mouse_x: + if (camera_pitch + speed_x) < 89.5: + camera_pitch += (speed_x / 4) + 1 + elif mouse_x > old_mouse_x: + if (camera_pitch - speed_x) > -89.5: + camera_pitch -= (speed_x / 4) + 1 + + if mouse_y < old_mouse_y: + camera_yaw += (speed_y / 4) + 1 + elif mouse_y > old_mouse_y: + camera_yaw -= (speed_y / 4) + 1 + + if mouse_state[1] == 3: + speed_x = abs(old_mouse_x - mouse_x) factor = 0.05 - if mouseX < oldMouseX: - dist = dist - speedX * factor - elif mouseX > oldMouseX: - dist = dist + speedX * factor + if mouse_x < old_mouse_x: + dist = dist - speed_x * factor + elif mouse_x > old_mouse_x: + dist = dist + speed_x * factor dist = max(dist, 0.1) # camera movement when the right mouse button is pressed - if mouseState[2] == 3: - speedX = abs(oldMouseX - mouseX) if (abs(oldMouseX - mouseX)) < 5 else 5 - speedY = abs(oldMouseY - mouseY) if (abs(oldMouseY - mouseY)) < 5 else 5 + if mouse_state[2] == 3: + speed_x = abs(old_mouse_x - mouse_x) if (abs(old_mouse_x - mouse_x)) < 5 else 5 + speed_y = abs(old_mouse_y - mouse_y) if (abs(old_mouse_y - mouse_y)) < 5 else 5 factor = 0.05 - if mouseX < oldMouseX: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - elif mouseX > oldMouseX: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, factor), speedX)) - - if mouseY < oldMouseY: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) - elif mouseY > oldMouseY: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, factor), speedY)) + if mouse_x < old_mouse_x: + camera_target_position = np.subtract(camera_target_position, + np.multiply(np.multiply(z_vec, factor), speed_x)) + elif mouse_x > old_mouse_x: + camera_target_position = np.add(camera_target_position, + np.multiply(np.multiply(z_vec, factor), speed_x)) + + if mouse_y < old_mouse_y: + camera_target_position = np.add(camera_target_position, + np.multiply(np.multiply(x_vec, factor), speed_y)) + elif mouse_y > old_mouse_y: + camera_target_position = np.subtract(camera_target_position, + np.multiply(np.multiply(x_vec, factor), speed_y)) # update oldMouse values - oldMouseY, oldMouseX = mouseY, mouseX + old_mouse_y, old_mouse_x = mouse_y, mouse_x # check the keyboard state if keys: # if shift is pressed, double the speed if p.B3G_SHIFT in keys: - speedMult = 5 + speed_mult = 5 else: - speedMult = 2.5 + speed_mult = 2.5 # if control is pressed, the movements caused by the arrowkeys, the '+' as well as the '-' key # change @@ -490,57 +455,57 @@ def run(self): # the up and down arrowkeys cause the targetPos to move along the z axis of the map if p.B3G_DOWN_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) + camera_target_position = np.subtract(camera_target_position, + np.multiply(np.multiply(z_vec, 0.03), speed_mult)) elif p.B3G_UP_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(zVec, 0.03), speedMult)) + camera_target_position = np.add(camera_target_position, + np.multiply(np.multiply(z_vec, 0.03), speed_mult)) # left and right arrowkeys cause the targetPos to move horizontally relative to the camera if p.B3G_LEFT_ARROW in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) + camera_target_position = np.subtract(camera_target_position, + np.multiply(np.multiply(x_vec, 0.03), speed_mult)) elif p.B3G_RIGHT_ARROW in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(xVec, 0.03), speedMult)) + camera_target_position = np.add(camera_target_position, + np.multiply(np.multiply(x_vec, 0.03), speed_mult)) # the '+' and '-' keys cause the targetpos to move forwards and backwards relative to the camera # while the camera stays at a constant distance. SHIFT + '=' is for US layout if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - cameraTargetPosition = np.subtract(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) + camera_target_position = np.subtract(camera_target_position, + np.multiply(np.multiply(y_vec, 0.03), speed_mult)) elif ord("-") in keys: - cameraTargetPosition = np.add(cameraTargetPosition, - np.multiply(np.multiply(yVec, 0.03), speedMult)) + camera_target_position = np.add(camera_target_position, + np.multiply(np.multiply(y_vec, 0.03), speed_mult)) # standard bindings for thearrowkeys, the '+' as well as the '-' key else: # left and right arrowkeys cause the camera to rotate around the yaw axis if p.B3G_RIGHT_ARROW in keys: - cameraYaw += (360 / width) * speedMult + camera_yaw += (360 / width) * speed_mult elif p.B3G_LEFT_ARROW in keys: - cameraYaw -= (360 / width) * speedMult + camera_yaw -= (360 / width) * speed_mult # the up and down arrowkeys cause the camera to rotate around the pitch axis if p.B3G_DOWN_ARROW in keys: - if (cameraPitch + (360 / height) * speedMult) < 89.5: - cameraPitch += (360 / height) * speedMult + if (camera_pitch + (360 / height) * speed_mult) < 89.5: + camera_pitch += (360 / height) * speed_mult elif p.B3G_UP_ARROW in keys: - if (cameraPitch - (360 / height) * speedMult) > -89.5: - cameraPitch -= (360 / height) * speedMult + if (camera_pitch - (360 / height) * speed_mult) > -89.5: + camera_pitch -= (360 / height) * speed_mult # the '+' and '-' keys cause the camera to zoom towards and away from the targetPos without # moving it. SHIFT + '=' is for US layout since the events can't handle shift plus something if ord("+") in keys or p.B3G_SHIFT in keys and ord("=") in keys: - if (dist - (dist * 0.02) * speedMult) > 0.1: - dist -= dist * 0.02 * speedMult + if (dist - (dist * 0.02) * speed_mult) > 0.1: + dist -= dist * 0.02 * speed_mult elif ord("-") in keys: - dist += dist * 0.02 * speedMult + dist += dist * 0.02 * speed_mult - p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=cameraYaw, cameraPitch=cameraPitch, - cameraTargetPosition=cameraTargetPosition) + p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=camera_yaw, cameraPitch=camera_pitch, + cameraTargetPosition=camera_target_position) if visible == 0: - cameraTargetPosition = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphereUid, cameraTargetPosition, [0, 0, 0, 1]) + camera_target_position = (0.0, -50, 50) + p.resetBasePositionAndOrientation(sphere_uid, camera_target_position, [0, 0, 0, 1]) time.sleep(1. / 80.) diff --git a/src/pycram/enums.py b/src/pycram/enums.py index b1c1cc011..2f03e422b 100644 --- a/src/pycram/enums.py +++ b/src/pycram/enums.py @@ -32,6 +32,9 @@ class JointType(Enum): CONTINUOUS = 6 FLOATING = 7 + # override enum method to return an int + + class Grasp(Enum): """ diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 25e9bc833..fd4958f6c 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -159,7 +159,7 @@ def spawn_object(object: Object) -> None: :param object: World object that should be spawned """ if len(object.link_name_to_id) == 1: - geometry = object.urdf_object.link_map[object.urdf_object.get_root()].collision.geometry + geometry = object.object_description.link_map[object.object_description.get_root()].collision.geometry if isinstance(geometry, urdf_parser_py.urdf.Mesh): filename = geometry.filename spawn_mesh(object.name + "_" + str(object.id), filename, object.get_pose()) @@ -239,8 +239,8 @@ def _manage_par_motion_goals(goal_func, *args) -> Optional['MoveResult']: if "tip_link" in par_value_pair.keys() and "root_link" in par_value_pair.keys(): if par_value_pair["tip_link"] == robot_description.base_link: continue - chain = World.robot.urdf_object.get_chain(par_value_pair["root_link"], - par_value_pair["tip_link"]) + chain = World.robot.object_description.get_chain(par_value_pair["root_link"], + par_value_pair["tip_link"]) if set(chain).intersection(used_joints) != set(): giskard_wrapper.cmd_seq = tmp raise AttributeError(f"The joint(s) {set(chain).intersection(used_joints)} is used by multiple Designators") diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py new file mode 100644 index 000000000..240e6b955 --- /dev/null +++ b/src/pycram/urdf_interface.py @@ -0,0 +1,348 @@ +import os +import pathlib +import re +from xml.etree import ElementTree + +import rospkg +import rospy +from geometry_msgs.msg import Point +from tf.transformations import quaternion_from_euler +from typing_extensions import Union, List +from urdf_parser_py import urdf +from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, + Sphere as URDF_Sphere, Mesh as URDF_Mesh) + +from pycram.enums import JointType, Shape +from pycram.pose import Pose +from pycram.world import JointDescription as AbstractJointDescription, Joint as AbstractJoint, \ + LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription, World, _is_cached + + +class LinkDescription(AbstractLinkDescription): + """ + A class that represents a link description of an object. + """ + urdf_shape_map = { + URDF_Box: Shape.BOX, + URDF_Cylinder: Shape.CYLINDER, + URDF_Sphere: Shape.SPHERE, + URDF_Mesh: Shape.MESH + } + + def __init__(self, urdf_description: urdf.Link): + super().__init__(urdf_description) + + @property + def geometry(self) -> Union[Shape, None]: + """ + Returns the geometry type of the URDF collision element of this link. + """ + return self.urdf_shape_map[type(self.collision.geometry)] + + @property + def origin(self) -> Pose: + return Pose(self.collision.origin.xyz, + quaternion_from_euler(*self.collision.origin.rpy)) + + @property + def name(self) -> str: + return self.parsed_description.name + + @property + def collision(self) -> Collision: + return self.parsed_description.collision + + +class JointDescription(AbstractJointDescription): + urdf_type_map = {'unknown': JointType.UNKNOWN, + 'revolute': JointType.REVOLUTE, + 'continuous': JointType.CONTINUOUS, + 'prismatic': JointType.PRISMATIC, + 'floating': JointType.FLOATING, + 'planar': JointType.PLANAR, + 'fixed': JointType.FIXED} + + def __init__(self, urdf_description: urdf.Joint): + super().__init__(urdf_description) + + @property + def origin(self) -> Pose: + return Pose(self.parsed_description.origin.xyz, + quaternion_from_euler(*self.parsed_description.origin.rpy)) + + @property + def name(self) -> str: + return self.parsed_description.name + + @property + def has_limits(self) -> bool: + return bool(self.parsed_description.limit) + + @property + def type(self) -> JointType: + """ + :return: The type of this joint. + """ + return self.urdf_type_map[self.parsed_description.type] + + @property + def axis(self) -> Point: + """ + :return: The axis of this joint, for example the rotation axis for a revolute joint. + """ + return Point(*self.parsed_description.axis) + + @property + def lower_limit(self) -> Union[float, None]: + """ + :return: The lower limit of this joint, or None if the joint has no limits. + """ + if self.has_limits: + return self.parsed_description.limit.lower + else: + return None + + @property + def upper_limit(self) -> Union[float, None]: + """ + :return: The upper limit of this joint, or None if the joint has no limits. + """ + if self.has_limits: + return self.parsed_description.limit.upper + else: + return None + + @property + def parent_link_name(self) -> str: + """ + :return: The name of the parent link of this joint. + """ + return self.parsed_description.parent + + @property + def child_link_name(self) -> str: + """ + :return: The name of the child link of this joint. + """ + return self.parsed_description.child + + @property + def damping(self) -> float: + """ + :return: The damping of this joint. + """ + return self.parsed_description.dynamics.damping + + @property + def friction(self) -> float: + """ + :return: The friction of this joint. + """ + return self.parsed_description.dynamics.friction + + +class Joint(AbstractJoint, JointDescription): + ... + + +class ObjectDescription(AbstractObjectDescription): + """ + A class that represents an object description of an object. + """ + def from_description_file(self, path) -> URDF: + """ + Create an object description from a description file. + + :param path: The path to the description file. + """ + with open(path, 'r') as file: + return URDF.from_xml_string(file.read()) + + def preprocess_file(self, path: str, ignore_cached_files: bool) -> str: + """ + Preprocesses the file, if it is a .obj or .stl file it will be converted to an URDF file. + """ + path_object = pathlib.Path(path) + extension = path_object.suffix + + path = _look_for_file_in_data_dir(path, path_object) + + _create_cache_dir_if_not_exists() + + # if file is not yet cached correct the urdf and save if in the cache directory + if not _is_cached(path) or ignore_cached_files: + if extension == ".obj" or extension == ".stl": + path = self._generate_urdf_file(path) + elif extension == ".urdf": + with open(path, mode="r") as f: + urdf_string = fix_missing_inertial(f.read()) + urdf_string = remove_error_tags(urdf_string) + urdf_string = fix_link_attributes(urdf_string) + try: + urdf_string = _correct_urdf_string(urdf_string) + except rospkg.ResourceNotFound as e: + rospy.logerr(f"Could not find resource package linked in this URDF") + raise e + path = World.cache_dir + path_object.name + with open(path, mode="w") as f: + f.write(urdf_string) + else: # Using the urdf from the parameter server + urdf_string = rospy.get_param(path) + path = World.cache_dir + self.name + ".urdf" + with open(path, mode="w") as f: + f.write(_correct_urdf_string(urdf_string)) + # save correct path in case the file is already in the cache directory + elif extension == ".obj" or extension == ".stl": + path = World.cache_dir + path_object.stem + ".urdf" + elif extension == ".urdf": + path = World.cache_dir + path_object.name + else: + path = World.cache_dir + self.name + ".urdf" + + return path + + def _generate_urdf_file(self, path) -> str: + """ + Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be + used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with + the name as filename. + + :return: The absolute path of the created file + """ + urdf_template = ' \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + \n \ + ' + urdf_template = fix_missing_inertial(urdf_template) + rgb = " ".join(list(map(str, self.color.get_rgba()))) + pathlib_obj = pathlib.Path(path) + path = str(pathlib_obj.resolve()) + content = urdf_template.replace("~a", self.name).replace("~b", path).replace("~c", rgb) + with open(World.cache_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: + file.write(content) + return World.cache_dir + pathlib_obj.stem + ".urdf" + + @property + def links(self) -> List[LinkDescription]: + """ + :return: A list of links descriptions of this object. + """ + return [LinkDescription(link) for link in self.parsed_description.links] + + @property + def joints(self) -> List[JointDescription]: + """ + :return: A list of joints descriptions of this object. + """ + return [JointDescription(joint) for joint in self.parsed_description.joints] + + def get_root(self) -> str: + """ + :return: the name of the root link of this object. + """ + return self.parsed_description.get_root() + + def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: + """ + :return: the chain of links from 'start_link_name' to 'end_link_name'. + """ + return self.parsed_description.get_chain(start_link_name, end_link_name) + + +def _correct_urdf_string(urdf_string: str) -> str: + """ + Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legac) + can't deal with ROS package paths. + + :param urdf_string: The name of the URDf on the parameter server + :return: The URDF string with paths in the filesystem instead of ROS packages + """ + r = rospkg.RosPack() + new_urdf_string = "" + for line in urdf_string.split('\n'): + if "package://" in line: + s = line.split('//') + s1 = s[1].split('/') + path = r.get_path(s1[0]) + line = line.replace("package://" + s1[0], path) + new_urdf_string += line + '\n' + + return fix_missing_inertial(new_urdf_string) + + +def fix_missing_inertial(urdf_string: str) -> str: + """ + Insert inertial tags for every URDF link that has no inertia. + This is used to prevent Legacy(PyBullet) from dumping warnings in the terminal + + :param urdf_string: The URDF description as string + :returns: The new, corrected URDF description as string. + """ + + inertia_tree = ElementTree.ElementTree(ElementTree.Element("inertial")) + inertia_tree.getroot().append(ElementTree.Element("mass", {"value": "0.1"})) + inertia_tree.getroot().append(ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) + inertia_tree.getroot().append(ElementTree.Element("inertia", {"ixx": "0.01", + "ixy": "0", + "ixz": "0", + "iyy": "0.01", + "iyz": "0", + "izz": "0.01"})) + + # create tree from string + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + + for link_element in tree.iter("link"): + inertial = [*link_element.iter("inertial")] + if len(inertial) == 0: + link_element.append(inertia_tree.getroot()) + + return ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def remove_error_tags(urdf_string: str) -> str: + """ + Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the + URDF_parser + + :param urdf_string: String of the URDF from which the tags should be removed + :return: The URDF string with the tags removed + """ + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + removing_tags = ["gazebo", "transmission"] + for tag_name in removing_tags: + all_tags = tree.findall(tag_name) + for tag in all_tags: + tree.getroot().remove(tag) + + return ElementTree.tostring(tree.getroot(), encoding='unicode') + + +def fix_link_attributes(urdf_string: str) -> str: + """ + Removes the attribute 'type' from links since this is not parsable by the URDF parser. + + :param urdf_string: The string of the URDF from which the attributes should be removed + :return: The URDF string with the attributes removed + """ + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + + for link in tree.iter("link"): + if "type" in link.attrib.keys(): + del link.attrib["type"] + + return ElementTree.tostring(tree.getroot(), encoding='unicode') diff --git a/src/pycram/world.py b/src/pycram/world.py index 736c6a3eb..08c80e300 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -7,32 +7,86 @@ import re import threading import time -import xml.etree.ElementTree from abc import ABC, abstractmethod from queue import Queue import numpy as np -import rospkg import rospy -import urdf_parser_py.urdf from geometry_msgs.msg import Quaternion, Point -from tf.transformations import quaternion_from_euler -from typing_extensions import List, Optional, Dict, Tuple, Callable +from typing_extensions import List, Optional, Dict, Tuple, Callable, Any from typing_extensions import Union -from urdf_parser_py.urdf import URDF, Collision, GeometricType -from .enums import JointType, ObjectType, WorldMode +from .enums import JointType, ObjectType, WorldMode, Shape from .event import Event from .local_transformer import LocalTransformer from .pose import Pose, Transform from .robot_descriptions import robot_description -from .world_dataclasses import (Color, Constraint, AxisAlignedBoundingBox, CollisionCallbacks, +from .world_dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, - LinkState, ObjectState, JointState) + LinkState, ObjectState, JointState, State, WorldState) -class World(ABC): +class StateEntity: + """ + The StateEntity class is used to store the state of an object or the physics simulator. This is used to save and + restore the state of the World. + """ + + def __init__(self): + self._saved_states: Dict[int, State] = {} + + @property + def saved_states(self) -> Dict[int, State]: + """ + Returns the saved states of this entity. + """ + return self._saved_states + + def save_state(self, state_id: int) -> None: + """ + Saves the state of this entity with the given state id. + + :param state_id: The unique id of the state. + """ + self._saved_states[state_id] = self.current_state + + @property + @abstractmethod + def current_state(self) -> State: + """ + Returns the current state of this entity. + + :return: The current state of this entity. + """ + pass + + @current_state.setter + @abstractmethod + def current_state(self, state: State) -> None: + """ + Sets the current state of this entity. + + :param state: The new state of this entity. + """ + pass + + def restore_state(self, state_id: int) -> None: + """ + Restores the state of this entity from a saved state using the given state id. + + :param state_id: The unique id of the state. + """ + self.current_state = self.saved_states[state_id] + + def remove_saved_states(self) -> None: + """ + Removes all saved states of this entity. + """ + self._saved_states = {} + + +class World(StateEntity, ABC): """ The World Class represents the physics Simulation and belief state, it is the main interface for reasoning about the World. This is implemented as a singleton, the current World can be accessed via the static variable @@ -63,7 +117,7 @@ class World(ABC): Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. """ - cach_dir = data_directory[0] + '/cached/' + cache_dir = data_directory[0] + '/cached/' """ Global reference for the cache directory, this is used to cache the URDF files of the robot and the objects. """ @@ -78,6 +132,8 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ :param is_prospection_world: For internal usage, decides if this World should be used as a prospection world. """ + StateEntity.__init__(self) + if World.current_world is None: World.current_world = self World.simulation_frequency = simulation_frequency @@ -91,7 +147,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.objects: List[Object] = [] # List of all Objects in the World - self.client_id: int = -1 + self.id: int = -1 # This is used to connect to the physics server (allows multiple clients) self.mode: WorldMode = mode @@ -101,8 +157,6 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self._init_events() - self.saved_states: List[int] = [] - def _init_events(self): """ Initializes dynamic events that can be used to react to changes in the World. @@ -156,11 +210,11 @@ def simulation_time_step(self): return 1 / World.simulation_frequency @abstractmethod - def load_urdf_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: """ - Loads a URDF file at the given pose and returns the id of the loaded object. + Loads a description file (e.g. URDF) at the given pose and returns the id of the loaded object. - :param path: The path to the URDF file. + :param path: The path to the description file. :param pose: The pose at which the object should be loaded. :return: The id of the loaded object. """ @@ -240,10 +294,10 @@ def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_par constraint = Constraint(parent_link=parent_link, child_link=child_link, - joint_type=JointType.FIXED, - joint_axis_in_child_link_frame=Point(0, 0, 0), - joint_frame_pose_wrt_parent_origin=child_to_parent_transform.to_pose(), - joint_frame_pose_wrt_child_origin=Pose() + _type=JointType.FIXED, + axis_in_child_frame=Point(0, 0, 0), + constraint_to_parent=child_to_parent_transform, + child_to_constraint=Transform(frame=child_link.tf_frame) ) constraint_id = self.add_constraint(constraint) return constraint_id @@ -266,56 +320,6 @@ def remove_constraint(self, constraint_id) -> None: """ pass - def get_joint_limits(self, obj: Object, joint_name: str) -> Tuple[float, float]: - """ - Get the joint limits of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: A tuple containing the upper and the lower limits of the joint respectively. - """ - return self.get_joint_upper_limit(obj, joint_name), self.get_joint_lower_limit(obj, joint_name) - - def get_joint_upper_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint upper limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint upper limit as a float. - """ - raise NotImplementedError - - def get_joint_lower_limit(self, obj: Object, joint_name: str) -> float: - """ - Get the joint lower limit of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The joint lower limit as a float. - """ - raise NotImplementedError - - def get_joint_axis(self, obj: Object, joint_name: str) -> Tuple[float]: - """ - Returns the axis along/around which a joint is moving. The given joint_name has to be part of this object. - - :param obj: The object. - :param joint_name: Name of the joint for which the axis should be returned. - :return: The axis which is a 3D vector of xyz values. - """ - raise NotImplementedError - - def get_joint_type(self, obj: Object, joint_name: str) -> JointType: - """ - Returns the type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - - :param obj: The object. - :param joint_name: Joint name for which the type should be returned. - :return: The type of the joint as element of the Enum :mod:`~pycram.enums.JointType`. - """ - raise NotImplementedError - @abstractmethod def get_joint_position(self, obj: Object, joint_name: str) -> float: """ @@ -402,58 +406,6 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> """ pass - def get_joint_rest_position(self, obj: Object, joint_name: str) -> float: - """ - Get the rest pose of a joint of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The rest pose of the joint. - """ - pass - - def get_joint_damping(self, obj: Object, joint_name: str) -> float: - """ - Get the damping of a joint of an articulated object - - :param obj: The object. - :param joint_name: The name of the joint. - :return: The damping of the joint. - """ - pass - - def get_joint_names(self, obj: Object) -> List[str]: - """ - Get the names of all joints of an articulated object. - :param obj: The object. - :return: A list of all joint names of the object. - """ - raise NotImplementedError - - def get_link_names(self, obj: Object) -> List[str]: - """ - Get the names of all links of an articulated object. - :param obj: The object. - :return: A list of all link names of the object. - """ - raise NotImplementedError - - def get_number_of_joints(self, obj: Object) -> int: - """ - Get the number of joints of an articulated object - :param obj: The object. - :return: The number of joints of the object. - """ - raise NotImplementedError - - def get_number_of_links(self, obj: Object) -> int: - """ - Get the number of links of an articulated object - :param obj: The object. - :return: The number of links of the object. - """ - raise NotImplementedError - @abstractmethod def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ @@ -483,22 +435,6 @@ def step(self): """ pass - def set_object_color(self, obj: Object, rgba_color: Color): - """ - Changes the color of this object, the color has to be given as a list - of RGBA values. - - :param obj: The object which should be colored - :param rgba_color: The color as Color object with RGBA values between 0 and 1 - """ - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if obj.links != {}: - for link in obj.links.values(): - self.set_link_color(link, rgba_color) - else: - self.set_link_color(obj.get_root_link(), rgba_color) - @abstractmethod def set_link_color(self, link: Link, rgba_color: Color): """ @@ -518,27 +454,6 @@ def get_link_color(self, link: Link) -> Color: """ pass - def get_object_color(self, obj: Object) -> Union[Color, Dict[str, Color]]: - """ - This method returns the rgba_color of this object. The return is either: - - 1. A Color object with RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. - Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which - the object is spawned. - - :param obj: The object for which the rgba_color should be returned. - :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and - the rgba_color as value. - """ - link_to_color_dict = self.get_colors_of_object_links(obj) - - if len(link_to_color_dict) == 1: - return list(link_to_color_dict.values())[0] - else: - return link_to_color_dict - @abstractmethod def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: """ @@ -691,17 +606,25 @@ def terminate_world_sync(self) -> None: self.world_sync.terminate = True self.world_sync.join() - def save_state(self) -> int: + def save_state(self, state_id: Optional[int] = None) -> int: """ Returns the id of the saved state of the World. The saved state contains the states of all the objects and the state of the physics simulator. :return: A unique id of the state """ + return self.current_state.state_id + + @property + def current_state(self) -> WorldState: state_id = self.save_physics_simulator_state() self.save_objects_state(state_id) self.saved_states.append(state_id) - return state_id + return WorldState(state_id) + + @current_state.setter + def current_state(self, state: WorldState) -> None: + self.restore_state(state.state_id) def save_objects_state(self, state_id: int) -> None: """ @@ -857,7 +780,7 @@ def remove_saved_states(self) -> None: """ for state_id in self.saved_states: self.remove_physics_simulator_state(state_id) - self.saved_states = [] + super().remove_saved_states() def update_transforms_for_objects_in_current_world(self) -> None: """ @@ -1183,1239 +1106,1510 @@ def check_for_equal(self) -> None: self.equal_states = eql -class Joint: +class WorldEntity(StateEntity, ABC): """ - Represents a joint of an Object in the World. + A data class that represents an entity of the world, such as an object or a link. """ - urdf_joint_types_mapping = {'unknown': JointType.UNKNOWN, - 'revolute': JointType.REVOLUTE, - 'continuous': JointType.CONTINUOUS, - 'prismatic': JointType.PRISMATIC, - 'floating': JointType.FLOATING, - 'planar': JointType.PLANAR, - 'fixed': JointType.FIXED} - def __init__(self, _id: int, - urdf_joint: urdf_parser_py.urdf.Joint, - obj: Object): - self.id: int = _id - self.urdf_joint: urdf_parser_py.urdf.Joint = urdf_joint - self.object: Object = obj - self.world: World = obj.world - self.saved_states: Dict[int, JointState] = {} - self._update_position() + def __init__(self, _id: int, world: Optional[World] = None): + StateEntity.__init__(self) + self.id = _id + self.world: World = world if world is not None else World.current_world - def _update_position(self) -> None: - """ - Updates the current position of the joint from the physics simulator. - """ - self._current_position = self.world.get_joint_position(self.object, self.name) - @property - def parent_link(self) -> Link: - """ - Returns the parent link of this joint. - :return: The parent link as a Link object. +class Object(WorldEntity): + """ + Represents a spawned Object in the World. + """ + object_description: ObjectDescription + prospection_world_prefix: str = "prospection/" + """ + The ObjectDescription of the object, this contains the name and type of the object as well as the path to the source + file. + """ + def __init__(self, name: str, obj_type: ObjectType, path: str, + pose: Optional[Pose] = None, + world: Optional[World] = None, + color: Optional[Color] = Color(), + ignore_cached_files: Optional[bool] = False): """ - return self.object.links[self.urdf_joint.parent.name] + The constructor loads the urdf file into the given World, if no World is specified the + :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. + The rgba_color parameter is only used when loading .stl or .obj files, + for URDFs :func:`~Object.set_color` can be used. - @property - def child_link(self) -> Link: - """ - Returns the child link of this joint. - :return: The child link as a Link object. + :param name: The name of the object + :param obj_type: The type of the object as an ObjectType enum. + :param path: The path to the source file, if only a filename is provided then the resourcer directories will be + searched + :param pose: The pose at which the Object should be spawned + :param world: The World in which the object should be spawned, + if no world is specified the :py:attr:`~World.current_world` will be used. + :param color: The rgba_color with which the object should be spawned. + :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ - return self.object.links[self.urdf_joint.child.name] - @property - def has_limits(self) -> bool: - """ - Checks if this joint has limits. - :return: True if the joint has limits, False otherwise. - """ - return bool(self.urdf_joint.limit) + if pose is None: + pose = Pose() - @property - def limits(self) -> Tuple[float, float]: - """ - Returns the lower and upper limit of a joint, if the lower limit is higher - than the upper they are swapped to ensure the lower limit is always the smaller one. - :return: A tuple with the lower and upper joint limits. - """ - lower, upper = self.lower_limit, self.upper_limit - if lower > upper: - lower, upper = upper, lower - return lower, upper + self.name: str = name + self.obj_type: ObjectType = obj_type + self.color: Color = color - @property - def upper_limit(self) -> float: - """ - Returns the upper joint limit of this joint. - :return: The upper joint limit as a float. - """ - return self.urdf_joint.limit.upper + self.local_transformer = LocalTransformer() + self.original_pose = self.local_transformer.transform_pose(pose, "map") + self._current_pose = self.original_pose - @property - def lower_limit(self) -> float: - """ - Returns the lower joint limit of this joint. - :return: The lower joint limit as a float. - """ - return self.urdf_joint.limit.lower + _id, self.path = self._load_object_and_get_id(path, ignore_cached_files) - @property - def axis(self) -> Point: - """ - Returns the joint axis of this joint. - :return: The joint axis as a Point object. - """ - return Point(*self.urdf_joint.axis) + super().__init__(_id, world) - @property - def type(self) -> JointType: - """ - Returns the joint type of this joint. - :return: The joint type as a JointType object. - """ - return self.urdf_joint_types_mapping[self.urdf_joint.type] + self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + + f"{self.name}_{self.id}") - @property - def position(self) -> float: - return self._current_position + # self.object_description = ObjectDescription(self.path) - @property - def rest_position(self) -> float: - return self.world.get_joint_rest_position(self.object, self.name) + if self.object_description.name == robot_description.name: + self.world.set_robot_if_not_set(self) - @property - def damping(self) -> float: - """ - Returns the damping of this joint. - :return: The damping as a float. - """ - return self.urdf_joint.dynamics.damping + self._init_joint_name_and_id_map() + self._init_link_name_and_id_map() - @property - def name(self) -> str: - """ - Returns the name of this joint. - :return: The name of this joint as a string. - """ - return self.urdf_joint.name + self._init_links_and_update_transforms() + self._init_joints() - def reset_position(self, position: float) -> None: - self.world.reset_joint_position(self.object, self.name, position) - self._update_position() + self.attachments: Dict[Object, Attachment] = {} + self.saved_states: Dict[int, ObjectState] = {} - def get_object_id(self) -> int: - """ - Returns the id of the object to which this joint belongs. - :return: The integer id of the object to which this joint belongs. - """ - return self.object.id + if not self.world.is_prospection_world: + self._add_to_world_sync_obj_queue(self.path) - @position.setter - def position(self, joint_position: float) -> None: - """ - Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. + self.world.objects.append(self) - :param joint_position: The target pose for this joint + def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: """ - # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - if self.has_limits: - low_lim, up_lim = self.limits - if not low_lim <= joint_position <= up_lim: - logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" - f" are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_position}") - # Temporarily disabled because kdl outputs values exciting joint limits - # return - self.reset_position(joint_position) - - def enable_force_torque_sensor(self) -> None: - self.world.enable_joint_force_torque_sensor(self.object, self.id) - - def disable_force_torque_sensor(self) -> None: - self.world.disable_joint_force_torque_sensor(self.object, self.id) - - def get_reaction_force_torque(self) -> List[float]: - return self.world.get_joint_reaction_force_torque(self.object, self.id) - - def get_applied_motor_torque(self) -> float: - return self.world.get_applied_joint_motor_torque(self.object, self.id) + Loads an object to the given World with the given position and orientation. The rgba_color will only be + used when an .obj or .stl file is given. + If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created + and this URDf file will be loaded instead. + When spawning a URDf file a new file will be created in the cache directory, if there exists none. + This new file will have resolved mesh file paths, meaning there will be no references + to ROS packges instead there will be absolute file paths. - def save_state(self, state_id: int) -> None: - self.saved_states[state_id] = self.state + :param ignore_cached_files: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path of the file that was loaded. + """ - def restore_state(self, state_id: int) -> None: - self.state = self.saved_states[state_id] + path = self.sync_cache_dir(path, ignore_cached_files) - def remove_saved_states(self) -> None: - self.saved_states = {} + try: + obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), + self.get_orientation_as_list())) + return obj_id, path + except Exception as e: + logging.error( + "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" + " the name of an URDF string on the parameter server.") + os.remove(path) + raise (e) - @property - def state(self) -> JointState: - return JointState(self.position) + def sync_cache_dir(self, path: str, ignore_cached_files: bool) -> str: + """ + Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + """ + path_object = pathlib.Path(path) + extension = path_object.suffix - @state.setter - def state(self, joint_state: JointState) -> None: - self.position = joint_state.position + path = _look_for_file_in_data_dir(path, path_object) + _create_cache_dir_if_not_exists() -class Link: - """ - Represents a link of an Object in the World. - """ + # if file is not yet cached preprocess the description file and save it in the cache directory. + if not _is_cached(path) or ignore_cached_files: + if extension == ".obj": + path = ObjectDescription.generate_from_obj_file(path) + elif extension == ".stl": + path = ObjectDescription.generate_from_stl_file(path) + elif extension == ObjectDescription.file_extension: + description_string = ObjectDescription.preprocess_file(path) + path = World.cache_dir + path_object.name + with open(path, mode="w") as f: + f.write(description_string) + else: # Using the description from the parameter server + description_string = ObjectDescription.preprocess_from_parameter_server(path) + path = f"{World.cache_dir}{self.name}{ObjectDescription.file_extension}" + with open(path, mode="w") as f: + f.write(description_string) + # save correct path in case the file is already in the cache directory + elif extension == ".obj" or extension == ".stl": + path = World.cache_dir + path_object.stem + ObjectDescription.file_extension + elif extension == ObjectDescription.file_extension: + path = World.cache_dir + path_object.name + else: + path = World.cache_dir + self.name + ObjectDescription.file_extension - def __init__(self, - _id: int, - urdf_link: urdf_parser_py.urdf.Link, - obj: Object): - self.id: int = _id - self.urdf_link: urdf_parser_py.urdf.Link = urdf_link - self.object: Object = obj - self.world: World = obj.world - self.local_transformer: LocalTransformer = LocalTransformer() - self.constraint_ids: Dict[Link, int] = {} - self.saved_states: Dict[int, LinkState] = {} - self._update_pose() + return path - def save_state(self, state_id: int) -> None: + def _init_joint_name_and_id_map(self) -> None: """ - Saves the state of this link. - :param state_id: The unique id of the state. + Creates a dictionary which maps the joint names to their unique ids and vice versa. """ - self.saved_states[state_id] = self.get_current_state() + n_joints = len(self.joint_names) + self.joint_name_to_id = dict(zip(self.joint_names, range(n_joints))) + self.joint_id_to_name = dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys())) - def restore_state(self, state_id: int) -> None: + def _init_link_name_and_id_map(self) -> None: """ - Restores the state of this link. - :param state_id: The unique id of the state. + Creates a dictionary which maps the link names to their unique ids and vice versa. """ - self.constraint_ids = self.saved_states[state_id].constraint_ids + n_links = len(self.link_names) + self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) + self.link_name_to_id[self.object_description.get_root()] = -1 + self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) - def remove_saved_states(self) -> None: + def _init_links_and_update_transforms(self) -> None: """ - Removes all saved states of this link. + Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the + corresponding link objects. """ - self.saved_states = {} + self.links = {} + for link_description in self.object_description.links: + link_name = link_description.name + link_id = self.link_name_to_id[link_name] + if link_name == self.object_description.get_root(): + self.links[link_name] = RootLink(self) + else: + self.links[link_name] = Link(link_id, link_description, self) - def get_current_state(self) -> LinkState: - """ - :return: The current state of this link as a LinkState object. - """ - return LinkState(self.constraint_ids.copy()) + self.update_link_transforms() - def add_fixed_constraint_with_link(self, child_link: Link) -> int: + def _init_joints(self): """ - Adds a fixed constraint between this link and the given link, used to create attachments for example. - :param child_link: The child link to which a fixed constraint should be added. - :return: The unique id of the constraint. + Initialize the joint objects from the URDF file and creates a dictionary which mas the joint names to the + corresponding joint objects """ - constraint_id = self.world.add_fixed_constraint(self, - child_link, - child_link.get_transform_from_link(self)) - self.constraint_ids[child_link] = constraint_id - child_link.constraint_ids[self] = constraint_id - return constraint_id + self.joints = {} + for joint_description in self.object_description.joints: + joint_name = joint_description.name + joint_id = self.joint_name_to_id[joint_name] + self.joints[joint_name] = Joint(joint_id, joint_description, self) - def remove_constraint_with_link(self, child_link: Link) -> None: + def _add_to_world_sync_obj_queue(self, path: str) -> None: """ - Removes the constraint between this link and the given link. - :param child_link: The child link of the constraint that should be removed. + Adds this object to the objects queue of the WorldSync object of the World. + :param path: The path of the URDF file of this object. """ - self.world.remove_constraint(self.constraint_ids[child_link]) - del self.constraint_ids[child_link] - del child_link.constraint_ids[self] + self.world.world_sync.add_obj_queue.put( + [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), + self.world.prospection_world, self.color, self]) - def get_object_id(self) -> int: + @property + def link_names(self) -> List[str]: """ - Returns the id of the object to which this link belongs. - :return: The integer id of the object to which this link belongs. + :return: The name of each link as a list. """ - return self.object.id + return [link.name for link in self.object_description.links] @property - def tf_frame(self) -> str: + def joint_names(self) -> List[str]: """ - Returns the tf frame of this link. - :return: The tf frame of this link as a string. + :return: The name of each joint as a list. """ - return f"{self.object.tf_frame}/{self.urdf_link.name}" + return [joint.name for joint in self.object_description.joints] @property - def is_root(self) -> bool: + def base_origin_shift(self) -> np.ndarray: """ - Returns whether this link is the root link of the object. - :return: True if this link is the root link, False otherwise. + The shift between the base of the object and the origin of the object. + :return: A numpy array with the shift between the base of the object and the origin of the object. """ - return self.object.get_root_link_id() == self.id + return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) - def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: + def __repr__(self): + skip_attr = ["links", "joints", "object_description", "attachments"] + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" + + def remove(self) -> None: """ - Updates the transformation of this link at the given time. - :param transform_time: The time at which the transformation should be updated. + Removes this object from the World it currently resides in. + For the object to be removed it has to be detached from all objects it + is currently attached to. After this is done a call to world remove object is done + to remove this Object from the simulation/world. """ - self.local_transformer.update_transforms([self.transform], transform_time) + self.world.remove_object(self) - @property - def transform(self) -> Transform: + def reset(self, remove_saved_states=True) -> None: """ - The transformation from the world frame to this link frame. - :return: A Transform object with the transformation from the world frame to this link frame. + Resets the Object to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and the object will be set to the position and + orientation in which it was spawned. + :param remove_saved_states: If True the saved states will be removed. """ - return self.pose.to_transform(self.tf_frame) + self.detach_all() + self.reset_all_joints_positions() + self.set_pose(self.original_pose) + if remove_saved_states: + self.saved_states = {} - def get_transform_to_link(self, link: Link) -> Transform: + def attach(self, + child_object: Object, + parent_link: Optional[str] = None, + child_link: Optional[str] = None, + bidirectional: Optional[bool] = True) -> None: """ - Returns the transformation from this link to the given link. - :param link: The link to which the transformation should be returned. - :return: A Transform object with the transformation from this link to the given link. + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a simulator constraint will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. For example, if this object moves the + other, attached, object will also move but not the other way around. + + :param child_object: The other object that should be attached. + :param parent_link: The link name of this object. + :param child_link: The link name of the other object. + :param bidirectional: If the attachment should be a loose attachment. """ - return link.get_transform_from_link(self) + parent_link = self.links[parent_link] if parent_link else self.root_link + child_link = child_object.links[child_link] if child_link else child_object.root_link - def get_transform_from_link(self, link: Link) -> Transform: + attachment = Attachment(parent_link, child_link, bidirectional) + + self.attachments[child_object] = attachment + child_object.attachments[self] = attachment.get_inverse() + + self.world.attachment_event(self, [self, child_object]) + + def detach(self, child_object: Object) -> None: """ - Returns the transformation from the given link to this link. - :param link: The link from which the transformation should be returned. - :return: A Transform object with the transformation from the given link to this link. + Detaches another object from this object. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of the simulator. + Afterward the detachment event of the corresponding World will be fired. + + :param child_object: The object which should be detached """ - return self.get_pose_wrt_link(link).to_transform(self.tf_frame) + del self.attachments[child_object] + del child_object.attachments[self] - def get_pose_wrt_link(self, link: Link) -> Pose: + self.world.detachment_event(self, [self, child_object]) + + def detach_all(self) -> None: """ - Returns the pose of this link with respect to the given link. - :param link: The link with respect to which the pose should be returned. - :return: A Pose object with the pose of this link with respect to the given link. + Detach all objects attached to this object. """ - return self.local_transformer.transform_pose(self.pose, link.tf_frame) + attachments = self.attachments.copy() + for att in attachments.keys(): + self.detach(att) - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + def update_attachment_with_object(self, child_object: Object): + self.attachments[child_object].update_transform_and_constraint() + + def get_position(self) -> Point: """ - Returns the axis aligned bounding box of this link. - :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. + Returns the position of this Object as a list of xyz. + + :return: The current position of this object """ - return self.world.get_link_axis_aligned_bounding_box(self) + return self.get_pose().position - @property - def position(self) -> Point: + def get_orientation(self) -> Pose.orientation: """ - The getter for the position of the link relative to the world frame. - :return: A Point object containing the position of the link relative to the world frame. + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw """ - return self.pose.position + return self.get_pose().orientation - @property - def position_as_list(self) -> List[float]: + def get_position_as_list(self) -> List[float]: """ - The getter for the position of the link relative to the world frame as a list. - :return: A list containing the position of the link relative to the world frame. + Returns the position of this Object as a list of xyz. + + :return: The current position of this object """ - return self.pose.position_as_list() + return self.get_pose().position_as_list() - @property - def orientation(self) -> Quaternion: + def get_orientation_as_list(self) -> List[float]: """ - The getter for the orientation of the link relative to the world frame. - :return: A Quaternion object containing the orientation of the link relative to the world frame. + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw """ - return self.pose.orientation + return self.get_pose().orientation_as_list() - @property - def orientation_as_list(self) -> List[float]: + def get_pose(self) -> Pose: """ - The getter for the orientation of the link relative to the world frame as a list. - :return: A list containing the orientation of the link relative to the world frame. + Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. + + :return: The current pose of this object """ - return self.pose.orientation_as_list() + return self._current_pose - def _update_pose(self) -> None: + def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Optional[bool] = True) -> None: """ - Updates the current pose of this link from the world. + Sets the Pose of the object. + + :param pose: New Pose for the object + :param base: If True places the object base instead of origin at the specified position and orientation + :param set_attachments: Whether to set the poses of the attached objects to this object or not. """ - self._current_pose = self.world.get_link_pose(self) + pose_in_map = self.local_transformer.transform_pose(pose, "map") + if base: + pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift - @property - def pose(self) -> Pose: + self.reset_base_pose(pose_in_map) + + if set_attachments: + self._set_attached_objects_poses() + + def reset_base_pose(self, pose: Pose): + self.world.reset_object_base_pose(self, pose) + self.update_pose() + + def update_pose(self): """ - The pose of the link relative to the world frame. - :return: A Pose object containing the pose of the link relative to the world frame. + Updates the current pose of this object from the world. """ - return self._current_pose + self._current_pose = self.world.get_object_pose(self) + self._update_all_joints_positions() + self._update_all_links_poses() + self.update_link_transforms() - @property - def pose_as_list(self) -> List[List[float]]: + def _update_all_joints_positions(self): """ - The pose of the link relative to the world frame as a list. - :return: A list containing the position and orientation of the link relative to the world frame. + Updates the posisitons of all joints by getting them from the simulator. """ - return self.pose.to_list() + for joint in self.joints.values(): + joint._update_position() - @property - def name(self) -> str: + def _update_all_links_poses(self): """ - The name of the link as defined in the URDF. - :return: The name of the link as a string. + Updates the poses of all links by getting them from the simulator. """ - return self.urdf_link.name + for link in self.links.values(): + link._update_pose() - def get_geometry(self) -> GeometricType: + def move_base_to_origin_pos(self) -> None: """ - Returns the geometry type of the URDF collision element of this link. + Move the object such that its base will be at the current origin position. + This is useful when placing objects on surfaces where you want the object base in contact with the surface. """ - return None if not self.collision else self.collision.geometry + self.set_pose(self.get_pose(), base=True) - def get_origin_transform(self) -> Transform: + def save_state(self, state_id) -> None: """ - Returns the transformation between the link frame and the origin frame of this link. + Saves the state of this object by saving the state of all links and attachments. + :param state_id: The unique id of the state. """ - return Transform(self.origin.xyz, list(quaternion_from_euler(*self.origin.rpy))) + self.save_links_states(state_id) + self.save_joints_states(state_id) + self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) - @property - def origin(self) -> urdf_parser_py.urdf.Pose: + def save_links_states(self, state_id: int) -> None: """ - The URDF origin pose of this link. - :return: A '~urdf_parser_py.urdf.Pose' object containing the origin pose of this link. + Saves the state of all links of this object. + :param state_id: The unique id of the state. """ - return self.collision.origin + for link in self.links.values(): + link.save_state(state_id) - @property - def collision(self) -> Collision: + def save_joints_states(self, state_id: int) -> None: """ - The URDF collision element of this link which has a geometry, and origin. - :return: A '~urdf_parser_py.urdf.Collision' object containing the collision element of this link. + Saves the state of all joints of this object. + :param state_id: The unique id of the state. """ - return self.urdf_link.collision + for joint in self.joints.values(): + joint.save_state(state_id) - @property - def color(self) -> Color: + def restore_state(self, state_id: int) -> None: """ - The getter for the rgba_color of this link. - :return: A Color object containing the rgba_color of this link. + Restores the state of this object by restoring the state of all links and attachments. + :param state_id: The unique id of the state. """ - return self.world.get_link_color(self) + self.restore_attachments(state_id) + self.restore_links_states(state_id) + self.restore_joints_states(state_id) - @color.setter - def color(self, color: List[float]) -> None: + def restore_attachments(self, state_id: int) -> None: """ - The setter for the color of this link, could be rgb or rgba. - :param color: The color as a list of floats, either rgb or rgba. + Restores the attachments of this object from a saved state using the given state id. + :param state_id: The unique id of the state. """ - self.world.set_link_color(self, Color.from_list(color)) + self.attachments = self.saved_states[state_id].attachments + def restore_links_states(self, state_id: int) -> None: + """ + Restores the states of all links of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + for link in self.links.values(): + link.restore_state(state_id) -class RootLink(Link): - """ - Represents the root link of an Object in the World. - It differs from the normal Link class in that the pose ande the tf_frame is the same as that of the object. - """ + def restore_joints_states(self, state_id: int) -> None: + """ + Restores the states of all joints of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + for joint in self.joints.values(): + joint.restore_state(state_id) - def __init__(self, obj: Object): - super().__init__(obj.get_root_link_id(), obj.get_root_urdf_link(), obj) + def remove_saved_states(self) -> None: + """ + Removes all saved states of this object. + """ + self.saved_states = {} + self.remove_links_saved_states() + self.remove_joints_saved_states() + + def remove_links_saved_states(self) -> None: + """ + Removes all saved states of the links of this object. + """ + for link in self.links.values(): + link.remove_saved_states() + + def remove_joints_saved_states(self) -> None: + """ + Removes all saved states of the joints of this object. + """ + for joint in self.joints.values(): + joint.remove_saved_states() + + def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent + loops in the update. + """ + + if already_moved_objects is None: + already_moved_objects = [] + + for child in self.attachments: + + if child in already_moved_objects: + continue + + attachment = self.attachments[child] + if not attachment.bidirectional: + self.update_attachment_with_object(child) + child.update_attachment_with_object(self) + + else: + link_to_object = attachment.parent_to_child_transform + child.set_pose(link_to_object.to_pose(), set_attachments=False) + child._set_attached_objects_poses(already_moved_objects + [self]) + + def set_position(self, position: Union[Pose, Point], base=False) -> None: + """ + Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position + instead of the origin in the center of the Object. The given position can either be a Pose, + in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + + :param position: Target position as xyz. + :param base: If the bottom of the Object should be placed or the origin in the center. + """ + pose = Pose() + if isinstance(position, Pose): + target_position = position.position + pose.frame = position.frame + elif isinstance(position, Point): + target_position = position + elif isinstance(position, list): + target_position = position + else: + raise TypeError("The given position has to be a Pose, Point or a list of xyz.") + + pose.position = target_position + pose.orientation = self.get_orientation() + self.set_pose(pose, base=base) + + def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: + """ + Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only + the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. + + :param orientation: Target orientation given as a list of xyzw. + """ + pose = Pose() + if isinstance(orientation, Pose): + target_orientation = orientation.orientation + pose.frame = orientation.frame + else: + target_orientation = orientation + + pose.pose.position = self.get_position() + pose.pose.orientation = target_orientation + self.set_pose(pose) + + def get_joint_id(self, name: str) -> int: + """ + Returns the unique id for a joint name. As used by the world/simulator. + + :param name: The joint name + :return: The unique id + """ + return self.joint_name_to_id[name] + + def get_root_link_description(self) -> LinkDescription: + """ + Returns the root link of the URDF of this object. + :return: The root link as defined in the URDF of this object. + """ + root_link_name = self.object_description.get_root() + for link_description in self.object_description.links: + if link_description.name == root_link_name: + return link_description @property - def tf_frame(self) -> str: + def root_link(self) -> Link: """ - Returns the tf frame of the root link, which is the same as the tf frame of the object. - :return: A string containing the tf frame of the root link. + Returns the root link of this object. + :return: The root link of this object. """ - return self.object.tf_frame + return self.links[self.object_description.get_root()] - def _update_pose(self) -> None: - self._current_pose = self.object.get_pose() + def get_root_link_id(self) -> int: + """ + Returns the unique id of the root link of this object. + :return: The unique id of the root link of this object. + """ + return self.get_link_id(self.object_description.get_root()) + def get_link_id(self, link_name: str) -> int: + """ + Returns a unique id for a link name. + :param link_name: The name of the link. + :return: The unique id of the link. + """ + assert link_name is not None + return self.link_name_to_id[link_name] -class Object: - """ - Represents a spawned Object in the World. - """ + def get_link_by_id(self, link_id: int) -> Link: + """ + Returns the link for a given unique link id + :param link_id: The unique id of the link. + :return: The link object. + """ + return self.links[self.link_id_to_name[link_id]] - def __init__(self, name: str, obj_type: ObjectType, path: str, - pose: Optional[Pose] = None, - world: Optional[World] = None, - color: Optional[Color] = Color(), - ignore_cached_files: Optional[bool] = False): + def get_joint_by_id(self, joint_id: int) -> str: """ - The constructor loads the urdf file into the given World, if no World is specified the - :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. - The rgba_color parameter is only used when loading .stl or .obj files, - for URDFs :func:`~Object.set_color` can be used. + Returns the joint name for a unique world id - :param name: The name of the object - :param obj_type: The type of the object as an ObjectType enum. - :param path: The path to the source file, if only a filename is provided then the resourcer directories will be - searched - :param pose: The pose at which the Object should be spawned - :param world: The World in which the object should be spawned, - if no world is specified the :py:attr:`~World.current_world` will be used. - :param color: The rgba_color with which the object should be spawned. - :param ignore_cached_files: If true the file will be spawned while ignoring cached files. + :param joint_id: The world id of for joint + :return: The joint name """ + return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] - if pose is None: - pose = Pose() + def reset_all_joints_positions(self) -> None: + """ + Sets the current position of all joints to 0. This is useful if the joints should be reset to their default + """ + joint_names = list(self.joint_name_to_id.keys()) + joint_positions = [0] * len(joint_names) + self.set_joint_positions(dict(zip(joint_names, joint_positions))) - self.world: World = world if world is not None else World.current_world + def set_joint_positions(self, joint_poses: dict) -> None: + """ + Sets the current position of multiple joints at once, this method should be preferred when setting + multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. - self.name: str = name - self.obj_type: ObjectType = obj_type - self.color: Color = color + :param joint_poses: + """ + for joint_name, joint_position in joint_poses.items(): + self.joints[joint_name].position = joint_position + self.update_pose() + self._set_attached_objects_poses() - self.local_transformer = LocalTransformer() - self.original_pose = self.local_transformer.transform_pose(pose, "map") - self._current_pose = self.original_pose + def set_joint_position(self, joint_name: str, joint_position: float) -> None: + """ + Sets the position of the given joint to the given joint pose and updates the poses of all attached objects. - self.id, self.path = self._load_object_and_get_id(path, ignore_cached_files) + :param joint_name: The name of the joint + :param joint_position: The target pose for this joint + """ + self.joints[joint_name].position = joint_position + self._update_all_links_poses() + self.update_link_transforms() + self._set_attached_objects_poses() - self.tf_frame = ("prospection/" if self.world.is_prospection_world else "") + self.name + "_" + str(self.id) + def get_joint_position(self, joint_name: str) -> float: + return self.joints[joint_name].position - self._init_urdf_object() + def get_joint_damping(self, joint_name: str) -> float: + return self.joints[joint_name].damping - if self.urdf_object.name == robot_description.name: - self.world.set_robot_if_not_set(self) + def get_joint_upper_limit(self, joint_name: str) -> float: + return self.joints[joint_name].upper_limit - self._init_joint_name_and_id_map() - self._init_link_name_and_id_map() + def get_joint_lower_limit(self, joint_name: str) -> float: + return self.joints[joint_name].lower_limit - self._init_links_and_update_transforms() - self._init_joints() + def get_joint_axis(self, joint_name: str) -> Point: + return self.joints[joint_name].axis - self.attachments: Dict[Object, Attachment] = {} - self.saved_states: Dict[int, ObjectState] = {} + def get_joint_type(self, joint_name: str) -> JointType: + return self.joints[joint_name].type - if not self.world.is_prospection_world: - self._add_to_world_sync_obj_queue(self.path) + def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: + return self.joints[joint_name].limits - self.world.objects.append(self) + def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + """ + Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. - def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: + :param link_name: Link name above which the joint should be found + :param joint_type: Joint type that should be searched for + :return: Name of the first joint which has the given type """ - Loads an object to the given World with the given position and orientation. The rgba_color will only be - used when an .obj or .stl file is given. - If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created - and this URDf file will be loaded instead. - When spawning a URDf file a new file will be created in the cache directory, if there exists none. - This new file will have resolved mesh file paths, meaning there will be no references - to ROS packges instead there will be absolute file paths. + chain = self.object_description.get_chain(self.object_description.get_root(), link_name) + reversed_chain = reversed(chain) + container_joint = None + for element in reversed_chain: + if element in self.joint_name_to_id and self.get_joint_type(element) == joint_type: + container_joint = element + break + if not container_joint: + rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") + return container_joint - :param ignore_cached_files: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path of the file that was loaded. + def get_positions_of_all_joints(self) -> Dict[str: float]: """ - pa = pathlib.Path(path) - extension = pa.suffix - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for data_dir in World.data_directory: - path = get_path_from_data_dir(path, data_dir) - if path: - break + Returns the positions of all joints of the object as a dictionary of joint names and joint positions. - if not path: - raise FileNotFoundError( - f"File {pa.name} could not be found in the resource directory {World.data_directory}") - if not pathlib.Path(World.cach_dir).exists(): - os.mkdir(World.cach_dir) + :return: A dictionary with all joints positions'. + """ + return {j.name: j.position for j in self.joints.values()} - # if file is not yet cached corrcet the urdf and save if in the cache directory - if not _is_cached(path) or ignore_cached_files: - if extension == ".obj" or extension == ".stl": - path = self._generate_urdf_file(path) - elif extension == ".urdf": - with open(path, mode="r") as f: - urdf_string = fix_missing_inertial(f.read()) - urdf_string = remove_error_tags(urdf_string) - urdf_string = fix_link_attributes(urdf_string) - try: - urdf_string = _correct_urdf_string(urdf_string) - except rospkg.ResourceNotFound as e: - rospy.logerr(f"Could not find resource package linked in this URDF") - raise e - path = World.cach_dir + pa.name - with open(path, mode="w") as f: - f.write(urdf_string) - else: # Using the urdf from the parameter server - urdf_string = rospy.get_param(path) - path = World.cach_dir + self.name + ".urdf" - with open(path, mode="w") as f: - f.write(_correct_urdf_string(urdf_string)) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = World.cach_dir + pa.stem + ".urdf" - elif extension == ".urdf": - path = World.cach_dir + pa.name + def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: + """ + Updates the transforms of all links of this object using time 'transform_time' or the current ros time. + """ + for link in self.links.values(): + link.update_transform(transform_time) + + def contact_points(self) -> List: + """ + Returns a list of contact points of this Object with other Objects. + + :return: A list of all contact points with other objects + """ + return self.world.get_object_contact_points(self) + + def contact_points_simulated(self) -> List: + """ + Returns a list of all contact points between this Object and other Objects after stepping the simulation once. + + :return: A list of contact points between this Object and other Objects + """ + state_id = self.world.save_state() + self.world.step() + contact_points = self.contact_points() + self.world.restore_state(state_id) + return contact_points + + def set_color(self, rgba_color: Color) -> None: + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. + + :param rgba_color: The color as Color object with RGBA values between 0 and 1 + """ + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if self.links != {}: + for link in self.links.values(): + link.color = rgba_color + else: + self.root_link.color = rgba_color + + def get_color(self) -> Union[Color, Dict[str, Color]]: + """ + This method returns the rgba_color of this object. The return is either: + + 1. A Color object with RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. + Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which + the object is spawned. + + :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and + the rgba_color as value. + """ + link_to_color_dict = self.links_colors + + if len(link_to_color_dict) == 1: + return list(link_to_color_dict.values())[0] else: - path = World.cach_dir + self.name + ".urdf" + return link_to_color_dict + + @property + def links_colors(self) -> Dict[str, Color]: + """ + The color of each link as a dictionary with link names as keys and RGBA colors as values. + """ + return self.world.get_colors_of_object_links(self) + + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis aligned bounding box of this object. + """ + return self.world.get_object_axis_aligned_bounding_box(self) + + def get_base_origin(self) -> Pose: + """ + :return: the origin of the base/bottom of this object. + """ + aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() + base_width = np.absolute(aabb.min_x - aabb.max_x) + base_length = np.absolute(aabb.min_y - aabb.max_y) + return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], + self.get_pose().orientation_as_list()) + + +def filter_contact_points(contact_points, exclude_ids) -> List: + """ + Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. + + :param contact_points: A list of contact points + :param exclude_ids: A list of unique ids of Objects that should be removed from the list + :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' + """ + return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) + + +class EntityDescription(ABC): + + @property + @abstractmethod + def origin(self) -> Pose: + """ + Returns the origin of this entity. + """ + pass + + @property + @abstractmethod + def name(self) -> str: + """ + Returns the name of this entity. + """ + pass + - try: - obj_id = self.world.load_urdf_and_get_object_id(path, Pose(self.get_position_as_list(), - self.get_orientation_as_list())) - return obj_id, path - except Exception as e: - logging.error( - "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" - " the name of an URDF string on the parameter server.") - os.remove(path) - raise (e) +class ObjectDescription(EntityDescription): - def _generate_urdf_file(self, path) -> str: - """ - Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be - used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with - the name as filename. - - :return: The absolute path of the created file - """ - urdf_template = ' \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - \n \ - ' - urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, self.color.get_rgba()))) - pathlib_obj = pathlib.Path(path) - path = str(pathlib_obj.resolve()) - content = urdf_template.replace("~a", self.name).replace("~b", path).replace("~c", rgb) - with open(World.cach_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: - file.write(content) - return World.cach_dir + pathlib_obj.stem + ".urdf" - - def _init_urdf_object(self) -> None: - """ - Initializes the URDF object from the URDF file. - """ - with open(self.path) as f: - self.urdf_object = URDF.from_xml_string(f.read()) + file_extension: str - def _init_joint_name_and_id_map(self) -> None: + def __init__(self, path: Any): + self.parsed_description = self.from_description_file(path) + + @abstractmethod + def from_description_file(self, path: str) -> Any: """ - Creates a dictionary which maps the joint names to their unique ids and vice versa. + Return the object parsed from the description file. + :path: The path of the description file. """ - joint_names = self.world.get_joint_names(self) - n_joints = len(joint_names) - self.joint_name_to_id = dict(zip(joint_names, range(n_joints))) - self.joint_id_to_name = dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys())) + pass - def _init_link_name_and_id_map(self) -> None: + @classmethod + @abstractmethod + def generate_from_obj_file(cls, path: str) -> str: """ - Creates a dictionary which maps the link names to their unique ids and vice versa. + Generates a description file from an .obj file and returns the path of the generated file. + :param path: The path to the .obj file. + :return: The path of the generated description file. """ - link_names = self.world.get_link_names(self) - n_links = len(link_names) - self.link_name_to_id: Dict[str, int] = dict(zip(link_names, range(n_links))) - self.link_name_to_id[self.urdf_object.get_root()] = -1 - self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) - def _init_links_and_update_transforms(self) -> None: + @classmethod + @abstractmethod + def generate_from_stl_file(cls, path: str) -> str: """ - Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the - corresponding link objects. + Generates a description file from an .stl file and returns the path of the generated file. + :param path: The path to the .stl file. + :return: The path of the generated description file. """ - self.links = {} - for urdf_link in self.urdf_object.links: - link_name = urdf_link.name - link_id = self.link_name_to_id[link_name] - if link_name == self.urdf_object.get_root(): - self.links[link_name] = RootLink(self) - else: - self.links[link_name] = Link(link_id, urdf_link, self) - - - self.update_link_transforms() + pass - def _init_joints(self): + @classmethod + @abstractmethod + def preprocess_file(cls, path: str) -> str: """ - Initialize the joint objects from the URDF file and creates a dictionary which mas the joint names to the - corresponding joint objects + Preprocesses the given file and returns the preprocessed description string. + :param path: The path of the file to preprocess. + :return: The preprocessed description string. """ - self.joints = {} - for urdf_joint in self.urdf_object.joints: - joint_name = urdf_joint.name - joint_id = self.joint_name_to_id[joint_name] - self.joints[joint_name] = Joint(joint_id, urdf_joint, self) + pass - def _add_to_world_sync_obj_queue(self, path: str) -> None: + @classmethod + @abstractmethod + def preprocess_from_parameter_server(cls, name: str) -> str: """ - Adds this object to the objects queue of the WorldSync object of the World. - :param path: The path of the URDF file of this object. + Preprocesses the description from the ROS parameter server and returns the preprocessed description string. + :param name: The name of the description on the parameter server. + :return: The preprocessed description string. """ - self.world.world_sync.add_obj_queue.put( - [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), - self.world.prospection_world, self.color, self]) + pass @property - def base_origin_shift(self) -> np.ndarray: + @abstractmethod + def links(self) -> List[LinkDescription]: """ - The shift between the base of the object and the origin of the object. - :return: A numpy array with the shift between the base of the object and the origin of the object. + :return: A list of links descriptions of this object. """ - return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) - - def __repr__(self): - skip_attr = ["links", "joints", "urdf_object", "attachments"] - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" + pass - def remove(self) -> None: + @property + @abstractmethod + def joints(self) -> List[JointDescription]: """ - Removes this object from the World it currently resides in. - For the object to be removed it has to be detached from all objects it - is currently attached to. After this is done a call to world remove object is done - to remove this Object from the simulation/world. + :return: A list of joints descriptions of this object. """ - self.world.remove_object(self) + pass - def reset(self, remove_saved_states=True) -> None: + @abstractmethod + def get_root(self) -> str: """ - Resets the Object to the state it was first spawned in. - All attached objects will be detached, all joints will be set to the - default position of 0 and the object will be set to the position and - orientation in which it was spawned. - :param remove_saved_states: If True the saved states will be removed. + :return: the name of the root link of this object. """ - self.detach_all() - self.reset_all_joints_positions() - self.set_pose(self.original_pose) - if remove_saved_states: - self.saved_states = {} + pass - def attach(self, - child_object: Object, - parent_link: Optional[str] = None, - child_link: Optional[str] = None, - bidirectional: Optional[bool] = True) -> None: + @abstractmethod + def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a simulator constraint will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. For example, if this object moves the - other, attached, object will also move but not the other way around. + :return: the chain of links from 'start_link_name' to 'end_link_name'. + """ + pass - :param child_object: The other object that should be attached. - :param parent_link: The link name of this object. - :param child_link: The link name of the other object. - :param bidirectional: If the attachment should be a loose attachment. + +class LinkDescription(EntityDescription): + """ + A class that represents a link description of an object. + """ + + def __init__(self, parsed_link_description: Any): + self.parsed_description = parsed_link_description + + @property + @abstractmethod + def geometry(self) -> Shape: """ - parent_link = self.links[parent_link] if parent_link else self.get_root_link() - child_link = child_object.links[child_link] if child_link else child_object.get_root_link() + Returns the geometry type of the URDF collision element of this link. + """ + pass - attachment = Attachment(parent_link, child_link, bidirectional) - self.attachments[child_object] = attachment - child_object.attachments[self] = attachment.get_inverse() +class JointDescription(EntityDescription): + """ + A class that represents a joint description of a URDF joint. + """ - self.world.attachment_event(self, [self, child_object]) + def __init__(self, parsed_joint_description: Any): + self.parsed_description = parsed_joint_description - def detach(self, child_object: Object) -> None: + @property + @abstractmethod + def type(self) -> JointType: """ - Detaches another object from this object. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of the simulator. - Afterward the detachment event of the corresponding World will be fired. + :return: The type of this joint. + """ + pass - :param child_object: The object which should be detached + @property + @abstractmethod + def axis(self) -> Point: """ - del self.attachments[child_object] - del child_object.attachments[self] + :return: The axis of this joint, for example the rotation axis for a revolute joint. + """ + pass - self.world.detachment_event(self, [self, child_object]) + @property + @abstractmethod + def has_limits(self) -> bool: + """ + Checks if this joint has limits. + :return: True if the joint has limits, False otherwise. + """ + pass - def detach_all(self) -> None: + @property + def limits(self) -> Tuple[float, float]: """ - Detach all objects attached to this object. + :return: The lower and upper limits of this joint. """ - attachments = self.attachments.copy() - for att in attachments.keys(): - self.detach(att) + lower, upper = self.lower_limit, self.upper_limit + if lower > upper: + lower, upper = upper, lower + return lower, upper - def update_attachment_with_object(self, child_object: Object): - self.attachments[child_object].update_transform_and_constraint() + @property + @abstractmethod + def lower_limit(self) -> Union[float, None]: + """ + :return: The lower limit of this joint, or None if the joint has no limits. + """ + pass - def get_position(self) -> Point: + @property + @abstractmethod + def upper_limit(self) -> Union[float, None]: """ - Returns the position of this Object as a list of xyz. + :return: The upper limit of this joint, or None if the joint has no limits. + """ + pass - :return: The current position of this object + @property + @abstractmethod + def parent_link_name(self) -> str: """ - return self.get_pose().position + :return: The name of the parent link of this joint. + """ + pass - def get_orientation(self) -> Pose.orientation: + @property + @abstractmethod + def child_link_name(self) -> str: """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. + :return: The name of the child link of this joint. + """ + pass - :return: A list of xyzw + @property + def damping(self) -> float: """ - return self.get_pose().orientation + :return: The damping of this joint. + """ + raise NotImplementedError - def get_position_as_list(self) -> List[float]: + @property + def friction(self) -> float: """ - Returns the position of this Object as a list of xyz. + :return: The friction of this joint. + """ + raise NotImplementedError - :return: The current position of this object + +class ObjectEntity(WorldEntity): + """ + An abstract base class that represents a physical part/entity of an Object. + This can be a link or a joint of an Object. + """ + + def __init__(self, _id: int, obj: Object): + WorldEntity.__init__(self, _id, obj.world) + self.object: Object = obj + + @property + @abstractmethod + def pose(self) -> Pose: """ - return self.get_pose().position_as_list() + :return: The pose of this entity relative to the world frame. + """ + pass - def get_orientation_as_list(self) -> List[float]: + @property + def transform(self) -> Transform: """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. + Returns the transform of this entity. - :return: A list of xyzw + :return: The transform of this entity. """ - return self.get_pose().orientation_as_list() + return self.pose.to_transform(self.tf_frame) - def get_pose(self) -> Pose: + @property + @abstractmethod + def tf_frame(self) -> str: """ - Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. + Returns the tf frame of this entity. - :return: The current pose of this object + :return: The tf frame of this entity. """ - return self._current_pose + pass - def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Optional[bool] = True) -> None: + @property + def object_id(self) -> int: """ - Sets the Pose of the object. + :return: the id of the object to which this entity belongs. + """ + return self.object.id - :param pose: New Pose for the object - :param base: If True places the object base instead of origin at the specified position and orientation - :param set_attachments: Whether to set the poses of the attached objects to this object or not. + def __repr__(self): + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" for key, value in self.__dict__.items()]) + ")" + + def __str__(self): + return self.__repr__() + + +class AbstractConstraint: + """ + Represents an abstract constraint concept, this could be used to create joints for example or any kind of constraint + between two links in the world. + """ + def __init__(self, + parent_link: Link, + child_link: Link, + _type: JointType, + parent_to_constraint: Transform, + child_to_constraint: Transform): + self.parent_link: Link = parent_link + self.child_link: Link = child_link + self.type: JointType = _type + self.parent_to_constraint = parent_to_constraint + self.child_to_constraint = child_to_constraint + self._parent_to_child = None + + @property + def parent_to_child_transform(self) -> Union[Transform, None]: + if self._parent_to_child is None: + if self.parent_to_constraint is not None and self.child_to_constraint is not None: + self._parent_to_child = self.parent_to_constraint * self.child_to_constraint.invert() + return self._parent_to_child + + @parent_to_child_transform.setter + def parent_to_child_transform(self, transform: Transform) -> None: + self._parent_to_child = transform + + @property + def parent_object_id(self) -> int: """ - pose_in_map = self.local_transformer.transform_pose(pose, "map") - if base: - pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift + Returns the id of the parent object of the constraint. - self.reset_base_pose(pose_in_map) + :return: The id of the parent object of the constraint + """ + return self.parent_link.object_id - if set_attachments: - self._set_attached_objects_poses() + @property + def child_object_id(self) -> int: + """ + Returns the id of the child object of the constraint. + + :return: The id of the child object of the constraint + """ + return self.child_link.object_id + + @property + def parent_link_id(self) -> int: + """ + Returns the id of the parent link of the constraint. - def reset_base_pose(self, pose: Pose): - self.world.reset_object_base_pose(self, pose) - self.update_pose() + :return: The id of the parent link of the constraint + """ + return self.parent_link.id - def update_pose(self): + @property + def child_link_id(self) -> int: """ - Updates the current pose of this object from the world. + Returns the id of the child link of the constraint. + + :return: The id of the child link of the constraint """ - self._current_pose = self.world.get_object_pose(self) - self._update_all_joints_positions() - self._update_all_links_poses() - self.update_link_transforms() + return self.child_link.id - def _update_all_joints_positions(self): + @property + def position_wrt_parent_as_list(self) -> List[float]: """ - Updates the posisitons of all joints by getting them from the simulator. + Returns the constraint frame pose with respect to the parent origin as a list. + + :return: The constraint frame pose with respect to the parent origin as a list """ - for joint in self.joints.values(): - joint._update_position() + return self.pose_wrt_parent.position_as_list() - def _update_all_links_poses(self): + @property + def orientation_wrt_parent_as_list(self) -> List[float]: """ - Updates the poses of all links by getting them from the simulator. + Returns the constraint frame orientation with respect to the parent origin as a list. + + :return: The constraint frame orientation with respect to the parent origin as a list """ - for link in self.links.values(): - link._update_pose() + return self.pose_wrt_parent.orientation_as_list() - def move_base_to_origin_pos(self) -> None: + @property + def pose_wrt_parent(self) -> Pose: """ - Move the object such that its base will be at the current origin position. - This is useful when placing objects on surfaces where you want the object base in contact with the surface. + Returns the joint frame pose with respect to the parent origin. + + :return: The joint frame pose with respect to the parent origin """ - self.set_pose(self.get_pose(), base=True) + return self.parent_to_constraint.to_pose() - def save_state(self, state_id) -> None: + @property + def position_wrt_child_as_list(self) -> List[float]: """ - Saves the state of this object by saving the state of all links and attachments. - :param state_id: The unique id of the state. + Returns the constraint frame pose with respect to the child origin as a list. + + :return: The constraint frame pose with respect to the child origin as a list """ - self.save_links_states(state_id) - self.save_joints_states(state_id) - self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) + return self.pose_wrt_child.position_as_list() - def save_links_states(self, state_id: int) -> None: + @property + def orientation_wrt_child_as_list(self) -> List[float]: """ - Saves the state of all links of this object. - :param state_id: The unique id of the state. + Returns the constraint frame orientation with respect to the child origin as a list. + + :return: The constraint frame orientation with respect to the child origin as a list """ - for link in self.links.values(): - link.save_state(state_id) + return self.pose_wrt_child.orientation_as_list() - def save_joints_states(self, state_id: int) -> None: + @property + def pose_wrt_child(self) -> Pose: """ - Saves the state of all joints of this object. - :param state_id: The unique id of the state. + Returns the joint frame pose with respect to the child origin. + + :return: The joint frame pose with respect to the child origin """ - for joint in self.joints.values(): - joint.save_state(state_id) + return self.child_to_constraint.to_pose() - def restore_state(self, state_id: int) -> None: + +class Constraint(AbstractConstraint): + """ + Represents a constraint between two links in the World. + """ + + def __init__(self, + parent_link: Link, + child_link: Link, + _type: JointType, + axis_in_child_frame: Point, + constraint_to_parent: Transform, + child_to_constraint: Transform): + parent_to_constraint = constraint_to_parent.invert() + AbstractConstraint.__init__(self, parent_link, child_link, _type, parent_to_constraint, child_to_constraint) + self.axis: Point = axis_in_child_frame + + @property + def axis_as_list(self) -> List[float]: """ - Restores the state of this object by restoring the state of all links and attachments. - :param state_id: The unique id of the state. + Returns the axis of this constraint as a list. + + :return: The axis of this constraint as a list of xyz """ - self.restore_attachments(state_id) - self.restore_links_states(state_id) - self.restore_joints_states(state_id) + return [self.axis.x, self.axis.y, self.axis.z] - def restore_attachments(self, state_id: int) -> None: + +class Joint(AbstractConstraint, ObjectEntity, JointDescription, ABC): + """ + Represents a joint of an Object in the World. + """ + + def __init__(self, _id: int, + joint_description: JointDescription, + obj: Object): + AbstractConstraint.__init__(self, + self.parent_link, + self.child_link, + joint_description.type, + self.parent_link.get_transform_to_link(self.child_link), + Transform(frame=self.child_link.tf_frame)) + ObjectEntity.__init__(self, _id, obj) + self._update_position() + + @property + def tf_frame(self) -> str: """ - Restores the attachments of this object from a saved state using the given state id. - :param state_id: The unique id of the state. + The tf frame of a joint is the tf frame of the child link. """ - self.attachments = self.saved_states[state_id].attachments + return self.child_link.tf_frame - def restore_links_states(self, state_id: int) -> None: + @property + def pose(self) -> Pose: """ - Restores the states of all links of this object from a saved state using the given state id. - :param state_id: The unique id of the state. + Returns the pose of this joint. The pose is the pose of the child link of this joint. + + :return: The pose of this joint. """ - for link in self.links.values(): - link.restore_state(state_id) + return self.child_link.pose - def restore_joints_states(self, state_id: int) -> None: + def _update_position(self) -> None: """ - Restores the states of all joints of this object from a saved state using the given state id. - :param state_id: The unique id of the state. + Updates the current position of the joint from the physics simulator. """ - for joint in self.joints.values(): - joint.restore_state(state_id) + self._current_position = self.world.get_joint_position(self.object, self.name) - def remove_saved_states(self) -> None: + @property + def parent_link(self) -> Link: """ - Removes all saved states of this object. + Returns the parent link of this joint. + :return: The parent link as a Link object. """ - self.saved_states = {} - self.remove_links_saved_states() - self.remove_joints_saved_states() + return self.object.links[self.parent_link_name] - def remove_links_saved_states(self) -> None: + @property + def child_link(self) -> Link: """ - Removes all saved states of the links of this object. + Returns the child link of this joint. + :return: The child link as a Link object. """ - for link in self.links.values(): - link.remove_saved_states() + return self.object.links[self.child_link_name] - def remove_joints_saved_states(self) -> None: + @property + def position(self) -> float: + return self._current_position + + def reset_position(self, position: float) -> None: + self.world.reset_joint_position(self.object, self.name, position) + self._update_position() + + def get_object_id(self) -> int: """ - Removes all saved states of the joints of this object. + Returns the id of the object to which this joint belongs. + :return: The integer id of the object to which this joint belongs. """ - for joint in self.joints.values(): - joint.remove_saved_states() + return self.object.id - def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: + @position.setter + def position(self, joint_position: float) -> None: """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. + Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated + in the URDF, an error will be printed. However, the joint will be set either way. - :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent - loops in the update. + :param joint_position: The target pose for this joint """ + # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly + if self.has_limits: + low_lim, up_lim = self.limits + if not low_lim <= joint_position <= up_lim: + logging.error( + f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" + f" are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_position}") + # Temporarily disabled because kdl outputs values exciting joint limits + # return + self.reset_position(joint_position) - if already_moved_objects is None: - already_moved_objects = [] + def enable_force_torque_sensor(self) -> None: + self.world.enable_joint_force_torque_sensor(self.object, self.id) - for child in self.attachments: + def disable_force_torque_sensor(self) -> None: + self.world.disable_joint_force_torque_sensor(self.object, self.id) - if child in already_moved_objects: - continue + def get_reaction_force_torque(self) -> List[float]: + return self.world.get_joint_reaction_force_torque(self.object, self.id) - attachment = self.attachments[child] - if not attachment.bidirectional: - self.update_attachment_with_object(child) - child.update_attachment_with_object(self) + def get_applied_motor_torque(self) -> float: + return self.world.get_applied_joint_motor_torque(self.object, self.id) - else: - link_to_object = attachment.parent_to_child_transform - child.set_pose(link_to_object.to_pose(), set_attachments=False) - child._set_attached_objects_poses(already_moved_objects + [self]) + def restore_state(self, state_id: int) -> None: + self.current_state = self.saved_states[state_id] - def set_position(self, position: Union[Pose, Point], base=False) -> None: - """ - Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position - instead of the origin in the center of the Object. The given position can either be a Pose, - in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + @property + def current_state(self) -> JointState: + return JointState(self.position) - :param position: Target position as xyz. - :param base: If the bottom of the Object should be placed or the origin in the center. - """ - pose = Pose() - if isinstance(position, Pose): - target_position = position.position - pose.frame = position.frame - elif isinstance(position, Point): - target_position = position - elif isinstance(position, list): - target_position = position - else: - raise TypeError("The given position has to be a Pose, Point or a list of xyz.") + @current_state.setter + def current_state(self, joint_state: JointState) -> None: + self.position = joint_state.position - pose.position = target_position - pose.orientation = self.get_orientation() - self.set_pose(pose, base=base) - def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: - """ - Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only - the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. +class Link(ObjectEntity, LinkDescription, ABC): + """ + Represents a link of an Object in the World. + """ - :param orientation: Target orientation given as a list of xyzw. - """ - pose = Pose() - if isinstance(orientation, Pose): - target_orientation = orientation.orientation - pose.frame = orientation.frame - else: - target_orientation = orientation + def __init__(self, _id: int, obj: Object, parsed_link_description: Any): + ObjectEntity.__init__(self, _id, obj) + LinkDescription.__init__(self, parsed_link_description) + self.local_transformer: LocalTransformer = LocalTransformer() + self.constraint_ids: Dict[Link, int] = {} + self._update_pose() - pose.pose.position = self.get_position() - pose.pose.orientation = target_orientation - self.set_pose(pose) + @property + def current_state(self) -> LinkState: + return LinkState(self.constraint_ids.copy()) - def get_joint_id(self, name: str) -> int: - """ - Returns the unique id for a joint name. As used by the world/simulator. + @current_state.setter + def current_state(self, link_state: LinkState) -> None: + self.constraint_ids = link_state.constraint_ids - :param name: The joint name - :return: The unique id + def add_fixed_constraint_with_link(self, child_link: Link) -> int: """ - return self.joint_name_to_id[name] + Adds a fixed constraint between this link and the given link, used to create attachments for example. + :param child_link: The child link to which a fixed constraint should be added. + :return: The unique id of the constraint. + """ + constraint_id = self.world.add_fixed_constraint(self, + child_link, + child_link.get_transform_from_link(self)) + self.constraint_ids[child_link] = constraint_id + child_link.constraint_ids[self] = constraint_id + return constraint_id - def get_root_urdf_link(self) -> urdf_parser_py.urdf.Link: + def remove_constraint_with_link(self, child_link: Link) -> None: """ - Returns the root link of the URDF of this object. - :return: The root link as defined in the URDF of this object. + Removes the constraint between this link and the given link. + :param child_link: The child link of the constraint that should be removed. + """ + self.world.remove_constraint(self.constraint_ids[child_link]) + del self.constraint_ids[child_link] + del child_link.constraint_ids[self] + + @property + def is_root(self) -> bool: """ - link_name = self.urdf_object.get_root() - for link in self.urdf_object.links: - if link.name == link_name: - return link + Returns whether this link is the root link of the object. + :return: True if this link is the root link, False otherwise. + """ + return self.object.get_root_link_id() == self.id - def get_root_link(self) -> Link: + def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: """ - Returns the root link of this object. - :return: The root link of this object. + Updates the transformation of this link at the given time. + :param transform_time: The time at which the transformation should be updated. """ - return self.links[self.urdf_object.get_root()] + self.local_transformer.update_transforms([self.transform], transform_time) - def get_root_link_id(self) -> int: + def get_transform_to_link(self, link: Link) -> Transform: """ - Returns the unique id of the root link of this object. - :return: The unique id of the root link of this object. + Returns the transformation from this link to the given link. + :param link: The link to which the transformation should be returned. + :return: A Transform object with the transformation from this link to the given link. """ - return self.get_link_id(self.urdf_object.get_root()) + return link.get_transform_from_link(self) - def get_link_id(self, link_name: str) -> int: + def get_transform_from_link(self, link: Link) -> Transform: """ - Returns a unique id for a link name. - :param link_name: The name of the link. - :return: The unique id of the link. + Returns the transformation from the given link to this link. + :param link: The link from which the transformation should be returned. + :return: A Transform object with the transformation from the given link to this link. """ - assert link_name is not None - return self.link_name_to_id[link_name] + return self.get_pose_wrt_link(link).to_transform(self.tf_frame) - def get_link_by_id(self, link_id: int) -> Link: + def get_pose_wrt_link(self, link: Link) -> Pose: """ - Returns the link for a given unique link id - :param link_id: The unique id of the link. - :return: The link object. + Returns the pose of this link with respect to the given link. + :param link: The link with respect to which the pose should be returned. + :return: A Pose object with the pose of this link with respect to the given link. """ - return self.links[self.link_id_to_name[link_id]] + return self.local_transformer.transform_pose(self.pose, link.tf_frame) - def get_joint_by_id(self, joint_id: int) -> str: + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: """ - Returns the joint name for a unique world id - - :param joint_id: The world id of for joint - :return: The joint name + Returns the axis aligned bounding box of this link. + :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. """ - return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] + return self.world.get_link_axis_aligned_bounding_box(self) - def reset_all_joints_positions(self) -> None: + @property + def position(self) -> Point: """ - Sets the current position of all joints to 0. This is useful if the joints should be reset to their default + The getter for the position of the link relative to the world frame. + :return: A Point object containing the position of the link relative to the world frame. """ - joint_names = list(self.joint_name_to_id.keys()) - joint_positions = [0] * len(joint_names) - self.set_joint_positions(dict(zip(joint_names, joint_positions))) + return self.pose.position - def set_joint_positions(self, joint_poses: dict) -> None: + @property + def position_as_list(self) -> List[float]: """ - Sets the current position of multiple joints at once, this method should be preferred when setting - multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. - - :param joint_poses: + The getter for the position of the link relative to the world frame as a list. + :return: A list containing the position of the link relative to the world frame. """ - for joint_name, joint_position in joint_poses.items(): - self.joints[joint_name].position = joint_position - self.update_pose() - self._set_attached_objects_poses() + return self.pose.position_as_list() - def set_joint_position(self, joint_name: str, joint_position: float) -> None: + @property + def orientation(self) -> Quaternion: """ - Sets the position of the given joint to the given joint pose and updates the poses of all attached objects. - - :param joint_name: The name of the joint - :param joint_position: The target pose for this joint + The getter for the orientation of the link relative to the world frame. + :return: A Quaternion object containing the orientation of the link relative to the world frame. """ - self.joints[joint_name].position = joint_position - self._update_all_links_poses() - self.update_link_transforms() - self._set_attached_objects_poses() - - def get_joint_position(self, joint_name: str) -> float: - return self.joints[joint_name].position - - def get_joint_rest_position(self, joint_name: str) -> float: - return self.joints[joint_name].rest_position - - def get_joint_damping(self, joint_name: str) -> float: - return self.joints[joint_name].damping - - def get_joint_upper_limit(self, joint_name: str) -> float: - return self.joints[joint_name].upper_limit - - def get_joint_lower_limit(self, joint_name: str) -> float: - return self.joints[joint_name].lower_limit - - def get_joint_axis(self, joint_name: str) -> Point: - return self.joints[joint_name].axis - - def get_joint_type(self, joint_name: str) -> JointType: - return self.joints[joint_name].type - - def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: - return self.joints[joint_name].limits + return self.pose.orientation - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + @property + def orientation_as_list(self) -> List[float]: """ - Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. - - :param link_name: Link name above which the joint should be found - :param joint_type: Joint type that should be searched for - :return: Name of the first joint which has the given type + The getter for the orientation of the link relative to the world frame as a list. + :return: A list containing the orientation of the link relative to the world frame. """ - chain = self.urdf_object.get_chain(self.urdf_object.get_root(), link_name) - reversed_chain = reversed(chain) - container_joint = None - for element in reversed_chain: - if element in self.joint_name_to_id and self.get_joint_type(element) == joint_type: - container_joint = element - break - if not container_joint: - rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") - return container_joint + return self.pose.orientation_as_list() - def get_positions_of_all_joints(self) -> Dict[str: float]: + def _update_pose(self) -> None: """ - Returns the positions of all joints of the object as a dictionary of joint names and joint positions. - - :return: A dictionary with all joints positions'. + Updates the current pose of this link from the world. """ - return {j.name: j.position for j in self.joints.values()} + self._current_pose = self.world.get_link_pose(self) - def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: + @property + def pose(self) -> Pose: """ - Updates the transforms of all links of this object using time 'transform_time' or the current ros time. + The pose of the link relative to the world frame. + :return: A Pose object containing the pose of the link relative to the world frame. """ - for link in self.links.values(): - link.update_transform(transform_time) + return self._current_pose - def contact_points(self) -> List: + @property + def pose_as_list(self) -> List[List[float]]: """ - Returns a list of contact points of this Object with other Objects. - - :return: A list of all contact points with other objects + The pose of the link relative to the world frame as a list. + :return: A list containing the position and orientation of the link relative to the world frame. """ - return self.world.get_object_contact_points(self) + return self.pose.to_list() - def contact_points_simulated(self) -> List: + def get_origin_transform(self) -> Transform: """ - Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - - :return: A list of contact points between this Object and other Objects + Returns the transformation between the link frame and the origin frame of this link. """ - state_id = self.world.save_state() - self.world.step() - contact_points = self.contact_points() - self.world.restore_state(state_id) - return contact_points + return self.origin.to_transform(self.tf_frame) - def set_color(self, color: Color) -> None: + @property + def color(self) -> Color: """ - Changes the rgba_color of this object, the rgba_color has to be given as a list - of RGBA values. All links of this object will be colored. - - :param color: The rgba_color as RGBA values between 0 and 1 + The getter for the rgba_color of this link. + :return: A Color object containing the rgba_color of this link. """ - self.world.set_object_color(self, color) + return self.world.get_link_color(self) - def get_color(self) -> Union[Color, Dict[str, Color]]: + @color.setter + def color(self, color: List[float]) -> None: """ - :return: The rgba_color of this object or a dictionary of link names and their colors. + The setter for the color of this link, could be rgb or rgba. + :param color: The color as a list of floats, either rgb or rgba. """ - return self.world.get_object_color(self) + self.world.set_link_color(self, Color.from_list(color)) - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + @property + def origin_transform(self) -> Transform: """ - :return: The axis aligned bounding box of this object. + :return: The transform from world to origin of entity. """ - return self.world.get_object_axis_aligned_bounding_box(self) + return self.origin.to_transform(self.tf_frame) - def get_base_origin(self) -> Pose: + @property + def tf_frame(self) -> str: """ - :return: the origin of the base/bottom of this object. + The name of the tf frame of this link. """ - aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() - base_width = np.absolute(aabb.min_x - aabb.max_x) - base_length = np.absolute(aabb.min_y - aabb.max_y) - return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], - self.get_pose().orientation_as_list()) + return f"{self.object.tf_frame}/{self.name}" -def filter_contact_points(contact_points, exclude_ids) -> List: +class RootLink(Link, ABC): """ - Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. - - :param contact_points: A list of contact points - :param exclude_ids: A list of unique ids of Objects that should be removed from the list - :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' + Represents the root link of an Object in the World. + It differs from the normal Link class in that the pose ande the tf_frame is the same as that of the object. """ - return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) + def __init__(self, obj: Object): + super().__init__(obj.get_root_link_id(), obj, obj.get_root_link_description()) -def get_path_from_data_dir(file_name: str, data_directory: str) -> str: - """ - Returns the full path for a given file name in the given directory. If there is no file with the given filename - this method returns None. + @property + def tf_frame(self) -> str: + """ + Returns the tf frame of the root link, which is the same as the tf frame of the object. + """ + return self.object.tf_frame - :param file_name: The filename of the searched file. - :param data_directory: The directory in which to search for the file. - :return: The full path in the filesystem or None if there is no file with the filename in the directory - """ - for file in os.listdir(data_directory): - if file == file_name: - return data_directory + f"/{file_name}" + def _update_pose(self) -> None: + self._current_pose = self.object.get_pose() -class Attachment: +class Attachment(AbstractConstraint): def __init__(self, parent_link: Link, child_link: Link, @@ -2431,17 +2625,16 @@ def __init__(self, :param parent_to_child_transform: The transform from the parent link to the child object link. :param constraint_id: The id of the constraint in the simulator. """ - self.parent_link: Link = parent_link - self.child_link: Link = child_link + super().__init__(parent_link, child_link, JointType.FIXED, parent_to_child_transform, + Transform(frame=child_link.tf_frame)) + self.id = constraint_id self.bidirectional: bool = bidirectional self._loose: bool = False - self.parent_to_child_transform: Transform = parent_to_child_transform if self.parent_to_child_transform is None: self.update_transform() - self.constraint_id: int = constraint_id - if self.constraint_id is None: + if self.id is None: self.add_fixed_constraint() def update_transform_and_constraint(self) -> None: @@ -2468,8 +2661,7 @@ def add_fixed_constraint(self) -> None: """ Adds a fixed constraint between the parent link and the child link. """ - cid = self.parent_link.add_fixed_constraint_with_link(self.child_link) - self.constraint_id = cid + self.id = self.parent_link.add_fixed_constraint_with_link(self.child_link) def calculate_transform(self) -> Transform: """ @@ -2489,7 +2681,7 @@ def get_inverse(self) -> Attachment: :return: A new Attachment object with the parent and child links swapped. """ attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, - constraint_id=self.constraint_id) + constraint_id=self.id) attachment.loose = not self._loose return attachment @@ -2522,106 +2714,63 @@ def __del__(self) -> None: self.remove_constraint_if_exists() -def _correct_urdf_string(urdf_string: str) -> str: - """ - Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legac) - can't deal with ROS package paths. - - :param urdf_string: The name of the URDf on the parameter server - :return: The URDF string with paths in the filesystem instead of ROS packages - """ - r = rospkg.RosPack() - new_urdf_string = "" - for line in urdf_string.split('\n'): - if "package://" in line: - s = line.split('//') - s1 = s[1].split('/') - path = r.get_path(s1[0]) - line = line.replace("package://" + s1[0], path) - new_urdf_string += line + '\n' - - return fix_missing_inertial(new_urdf_string) - - -def fix_missing_inertial(urdf_string: str) -> str: - """ - Insert inertial tags for every URDF link that has no inertia. - This is used to prevent Legacy(PyBullet) from dumping warnings in the terminal - - :param urdf_string: The URDF description as string - :returns: The new, corrected URDF description as string. - """ - - inertia_tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.Element("inertial")) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("mass", {"value": "0.1"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) - inertia_tree.getroot().append(xml.etree.ElementTree.Element("inertia", {"ixx": "0.01", - "ixy": "0", - "ixz": "0", - "iyy": "0.01", - "iyz": "0", - "izz": "0.01"})) - - # create tree from string - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - - for link_element in tree.iter("link"): - inertial = [*link_element.iter("inertial")] - if len(inertial) == 0: - link_element.append(inertia_tree.getroot()) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def remove_error_tags(urdf_string: str) -> str: - """ - Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the - URDF_parser - - :param urdf_string: String of the URDF from which the tags should be removed - :return: The URDF string with the tags removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) - removing_tags = ["gazebo", "transmission"] - for tag_name in removing_tags: - all_tags = tree.findall(tag_name) - for tag in all_tags: - tree.getroot().remove(tag) - - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') - - -def fix_link_attributes(urdf_string: str) -> str: - """ - Removes the attribute 'type' from links since this is not parsable by the URDF parser. +class CacheManager: + @staticmethod + def _look_for_file_in_data_dir(path: str, path_object: pathlib.Path) -> str: + """ + Looks for a file in the data directory of the World. If the file is not found in the data directory, this method + raises a FileNotFoundError. + """ + if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): + for data_dir in World.data_directory: + path = get_path_from_data_dir(path, data_dir) + if path: + break - :param urdf_string: The string of the URDF from which the attributes should be removed - :return: The URDF string with the attributes removed - """ - tree = xml.etree.ElementTree.ElementTree(xml.etree.ElementTree.fromstring(urdf_string)) + if not path: + raise FileNotFoundError( + f"File {path_object.name} could not be found in the resource directory {World.data_directory}") - for link in tree.iter("link"): - if "type" in link.attrib.keys(): - del link.attrib["type"] + return path - return xml.etree.ElementTree.tostring(tree.getroot(), encoding='unicode') + @staticmethod + def get_path_from_data_dir(file_name: str, data_directory: str) -> str: + """ + Returns the full path for a given file name in the given directory. If there is no file with the given filename + this method returns None. + :param file_name: The filename of the searched file. + :param data_directory: The directory in which to search for the file. + :return: The full path in the filesystem or None if there is no file with the filename in the directory + """ + for file in os.listdir(data_directory): + if file == file_name: + return data_directory + f"/{file_name}" -def _is_cached(path) -> bool: - """ - Checks if the file in the given path is already cached or if - there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from - the parameter server is used. + @staticmethod + def _create_cache_dir_if_not_exists(): + """ + Creates the cache directory if it does not exist. + """ + if not pathlib.Path(World.cache_dir).exists(): + os.mkdir(World.cache_dir) - :return: True if there already exists a cached file, False in any other case. - """ - file_name = pathlib.Path(path).name - full_path = pathlib.Path(World.cach_dir + file_name) - if full_path.exists(): - return True - # Returns filename without the filetype, e.g. returns "test" for "test.txt" - file_stem = pathlib.Path(path).stem - full_path = pathlib.Path(World.cach_dir + file_stem + ".urdf") - if full_path.exists(): - return True - return False + @staticmethod + def _is_cached(path) -> bool: + """ + Checks if the file in the given path is already cached or if + there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from + the parameter server is used. + + :return: True if there already exists a cached file, False in any other case. + """ + file_name = pathlib.Path(path).name + full_path = pathlib.Path(World.cache_dir + file_name) + if full_path.exists(): + return True + # Returns filename without the filetype, e.g. returns "test" for "test.txt" + file_stem = pathlib.Path(path).stem + full_path = pathlib.Path(World.cache_dir + file_stem + ObjectDescription.file_extension) + if full_path.exists(): + return True + return False diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index fc96cd60e..e344dcf5e 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -5,6 +5,16 @@ from abc import ABC, abstractmethod +def get_point_as_list(point: Point) -> List[float]: + """ + Returns the point as a list. + + :param point: The point + :return: The point as a list + """ + return [point.x, point.y, point.z] + + @dataclass class Color: """ @@ -78,6 +88,54 @@ class Constraint: joint_frame_pose_wrt_parent_origin: Pose joint_frame_pose_wrt_child_origin: Pose + def get_parent_object_id(self) -> int: + """ + Returns the id of the parent object of the constraint. + + :return: The id of the parent object of the constraint + """ + return self.parent_link.object.id + + def get_child_object_id(self) -> int: + """ + Returns the id of the child object of the constraint. + + :return: The id of the child object of the constraint + """ + return self.child_link.object.id + + def get_parent_link_id(self) -> int: + """ + Returns the id of the parent link of the constraint. + + :return: The id of the parent link of the constraint + """ + return self.parent_link.id + + def get_child_link_id(self) -> int: + """ + Returns the id of the child link of the constraint. + + :return: The id of the child link of the constraint + """ + return self.child_link.id + + def get_joint_axis_as_list(self) -> List[float]: + """ + Returns the joint axis of the constraint as a list. + + :return: The joint axis of the constraint as a list + """ + return get_point_as_list(self.joint_axis_in_child_link_frame) + + def get_joint_position_wrt_parent_as_list(self) -> List[float]: + """ + Returns the joint frame pose with respect to the parent origin as a list. + + :return: The joint frame pose with respect to the parent origin as a list + """ + return self.joint_frame_pose_wrt_parent_origin.position_as_list() + @dataclass class AxisAlignedBoundingBox: @@ -262,16 +320,26 @@ def visual_geometry_type(self) -> Shape: @dataclass -class ObjectState: +class State(ABC): + pass + + +@dataclass +class WorldState(State): + state_id: int + + +@dataclass +class ObjectState(State): state_id: int attachments: Dict['Object', 'Attachment'] @dataclass -class LinkState: +class LinkState(State): constraint_ids: Dict['Link', int] @dataclass -class JointState: +class JointState(State): position: float diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 15e46e637..42725316f 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -26,8 +26,8 @@ def test_robot_orientation(self): def test_save_and_restore_state(self): self.robot.attach(self.milk) state_id = self.world.save_state() - robot_link = self.robot.get_root_link() - milk_link = self.milk.get_root_link() + robot_link = self.robot.root_link + milk_link = self.milk.root_link cid = robot_link.constraint_ids[milk_link] self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) self.world.remove_constraint(cid) @@ -45,24 +45,6 @@ def test_remove_object(self): self.assertTrue(milk_id not in [obj.id for obj in self.world.objects]) BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) - def test_get_joint_rest_pose(self): - self.assertEqual(self.robot.get_joint_rest_position("head_pan_joint"), 0.0) - - def test_get_joint_damping(self): - self.assertEqual(self.robot.get_joint_damping("head_pan_joint"), 0.5) - - def test_get_joint_upper_limit(self): - self.assertEqual(self.robot.get_joint_upper_limit("head_pan_joint"), 3.007) - - def test_get_joint_lower_limit(self): - self.assertEqual(self.robot.get_joint_lower_limit("head_pan_joint"), -3.007) - - def test_get_joint_axis(self): - self.assertEqual(self.robot.get_joint_axis("head_pan_joint"), Point(0.0, 0.0, 1.0)) - - def test_get_joint_type(self): - self.assertEqual(self.robot.get_joint_type("head_pan_joint"), JointType.REVOLUTE) - def test_get_joint_position(self): self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) diff --git a/test/test_links.py b/test/test_links.py index a2f7f1c4f..1205b4e23 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -4,23 +4,23 @@ class TestLinks(BulletWorldTestCase): def test_add_constraint(self): - milk_link = self.milk.get_root_link() - robot_link = self.robot.get_root_link() + milk_link = self.milk.root_link + robot_link = self.robot.root_link robot_link.add_fixed_constraint_with_link(milk_link) self.assertTrue(milk_link in robot_link.constraint_ids) self.assertTrue(robot_link in milk_link.constraint_ids) def test_remove_constraint(self): - milk_link = self.milk.get_root_link() - robot_link = self.robot.get_root_link() + milk_link = self.milk.root_link + robot_link = self.robot.root_link robot_link.add_fixed_constraint_with_link(milk_link) robot_link.remove_constraint_with_link(milk_link) self.assertTrue(milk_link not in robot_link.constraint_ids) self.assertTrue(robot_link not in milk_link.constraint_ids) def test_transform_link(self): - milk_link = self.milk.get_root_link() - robot_link = self.robot.get_root_link() + milk_link = self.milk.root_link + robot_link = self.robot.root_link milk_to_robot = milk_link.get_transform_to_link(robot_link) robot_to_milk = robot_link.get_transform_to_link(milk_link) self.assertAlmostEqual(robot_to_milk, milk_to_robot.invert()) diff --git a/test/test_object.py b/test/test_object.py index 409b1db9e..3391eddd6 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -1,4 +1,5 @@ from bullet_world_testcase import BulletWorldTestCase +from pycram.enums import JointType from pycram.pose import Pose from geometry_msgs.msg import Point @@ -17,6 +18,21 @@ def test_set_position_as_list(self): self.milk.set_position([1, 2, 3]) self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + def test_get_joint_axis(self): + self.assertEqual(self.robot.get_joint_axis("head_pan_joint"), Point(0.0, 0.0, 1.0)) + + def test_get_joint_type(self): + self.assertEqual(self.robot.get_joint_type("head_pan_joint"), JointType.REVOLUTE) + + def test_get_joint_lower_limit(self): + self.assertEqual(self.robot.get_joint_lower_limit("head_pan_joint"), -3.007) + + def test_get_joint_upper_limit(self): + self.assertEqual(self.robot.get_joint_upper_limit("head_pan_joint"), 3.007) + + def test_get_joint_damping(self): + self.assertEqual(self.robot.get_joint_damping("head_pan_joint"), 0.5) + def test_save_state(self): self.robot.attach(self.milk) self.robot.save_state(1) From 85a6cb3e526a5322514325efa2a369d70af45254 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 9 Feb 2024 21:43:33 +0100 Subject: [PATCH 078/195] [Abstract World] Abstracted URDF dependency. Added a SateEntity for abstract state preserving classes. Cleaned code. Still needs to run tests. --- src/pycram/external_interfaces/giskard.py | 6 +- src/pycram/urdf_interface.py | 234 ++++++------- src/pycram/world.py | 396 +++++++++++++++------- src/pycram/world_dataclasses.py | 6 +- 4 files changed, 394 insertions(+), 248 deletions(-) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index fd4958f6c..686f6bfab 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -159,7 +159,7 @@ def spawn_object(object: Object) -> None: :param object: World object that should be spawned """ if len(object.link_name_to_id) == 1: - geometry = object.object_description.link_map[object.object_description.get_root()].collision.geometry + geometry = object.description.link_map[object.description.get_root()].collision.geometry if isinstance(geometry, urdf_parser_py.urdf.Mesh): filename = geometry.filename spawn_mesh(object.name + "_" + str(object.id), filename, object.get_pose()) @@ -239,8 +239,8 @@ def _manage_par_motion_goals(goal_func, *args) -> Optional['MoveResult']: if "tip_link" in par_value_pair.keys() and "root_link" in par_value_pair.keys(): if par_value_pair["tip_link"] == robot_description.base_link: continue - chain = World.robot.object_description.get_chain(par_value_pair["root_link"], - par_value_pair["tip_link"]) + chain = World.robot.description.get_chain(par_value_pair["root_link"], + par_value_pair["tip_link"]) if set(chain).intersection(used_joints) != set(): giskard_wrapper.cmd_seq = tmp raise AttributeError(f"The joint(s) {set(chain).intersection(used_joints)} is used by multiple Designators") diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index 240e6b955..ce82bde9a 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -1,13 +1,11 @@ -import os import pathlib -import re from xml.etree import ElementTree import rospkg import rospy from geometry_msgs.msg import Point from tf.transformations import quaternion_from_euler -from typing_extensions import Union, List +from typing_extensions import Union, List, Optional from urdf_parser_py import urdf from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, Sphere as URDF_Sphere, Mesh as URDF_Mesh) @@ -15,7 +13,8 @@ from pycram.enums import JointType, Shape from pycram.pose import Pose from pycram.world import JointDescription as AbstractJointDescription, Joint as AbstractJoint, \ - LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription, World, _is_cached + LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription +from pycram.world_dataclasses import Color class LinkDescription(AbstractLinkDescription): @@ -149,64 +148,18 @@ class ObjectDescription(AbstractObjectDescription): """ A class that represents an object description of an object. """ - def from_description_file(self, path) -> URDF: - """ - Create an object description from a description file. - :param path: The path to the description file. - """ + def load_description(self, path) -> URDF: with open(path, 'r') as file: return URDF.from_xml_string(file.read()) - def preprocess_file(self, path: str, ignore_cached_files: bool) -> str: - """ - Preprocesses the file, if it is a .obj or .stl file it will be converted to an URDF file. - """ - path_object = pathlib.Path(path) - extension = path_object.suffix - - path = _look_for_file_in_data_dir(path, path_object) - - _create_cache_dir_if_not_exists() - - # if file is not yet cached correct the urdf and save if in the cache directory - if not _is_cached(path) or ignore_cached_files: - if extension == ".obj" or extension == ".stl": - path = self._generate_urdf_file(path) - elif extension == ".urdf": - with open(path, mode="r") as f: - urdf_string = fix_missing_inertial(f.read()) - urdf_string = remove_error_tags(urdf_string) - urdf_string = fix_link_attributes(urdf_string) - try: - urdf_string = _correct_urdf_string(urdf_string) - except rospkg.ResourceNotFound as e: - rospy.logerr(f"Could not find resource package linked in this URDF") - raise e - path = World.cache_dir + path_object.name - with open(path, mode="w") as f: - f.write(urdf_string) - else: # Using the urdf from the parameter server - urdf_string = rospy.get_param(path) - path = World.cache_dir + self.name + ".urdf" - with open(path, mode="w") as f: - f.write(_correct_urdf_string(urdf_string)) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = World.cache_dir + path_object.stem + ".urdf" - elif extension == ".urdf": - path = World.cache_dir + path_object.name - else: - path = World.cache_dir + self.name + ".urdf" - - return path - - def _generate_urdf_file(self, path) -> str: + def generate_from_mesh_file(self, path, color: Optional[Color] = Color()) -> str: """ Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be - used to crate a material tag in the URDF. The resulting file will then be saved in the cach_dir path with - the name as filename. + used to create a material tag in the URDF. + :param path: The path to the mesh file. + :param color: The color of the object. :return: The absolute path of the created file """ urdf_template = ' \n \ @@ -227,14 +180,28 @@ def _generate_urdf_file(self, path) -> str: \n \ \n \ ' - urdf_template = fix_missing_inertial(urdf_template) - rgb = " ".join(list(map(str, self.color.get_rgba()))) + urdf_template = self.fix_missing_inertial(urdf_template) + rgb = " ".join(list(map(str, color.get_rgba()))) pathlib_obj = pathlib.Path(path) path = str(pathlib_obj.resolve()) content = urdf_template.replace("~a", self.name).replace("~b", path).replace("~c", rgb) - with open(World.cache_dir + pathlib_obj.stem + ".urdf", "w", encoding="utf-8") as file: - file.write(content) - return World.cache_dir + pathlib_obj.stem + ".urdf" + return content + + def generate_from_description_file(self, path: str) -> str: + with open(path, mode="r") as f: + urdf_string = self.fix_missing_inertial(f.read()) + urdf_string = self.remove_error_tags(urdf_string) + urdf_string = self.fix_link_attributes(urdf_string) + try: + urdf_string = self.correct_urdf_string(urdf_string) + except rospkg.ResourceNotFound as e: + rospy.logerr(f"Could not find resource package linked in this URDF") + raise e + return urdf_string + + def generate_from_parameter_server(self, name: str) -> str: + urdf_string = rospy.get_param(name) + return self.correct_urdf_string(urdf_string) @property def links(self) -> List[LinkDescription]: @@ -262,87 +229,102 @@ def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: """ return self.parsed_description.get_chain(start_link_name, end_link_name) + def correct_urdf_string(self, urdf_string: str) -> str: + """ + Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legacy) + can't deal with ROS package paths. -def _correct_urdf_string(urdf_string: str) -> str: - """ - Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legac) - can't deal with ROS package paths. - - :param urdf_string: The name of the URDf on the parameter server - :return: The URDF string with paths in the filesystem instead of ROS packages - """ - r = rospkg.RosPack() - new_urdf_string = "" - for line in urdf_string.split('\n'): - if "package://" in line: - s = line.split('//') - s1 = s[1].split('/') - path = r.get_path(s1[0]) - line = line.replace("package://" + s1[0], path) - new_urdf_string += line + '\n' + :param urdf_string: The name of the URDf on the parameter server + :return: The URDF string with paths in the filesystem instead of ROS packages + """ + r = rospkg.RosPack() + new_urdf_string = "" + for line in urdf_string.split('\n'): + if "package://" in line: + s = line.split('//') + s1 = s[1].split('/') + path = r.get_path(s1[0]) + line = line.replace("package://" + s1[0], path) + new_urdf_string += line + '\n' - return fix_missing_inertial(new_urdf_string) + return self.fix_missing_inertial(new_urdf_string) + @staticmethod + def fix_missing_inertial(urdf_string: str) -> str: + """ + Insert inertial tags for every URDF link that has no inertia. + This is used to prevent Legacy(PyBullet) from dumping warnings in the terminal -def fix_missing_inertial(urdf_string: str) -> str: - """ - Insert inertial tags for every URDF link that has no inertia. - This is used to prevent Legacy(PyBullet) from dumping warnings in the terminal + :param urdf_string: The URDF description as string + :returns: The new, corrected URDF description as string. + """ - :param urdf_string: The URDF description as string - :returns: The new, corrected URDF description as string. - """ + inertia_tree = ElementTree.ElementTree(ElementTree.Element("inertial")) + inertia_tree.getroot().append(ElementTree.Element("mass", {"value": "0.1"})) + inertia_tree.getroot().append(ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) + inertia_tree.getroot().append(ElementTree.Element("inertia", {"ixx": "0.01", + "ixy": "0", + "ixz": "0", + "iyy": "0.01", + "iyz": "0", + "izz": "0.01"})) - inertia_tree = ElementTree.ElementTree(ElementTree.Element("inertial")) - inertia_tree.getroot().append(ElementTree.Element("mass", {"value": "0.1"})) - inertia_tree.getroot().append(ElementTree.Element("origin", {"rpy": "0 0 0", "xyz": "0 0 0"})) - inertia_tree.getroot().append(ElementTree.Element("inertia", {"ixx": "0.01", - "ixy": "0", - "ixz": "0", - "iyy": "0.01", - "iyz": "0", - "izz": "0.01"})) + # create tree from string + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) - # create tree from string - tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + for link_element in tree.iter("link"): + inertial = [*link_element.iter("inertial")] + if len(inertial) == 0: + link_element.append(inertia_tree.getroot()) - for link_element in tree.iter("link"): - inertial = [*link_element.iter("inertial")] - if len(inertial) == 0: - link_element.append(inertia_tree.getroot()) + return ElementTree.tostring(tree.getroot(), encoding='unicode') - return ElementTree.tostring(tree.getroot(), encoding='unicode') + @staticmethod + def remove_error_tags(urdf_string: str) -> str: + """ + Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the + URDF_parser + :param urdf_string: String of the URDF from which the tags should be removed + :return: The URDF string with the tags removed + """ + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + removing_tags = ["gazebo", "transmission"] + for tag_name in removing_tags: + all_tags = tree.findall(tag_name) + for tag in all_tags: + tree.getroot().remove(tag) -def remove_error_tags(urdf_string: str) -> str: - """ - Removes all tags in the removing_tags list from the URDF since these tags are known to cause errors with the - URDF_parser + return ElementTree.tostring(tree.getroot(), encoding='unicode') - :param urdf_string: String of the URDF from which the tags should be removed - :return: The URDF string with the tags removed - """ - tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) - removing_tags = ["gazebo", "transmission"] - for tag_name in removing_tags: - all_tags = tree.findall(tag_name) - for tag in all_tags: - tree.getroot().remove(tag) + @staticmethod + def fix_link_attributes(urdf_string: str) -> str: + """ + Removes the attribute 'type' from links since this is not parsable by the URDF parser. - return ElementTree.tostring(tree.getroot(), encoding='unicode') + :param urdf_string: The string of the URDF from which the attributes should be removed + :return: The URDF string with the attributes removed + """ + tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + for link in tree.iter("link"): + if "type" in link.attrib.keys(): + del link.attrib["type"] -def fix_link_attributes(urdf_string: str) -> str: - """ - Removes the attribute 'type' from links since this is not parsable by the URDF parser. + return ElementTree.tostring(tree.getroot(), encoding='unicode') - :param urdf_string: The string of the URDF from which the attributes should be removed - :return: The URDF string with the attributes removed - """ - tree = ElementTree.ElementTree(ElementTree.fromstring(urdf_string)) + @property + def file_extension(self) -> str: + """ + :return: The file extension of the URDF file. + """ + return '.urdf' - for link in tree.iter("link"): - if "type" in link.attrib.keys(): - del link.attrib["type"] + @property + def origin(self) -> Pose: + return Pose(self.parsed_description.origin.xyz, + quaternion_from_euler(*self.parsed_description.origin.rpy)) - return ElementTree.tostring(tree.getroot(), encoding='unicode') + @property + def name(self) -> str: + return self.parsed_description.name diff --git a/src/pycram/world.py b/src/pycram/world.py index 08c80e300..e01ad2955 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -13,7 +13,7 @@ import numpy as np import rospy from geometry_msgs.msg import Quaternion, Point -from typing_extensions import List, Optional, Dict, Tuple, Callable, Any +from typing_extensions import List, Optional, Dict, Tuple, Callable, Any, Type from typing_extensions import Union from .enums import JointType, ObjectType, WorldMode, Shape @@ -43,13 +43,14 @@ def saved_states(self) -> Dict[int, State]: """ return self._saved_states - def save_state(self, state_id: int) -> None: + def save_state(self, state_id: int) -> int: """ Saves the state of this entity with the given state id. :param state_id: The unique id of the state. """ self._saved_states[state_id] = self.current_state + return state_id @property @abstractmethod @@ -138,6 +139,8 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ World.current_world = self World.simulation_frequency = simulation_frequency + self.cache_manager = CacheManager() + self.is_prospection_world: bool = is_prospection_world self._init_and_sync_prospection_world() @@ -202,6 +205,17 @@ def _sync_prospection_world(self): self.world_sync: WorldSync = WorldSync(self, self.prospection_world) self.world_sync.start() + def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, + obj: Object) -> str: + """ + Updates the cache directory with the given object. + + :param path: The path to the object. + :param ignore_cached_files: If the cached files should be ignored. + :param obj: The object to be added to the cache directory. + """ + return self.cache_manager.update_cache_dir_with_object(path, ignore_cached_files, obj.description) + @property def simulation_time_step(self): """ @@ -613,18 +627,34 @@ def save_state(self, state_id: Optional[int] = None) -> int: :return: A unique id of the state """ - return self.current_state.state_id + state_id = self.save_physics_simulator_state() + self.save_objects_state(state_id) + return super().save_state(state_id) @property def current_state(self) -> WorldState: - state_id = self.save_physics_simulator_state() - self.save_objects_state(state_id) - self.saved_states.append(state_id) - return WorldState(state_id) + return WorldState(self.save_physics_simulator_state(), self.object_states) @current_state.setter def current_state(self, state: WorldState) -> None: - self.restore_state(state.state_id) + self.restore_physics_simulator_state(state.simulator_state_id) + self.object_states = state.object_states + + @property + def object_states(self) -> Dict[int, ObjectState]: + """ + Returns the states of all objects in the World. + :return: A dictionary with the object id as key and the object state as value. + """ + return {obj.id: obj.current_state for obj in self.objects} + + @object_states.setter + def object_states(self, states: Dict[int, ObjectState]) -> None: + """ + Sets the states of all objects in the World. + """ + for obj_id, obj_state in states.items(): + self.get_object_by_id(obj_id).current_state = obj_state def save_objects_state(self, state_id: int) -> None: """ @@ -1055,10 +1085,11 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [name, type, path, position, orientation, self.world.prospection_world, rgba_color, world object] - o = Object(obj[0], obj[1], obj[2], Pose(obj[3], obj[4]), obj[5], obj[6]) + # [0:name, 1:type, 2:path, 3:description, 4:position, 5:orientation, + # 6:self.world.prospection_world, 7:rgba_color, 8:world object] + o = Object(obj[0], obj[1], obj[2], obj[3], Pose(obj[4], obj[5]), obj[6], obj[7]) # Maps the World object to the prospection world object - self.object_mapping[obj[7]] = o + self.object_mapping[obj[8]] = o self.add_obj_queue.task_done() for i in range(self.remove_obj_queue.qsize()): obj = self.remove_obj_queue.get() @@ -1121,13 +1152,15 @@ class Object(WorldEntity): """ Represents a spawned Object in the World. """ - object_description: ObjectDescription + prospection_world_prefix: str = "prospection/" """ The ObjectDescription of the object, this contains the name and type of the object as well as the path to the source file. """ + def __init__(self, name: str, obj_type: ObjectType, path: str, + description: Type[ObjectDescription], pose: Optional[Pose] = None, world: Optional[World] = None, color: Optional[Color] = Color(), @@ -1140,8 +1173,9 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, :param name: The name of the object :param obj_type: The type of the object as an ObjectType enum. - :param path: The path to the source file, if only a filename is provided then the resourcer directories will be - searched + :param path: The path to the source file, if only a filename is provided then the resources directories will be + searched. + :param description: The ObjectDescription of the object, this contains the joints and links of the object. :param pose: The pose at which the Object should be spawned :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used. @@ -1162,14 +1196,16 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, _id, self.path = self._load_object_and_get_id(path, ignore_cached_files) + self.description = description(self.path) + super().__init__(_id, world) self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + f"{self.name}_{self.id}") - # self.object_description = ObjectDescription(self.path) + self._update_object_description_from_file(self.path) - if self.object_description.name == robot_description.name: + if self.description.name == robot_description.name: self.world.set_robot_if_not_set(self) self._init_joint_name_and_id_map() @@ -1179,7 +1215,6 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self._init_joints() self.attachments: Dict[Object, Attachment] = {} - self.saved_states: Dict[int, ObjectState] = {} if not self.world.is_prospection_world: self._add_to_world_sync_obj_queue(self.path) @@ -1200,7 +1235,7 @@ def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, :return: The unique id of the object and the path of the file that was loaded. """ - path = self.sync_cache_dir(path, ignore_cached_files) + path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) try: obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), @@ -1213,42 +1248,12 @@ def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, os.remove(path) raise (e) - def sync_cache_dir(self, path: str, ignore_cached_files: bool) -> str: + def _update_object_description_from_file(self, path: str) -> None: """ - Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + Updates the object description from the given file path. + :param path: The path to the file from which the object description should be updated. """ - path_object = pathlib.Path(path) - extension = path_object.suffix - - path = _look_for_file_in_data_dir(path, path_object) - - _create_cache_dir_if_not_exists() - - # if file is not yet cached preprocess the description file and save it in the cache directory. - if not _is_cached(path) or ignore_cached_files: - if extension == ".obj": - path = ObjectDescription.generate_from_obj_file(path) - elif extension == ".stl": - path = ObjectDescription.generate_from_stl_file(path) - elif extension == ObjectDescription.file_extension: - description_string = ObjectDescription.preprocess_file(path) - path = World.cache_dir + path_object.name - with open(path, mode="w") as f: - f.write(description_string) - else: # Using the description from the parameter server - description_string = ObjectDescription.preprocess_from_parameter_server(path) - path = f"{World.cache_dir}{self.name}{ObjectDescription.file_extension}" - with open(path, mode="w") as f: - f.write(description_string) - # save correct path in case the file is already in the cache directory - elif extension == ".obj" or extension == ".stl": - path = World.cache_dir + path_object.stem + ObjectDescription.file_extension - elif extension == ObjectDescription.file_extension: - path = World.cache_dir + path_object.name - else: - path = World.cache_dir + self.name + ObjectDescription.file_extension - - return path + self.description.update_description_from_file(path) def _init_joint_name_and_id_map(self) -> None: """ @@ -1264,7 +1269,7 @@ def _init_link_name_and_id_map(self) -> None: """ n_links = len(self.link_names) self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) - self.link_name_to_id[self.object_description.get_root()] = -1 + self.link_name_to_id[self.description.get_root()] = -1 self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) def _init_links_and_update_transforms(self) -> None: @@ -1273,10 +1278,10 @@ def _init_links_and_update_transforms(self) -> None: corresponding link objects. """ self.links = {} - for link_description in self.object_description.links: + for link_description in self.description.links: link_name = link_description.name link_id = self.link_name_to_id[link_name] - if link_name == self.object_description.get_root(): + if link_name == self.description.get_root(): self.links[link_name] = RootLink(self) else: self.links[link_name] = Link(link_id, link_description, self) @@ -1289,7 +1294,7 @@ def _init_joints(self): corresponding joint objects """ self.joints = {} - for joint_description in self.object_description.joints: + for joint_description in self.description.joints: joint_name = joint_description.name joint_id = self.joint_name_to_id[joint_name] self.joints[joint_name] = Joint(joint_id, joint_description, self) @@ -1300,7 +1305,8 @@ def _add_to_world_sync_obj_queue(self, path: str) -> None: :param path: The path of the URDF file of this object. """ self.world.world_sync.add_obj_queue.put( - [self.name, self.obj_type, path, self.get_position_as_list(), self.get_orientation_as_list(), + [self.name, self.obj_type, path, type(self.description), self.get_position_as_list(), + self.get_orientation_as_list(), self.world.prospection_world, self.color, self]) @property @@ -1308,14 +1314,14 @@ def link_names(self) -> List[str]: """ :return: The name of each link as a list. """ - return [link.name for link in self.object_description.links] + return [link.name for link in self.description.links] @property def joint_names(self) -> List[str]: """ :return: The name of each joint as a list. """ - return [joint.name for joint in self.object_description.joints] + return [joint.name for joint in self.description.joints] @property def base_origin_shift(self) -> np.ndarray: @@ -1326,7 +1332,7 @@ def base_origin_shift(self) -> np.ndarray: return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) def __repr__(self): - skip_attr = ["links", "joints", "object_description", "attachments"] + skip_attr = ["links", "joints", "description", "attachments"] return self.__class__.__qualname__ + f"(" + ', \n'.join( [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" @@ -1351,7 +1357,7 @@ def reset(self, remove_saved_states=True) -> None: self.reset_all_joints_positions() self.set_pose(self.original_pose) if remove_saved_states: - self.saved_states = {} + self.remove_saved_states() def attach(self, child_object: Object, @@ -1506,7 +1512,7 @@ def save_state(self, state_id) -> None: """ self.save_links_states(state_id) self.save_joints_states(state_id) - self.saved_states[state_id] = ObjectState(state_id, self.attachments.copy()) + super().save_state(state_id) def save_links_states(self, state_id: int) -> None: """ @@ -1524,6 +1530,50 @@ def save_joints_states(self, state_id: int) -> None: for joint in self.joints.values(): joint.save_state(state_id) + @property + def current_state(self) -> ObjectState: + return ObjectState(self.attachments.copy(), self.link_states, self.joint_states) + + @current_state.setter + def current_state(self, state: ObjectState) -> None: + self.attachments = state.attachments + self.link_states = state.link_states + self.joint_states = state.joint_states + + @property + def link_states(self) -> Dict[int, LinkState]: + """ + Returns the current state of all links of this object. + :return: A dictionary with the link id as key and the current state of the link as value. + """ + return {link.id: link.current_state for link in self.links.values()} + + @link_states.setter + def link_states(self, link_states: Dict[int, LinkState]) -> None: + """ + Sets the current state of all links of this object. + :param link_states: A dictionary with the link id as key and the current state of the link as value. + """ + for link in self.links.values(): + link.current_state = link_states[link.id] + + @property + def joint_states(self) -> Dict[int, JointState]: + """ + Returns the current state of all joints of this object. + :return: A dictionary with the joint id as key and the current state of the joint as value. + """ + return {joint.id: joint.current_state for joint in self.joints.values()} + + @joint_states.setter + def joint_states(self, joint_states: Dict[int, JointState]) -> None: + """ + Sets the current state of all joints of this object. + :param joint_states: A dictionary with the joint id as key and the current state of the joint as value. + """ + for joint in self.joints.values(): + joint.current_state = joint_states[joint.id] + def restore_state(self, state_id: int) -> None: """ Restores the state of this object by restoring the state of all links and attachments. @@ -1560,7 +1610,7 @@ def remove_saved_states(self) -> None: """ Removes all saved states of this object. """ - self.saved_states = {} + super().remove_saved_states() self.remove_links_saved_states() self.remove_joints_saved_states() @@ -1664,8 +1714,8 @@ def get_root_link_description(self) -> LinkDescription: Returns the root link of the URDF of this object. :return: The root link as defined in the URDF of this object. """ - root_link_name = self.object_description.get_root() - for link_description in self.object_description.links: + root_link_name = self.description.get_root() + for link_description in self.description.links: if link_description.name == root_link_name: return link_description @@ -1675,14 +1725,14 @@ def root_link(self) -> Link: Returns the root link of this object. :return: The root link of this object. """ - return self.links[self.object_description.get_root()] + return self.links[self.description.get_root()] def get_root_link_id(self) -> int: """ Returns the unique id of the root link of this object. :return: The unique id of the root link of this object. """ - return self.get_link_id(self.object_description.get_root()) + return self.get_link_id(self.description.get_root()) def get_link_id(self, link_name: str) -> int: """ @@ -1771,7 +1821,7 @@ def find_joint_above(self, link_name: str, joint_type: JointType) -> str: :param joint_type: Joint type that should be searched for :return: Name of the first joint which has the given type """ - chain = self.object_description.get_chain(self.object_description.get_root(), link_name) + chain = self.description.get_chain(self.description.get_root(), link_name) reversed_chain = reversed(chain) container_joint = None for element in reversed_chain: @@ -1907,42 +1957,91 @@ def name(self) -> str: class ObjectDescription(EntityDescription): + MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") - file_extension: str + def __init__(self, path: Optional[str] = None): + if path: + self.update_description_from_file(path) + else: + self._parsed_description = None - def __init__(self, path: Any): - self.parsed_description = self.from_description_file(path) + def update_description_from_file(self, path: str) -> None: + """ + Updates the description of this object from the file at the given path. + :param path: The path of the file to update from. + """ + self._parsed_description = self.load_description(path) - @abstractmethod - def from_description_file(self, path: str) -> Any: + @property + def parsed_description(self) -> Any: """ Return the object parsed from the description file. - :path: The path of the description file. """ - pass + return self._parsed_description + + @parsed_description.setter + def parsed_description(self, parsed_description: Any): + """ + Return the object parsed from the description file. + :param parsed_description: The parsed description object. + """ + self._parsed_description = parsed_description - @classmethod @abstractmethod - def generate_from_obj_file(cls, path: str) -> str: + def load_description(self, path: str) -> Any: """ - Generates a description file from an .obj file and returns the path of the generated file. - :param path: The path to the .obj file. - :return: The path of the generated description file. + Loads the description from the file at the given path. + :param path: The path to the source file, if only a filename is provided then the resources directories will be + searched. + """ + pass + + def generate_description_from_file(self, path: str, extension: str) -> str: + """ + Generates and preprocesses the description from the file at the given path and returns the preprocessed + description as a string. + :param path: The path of the file to preprocess. + :param extension: The file extension of the file to preprocess. + :return: The processed description string. + """ + + if extension in self.MESH_EXTENSIONS: + description_string = self.generate_from_mesh_file(path) + elif extension == self.file_extension: + description_string = self.generate_from_description_file(path) + else: + # Using the description from the parameter server + description_string = self.generate_from_parameter_server(path) + + return description_string + + def get_file_name(self, path_object: pathlib.Path, extension: str) -> str: """ + Returns the file name of the description file. + """ + if extension in self.MESH_EXTENSIONS: + file_name = path_object.stem + self.file_extension + elif extension == self.file_extension: + file_name = path_object.name + else: + file_name = self.name + self.file_extension + + return file_name @classmethod @abstractmethod - def generate_from_stl_file(cls, path: str) -> str: + def generate_from_mesh_file(cls, path: str) -> str: """ - Generates a description file from an .stl file and returns the path of the generated file. - :param path: The path to the .stl file. + Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and + returns the path of the generated file. + :param path: The path to the .obj file. :return: The path of the generated description file. """ pass @classmethod @abstractmethod - def preprocess_file(cls, path: str) -> str: + def generate_from_description_file(cls, path: str) -> str: """ Preprocesses the given file and returns the preprocessed description string. :param path: The path of the file to preprocess. @@ -1952,7 +2051,7 @@ def preprocess_file(cls, path: str) -> str: @classmethod @abstractmethod - def preprocess_from_parameter_server(cls, name: str) -> str: + def generate_from_parameter_server(cls, name: str) -> str: """ Preprocesses the description from the ROS parameter server and returns the preprocessed description string. :param name: The name of the description on the parameter server. @@ -1990,6 +2089,14 @@ def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: """ pass + @property + @abstractmethod + def file_extension(self) -> str: + """ + :return: The file extension of the description file. + """ + pass + class LinkDescription(EntityDescription): """ @@ -2155,6 +2262,7 @@ class AbstractConstraint: Represents an abstract constraint concept, this could be used to create joints for example or any kind of constraint between two links in the world. """ + def __init__(self, parent_link: Link, child_link: Link, @@ -2415,7 +2523,7 @@ class Link(ObjectEntity, LinkDescription, ABC): Represents a link of an Object in the World. """ - def __init__(self, _id: int, obj: Object, parsed_link_description: Any): + def __init__(self, _id: int, parsed_link_description: Any, obj: Object): ObjectEntity.__init__(self, _id, obj) LinkDescription.__init__(self, parsed_link_description) self.local_transformer: LocalTransformer = LocalTransformer() @@ -2596,7 +2704,7 @@ class RootLink(Link, ABC): """ def __init__(self, obj: Object): - super().__init__(obj.get_root_link_id(), obj, obj.get_root_link_description()) + super().__init__(obj.get_root_link_id(), obj.get_root_link_description(), obj) @property def tf_frame(self) -> str: @@ -2715,15 +2823,72 @@ def __del__(self) -> None: class CacheManager: + cache_dir: str = World.cache_dir + """ + The directory where the cached files are stored. + """ + + mesh_extensions: List[str] = [".obj", ".stl"] + """ + The file extensions of mesh files. + """ + + def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, + object_description: ObjectDescription) -> str: + """ + Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + """ + path_object = pathlib.Path(path) + extension = path_object.suffix + + path = self.look_for_file_in_data_dir(path, path_object) + + self.create_cache_dir_if_not_exists() + + # save correct path in case the file is already in the cache directory + cache_path = self.cache_dir + object_description.get_file_name(path_object, extension) + + # if file is not yet cached preprocess the description file and save it in the cache directory. + if not self.is_cached(path, object_description) or ignore_cached_files: + self.generate_description_and_write_to_cache(path, extension, cache_path, object_description) + + return cache_path + + def generate_description_and_write_to_cache(self, path: str, extension: str, cache_path: str, + object_description: ObjectDescription) -> None: + """ + Generates the description from the file at the given path and writes it to the cache directory. + :param path: The path of the file to preprocess. + :param extension: The file extension of the file to preprocess. + :param cache_path: The path of the file in the cache directory. + :param object_description: The object description of the file. + """ + description_string = object_description.generate_description_from_file(path, extension) + self.write_to_cache(description_string, cache_path) + @staticmethod - def _look_for_file_in_data_dir(path: str, path_object: pathlib.Path) -> str: + def write_to_cache(description_string: str, cache_path: str) -> None: + """ + Writes the description string to the cache directory. + :param description_string: The description string to write to the cache directory. + :param cache_path: The path of the file in the cache directory. + """ + with open(cache_path, "w") as file: + file.write(description_string) + + @staticmethod + def look_for_file_in_data_dir(path: str, path_object: pathlib.Path) -> str: """ Looks for a file in the data directory of the World. If the file is not found in the data directory, this method raises a FileNotFoundError. + :param path: The path of the file to look for. + :param path_object: The pathlib object of the file to look for. """ if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): for data_dir in World.data_directory: - path = get_path_from_data_dir(path, data_dir) + for file in os.listdir(data_dir): + if file == path: + return data_dir + f"/{path}" if path: break @@ -2733,44 +2898,41 @@ def _look_for_file_in_data_dir(path: str, path_object: pathlib.Path) -> str: return path - @staticmethod - def get_path_from_data_dir(file_name: str, data_directory: str) -> str: - """ - Returns the full path for a given file name in the given directory. If there is no file with the given filename - this method returns None. - - :param file_name: The filename of the searched file. - :param data_directory: The directory in which to search for the file. - :return: The full path in the filesystem or None if there is no file with the filename in the directory - """ - for file in os.listdir(data_directory): - if file == file_name: - return data_directory + f"/{file_name}" - - @staticmethod - def _create_cache_dir_if_not_exists(): + def create_cache_dir_if_not_exists(self): """ Creates the cache directory if it does not exist. """ - if not pathlib.Path(World.cache_dir).exists(): - os.mkdir(World.cache_dir) + if not pathlib.Path(self.cache_dir).exists(): + os.mkdir(self.cache_dir) - @staticmethod - def _is_cached(path) -> bool: + def is_cached(self, path: str, object_description: ObjectDescription) -> bool: """ Checks if the file in the given path is already cached or if there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from the parameter server is used. + :param path: The path of the file to check. + :param object_description: The object description of the file. :return: True if there already exists a cached file, False in any other case. """ + return True if self.check_with_extension(path) else self.check_without_extension(path, object_description) + + def check_with_extension(self, path: str) -> bool: + """ + Checks if the file in the given ath exists in the cache directory including file extension. + :param path: The path of the file to check. + """ file_name = pathlib.Path(path).name - full_path = pathlib.Path(World.cache_dir + file_name) - if full_path.exists(): - return True - # Returns filename without the filetype, e.g. returns "test" for "test.txt" + full_path = pathlib.Path(self.cache_dir + file_name) + return full_path.exists() + + def check_without_extension(self, path: str, object_description: ObjectDescription) -> bool: + """ + Checks if the file in the given path exists in the cache directory without file extension, + the extension is added after the file name manually in this case. + :param path: The path of the file to check. + :param object_description: The object description of the file. + """ file_stem = pathlib.Path(path).stem - full_path = pathlib.Path(World.cache_dir + file_stem + ObjectDescription.file_extension) - if full_path.exists(): - return True - return False + full_path = pathlib.Path(self.cache_dir + file_stem + object_description.file_extension) + return full_path.exists() diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index e344dcf5e..e7b0a8692 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -326,13 +326,15 @@ class State(ABC): @dataclass class WorldState(State): - state_id: int + simulator_state_id: int + object_states: Dict[int, 'ObjectState'] @dataclass class ObjectState(State): - state_id: int attachments: Dict['Object', 'Attachment'] + link_states: Dict[int, 'LinkState'] + joint_states: Dict[int, 'JointState'] @dataclass From d2b9f9759cda6a572dab2c96ed5ee3ea1d2e1e24 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Tue, 13 Feb 2024 16:54:06 +0100 Subject: [PATCH 079/195] [AbstractWorld] Fixing tests for Description Abstraction --- src/pycram/bullet_world.py | 25 ++- src/pycram/urdf_interface.py | 19 +- src/pycram/world.py | 379 ++++++++++++++++++--------------- test/bullet_world_testcase.py | 14 +- test/test_action_designator.py | 4 +- test/test_bullet_world.py | 13 +- 6 files changed, 257 insertions(+), 197 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index a4317cce4..8556035d7 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -10,10 +10,15 @@ import rosgraph import rospy -from .enums import JointType, ObjectType, WorldMode +from .enums import ObjectType, WorldMode from .pose import Pose -from .world import World, Object, Link, Constraint +from .world import World, Object, Constraint from .world_dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape +from .urdf_interface import ObjectDescription + +Link = ObjectDescription.Link +RootLink = ObjectDescription.RootLink +Joint = ObjectDescription.Joint class BulletWorld(World): @@ -23,6 +28,8 @@ class is the main interface to the Bullet Physics Engine and should be used to s manipulate the Bullet World. """ + extension: str = ObjectDescription.get_file_extension() + # Check is for sphinx autoAPI to be able to work in a CI workflow if rosgraph.is_master_online(): # and "/pycram" not in rosnode.get_node_names(): rospy.init_node('pycram') @@ -53,7 +60,8 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo self.set_gravity([0, 0, -9.8]) if not is_prospection_world: - plane = Object("floor", ObjectType.ENVIRONMENT, "plane.urdf", world=self) + plane = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, ObjectDescription, + world=self) def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: return p.loadURDF(path, @@ -71,10 +79,10 @@ def add_constraint(self, constraint: Constraint) -> int: constraint.child_link_id, constraint.type.value, constraint.axis_as_list, - constraint.position_wrt_parent_as_list(), - constraint.position_wrt_child_as_list(), - constraint.orientation_wrt_parent_as_list(), - constraint.orientation_wrt_child_as_list(), + constraint.position_wrt_parent_as_list, + constraint.position_wrt_child_as_list, + constraint.orientation_wrt_parent_as_list, + constraint.orientation_wrt_child_as_list, physicsClientId=self.id) return constraint_id @@ -85,7 +93,8 @@ def get_joint_position(self, obj: Object, joint_name: str) -> float: return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.id)[0] def get_link_pose(self, link: Link) -> Pose: - return Pose(*p.getLinkState(link.object_id, link.id, physicsClientId=self.id)[4:6]) + bullet_link_state = p.getLinkState(link.object_id, link.id, physicsClientId=self.id)[4:6] + return Pose(*bullet_link_state) def perform_collision_detection(self) -> None: p.performCollisionDetection(physicsClientId=self.id) diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index ce82bde9a..357dbf8e9 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -12,7 +12,7 @@ from pycram.enums import JointType, Shape from pycram.pose import Pose -from pycram.world import JointDescription as AbstractJointDescription, Joint as AbstractJoint, \ +from pycram.world import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription from pycram.world_dataclasses import Color @@ -140,15 +140,20 @@ def friction(self) -> float: return self.parsed_description.dynamics.friction -class Joint(AbstractJoint, JointDescription): - ... - - class ObjectDescription(AbstractObjectDescription): """ A class that represents an object description of an object. """ + class Link(AbstractObjectDescription.Link, LinkDescription): + ... + + class RootLink(AbstractObjectDescription.RootLink, Link): + ... + + class Joint(AbstractObjectDescription.Joint, JointDescription): + ... + def load_description(self, path) -> URDF: with open(path, 'r') as file: return URDF.from_xml_string(file.read()) @@ -313,8 +318,8 @@ def fix_link_attributes(urdf_string: str) -> str: return ElementTree.tostring(tree.getroot(), encoding='unicode') - @property - def file_extension(self) -> str: + @staticmethod + def get_file_extension() -> str: """ :return: The file extension of the URDF file. """ diff --git a/src/pycram/world.py b/src/pycram/world.py index e01ad2955..a93d4d8cf 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -214,7 +214,7 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, :param ignore_cached_files: If the cached files should be ignored. :param obj: The object to be added to the cache directory. """ - return self.cache_manager.update_cache_dir_with_object(path, ignore_cached_files, obj.description) + return self.cache_manager.update_cache_dir_with_object(path, ignore_cached_files, obj.description, obj.name) @property def simulation_time_step(self): @@ -350,7 +350,7 @@ def get_link_pose(self, link: Link) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. - :param link: The link as a Link object. + :param link: The link as a AbstractLink object. :return: The pose of the link as a Pose object. """ pass @@ -1166,7 +1166,7 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, color: Optional[Color] = Color(), ignore_cached_files: Optional[bool] = False): """ - The constructor loads the urdf file into the given World, if no World is specified the + The constructor loads the description file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. The rgba_color parameter is only used when loading .stl or .obj files, for URDFs :func:`~Object.set_color` can be used. @@ -1183,22 +1183,24 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ + super().__init__(-1, world) + if pose is None: pose = Pose() self.name: str = name self.obj_type: ObjectType = obj_type self.color: Color = color + self.description = description() + self.cache_manager = self.world.cache_manager self.local_transformer = LocalTransformer() self.original_pose = self.local_transformer.transform_pose(pose, "map") self._current_pose = self.original_pose - _id, self.path = self._load_object_and_get_id(path, ignore_cached_files) - - self.description = description(self.path) + self.id, self.path = self._load_object_and_get_id(path, ignore_cached_files) - super().__init__(_id, world) + self.description.update_description_from_file(self.path) self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + f"{self.name}_{self.id}") @@ -1267,8 +1269,8 @@ def _init_link_name_and_id_map(self) -> None: """ Creates a dictionary which maps the link names to their unique ids and vice versa. """ - n_links = len(self.link_names) - self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) + n_links = len(self.link_names_without_root) + self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names_without_root, range(n_links))) self.link_name_to_id[self.description.get_root()] = -1 self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) @@ -1282,9 +1284,9 @@ def _init_links_and_update_transforms(self) -> None: link_name = link_description.name link_id = self.link_name_to_id[link_name] if link_name == self.description.get_root(): - self.links[link_name] = RootLink(self) + self.links[link_name] = self.description.RootLink(self) else: - self.links[link_name] = Link(link_id, link_description, self) + self.links[link_name] = self.description.Link(link_id, link_description, self) self.update_link_transforms() @@ -1297,7 +1299,7 @@ def _init_joints(self): for joint_description in self.description.joints: joint_name = joint_description.name joint_id = self.joint_name_to_id[joint_name] - self.joints[joint_name] = Joint(joint_id, joint_description, self) + self.joints[joint_name] = self.description.Joint(joint_id, joint_description, self) def _add_to_world_sync_obj_queue(self, path: str) -> None: """ @@ -1309,6 +1311,13 @@ def _add_to_world_sync_obj_queue(self, path: str) -> None: self.get_orientation_as_list(), self.world.prospection_world, self.color, self]) + @property + def link_names_without_root(self): + """ + :return: The name of each link except the root link as a list. + """ + return list(filter(lambda x: x != self.root_link_name, self.link_names)) + @property def link_names(self) -> List[str]: """ @@ -1316,6 +1325,13 @@ def link_names(self) -> List[str]: """ return [link.name for link in self.description.links] + @property + def number_of_links(self) -> int: + """ + :return: The number of links of this object. + """ + return len(self.description.links) + @property def joint_names(self) -> List[str]: """ @@ -1323,6 +1339,13 @@ def joint_names(self) -> List[str]: """ return [joint.name for joint in self.description.joints] + @property + def number_of_joints(self) -> int: + """ + :return: The number of joints of this object. + """ + return len(self.description.joints) + @property def base_origin_shift(self) -> np.ndarray: """ @@ -1727,6 +1750,14 @@ def root_link(self) -> Link: """ return self.links[self.description.get_root()] + @property + def root_link_name(self) -> str: + """ + Returns the name of the root link of this object. + :return: The name of the root link of this object. + """ + return self.description.get_root() + def get_root_link_id(self) -> int: """ Returns the unique id of the root link of this object. @@ -1817,7 +1848,7 @@ def find_joint_above(self, link_name: str, joint_type: JointType) -> str: """ Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. - :param link_name: Link name above which the joint should be found + :param link_name: AbstractLink name above which the joint should be found :param joint_type: Joint type that should be searched for :return: Name of the first joint which has the given type """ @@ -1956,148 +1987,6 @@ def name(self) -> str: pass -class ObjectDescription(EntityDescription): - MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") - - def __init__(self, path: Optional[str] = None): - if path: - self.update_description_from_file(path) - else: - self._parsed_description = None - - def update_description_from_file(self, path: str) -> None: - """ - Updates the description of this object from the file at the given path. - :param path: The path of the file to update from. - """ - self._parsed_description = self.load_description(path) - - @property - def parsed_description(self) -> Any: - """ - Return the object parsed from the description file. - """ - return self._parsed_description - - @parsed_description.setter - def parsed_description(self, parsed_description: Any): - """ - Return the object parsed from the description file. - :param parsed_description: The parsed description object. - """ - self._parsed_description = parsed_description - - @abstractmethod - def load_description(self, path: str) -> Any: - """ - Loads the description from the file at the given path. - :param path: The path to the source file, if only a filename is provided then the resources directories will be - searched. - """ - pass - - def generate_description_from_file(self, path: str, extension: str) -> str: - """ - Generates and preprocesses the description from the file at the given path and returns the preprocessed - description as a string. - :param path: The path of the file to preprocess. - :param extension: The file extension of the file to preprocess. - :return: The processed description string. - """ - - if extension in self.MESH_EXTENSIONS: - description_string = self.generate_from_mesh_file(path) - elif extension == self.file_extension: - description_string = self.generate_from_description_file(path) - else: - # Using the description from the parameter server - description_string = self.generate_from_parameter_server(path) - - return description_string - - def get_file_name(self, path_object: pathlib.Path, extension: str) -> str: - """ - Returns the file name of the description file. - """ - if extension in self.MESH_EXTENSIONS: - file_name = path_object.stem + self.file_extension - elif extension == self.file_extension: - file_name = path_object.name - else: - file_name = self.name + self.file_extension - - return file_name - - @classmethod - @abstractmethod - def generate_from_mesh_file(cls, path: str) -> str: - """ - Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and - returns the path of the generated file. - :param path: The path to the .obj file. - :return: The path of the generated description file. - """ - pass - - @classmethod - @abstractmethod - def generate_from_description_file(cls, path: str) -> str: - """ - Preprocesses the given file and returns the preprocessed description string. - :param path: The path of the file to preprocess. - :return: The preprocessed description string. - """ - pass - - @classmethod - @abstractmethod - def generate_from_parameter_server(cls, name: str) -> str: - """ - Preprocesses the description from the ROS parameter server and returns the preprocessed description string. - :param name: The name of the description on the parameter server. - :return: The preprocessed description string. - """ - pass - - @property - @abstractmethod - def links(self) -> List[LinkDescription]: - """ - :return: A list of links descriptions of this object. - """ - pass - - @property - @abstractmethod - def joints(self) -> List[JointDescription]: - """ - :return: A list of joints descriptions of this object. - """ - pass - - @abstractmethod - def get_root(self) -> str: - """ - :return: the name of the root link of this object. - """ - pass - - @abstractmethod - def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: - """ - :return: the chain of links from 'start_link_name' to 'end_link_name'. - """ - pass - - @property - @abstractmethod - def file_extension(self) -> str: - """ - :return: The file extension of the description file. - """ - pass - - class LinkDescription(EntityDescription): """ A class that represents a link description of an object. @@ -2404,7 +2293,7 @@ def axis_as_list(self) -> List[float]: return [self.axis.x, self.axis.y, self.axis.z] -class Joint(AbstractConstraint, ObjectEntity, JointDescription, ABC): +class Joint(ObjectEntity, JointDescription, ABC): """ Represents a joint of an Object in the World. """ @@ -2412,13 +2301,8 @@ class Joint(AbstractConstraint, ObjectEntity, JointDescription, ABC): def __init__(self, _id: int, joint_description: JointDescription, obj: Object): - AbstractConstraint.__init__(self, - self.parent_link, - self.child_link, - joint_description.type, - self.parent_link.get_transform_to_link(self.child_link), - Transform(frame=self.child_link.tf_frame)) ObjectEntity.__init__(self, _id, obj) + JointDescription.__init__(self, joint_description.parsed_description) self._update_position() @property @@ -2447,7 +2331,7 @@ def _update_position(self) -> None: def parent_link(self) -> Link: """ Returns the parent link of this joint. - :return: The parent link as a Link object. + :return: The parent link as a AbstractLink object. """ return self.object.links[self.parent_link_name] @@ -2455,7 +2339,7 @@ def parent_link(self) -> Link: def child_link(self) -> Link: """ Returns the child link of this joint. - :return: The child link as a Link object. + :return: The child link as a AbstractLink object. """ return self.object.links[self.child_link_name] @@ -2523,9 +2407,9 @@ class Link(ObjectEntity, LinkDescription, ABC): Represents a link of an Object in the World. """ - def __init__(self, _id: int, parsed_link_description: Any, obj: Object): + def __init__(self, _id: int, link_description: LinkDescription, obj: Object): ObjectEntity.__init__(self, _id, obj) - LinkDescription.__init__(self, parsed_link_description) + LinkDescription.__init__(self, link_description.parsed_description) self.local_transformer: LocalTransformer = LocalTransformer() self.constraint_ids: Dict[Link, int] = {} self._update_pose() @@ -2700,7 +2584,7 @@ def tf_frame(self) -> str: class RootLink(Link, ABC): """ Represents the root link of an Object in the World. - It differs from the normal Link class in that the pose ande the tf_frame is the same as that of the object. + It differs from the normal AbstractLink class in that the pose ande the tf_frame is the same as that of the object. """ def __init__(self, obj: Object): @@ -2717,6 +2601,161 @@ def _update_pose(self) -> None: self._current_pose = self.object.get_pose() +class ObjectDescription(EntityDescription): + MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") + + class Link(Link, ABC): + ... + + class RootLink(RootLink, ABC): + ... + + class Joint(Joint, ABC): + ... + + def __init__(self, path: Optional[str] = None): + if path: + self.update_description_from_file(path) + else: + self._parsed_description = None + + def update_description_from_file(self, path: str) -> None: + """ + Updates the description of this object from the file at the given path. + :param path: The path of the file to update from. + """ + self._parsed_description = self.load_description(path) + + @property + def parsed_description(self) -> Any: + """ + Return the object parsed from the description file. + """ + return self._parsed_description + + @parsed_description.setter + def parsed_description(self, parsed_description: Any): + """ + Return the object parsed from the description file. + :param parsed_description: The parsed description object. + """ + self._parsed_description = parsed_description + + @abstractmethod + def load_description(self, path: str) -> Any: + """ + Loads the description from the file at the given path. + :param path: The path to the source file, if only a filename is provided then the resources directories will be + searched. + """ + pass + + def generate_description_from_file(self, path: str, extension: str) -> str: + """ + Generates and preprocesses the description from the file at the given path and returns the preprocessed + description as a string. + :param path: The path of the file to preprocess. + :param extension: The file extension of the file to preprocess. + :return: The processed description string. + """ + + if extension in self.MESH_EXTENSIONS: + description_string = self.generate_from_mesh_file(path) + elif extension == self.get_file_extension(): + description_string = self.generate_from_description_file(path) + else: + # Using the description from the parameter server + description_string = self.generate_from_parameter_server(path) + + return description_string + + def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: str) -> str: + """ + Returns the file name of the description file. + :param path_object: The path object of the description file or the mesh file. + :param extension: The file extension of the description file or the mesh file. + :param object_name: The name of the object. + :return: The file name of the description file. + """ + if extension in self.MESH_EXTENSIONS: + file_name = path_object.stem + self.get_file_extension() + elif extension == self.get_file_extension(): + file_name = path_object.name + else: + file_name = object_name + self.get_file_extension() + + return file_name + + @classmethod + @abstractmethod + def generate_from_mesh_file(cls, path: str) -> str: + """ + Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and + returns the path of the generated file. + :param path: The path to the .obj file. + :return: The path of the generated description file. + """ + pass + + @classmethod + @abstractmethod + def generate_from_description_file(cls, path: str) -> str: + """ + Preprocesses the given file and returns the preprocessed description string. + :param path: The path of the file to preprocess. + :return: The preprocessed description string. + """ + pass + + @classmethod + @abstractmethod + def generate_from_parameter_server(cls, name: str) -> str: + """ + Preprocesses the description from the ROS parameter server and returns the preprocessed description string. + :param name: The name of the description on the parameter server. + :return: The preprocessed description string. + """ + pass + + @property + @abstractmethod + def links(self) -> List[LinkDescription]: + """ + :return: A list of links descriptions of this object. + """ + pass + + @property + @abstractmethod + def joints(self) -> List[JointDescription]: + """ + :return: A list of joints descriptions of this object. + """ + pass + + @abstractmethod + def get_root(self) -> str: + """ + :return: the name of the root link of this object. + """ + pass + + @abstractmethod + def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: + """ + :return: the chain of links from 'start_link_name' to 'end_link_name'. + """ + pass + + @staticmethod + @abstractmethod + def get_file_extension() -> str: + """ + :return: The file extension of the description file. + """ + pass + + class Attachment(AbstractConstraint): def __init__(self, parent_link: Link, @@ -2834,7 +2873,7 @@ class CacheManager: """ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, - object_description: ObjectDescription) -> str: + object_description: ObjectDescription, object_name: str) -> str: """ Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. """ @@ -2846,7 +2885,7 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, self.create_cache_dir_if_not_exists() # save correct path in case the file is already in the cache directory - cache_path = self.cache_dir + object_description.get_file_name(path_object, extension) + cache_path = self.cache_dir + object_description.get_file_name(path_object, extension, object_name) # if file is not yet cached preprocess the description file and save it in the cache directory. if not self.is_cached(path, object_description) or ignore_cached_files: @@ -2934,5 +2973,5 @@ def check_without_extension(self, path: str, object_description: ObjectDescripti :param object_description: The object description of the file. """ file_stem = pathlib.Path(path).stem - full_path = pathlib.Path(self.cache_dir + file_stem + object_description.file_extension) + full_path = pathlib.Path(self.cache_dir + file_stem + object_description.get_file_extension()) return full_path.exists() diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 755dfbb9a..9b53f0cd4 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -5,19 +5,23 @@ from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule from pycram.enums import ObjectType, WorldMode +from pycram.urdf_interface import ObjectDescription class BulletWorldTestCase(unittest.TestCase): world: BulletWorld + extension: str = ObjectDescription.get_file_extension() @classmethod def setUpClass(cls): - cls.world = BulletWorld(WorldMode.DIRECT) - cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") - cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") - cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) - cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95])) + cls.world = BulletWorld(WorldMode.GUI) + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + cls.robot = Object(robot_description.name, ObjectType.ROBOT, + robot_description.name + cls.extension, ObjectDescription) + cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension, ObjectDescription) + cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", + ObjectDescription, pose=Pose([1.3, 0.7, 0.95])) ProcessModule.execution_delay = False def setUp(self): diff --git a/test/test_action_designator.py b/test/test_action_designator.py index d6867b6f5..4d8258f4b 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -43,6 +43,7 @@ def test_grip(self): self.assertEqual(description.ground().object_designator.name, "milk") def test_park_arms(self): + time.sleep(5) description = action_designator.ParkArmsAction([pycram.enums.Arms.BOTH]) self.assertEqual(description.ground().arm, pycram.enums.Arms.BOTH) with simulated_robot: @@ -119,7 +120,8 @@ def test_transport(self): action_designator.MoveTorsoAction([0.2]).resolve().perform() description.resolve().perform() self.assertEqual(description.ground().object_designator.name, "milk") - dist = np.linalg.norm(np.array(self.milk.get_pose().position_as_list()) - np.array([-1.35, 0.78, 0.95])) + milk_position = np.array(self.milk.get_pose().position_as_list()) + dist = np.linalg.norm(milk_position - np.array([-1.35, 0.78, 0.95])) self.assertTrue(dist < 0.01) def test_grasping(self): diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 42725316f..9542edf98 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -2,13 +2,14 @@ import unittest import rospkg -from geometry_msgs.msg import Point from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose -from pycram.world import fix_missing_inertial, Object, ObjectType +from pycram.world import Object, ObjectType import xml.etree.ElementTree as ET -from pycram.enums import JointType +from pycram.urdf_interface import ObjectDescription + +fix_missing_inertial = ObjectDescription.fix_missing_inertial class BulletWorldTest(BulletWorldTestCase): @@ -29,13 +30,13 @@ def test_save_and_restore_state(self): robot_link = self.robot.root_link milk_link = self.milk.root_link cid = robot_link.constraint_ids[milk_link] - self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) + self.assertTrue(cid == self.robot.attachments[self.milk].id) self.world.remove_constraint(cid) self.world.restore_state(state_id) cid = robot_link.constraint_ids[milk_link] self.assertTrue(milk_link in robot_link.constraint_ids) self.assertTrue(self.milk in self.robot.attachments) - self.assertTrue(cid == self.robot.attachments[self.milk].constraint_id) + self.assertTrue(cid == self.robot.attachments[self.milk].id) def test_remove_object(self): time.sleep(2) @@ -43,7 +44,7 @@ def test_remove_object(self): self.assertTrue(milk_id in [obj.id for obj in self.world.objects]) self.world.remove_object(self.milk) self.assertTrue(milk_id not in [obj.id for obj in self.world.objects]) - BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) def test_get_joint_position(self): self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) From 0d8094514ac6dc9ca1431557bd73c26654d01117 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 13 Feb 2024 21:45:58 +0100 Subject: [PATCH 080/195] [Abstract World] Fixing tests (test_detect) --- src/pycram/bullet_world.py | 5 ++--- src/pycram/world.py | 21 +++++++++++++++++---- test/bullet_world_testcase.py | 2 +- test/test_action_designator.py | 8 ++++---- 4 files changed, 24 insertions(+), 12 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 8556035d7..b026dd991 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -260,9 +260,8 @@ def get_images_for_target(self, near = 0.2 far = 100 - view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1], - physicsClientId=self.id) - projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far, physicsClientId=self.id) + view_matrix = p.computeViewMatrix(cam_pose.position_as_list(), target_pose.position_as_list(), [0, 0, 1]) + projection_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far) return list(p.getCameraImage(size, size, view_matrix, projection_matrix, physicsClientId=self.id))[2:5] diff --git a/src/pycram/world.py b/src/pycram/world.py index a93d4d8cf..517464448 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -629,11 +629,12 @@ def save_state(self, state_id: Optional[int] = None) -> int: """ state_id = self.save_physics_simulator_state() self.save_objects_state(state_id) + self._current_state = WorldState(state_id, self.object_states) return super().save_state(state_id) @property def current_state(self) -> WorldState: - return WorldState(self.save_physics_simulator_state(), self.object_states) + return self._current_state @current_state.setter def current_state(self, state: WorldState) -> None: @@ -1500,10 +1501,9 @@ def reset_base_pose(self, pose: Pose): def update_pose(self): """ - Updates the current pose of this object from the world. + Updates the current pose of this object from the world, and updates the poses of all links. """ self._current_pose = self.world.get_object_pose(self) - self._update_all_joints_positions() self._update_all_links_poses() self.update_link_transforms() @@ -1808,7 +1808,9 @@ def set_joint_positions(self, joint_poses: dict) -> None: """ for joint_name, joint_position in joint_poses.items(): self.joints[joint_name].position = joint_position - self.update_pose() + # self.update_pose() + self._update_all_links_poses() + self.update_link_transforms() self._set_attached_objects_poses() def set_joint_position(self, joint_name: str, joint_position: float) -> None: @@ -2349,7 +2351,18 @@ def position(self) -> float: def reset_position(self, position: float) -> None: self.world.reset_joint_position(self.object, self.name, position) + self._current_position = position self._update_position() + # if self.name == "r_upper_arm_roll_joint": + # if position == -1.463: + # print("here") + # print(self.object.name) + # print(self.object.world.id) + # print(self.name) + # print("required", position) + # print("actual", self._current_position) + # print(position == self._current_position) + # print("===================================") def get_object_id(self) -> int: """ diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 9b53f0cd4..9a8f5a808 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -15,7 +15,7 @@ class BulletWorldTestCase(unittest.TestCase): @classmethod def setUpClass(cls): - cls.world = BulletWorld(WorldMode.GUI) + cls.world = BulletWorld(WorldMode.DIRECT) cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + cls.extension, ObjectDescription) diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 4d8258f4b..66f56b2f6 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -43,19 +43,19 @@ def test_grip(self): self.assertEqual(description.ground().object_designator.name, "milk") def test_park_arms(self): - time.sleep(5) description = action_designator.ParkArmsAction([pycram.enums.Arms.BOTH]) self.assertEqual(description.ground().arm, pycram.enums.Arms.BOTH) with simulated_robot: description.resolve().perform() for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): - self.assertEqual(self.world.robot.get_joint_position(joint), pose) + joint_position = self.world.robot.get_joint_position(joint) + self.assertEqual(joint_position, pose) for joint, pose in robot_description.get_static_joint_chain("left", "park").items(): self.assertEqual(self.world.robot.get_joint_position(joint), pose) def test_navigate(self): - description = action_designator.NavigateAction([Pose([0, 0, 0], [0, 0, 0, 1])]) - self.assertEqual(description.ground().target_location, Pose([0, 0, 0], [0, 0, 0, 1])) + description = action_designator.NavigateAction([Pose([1, 0, 0], [0, 0, 0, 1])]) + self.assertEqual(description.ground().target_location, Pose([1, 0, 0], [0, 0, 0, 1])) def test_pick_up(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) From 17018f930fee44b1197f09def92f528590c3263c Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 13 Feb 2024 21:46:47 +0100 Subject: [PATCH 081/195] [Abstract World] Fixing tests (test_detect) --- src/pycram/world.py | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 517464448..ebe147520 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -2351,18 +2351,7 @@ def position(self) -> float: def reset_position(self, position: float) -> None: self.world.reset_joint_position(self.object, self.name, position) - self._current_position = position self._update_position() - # if self.name == "r_upper_arm_roll_joint": - # if position == -1.463: - # print("here") - # print(self.object.name) - # print(self.object.world.id) - # print(self.name) - # print("required", position) - # print("actual", self._current_position) - # print(position == self._current_position) - # print("===================================") def get_object_id(self) -> int: """ From 3fa6880af1430729eb57f901b4e747f7627a3576 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 14 Feb 2024 16:55:52 +0100 Subject: [PATCH 082/195] [Abstract World] Tests are running. --- src/pycram/bullet_world.py | 21 +++++++++-- src/pycram/urdf_interface.py | 18 +++++++++ src/pycram/world.py | 58 ++++++++++++++++++++--------- src/pycram/world_reasoning.py | 2 +- test/test_action_designator.py | 1 - test/test_bullet_world_reasoning.py | 4 +- test/test_failure_handling.py | 6 ++- test/test_object.py | 6 +-- 8 files changed, 89 insertions(+), 27 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index b026dd991..0875edcd2 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -92,9 +92,23 @@ def remove_constraint(self, constraint_id): def get_joint_position(self, obj: Object, joint_name: str) -> float: return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.id)[0] + def get_object_joint_names(self, obj: Object) -> List[str]: + return [p.getJointInfo(obj.id, i, physicsClientId=self.id)[1].decode('utf-8') + for i in range(self.get_object_number_of_joints(obj))] + def get_link_pose(self, link: Link) -> Pose: - bullet_link_state = p.getLinkState(link.object_id, link.id, physicsClientId=self.id)[4:6] - return Pose(*bullet_link_state) + bullet_link_state = p.getLinkState(link.object_id, link.id, physicsClientId=self.id) + return Pose(*bullet_link_state[4:6]) + + def get_object_link_names(self, obj: Object) -> List[str]: + num_links = self.get_object_number_of_links(obj) + return [p.getJointInfo(obj.id, i, physicsClientId=self.id)[12].decode('utf-8') + for i in range(num_links)] + + def get_object_number_of_links(self, obj: Object) -> int: + return p.getNumJoints(obj.id, physicsClientId=self.id) + + get_object_number_of_joints = get_object_number_of_links def perform_collision_detection(self) -> None: p.performCollisionDetection(physicsClientId=self.id) @@ -228,7 +242,8 @@ def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[L physicsClientId=self.id) def create_visual_shape(self, visual_shape: VisualShape) -> int: - return p.createVisualShape(visual_shape.visual_geometry_type.value, rgbaColor=visual_shape.rgba_color, + return p.createVisualShape(visual_shape.visual_geometry_type.value, + rgbaColor=visual_shape.rgba_color.get_rgba(), visualFramePosition=visual_shape.visual_frame_position, physicsClientId=self.id, **visual_shape.shape_data()) diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index 357dbf8e9..aa755d1c6 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -208,6 +208,15 @@ def generate_from_parameter_server(self, name: str) -> str: urdf_string = rospy.get_param(name) return self.correct_urdf_string(urdf_string) + def get_link_by_name(self, link_name: str) -> LinkDescription: + """ + :return: The link description with the given name. + """ + for link in self.links: + if link.name == link_name: + return link + raise ValueError(f"Link with name {link_name} not found") + @property def links(self) -> List[LinkDescription]: """ @@ -215,6 +224,15 @@ def links(self) -> List[LinkDescription]: """ return [LinkDescription(link) for link in self.parsed_description.links] + def get_joint_by_name(self, joint_name: str) -> JointDescription: + """ + :return: The joint description with the given name. + """ + for joint in self.joints: + if joint.name == joint_name: + return joint + raise ValueError(f"Joint with name {joint_name} not found") + @property def joints(self) -> List[JointDescription]: """ diff --git a/src/pycram/world.py b/src/pycram/world.py index ebe147520..fbc6ffd4f 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -345,6 +345,16 @@ def get_joint_position(self, obj: Object, joint_name: str) -> float: """ pass + @abstractmethod + def get_object_joint_names(self, obj: Object) -> List[str]: + """ + Returns the names of all joints of this object. + + :param obj: The object. + :return: A list of joint names. + """ + pass + @abstractmethod def get_link_pose(self, link: Link) -> Pose: """ @@ -355,6 +365,15 @@ def get_link_pose(self, link: Link) -> Pose: """ pass + @abstractmethod + def get_object_link_names(self, obj: Object) -> List[str]: + """ + Returns the names of all links of this object. + :param obj: The object. + :return: A list of link names. + """ + pass + def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: """ Simulates Physics in the World for a given amount of seconds. Usually this simulation is faster than real @@ -1270,8 +1289,8 @@ def _init_link_name_and_id_map(self) -> None: """ Creates a dictionary which maps the link names to their unique ids and vice versa. """ - n_links = len(self.link_names_without_root) - self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names_without_root, range(n_links))) + n_links = len(self.link_names) + self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) self.link_name_to_id[self.description.get_root()] = -1 self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) @@ -1281,9 +1300,8 @@ def _init_links_and_update_transforms(self) -> None: corresponding link objects. """ self.links = {} - for link_description in self.description.links: - link_name = link_description.name - link_id = self.link_name_to_id[link_name] + for link_name, link_id in self.link_name_to_id.items(): + link_description = self.description.get_link_by_name(link_name) if link_name == self.description.get_root(): self.links[link_name] = self.description.RootLink(self) else: @@ -1297,9 +1315,8 @@ def _init_joints(self): corresponding joint objects """ self.joints = {} - for joint_description in self.description.joints: - joint_name = joint_description.name - joint_id = self.joint_name_to_id[joint_name] + for joint_name, joint_id in self.joint_name_to_id.items(): + joint_description = self.description.get_joint_by_name(joint_name) self.joints[joint_name] = self.description.Joint(joint_id, joint_description, self) def _add_to_world_sync_obj_queue(self, path: str) -> None: @@ -1312,19 +1329,12 @@ def _add_to_world_sync_obj_queue(self, path: str) -> None: self.get_orientation_as_list(), self.world.prospection_world, self.color, self]) - @property - def link_names_without_root(self): - """ - :return: The name of each link except the root link as a list. - """ - return list(filter(lambda x: x != self.root_link_name, self.link_names)) - @property def link_names(self) -> List[str]: """ :return: The name of each link as a list. """ - return [link.name for link in self.description.links] + return self.world.get_object_link_names(self) @property def number_of_links(self) -> int: @@ -1338,7 +1348,7 @@ def joint_names(self) -> List[str]: """ :return: The name of each joint as a list. """ - return [joint.name for joint in self.description.joints] + return self.world.get_object_joint_names(self) @property def number_of_joints(self) -> int: @@ -2727,6 +2737,13 @@ def links(self) -> List[LinkDescription]: """ pass + @abstractmethod + def get_link_by_name(self, link_name: str) -> LinkDescription: + """ + :return: The link description with the given name. + """ + pass + @property @abstractmethod def joints(self) -> List[JointDescription]: @@ -2735,6 +2752,13 @@ def joints(self) -> List[JointDescription]: """ pass + @abstractmethod + def get_joint_by_name(self, joint_name: str) -> JointDescription: + """ + :return: The joint description with the given name. + """ + pass + @abstractmethod def get_root(self) -> str: """ diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 80cfa0ae9..9c8f4f764 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -111,7 +111,7 @@ def visible( state_id = World.current_world.save_state() for obj in World.current_world.objects: - if obj == prospection_obj or World.robot and obj == prospection_robot: + if obj == prospection_obj or (World.robot and obj == prospection_robot): continue else: obj.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 66f56b2f6..37a5f13d4 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -1,4 +1,3 @@ -import time import unittest from pycram.designators import action_designator, object_designator from pycram.robot_descriptions import robot_description diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index c69b34093..2643eb40e 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -20,7 +20,9 @@ def test_visible(self): self.milk.set_pose(Pose([1.5, 0, 1.2])) self.robot.set_pose(Pose()) time.sleep(1) - self.assertTrue(btr.visible(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, + camera_frame = robot_description.get_camera_frame() + self.world.add_vis_axis(self.robot.links[camera_frame].pose) + self.assertTrue(btr.visible(self.milk, self.robot.links[camera_frame].pose, robot_description.front_facing_axis)) def test_occluding(self): diff --git a/test/test_failure_handling.py b/test/test_failure_handling.py index 7a97d308a..cc9e7fd5e 100644 --- a/test/test_failure_handling.py +++ b/test/test_failure_handling.py @@ -10,6 +10,9 @@ from pycram.plan_failures import PlanFailure from pycram.process_module import ProcessModule, simulated_robot from pycram.robot_descriptions import robot_description +from pycram.urdf_interface import ObjectDescription + +extension = ObjectDescription.get_file_extension() # start ik_and_description.launch @@ -30,7 +33,8 @@ class FailureHandlingTest(unittest.TestCase): @classmethod def setUpClass(cls): cls.world = BulletWorld(WorldMode.DIRECT) - cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") + cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + extension, + ObjectDescription) ProcessModule.execution_delay = True def setUp(self): diff --git a/test/test_object.py b/test/test_object.py index 3391eddd6..ff9361eb5 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -39,7 +39,7 @@ def test_save_state(self): self.assertEqual(self.robot.saved_states[1].attachments, self.robot.attachments) self.assertTrue(self.milk in self.robot.saved_states[1].attachments) for link in self.robot.links.values(): - self.assertEqual(link.get_current_state(), link.saved_states[1]) + self.assertEqual(link.current_state, link.saved_states[1]) def test_restore_state(self): self.robot.attach(self.milk) @@ -52,7 +52,7 @@ def test_restore_state(self): self.milk.restore_state(1) self.assertTrue(self.milk in self.robot.attachments) for link in self.robot.links.values(): - curr_state = link.get_current_state() + curr_state = link.current_state saved_state = link.saved_states[1] self.assertEqual(curr_state, saved_state) - self.assertEqual(curr_state.constraint_ids, saved_state.constraint_ids) \ No newline at end of file + self.assertEqual(curr_state.constraint_ids, saved_state.constraint_ids) From 8433035742a414325ca4a53ca97d49c340b1be8f Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Wed, 14 Feb 2024 21:30:42 +0100 Subject: [PATCH 083/195] [Abstract World] Refactored File structure (Moved Classes to separate Files). Tests are running. --- demos/pycram_bullet_world_demo/demo.py | 32 +- src/pycram/bullet_world.py | 8 +- src/pycram/cache_manager.py | 123 + src/pycram/costmaps.py | 4 +- src/pycram/description.py | 669 ++++++ src/pycram/designator.py | 3 +- src/pycram/designators/motion_designator.py | 3 +- src/pycram/designators/object_designator.py | 3 +- src/pycram/external_interfaces/giskard.py | 3 +- src/pycram/external_interfaces/ik.py | 2 +- src/pycram/helper.py | 2 +- src/pycram/pose_generator_and_validator.py | 3 +- .../process_modules/pr2_process_modules.py | 3 +- src/pycram/urdf_interface.py | 2 +- src/pycram/world.py | 1978 +---------------- src/pycram/world_constraints.py | 257 +++ src/pycram/world_object.py | 822 +++++++ src/pycram/world_reasoning.py | 4 +- test/bullet_world_testcase.py | 3 +- test/test_bullet_world.py | 19 +- test/test_database_merger.py | 3 +- test/test_database_resolver.py | 2 +- test/test_jpt_resolver.py | 2 +- test/test_language.py | 1 + test/test_links.py | 9 + 25 files changed, 2021 insertions(+), 1939 deletions(-) create mode 100644 src/pycram/cache_manager.py create mode 100644 src/pycram/description.py create mode 100644 src/pycram/world_constraints.py create mode 100644 src/pycram/world_object.py diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index eabdd2ac2..24917d05d 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -1,22 +1,28 @@ +from pycram.bullet_world import BulletWorld from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.designators.object_designator import * +from pycram.enums import ObjectType from pycram.pose import Pose -from pycram.bullet_world import BulletWorld +from pycram.process_module import simulated_robot, with_simulated_robot +from pycram.urdf_interface import ObjectDescription from pycram.world import Object from pycram.world_dataclasses import Color -from pycram.process_module import simulated_robot, with_simulated_robot -from pycram.enums import ObjectType + +extension = ObjectDescription.get_file_extension() world = BulletWorld() -robot = Object("pr2", ObjectType.ROBOT, "pr2.urdf", pose=Pose([1, 2, 0])) -apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") - -milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([2.5, 2, 1.02]), color=Color(1, 0, 0, 1)) -cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([2.5, 2.3, 1.05]), - color=[0, 1, 0, 1]) -spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", pose=Pose([2.4, 2.2, 0.85]), color=Color(0, 0, 1, 1)) -bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=Pose([2.5, 2.2, 1.02]), color=Color(1, 1, 0, 1)) +robot = Object("pr2", ObjectType.ROBOT, f"pr2{extension}", ObjectDescription, pose=Pose([1, 2, 0])) +apartment = Object("apartment", ObjectType.ENVIRONMENT, f"apartment{extension}", ObjectDescription) + +milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([2.5, 2, 1.02]), + color=Color(1, 0, 0, 1)) +cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", ObjectDescription, + pose=Pose([2.5, 2.3, 1.05]), color=Color(0, 1, 0, 1)) +spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", ObjectDescription, pose=Pose([2.4, 2.2, 0.85]), + color=Color(0, 0, 1, 1)) +bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", ObjectDescription, pose=Pose([2.5, 2.2, 1.02]), + color=Color(1, 1, 0, 1)) apartment.attach(spoon, 'cabinet10_drawer_top') pick_pose = Pose([2.7, 2.15, 1]) @@ -55,7 +61,8 @@ def move_and_detect(obj_type): # Finding and navigating to the drawer holding the spoon handle_desig = ObjectPart(names=["handle_cab10_t"], part_of=apartment_desig.resolve()) - drawer_open_loc = AccessingLocation(handle_desig=handle_desig.resolve(), robot_desig=robot_desig.resolve()).resolve() + drawer_open_loc = AccessingLocation(handle_desig=handle_desig.resolve(), + robot_desig=robot_desig.resolve()).resolve() NavigateAction([drawer_open_loc.pose]).resolve().perform() @@ -91,4 +98,3 @@ def move_and_detect(obj_type): PlaceAction(spoon_desig, [spoon_target_pose], [pickup_arm]).resolve().perform() ParkArmsAction([Arms.BOTH]).resolve().perform() - diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 0875edcd2..5cb332084 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -12,7 +12,9 @@ from .enums import ObjectType, WorldMode from .pose import Pose -from .world import World, Object, Constraint +from .world import World +from .world_object import Object +from .world_constraints import Constraint from .world_dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape from .urdf_interface import ObjectDescription @@ -140,7 +142,7 @@ def get_object_pose(self, obj: Object) -> Pose: return Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.id)) def set_link_color(self, link: Link, rgba_color: Color): - p.changeVisualShape(link.object_id, link.id, rgbaColor=rgba_color, physicsClientId=self.id) + p.changeVisualShape(link.object_id, link.id, rgbaColor=rgba_color.get_rgba(), physicsClientId=self.id) def get_link_color(self, link: Link) -> Color: return self.get_colors_of_object_links(link.object)[link.name] @@ -148,7 +150,7 @@ def get_link_color(self, link: Link) -> Color: def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: visual_data = p.getVisualShapeData(obj.id, physicsClientId=self.id) link_id_to_name = {v: k for k, v in obj.link_name_to_id.items()} - links = list(map(lambda x: link_id_to_name[x[1]] if x[1] != -1 else "base", visual_data)) + links = list(map(lambda x: link_id_to_name[x[1]], visual_data)) colors = list(map(lambda x: Color.from_rgba(x[7]), visual_data)) link_to_color = dict(zip(links, colors)) return link_to_color diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py new file mode 100644 index 000000000..24d3989e7 --- /dev/null +++ b/src/pycram/cache_manager.py @@ -0,0 +1,123 @@ +import os +import pathlib +import re + +from typing_extensions import List + + +class CacheManager: + + mesh_extensions: List[str] = [".obj", ".stl"] + """ + The file extensions of mesh files. + """ + + def __init__(self, cache_dir: str, data_directory: List[str]): + self.cache_dir = cache_dir + # The directory where the cached files are stored. + + self.data_directory = data_directory + # The directory where all resource files are stored. + + def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, + object_description: 'ObjectDescription', object_name: str) -> str: + """ + Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + """ + path_object = pathlib.Path(path) + extension = path_object.suffix + + path = self.look_for_file_in_data_dir(path, path_object) + + self.create_cache_dir_if_not_exists() + + # save correct path in case the file is already in the cache directory + cache_path = self.cache_dir + object_description.get_file_name(path_object, extension, object_name) + + # if file is not yet cached preprocess the description file and save it in the cache directory. + if not self.is_cached(path, object_description) or ignore_cached_files: + self.generate_description_and_write_to_cache(path, extension, cache_path, object_description) + + return cache_path + + def generate_description_and_write_to_cache(self, path: str, extension: str, cache_path: str, + object_description: 'ObjectDescription') -> None: + """ + Generates the description from the file at the given path and writes it to the cache directory. + :param path: The path of the file to preprocess. + :param extension: The file extension of the file to preprocess. + :param cache_path: The path of the file in the cache directory. + :param object_description: The object description of the file. + """ + description_string = object_description.generate_description_from_file(path, extension) + self.write_to_cache(description_string, cache_path) + + @staticmethod + def write_to_cache(description_string: str, cache_path: str) -> None: + """ + Writes the description string to the cache directory. + :param description_string: The description string to write to the cache directory. + :param cache_path: The path of the file in the cache directory. + """ + with open(cache_path, "w") as file: + file.write(description_string) + + def look_for_file_in_data_dir(self, path: str, path_object: pathlib.Path) -> str: + """ + Looks for a file in the data directory of the World. If the file is not found in the data directory, this method + raises a FileNotFoundError. + :param path: The path of the file to look for. + :param path_object: The pathlib object of the file to look for. + """ + if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): + for data_dir in self.data_directory: + for file in os.listdir(data_dir): + if file == path: + return data_dir + f"/{path}" + if path: + break + + if not path: + raise FileNotFoundError( + f"File {path_object.name} could not be found in the resource directory {self.data_directory}") + + return path + + def create_cache_dir_if_not_exists(self): + """ + Creates the cache directory if it does not exist. + """ + if not pathlib.Path(self.cache_dir).exists(): + os.mkdir(self.cache_dir) + + def is_cached(self, path: str, object_description: 'ObjectDescription') -> bool: + """ + Checks if the file in the given path is already cached or if + there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from + the parameter server is used. + + :param path: The path of the file to check. + :param object_description: The object description of the file. + :return: True if there already exists a cached file, False in any other case. + """ + return True if self.check_with_extension(path) else self.check_without_extension(path, object_description) + + def check_with_extension(self, path: str) -> bool: + """ + Checks if the file in the given ath exists in the cache directory including file extension. + :param path: The path of the file to check. + """ + file_name = pathlib.Path(path).name + full_path = pathlib.Path(self.cache_dir + file_name) + return full_path.exists() + + def check_without_extension(self, path: str, object_description: 'ObjectDescription') -> bool: + """ + Checks if the file in the given path exists in the cache directory without file extension, + the extension is added after the file name manually in this case. + :param path: The path of the file to check. + :param object_description: The object description of the file. + """ + file_stem = pathlib.Path(path).stem + full_path = pathlib.Path(self.cache_dir + file_stem + object_description.get_file_extension()) + return full_path.exists() diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index db5a83a3d..11ae3ab0f 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -10,7 +10,9 @@ from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData -from .world import UseProspectionWorld, Object, Link +from .world import UseProspectionWorld +from .world_object import Object +from .description import Link from .local_transformer import LocalTransformer from .pose import Pose, Transform from .world import World diff --git a/src/pycram/description.py b/src/pycram/description.py new file mode 100644 index 000000000..8c86a7ea9 --- /dev/null +++ b/src/pycram/description.py @@ -0,0 +1,669 @@ +import pathlib +from abc import ABC, abstractmethod +import logging + +import rospy +from geometry_msgs.msg import Point, Quaternion +from typing_extensions import Tuple, Union, Any, List, Optional, Dict + +from pycram.enums import Shape, JointType +from pycram.local_transformer import LocalTransformer +from pycram.pose import Pose, Transform +from pycram.world import WorldEntity +from pycram.world_object import Object +from pycram.world_dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState + + +class EntityDescription(ABC): + + @property + @abstractmethod + def origin(self) -> Pose: + """ + Returns the origin of this entity. + """ + pass + + @property + @abstractmethod + def name(self) -> str: + """ + Returns the name of this entity. + """ + pass + + +class LinkDescription(EntityDescription): + """ + A class that represents a link description of an object. + """ + + def __init__(self, parsed_link_description: Any): + self.parsed_description = parsed_link_description + + @property + @abstractmethod + def geometry(self) -> Shape: + """ + Returns the geometry type of the URDF collision element of this link. + """ + pass + + +class JointDescription(EntityDescription): + """ + A class that represents a joint description of a URDF joint. + """ + + def __init__(self, parsed_joint_description: Any): + self.parsed_description = parsed_joint_description + + @property + @abstractmethod + def type(self) -> JointType: + """ + :return: The type of this joint. + """ + pass + + @property + @abstractmethod + def axis(self) -> Point: + """ + :return: The axis of this joint, for example the rotation axis for a revolute joint. + """ + pass + + @property + @abstractmethod + def has_limits(self) -> bool: + """ + Checks if this joint has limits. + :return: True if the joint has limits, False otherwise. + """ + pass + + @property + def limits(self) -> Tuple[float, float]: + """ + :return: The lower and upper limits of this joint. + """ + lower, upper = self.lower_limit, self.upper_limit + if lower > upper: + lower, upper = upper, lower + return lower, upper + + @property + @abstractmethod + def lower_limit(self) -> Union[float, None]: + """ + :return: The lower limit of this joint, or None if the joint has no limits. + """ + pass + + @property + @abstractmethod + def upper_limit(self) -> Union[float, None]: + """ + :return: The upper limit of this joint, or None if the joint has no limits. + """ + pass + + @property + @abstractmethod + def parent_link_name(self) -> str: + """ + :return: The name of the parent link of this joint. + """ + pass + + @property + @abstractmethod + def child_link_name(self) -> str: + """ + :return: The name of the child link of this joint. + """ + pass + + @property + def damping(self) -> float: + """ + :return: The damping of this joint. + """ + raise NotImplementedError + + @property + def friction(self) -> float: + """ + :return: The friction of this joint. + """ + raise NotImplementedError + + +class ObjectEntity(WorldEntity): + """ + An abstract base class that represents a physical part/entity of an Object. + This can be a link or a joint of an Object. + """ + + def __init__(self, _id: int, obj: Object): + WorldEntity.__init__(self, _id, obj.world) + self.object: Object = obj + + @property + @abstractmethod + def pose(self) -> Pose: + """ + :return: The pose of this entity relative to the world frame. + """ + pass + + @property + def transform(self) -> Transform: + """ + Returns the transform of this entity. + + :return: The transform of this entity. + """ + return self.pose.to_transform(self.tf_frame) + + @property + @abstractmethod + def tf_frame(self) -> str: + """ + Returns the tf frame of this entity. + + :return: The tf frame of this entity. + """ + pass + + @property + def object_id(self) -> int: + """ + :return: the id of the object to which this entity belongs. + """ + return self.object.id + + def __repr__(self): + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" for key, value in self.__dict__.items()]) + ")" + + def __str__(self): + return self.__repr__() + + +class Link(ObjectEntity, LinkDescription, ABC): + """ + Represents a link of an Object in the World. + """ + + def __init__(self, _id: int, link_description: LinkDescription, obj: Object): + ObjectEntity.__init__(self, _id, obj) + LinkDescription.__init__(self, link_description.parsed_description) + self.local_transformer: LocalTransformer = LocalTransformer() + self.constraint_ids: Dict[Link, int] = {} + self._update_pose() + + @property + def current_state(self) -> LinkState: + return LinkState(self.constraint_ids.copy()) + + @current_state.setter + def current_state(self, link_state: LinkState) -> None: + self.constraint_ids = link_state.constraint_ids + + def add_fixed_constraint_with_link(self, child_link: 'Link') -> int: + """ + Adds a fixed constraint between this link and the given link, used to create attachments for example. + :param child_link: The child link to which a fixed constraint should be added. + :return: The unique id of the constraint. + """ + constraint_id = self.world.add_fixed_constraint(self, + child_link, + child_link.get_transform_from_link(self)) + self.constraint_ids[child_link] = constraint_id + child_link.constraint_ids[self] = constraint_id + return constraint_id + + def remove_constraint_with_link(self, child_link: 'Link') -> None: + """ + Removes the constraint between this link and the given link. + :param child_link: The child link of the constraint that should be removed. + """ + self.world.remove_constraint(self.constraint_ids[child_link]) + del self.constraint_ids[child_link] + del child_link.constraint_ids[self] + + @property + def is_root(self) -> bool: + """ + Returns whether this link is the root link of the object. + :return: True if this link is the root link, False otherwise. + """ + return self.object.get_root_link_id() == self.id + + def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: + """ + Updates the transformation of this link at the given time. + :param transform_time: The time at which the transformation should be updated. + """ + self.local_transformer.update_transforms([self.transform], transform_time) + + def get_transform_to_link(self, link: 'Link') -> Transform: + """ + Returns the transformation from this link to the given link. + :param link: The link to which the transformation should be returned. + :return: A Transform object with the transformation from this link to the given link. + """ + return link.get_transform_from_link(self) + + def get_transform_from_link(self, link: 'Link') -> Transform: + """ + Returns the transformation from the given link to this link. + :param link: The link from which the transformation should be returned. + :return: A Transform object with the transformation from the given link to this link. + """ + return self.get_pose_wrt_link(link).to_transform(self.tf_frame) + + def get_pose_wrt_link(self, link: 'Link') -> Pose: + """ + Returns the pose of this link with respect to the given link. + :param link: The link with respect to which the pose should be returned. + :return: A Pose object with the pose of this link with respect to the given link. + """ + return self.local_transformer.transform_pose(self.pose, link.tf_frame) + + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + Returns the axis aligned bounding box of this link. + :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. + """ + return self.world.get_link_axis_aligned_bounding_box(self) + + @property + def position(self) -> Point: + """ + The getter for the position of the link relative to the world frame. + :return: A Point object containing the position of the link relative to the world frame. + """ + return self.pose.position + + @property + def position_as_list(self) -> List[float]: + """ + The getter for the position of the link relative to the world frame as a list. + :return: A list containing the position of the link relative to the world frame. + """ + return self.pose.position_as_list() + + @property + def orientation(self) -> Quaternion: + """ + The getter for the orientation of the link relative to the world frame. + :return: A Quaternion object containing the orientation of the link relative to the world frame. + """ + return self.pose.orientation + + @property + def orientation_as_list(self) -> List[float]: + """ + The getter for the orientation of the link relative to the world frame as a list. + :return: A list containing the orientation of the link relative to the world frame. + """ + return self.pose.orientation_as_list() + + def _update_pose(self) -> None: + """ + Updates the current pose of this link from the world. + """ + self._current_pose = self.world.get_link_pose(self) + + @property + def pose(self) -> Pose: + """ + The pose of the link relative to the world frame. + :return: A Pose object containing the pose of the link relative to the world frame. + """ + return self._current_pose + + @property + def pose_as_list(self) -> List[List[float]]: + """ + The pose of the link relative to the world frame as a list. + :return: A list containing the position and orientation of the link relative to the world frame. + """ + return self.pose.to_list() + + def get_origin_transform(self) -> Transform: + """ + Returns the transformation between the link frame and the origin frame of this link. + """ + return self.origin.to_transform(self.tf_frame) + + @property + def color(self) -> Color: + """ + The getter for the rgba_color of this link. + :return: A Color object containing the rgba_color of this link. + """ + return self.world.get_link_color(self) + + @color.setter + def color(self, color: Color) -> None: + """ + The setter for the color of this link, could be rgb or rgba. + :param color: The color as a list of floats, either rgb or rgba. + """ + self.world.set_link_color(self, color) + + @property + def origin_transform(self) -> Transform: + """ + :return: The transform from world to origin of entity. + """ + return self.origin.to_transform(self.tf_frame) + + @property + def tf_frame(self) -> str: + """ + The name of the tf frame of this link. + """ + return f"{self.object.tf_frame}/{self.name}" + + +class RootLink(Link, ABC): + """ + Represents the root link of an Object in the World. + It differs from the normal AbstractLink class in that the pose ande the tf_frame is the same as that of the object. + """ + + def __init__(self, obj: Object): + super().__init__(obj.get_root_link_id(), obj.get_root_link_description(), obj) + + @property + def tf_frame(self) -> str: + """ + Returns the tf frame of the root link, which is the same as the tf frame of the object. + """ + return self.object.tf_frame + + def _update_pose(self) -> None: + self._current_pose = self.object.get_pose() + + +class Joint(ObjectEntity, JointDescription, ABC): + """ + Represents a joint of an Object in the World. + """ + + def __init__(self, _id: int, + joint_description: JointDescription, + obj: Object): + ObjectEntity.__init__(self, _id, obj) + JointDescription.__init__(self, joint_description.parsed_description) + self._update_position() + + @property + def tf_frame(self) -> str: + """ + The tf frame of a joint is the tf frame of the child link. + """ + return self.child_link.tf_frame + + @property + def pose(self) -> Pose: + """ + Returns the pose of this joint. The pose is the pose of the child link of this joint. + + :return: The pose of this joint. + """ + return self.child_link.pose + + def _update_position(self) -> None: + """ + Updates the current position of the joint from the physics simulator. + """ + self._current_position = self.world.get_joint_position(self.object, self.name) + + @property + def parent_link(self) -> Link: + """ + Returns the parent link of this joint. + :return: The parent link as a AbstractLink object. + """ + return self.object.links[self.parent_link_name] + + @property + def child_link(self) -> Link: + """ + Returns the child link of this joint. + :return: The child link as a AbstractLink object. + """ + return self.object.links[self.child_link_name] + + @property + def position(self) -> float: + return self._current_position + + def reset_position(self, position: float) -> None: + self.world.reset_joint_position(self.object, self.name, position) + self._update_position() + + def get_object_id(self) -> int: + """ + Returns the id of the object to which this joint belongs. + :return: The integer id of the object to which this joint belongs. + """ + return self.object.id + + @position.setter + def position(self, joint_position: float) -> None: + """ + Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated + in the URDF, an error will be printed. However, the joint will be set either way. + + :param joint_position: The target pose for this joint + """ + # TODO Limits for rotational (infinite) joints are 0 and 1, they should be considered separately + if self.has_limits: + low_lim, up_lim = self.limits + if not low_lim <= joint_position <= up_lim: + logging.error( + f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" + f" are {low_lim} and {up_lim}") + logging.error(f"The given joint position was: {joint_position}") + # Temporarily disabled because kdl outputs values exciting joint limits + # return + self.reset_position(joint_position) + + def enable_force_torque_sensor(self) -> None: + self.world.enable_joint_force_torque_sensor(self.object, self.id) + + def disable_force_torque_sensor(self) -> None: + self.world.disable_joint_force_torque_sensor(self.object, self.id) + + def get_reaction_force_torque(self) -> List[float]: + return self.world.get_joint_reaction_force_torque(self.object, self.id) + + def get_applied_motor_torque(self) -> float: + return self.world.get_applied_joint_motor_torque(self.object, self.id) + + def restore_state(self, state_id: int) -> None: + self.current_state = self.saved_states[state_id] + + @property + def current_state(self) -> JointState: + return JointState(self.position) + + @current_state.setter + def current_state(self, joint_state: JointState) -> None: + self.position = joint_state.position + + +class ObjectDescription(EntityDescription): + MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") + + class Link(Link, ABC): + ... + + class RootLink(RootLink, ABC): + ... + + class Joint(Joint, ABC): + ... + + def __init__(self, path: Optional[str] = None): + if path: + self.update_description_from_file(path) + else: + self._parsed_description = None + + def update_description_from_file(self, path: str) -> None: + """ + Updates the description of this object from the file at the given path. + :param path: The path of the file to update from. + """ + self._parsed_description = self.load_description(path) + + @property + def parsed_description(self) -> Any: + """ + Return the object parsed from the description file. + """ + return self._parsed_description + + @parsed_description.setter + def parsed_description(self, parsed_description: Any): + """ + Return the object parsed from the description file. + :param parsed_description: The parsed description object. + """ + self._parsed_description = parsed_description + + @abstractmethod + def load_description(self, path: str) -> Any: + """ + Loads the description from the file at the given path. + :param path: The path to the source file, if only a filename is provided then the resources directories will be + searched. + """ + pass + + def generate_description_from_file(self, path: str, extension: str) -> str: + """ + Generates and preprocesses the description from the file at the given path and returns the preprocessed + description as a string. + :param path: The path of the file to preprocess. + :param extension: The file extension of the file to preprocess. + :return: The processed description string. + """ + + if extension in self.MESH_EXTENSIONS: + description_string = self.generate_from_mesh_file(path) + elif extension == self.get_file_extension(): + description_string = self.generate_from_description_file(path) + else: + # Using the description from the parameter server + description_string = self.generate_from_parameter_server(path) + + return description_string + + def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: str) -> str: + """ + Returns the file name of the description file. + :param path_object: The path object of the description file or the mesh file. + :param extension: The file extension of the description file or the mesh file. + :param object_name: The name of the object. + :return: The file name of the description file. + """ + if extension in self.MESH_EXTENSIONS: + file_name = path_object.stem + self.get_file_extension() + elif extension == self.get_file_extension(): + file_name = path_object.name + else: + file_name = object_name + self.get_file_extension() + + return file_name + + @classmethod + @abstractmethod + def generate_from_mesh_file(cls, path: str) -> str: + """ + Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and + returns the path of the generated file. + :param path: The path to the .obj file. + :return: The path of the generated description file. + """ + pass + + @classmethod + @abstractmethod + def generate_from_description_file(cls, path: str) -> str: + """ + Preprocesses the given file and returns the preprocessed description string. + :param path: The path of the file to preprocess. + :return: The preprocessed description string. + """ + pass + + @classmethod + @abstractmethod + def generate_from_parameter_server(cls, name: str) -> str: + """ + Preprocesses the description from the ROS parameter server and returns the preprocessed description string. + :param name: The name of the description on the parameter server. + :return: The preprocessed description string. + """ + pass + + @property + @abstractmethod + def links(self) -> List[LinkDescription]: + """ + :return: A list of links descriptions of this object. + """ + pass + + @abstractmethod + def get_link_by_name(self, link_name: str) -> LinkDescription: + """ + :return: The link description with the given name. + """ + pass + + @property + @abstractmethod + def joints(self) -> List[JointDescription]: + """ + :return: A list of joints descriptions of this object. + """ + pass + + @abstractmethod + def get_joint_by_name(self, joint_name: str) -> JointDescription: + """ + :return: The joint description with the given name. + """ + pass + + @abstractmethod + def get_root(self) -> str: + """ + :return: the name of the root link of this object. + """ + pass + + @abstractmethod + def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: + """ + :return: the chain of links from 'start_link_name' to 'end_link_name'. + """ + pass + + @staticmethod + @abstractmethod + def get_file_extension() -> str: + """ + :return: The file extension of the description file. + """ + pass diff --git a/src/pycram/designator.py b/src/pycram/designator.py index a22f51a74..4dc524b4e 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -8,7 +8,8 @@ from sqlalchemy.orm.session import Session import rospy -from .world import World, Object as WorldObject +from .world import World +from .world_object import Object as WorldObject from .helper import GeneratorList, bcolors from threading import Lock from time import time diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 4efa64e49..88604d71f 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -2,7 +2,8 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..world import Object, World +from ..world import World +from ..world_object import Object from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index e52be0235..23dacdbdf 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,7 +1,8 @@ import dataclasses from typing_extensions import List, Optional, Callable import sqlalchemy.orm -from ..world import World, Object as WorldObject +from ..world import World +from ..world_object import Object as WorldObject from ..designator import ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 686f6bfab..d2c83e8e4 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -11,7 +11,8 @@ from ..pose import Pose from ..robot_descriptions import robot_description -from ..world import World, Object +from ..world import World +from ..world_object import Object from ..robot_description import ManipulatorDescription from typing_extensions import List, Tuple, Dict, Callable, Optional diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 48657fa97..4d60d7d52 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -6,7 +6,7 @@ from moveit_msgs.srv import GetPositionIK from sensor_msgs.msg import JointState -from ..world import Object +from ..world_object import Object from ..helper import calculate_wrist_tool_offset, _apply_ik from ..local_transformer import LocalTransformer from ..pose import Pose diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 4503e7a4d..a0c9fb4ae 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -13,7 +13,7 @@ from pytransform3d.rotations import quaternion_wxyz_from_xyzw, quaternion_xyzw_from_wxyz from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform -from .world import Object as WorldObject +from .world_object import Object as WorldObject from .pose import Transform, Pose import math diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index dfcc50176..a1bc00019 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -1,7 +1,8 @@ import tf import numpy as np -from .world import Object, World +from .world import World +from .world_object import Object from .world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index e4d02d306..aa2c3bc53 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -18,7 +18,8 @@ DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ MoveGripperMotion, OpeningMotion, ClosingMotion, MotionDesignatorDescription from ..robot_descriptions import robot_description -from ..world import World, Object +from ..world import World +from ..world_object import Object from ..pose import Pose from ..enums import JointType, ObjectType from ..external_interfaces import giskard diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index aa755d1c6..51ce8c3b3 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -12,7 +12,7 @@ from pycram.enums import JointType, Shape from pycram.pose import Pose -from pycram.world import JointDescription as AbstractJointDescription, \ +from pycram.description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription from pycram.world_dataclasses import Color diff --git a/src/pycram/world.py b/src/pycram/world.py index fbc6ffd4f..463ddf62f 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1,30 +1,29 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations -import logging import os -import pathlib -import re import threading import time from abc import ABC, abstractmethod +from copy import copy from queue import Queue import numpy as np import rospy -from geometry_msgs.msg import Quaternion, Point -from typing_extensions import List, Optional, Dict, Tuple, Callable, Any, Type +from geometry_msgs.msg import Point +from typing_extensions import List, Optional, Dict, Tuple, Callable from typing_extensions import Union -from .enums import JointType, ObjectType, WorldMode, Shape +from .cache_manager import CacheManager +from .enums import JointType, ObjectType, WorldMode from .event import Event from .local_transformer import LocalTransformer from .pose import Pose, Transform -from .robot_descriptions import robot_description +from .world_constraints import Constraint from .world_dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, - LinkState, ObjectState, JointState, State, WorldState) + ObjectState, State, WorldState) class StateEntity: @@ -87,6 +86,17 @@ def remove_saved_states(self) -> None: self._saved_states = {} +class WorldEntity(StateEntity, ABC): + """ + A data class that represents an entity of the world, such as an object or a link. + """ + + def __init__(self, _id: int, world: Optional[World] = None): + StateEntity.__init__(self) + self.id = _id + self.world: World = world if world is not None else World.current_world + + class World(StateEntity, ABC): """ The World Class represents the physics Simulation and belief state, it is the main interface for reasoning about @@ -107,9 +117,9 @@ class World(StateEntity, ABC): used at the moment. """ - robot: Optional[Object] = None + robot: Optional['Object'] = None """ - Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in + Global reference to the spawned 'Object'that represents the robot. The robot is identified by checking the name in the URDF with the name of the URDF on the parameter server. """ @@ -139,7 +149,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ World.current_world = self World.simulation_frequency = simulation_frequency - self.cache_manager = CacheManager() + self.cache_manager = CacheManager(self.cache_dir, self.data_directory) self.is_prospection_world: bool = is_prospection_world self._init_and_sync_prospection_world() @@ -147,7 +157,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.local_transformer = LocalTransformer() self._update_local_transformer_worlds() - self.objects: List[Object] = [] + self.objects: List['Object'] = [] # List of all Objects in the World self.id: int = -1 @@ -156,7 +166,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.mode: WorldMode = mode # The mode of the simulation, can be "GUI" or "DIRECT" - self.coll_callbacks: Dict[Tuple[Object, Object], CollisionCallbacks] = {} + self.coll_callbacks: Dict[Tuple['Object', 'Object'], CollisionCallbacks] = {} self._init_events() @@ -206,7 +216,7 @@ def _sync_prospection_world(self): self.world_sync.start() def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, - obj: Object) -> str: + obj: 'Object') -> str: """ Updates the cache directory with the given object. @@ -235,7 +245,7 @@ def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: pass # TODO: This is not used anywhere, should it be removed? - def get_objects_by_name(self, name: str) -> List[Object]: + def get_objects_by_name(self, name: str) -> List['Object']: """ Returns a list of all Objects in this World with the same name as the given one. @@ -244,7 +254,7 @@ def get_objects_by_name(self, name: str) -> List[Object]: """ return list(filter(lambda obj: obj.name == name, self.objects)) - def get_objects_by_type(self, obj_type: ObjectType) -> List[Object]: + def get_objects_by_type(self, obj_type: ObjectType) -> List['Object']: """ Returns a list of all Objects which have the type 'obj_type'. @@ -253,29 +263,29 @@ def get_objects_by_type(self, obj_type: ObjectType) -> List[Object]: """ return list(filter(lambda obj: obj.obj_type == obj_type, self.objects)) - def get_object_by_id(self, obj_id: int) -> Object: + def get_object_by_id(self, obj_id: int) -> 'Object': """ - Returns the single Object that has the unique id. + Returns the single 'Object'that has the unique id. - :param obj_id: The unique id for which the Object should be returned. - :return: The Object with the id 'id'. + :param obj_id: The unique id for which the 'Object'should be returned. + :return: The 'Object'with the id 'id'. """ return list(filter(lambda obj: obj.id == obj_id, self.objects))[0] @abstractmethod - def remove_object_from_simulator(self, obj: Object) -> None: + def remove_object_from_simulator(self, obj: 'Object') -> None: """ Removes an object from the physics simulator. :param obj: The object to be removed. """ pass - def remove_object(self, obj: Object) -> None: + def remove_object(self, obj: 'Object') -> None: """ Removes this object from the current world. For the object to be removed it has to be detached from all objects it is currently attached to. After this is done a call to world remove object is done - to remove this Object from the simulation/world. + to remove this 'Object'from the simulation/world. :param obj: The object to be removed. """ @@ -294,7 +304,8 @@ def remove_object(self, obj: Object) -> None: if World.robot == self: World.robot = None - def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_parent_transform: Transform) -> int: + def add_fixed_constraint(self, parent_link: 'Link', child_link: 'Link', + child_to_parent_transform: Transform) -> int: """ Creates a fixed joint constraint between the given parent and child links, the joint frame will be at the origin of the child link frame, and would have the same orientation @@ -335,7 +346,7 @@ def remove_constraint(self, constraint_id) -> None: pass @abstractmethod - def get_joint_position(self, obj: Object, joint_name: str) -> float: + def get_joint_position(self, obj: 'Object', joint_name: str) -> float: """ Get the position of a joint of an articulated object @@ -346,7 +357,7 @@ def get_joint_position(self, obj: Object, joint_name: str) -> float: pass @abstractmethod - def get_object_joint_names(self, obj: Object) -> List[str]: + def get_object_joint_names(self, obj: 'Object') -> List[str]: """ Returns the names of all joints of this object. @@ -356,7 +367,7 @@ def get_object_joint_names(self, obj: Object) -> List[str]: pass @abstractmethod - def get_link_pose(self, link: Link) -> Pose: + def get_link_pose(self, link: 'Link') -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. @@ -366,7 +377,7 @@ def get_link_pose(self, link: Link) -> Pose: pass @abstractmethod - def get_object_link_names(self, obj: Object) -> List[str]: + def get_object_link_names(self, obj: 'Object') -> List[str]: """ Returns the names of all links of this object. :param obj: The object. @@ -374,7 +385,7 @@ def get_object_link_names(self, obj: Object) -> List[str]: """ pass - def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: + def simulate(self, seconds: float, real_time: Optional[bool] = False) -> None: """ Simulates Physics in the World for a given amount of seconds. Usually this simulation is faster than real time. By setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal @@ -383,6 +394,7 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: :param seconds: The amount of seconds that should be simulated. :param real_time: If the simulation should happen in real time or faster. """ + self.set_realtime(real_time) for i in range(0, int(seconds * self.simulation_frequency)): curr_time = rospy.Time.now() self.step() @@ -394,7 +406,8 @@ def simulate(self, seconds: float, real_time: Optional[float] = False) -> None: callbacks.no_collision_cb() if real_time: loop_time = rospy.Time.now() - curr_time - time.sleep(max(0, self.simulation_time_step - loop_time.to_sec())) + time_diff = self.simulation_time_step - loop_time.to_sec() + time.sleep(max(0, time_diff)) self.update_all_objects_poses() def update_all_objects_poses(self) -> None: @@ -405,7 +418,7 @@ def update_all_objects_poses(self) -> None: obj.update_pose() @abstractmethod - def get_object_pose(self, obj: Object) -> Pose: + def get_object_pose(self, obj: 'Object') -> Pose: """ Get the pose of an object in the world frame from the current object pose in the simulator. """ @@ -419,9 +432,9 @@ def perform_collision_detection(self) -> None: pass @abstractmethod - def get_object_contact_points(self, obj: Object) -> List: + def get_object_contact_points(self, obj: 'Object') -> List: """ - Returns a list of contact points of this Object with all other Objects. + Returns a list of contact points of this 'Object'with all other Objects. :param obj: The object. :return: A list of all contact points with other objects @@ -429,7 +442,7 @@ def get_object_contact_points(self, obj: Object) -> List: pass @abstractmethod - def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: + def get_contact_points_between_two_objects(self, obj1: 'Object', obj2: 'Object') -> List: """ Returns a list of contact points between obj1 and obj2. @@ -440,7 +453,7 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> pass @abstractmethod - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_joint_position(self, obj: 'Object', joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -451,7 +464,7 @@ def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) pass @abstractmethod - def reset_object_base_pose(self, obj: Object, pose: Pose): + def reset_object_base_pose(self, obj: 'Object', pose: Pose): """ Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. @@ -469,7 +482,7 @@ def step(self): pass @abstractmethod - def set_link_color(self, link: Link, rgba_color: Color): + def set_link_color(self, link: 'Link', rgba_color: Color): """ Changes the rgba_color of a link of this object, the rgba_color has to be given as Color object. @@ -479,7 +492,7 @@ def set_link_color(self, link: Link, rgba_color: Color): pass @abstractmethod - def get_link_color(self, link: Link) -> Color: + def get_link_color(self, link: 'Link') -> Color: """ This method returns the rgba_color of this link. :param link: The link for which the rgba_color should be returned. @@ -488,7 +501,7 @@ def get_link_color(self, link: Link) -> Color: pass @abstractmethod - def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: + def get_colors_of_object_links(self, obj: 'Object') -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. @@ -498,7 +511,7 @@ def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: pass @abstractmethod - def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: + def get_object_axis_aligned_bounding_box(self, obj: 'Object') -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. @@ -509,7 +522,7 @@ def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundi pass @abstractmethod - def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: + def get_link_axis_aligned_bounding_box(self, link: 'Link') -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -560,21 +573,21 @@ def set_gravity(self, gravity_vector: List[float]) -> None: """ pass - def set_robot_if_not_set(self, robot: Object) -> None: + def set_robot_if_not_set(self, robot: 'Object') -> None: """ Sets the robot if it is not set yet. - :param robot: The Object reference to the Object representing the robot. + :param robot: The 'Object'reference to the 'Object'representing the robot. """ if not self.robot_is_set(): self.set_robot(robot) @staticmethod - def set_robot(robot: Union[Object, None]) -> None: + def set_robot(robot: Union['Object', None]) -> None: """ - Sets the global variable for the robot Object. This should be set on spawning the robot. + Sets the global variable for the robot 'Object' This should be set on spawning the robot. - :param robot: The Object reference to the Object representing the robot. + :param robot: The 'Object'reference to the 'Object'representing the robot. """ World.robot = robot @@ -738,7 +751,7 @@ def get_images_for_target(self, 1. An RGB image 2. A depth image - 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object. + 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible 'Object' :param target_pose: The pose to which the camera should point. :param cam_pose: The pose of the camera. @@ -748,8 +761,8 @@ def get_images_for_target(self, pass def register_two_objects_collision_callbacks(self, - object_a: Object, - object_b: Object, + object_a: 'Object', + object_b: 'Object', on_collision_callback: Callable, on_collision_removal_callback: Optional[Callable] = None) -> None: """ @@ -768,16 +781,16 @@ def register_two_objects_collision_callbacks(self, def add_resource_path(cls, path: str) -> None: """ Adds a resource path in which the World will search for files. This resource directory is searched if an - Object is spawned only with a filename. + 'Object'is spawned only with a filename. :param path: A path in the filesystem in which to search for files. """ cls.data_directory.append(path) - def get_prospection_object_for_object(self, obj: Object) -> Object: + def get_prospection_object_for_object(self, obj: 'Object') -> 'Object': """ Returns the corresponding object from the prospection world for a given object in the main world. - If the given Object is already in the prospection world, it is returned. + If the given 'Object'is already in the prospection world, it is returned. :param obj: The object for which the corresponding object in the prospection World should be found. :return: The corresponding object in the prospection world. @@ -794,7 +807,7 @@ def get_prospection_object_for_object(self, obj: Object) -> Object: f" the object isn't anymore in the main (graphical) World" f" or if the given object is already a prospection object. ") - def get_object_for_prospection_object(self, prospection_object: Object) -> Object: + def get_object_for_prospection_object(self, prospection_object: 'Object') -> 'Object': """ Returns the corresponding object from the main World for a given object in the prospection world. If the given object is not in the prospection @@ -989,7 +1002,7 @@ def remove_text(self, text_id: Optional[int] = None) -> None: """ raise NotImplementedError - def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: + def enable_joint_force_torque_sensor(self, obj: 'Object', fts_joint_idx: int) -> None: """ You can enable a joint force/torque sensor in each joint. Once enabled, if you perform a simulation step, the get_joint_reaction_force_torque will report the joint reaction forces in @@ -1001,7 +1014,7 @@ def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> N """ raise NotImplementedError - def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: + def disable_joint_force_torque_sensor(self, obj: 'Object', joint_id: int) -> None: """ Disables the force torque sensor of a joint. :param obj: The object in which the joint is located. @@ -1009,7 +1022,7 @@ def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: """ raise NotImplementedError - def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: + def get_joint_reaction_force_torque(self, obj: 'Object', joint_id: int) -> List[float]: """ Returns the joint reaction forces and torques of the specified joint. :param obj: The object in which the joint is located. @@ -1018,7 +1031,7 @@ def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[fl """ raise NotImplementedError - def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: + def get_applied_joint_motor_torque(self, obj: 'Object', joint_id: int) -> float: """ Returns the applied torque by a joint motor. :param obj: The object in which the joint is located. @@ -1086,7 +1099,7 @@ def __init__(self, world: World, prospection_world: World): self.remove_obj_queue: Queue = Queue() self.pause_sync: bool = False # Maps world to prospection world objects - self.object_mapping: Dict[Object, Object] = {} + self.object_mapping: Dict['Object', 'Object'] = {} self.equal_states = False def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): @@ -1107,9 +1120,8 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): obj = self.add_obj_queue.get() # [0:name, 1:type, 2:path, 3:description, 4:position, 5:orientation, # 6:self.world.prospection_world, 7:rgba_color, 8:world object] - o = Object(obj[0], obj[1], obj[2], obj[3], Pose(obj[4], obj[5]), obj[6], obj[7]) # Maps the World object to the prospection world object - self.object_mapping[obj[8]] = o + self.object_mapping[obj[8]] = copy(obj[8]) self.add_obj_queue.task_done() for i in range(self.remove_obj_queue.qsize()): obj = self.remove_obj_queue.get() @@ -1155,1849 +1167,3 @@ def check_for_equal(self) -> None: for obj, prospection_obj in self.object_mapping.items(): eql = eql and obj.get_pose() == prospection_obj.get_pose() self.equal_states = eql - - -class WorldEntity(StateEntity, ABC): - """ - A data class that represents an entity of the world, such as an object or a link. - """ - - def __init__(self, _id: int, world: Optional[World] = None): - StateEntity.__init__(self) - self.id = _id - self.world: World = world if world is not None else World.current_world - - -class Object(WorldEntity): - """ - Represents a spawned Object in the World. - """ - - prospection_world_prefix: str = "prospection/" - """ - The ObjectDescription of the object, this contains the name and type of the object as well as the path to the source - file. - """ - - def __init__(self, name: str, obj_type: ObjectType, path: str, - description: Type[ObjectDescription], - pose: Optional[Pose] = None, - world: Optional[World] = None, - color: Optional[Color] = Color(), - ignore_cached_files: Optional[bool] = False): - """ - The constructor loads the description file into the given World, if no World is specified the - :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. - The rgba_color parameter is only used when loading .stl or .obj files, - for URDFs :func:`~Object.set_color` can be used. - - :param name: The name of the object - :param obj_type: The type of the object as an ObjectType enum. - :param path: The path to the source file, if only a filename is provided then the resources directories will be - searched. - :param description: The ObjectDescription of the object, this contains the joints and links of the object. - :param pose: The pose at which the Object should be spawned - :param world: The World in which the object should be spawned, - if no world is specified the :py:attr:`~World.current_world` will be used. - :param color: The rgba_color with which the object should be spawned. - :param ignore_cached_files: If true the file will be spawned while ignoring cached files. - """ - - super().__init__(-1, world) - - if pose is None: - pose = Pose() - - self.name: str = name - self.obj_type: ObjectType = obj_type - self.color: Color = color - self.description = description() - self.cache_manager = self.world.cache_manager - - self.local_transformer = LocalTransformer() - self.original_pose = self.local_transformer.transform_pose(pose, "map") - self._current_pose = self.original_pose - - self.id, self.path = self._load_object_and_get_id(path, ignore_cached_files) - - self.description.update_description_from_file(self.path) - - self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") - + f"{self.name}_{self.id}") - - self._update_object_description_from_file(self.path) - - if self.description.name == robot_description.name: - self.world.set_robot_if_not_set(self) - - self._init_joint_name_and_id_map() - self._init_link_name_and_id_map() - - self._init_links_and_update_transforms() - self._init_joints() - - self.attachments: Dict[Object, Attachment] = {} - - if not self.world.is_prospection_world: - self._add_to_world_sync_obj_queue(self.path) - - self.world.objects.append(self) - - def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: - """ - Loads an object to the given World with the given position and orientation. The rgba_color will only be - used when an .obj or .stl file is given. - If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created - and this URDf file will be loaded instead. - When spawning a URDf file a new file will be created in the cache directory, if there exists none. - This new file will have resolved mesh file paths, meaning there will be no references - to ROS packges instead there will be absolute file paths. - - :param ignore_cached_files: Whether to ignore files in the cache directory. - :return: The unique id of the object and the path of the file that was loaded. - """ - - path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) - - try: - obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), - self.get_orientation_as_list())) - return obj_id, path - except Exception as e: - logging.error( - "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" - " the name of an URDF string on the parameter server.") - os.remove(path) - raise (e) - - def _update_object_description_from_file(self, path: str) -> None: - """ - Updates the object description from the given file path. - :param path: The path to the file from which the object description should be updated. - """ - self.description.update_description_from_file(path) - - def _init_joint_name_and_id_map(self) -> None: - """ - Creates a dictionary which maps the joint names to their unique ids and vice versa. - """ - n_joints = len(self.joint_names) - self.joint_name_to_id = dict(zip(self.joint_names, range(n_joints))) - self.joint_id_to_name = dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys())) - - def _init_link_name_and_id_map(self) -> None: - """ - Creates a dictionary which maps the link names to their unique ids and vice versa. - """ - n_links = len(self.link_names) - self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) - self.link_name_to_id[self.description.get_root()] = -1 - self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) - - def _init_links_and_update_transforms(self) -> None: - """ - Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the - corresponding link objects. - """ - self.links = {} - for link_name, link_id in self.link_name_to_id.items(): - link_description = self.description.get_link_by_name(link_name) - if link_name == self.description.get_root(): - self.links[link_name] = self.description.RootLink(self) - else: - self.links[link_name] = self.description.Link(link_id, link_description, self) - - self.update_link_transforms() - - def _init_joints(self): - """ - Initialize the joint objects from the URDF file and creates a dictionary which mas the joint names to the - corresponding joint objects - """ - self.joints = {} - for joint_name, joint_id in self.joint_name_to_id.items(): - joint_description = self.description.get_joint_by_name(joint_name) - self.joints[joint_name] = self.description.Joint(joint_id, joint_description, self) - - def _add_to_world_sync_obj_queue(self, path: str) -> None: - """ - Adds this object to the objects queue of the WorldSync object of the World. - :param path: The path of the URDF file of this object. - """ - self.world.world_sync.add_obj_queue.put( - [self.name, self.obj_type, path, type(self.description), self.get_position_as_list(), - self.get_orientation_as_list(), - self.world.prospection_world, self.color, self]) - - @property - def link_names(self) -> List[str]: - """ - :return: The name of each link as a list. - """ - return self.world.get_object_link_names(self) - - @property - def number_of_links(self) -> int: - """ - :return: The number of links of this object. - """ - return len(self.description.links) - - @property - def joint_names(self) -> List[str]: - """ - :return: The name of each joint as a list. - """ - return self.world.get_object_joint_names(self) - - @property - def number_of_joints(self) -> int: - """ - :return: The number of joints of this object. - """ - return len(self.description.joints) - - @property - def base_origin_shift(self) -> np.ndarray: - """ - The shift between the base of the object and the origin of the object. - :return: A numpy array with the shift between the base of the object and the origin of the object. - """ - return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) - - def __repr__(self): - skip_attr = ["links", "joints", "description", "attachments"] - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" - - def remove(self) -> None: - """ - Removes this object from the World it currently resides in. - For the object to be removed it has to be detached from all objects it - is currently attached to. After this is done a call to world remove object is done - to remove this Object from the simulation/world. - """ - self.world.remove_object(self) - - def reset(self, remove_saved_states=True) -> None: - """ - Resets the Object to the state it was first spawned in. - All attached objects will be detached, all joints will be set to the - default position of 0 and the object will be set to the position and - orientation in which it was spawned. - :param remove_saved_states: If True the saved states will be removed. - """ - self.detach_all() - self.reset_all_joints_positions() - self.set_pose(self.original_pose) - if remove_saved_states: - self.remove_saved_states() - - def attach(self, - child_object: Object, - parent_link: Optional[str] = None, - child_link: Optional[str] = None, - bidirectional: Optional[bool] = True) -> None: - """ - Attaches another object to this object. This is done by - saving the transformation between the given link, if there is one, and - the base pose of the other object. Additionally, the name of the link, to - which the object is attached, will be saved. - Furthermore, a simulator constraint will be created so the attachment - also works while simulation. - Loose attachments means that the attachment will only be one-directional. For example, if this object moves the - other, attached, object will also move but not the other way around. - - :param child_object: The other object that should be attached. - :param parent_link: The link name of this object. - :param child_link: The link name of the other object. - :param bidirectional: If the attachment should be a loose attachment. - """ - parent_link = self.links[parent_link] if parent_link else self.root_link - child_link = child_object.links[child_link] if child_link else child_object.root_link - - attachment = Attachment(parent_link, child_link, bidirectional) - - self.attachments[child_object] = attachment - child_object.attachments[self] = attachment.get_inverse() - - self.world.attachment_event(self, [self, child_object]) - - def detach(self, child_object: Object) -> None: - """ - Detaches another object from this object. This is done by - deleting the attachment from the attachments dictionary of both objects - and deleting the constraint of the simulator. - Afterward the detachment event of the corresponding World will be fired. - - :param child_object: The object which should be detached - """ - del self.attachments[child_object] - del child_object.attachments[self] - - self.world.detachment_event(self, [self, child_object]) - - def detach_all(self) -> None: - """ - Detach all objects attached to this object. - """ - attachments = self.attachments.copy() - for att in attachments.keys(): - self.detach(att) - - def update_attachment_with_object(self, child_object: Object): - self.attachments[child_object].update_transform_and_constraint() - - def get_position(self) -> Point: - """ - Returns the position of this Object as a list of xyz. - - :return: The current position of this object - """ - return self.get_pose().position - - def get_orientation(self) -> Pose.orientation: - """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. - - :return: A list of xyzw - """ - return self.get_pose().orientation - - def get_position_as_list(self) -> List[float]: - """ - Returns the position of this Object as a list of xyz. - - :return: The current position of this object - """ - return self.get_pose().position_as_list() - - def get_orientation_as_list(self) -> List[float]: - """ - Returns the orientation of this object as a list of xyzw, representing a quaternion. - - :return: A list of xyzw - """ - return self.get_pose().orientation_as_list() - - def get_pose(self) -> Pose: - """ - Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. - - :return: The current pose of this object - """ - return self._current_pose - - def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Optional[bool] = True) -> None: - """ - Sets the Pose of the object. - - :param pose: New Pose for the object - :param base: If True places the object base instead of origin at the specified position and orientation - :param set_attachments: Whether to set the poses of the attached objects to this object or not. - """ - pose_in_map = self.local_transformer.transform_pose(pose, "map") - if base: - pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift - - self.reset_base_pose(pose_in_map) - - if set_attachments: - self._set_attached_objects_poses() - - def reset_base_pose(self, pose: Pose): - self.world.reset_object_base_pose(self, pose) - self.update_pose() - - def update_pose(self): - """ - Updates the current pose of this object from the world, and updates the poses of all links. - """ - self._current_pose = self.world.get_object_pose(self) - self._update_all_links_poses() - self.update_link_transforms() - - def _update_all_joints_positions(self): - """ - Updates the posisitons of all joints by getting them from the simulator. - """ - for joint in self.joints.values(): - joint._update_position() - - def _update_all_links_poses(self): - """ - Updates the poses of all links by getting them from the simulator. - """ - for link in self.links.values(): - link._update_pose() - - def move_base_to_origin_pos(self) -> None: - """ - Move the object such that its base will be at the current origin position. - This is useful when placing objects on surfaces where you want the object base in contact with the surface. - """ - self.set_pose(self.get_pose(), base=True) - - def save_state(self, state_id) -> None: - """ - Saves the state of this object by saving the state of all links and attachments. - :param state_id: The unique id of the state. - """ - self.save_links_states(state_id) - self.save_joints_states(state_id) - super().save_state(state_id) - - def save_links_states(self, state_id: int) -> None: - """ - Saves the state of all links of this object. - :param state_id: The unique id of the state. - """ - for link in self.links.values(): - link.save_state(state_id) - - def save_joints_states(self, state_id: int) -> None: - """ - Saves the state of all joints of this object. - :param state_id: The unique id of the state. - """ - for joint in self.joints.values(): - joint.save_state(state_id) - - @property - def current_state(self) -> ObjectState: - return ObjectState(self.attachments.copy(), self.link_states, self.joint_states) - - @current_state.setter - def current_state(self, state: ObjectState) -> None: - self.attachments = state.attachments - self.link_states = state.link_states - self.joint_states = state.joint_states - - @property - def link_states(self) -> Dict[int, LinkState]: - """ - Returns the current state of all links of this object. - :return: A dictionary with the link id as key and the current state of the link as value. - """ - return {link.id: link.current_state for link in self.links.values()} - - @link_states.setter - def link_states(self, link_states: Dict[int, LinkState]) -> None: - """ - Sets the current state of all links of this object. - :param link_states: A dictionary with the link id as key and the current state of the link as value. - """ - for link in self.links.values(): - link.current_state = link_states[link.id] - - @property - def joint_states(self) -> Dict[int, JointState]: - """ - Returns the current state of all joints of this object. - :return: A dictionary with the joint id as key and the current state of the joint as value. - """ - return {joint.id: joint.current_state for joint in self.joints.values()} - - @joint_states.setter - def joint_states(self, joint_states: Dict[int, JointState]) -> None: - """ - Sets the current state of all joints of this object. - :param joint_states: A dictionary with the joint id as key and the current state of the joint as value. - """ - for joint in self.joints.values(): - joint.current_state = joint_states[joint.id] - - def restore_state(self, state_id: int) -> None: - """ - Restores the state of this object by restoring the state of all links and attachments. - :param state_id: The unique id of the state. - """ - self.restore_attachments(state_id) - self.restore_links_states(state_id) - self.restore_joints_states(state_id) - - def restore_attachments(self, state_id: int) -> None: - """ - Restores the attachments of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - self.attachments = self.saved_states[state_id].attachments - - def restore_links_states(self, state_id: int) -> None: - """ - Restores the states of all links of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - for link in self.links.values(): - link.restore_state(state_id) - - def restore_joints_states(self, state_id: int) -> None: - """ - Restores the states of all joints of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - for joint in self.joints.values(): - joint.restore_state(state_id) - - def remove_saved_states(self) -> None: - """ - Removes all saved states of this object. - """ - super().remove_saved_states() - self.remove_links_saved_states() - self.remove_joints_saved_states() - - def remove_links_saved_states(self) -> None: - """ - Removes all saved states of the links of this object. - """ - for link in self.links.values(): - link.remove_saved_states() - - def remove_joints_saved_states(self) -> None: - """ - Removes all saved states of the joints of this object. - """ - for joint in self.joints.values(): - joint.remove_saved_states() - - def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: - """ - Updates the positions of all attached objects. This is done - by calculating the new pose in world coordinate frame and setting the - base pose of the attached objects to this new pose. - After this the _set_attached_objects method of all attached objects - will be called. - - :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent - loops in the update. - """ - - if already_moved_objects is None: - already_moved_objects = [] - - for child in self.attachments: - - if child in already_moved_objects: - continue - - attachment = self.attachments[child] - if not attachment.bidirectional: - self.update_attachment_with_object(child) - child.update_attachment_with_object(self) - - else: - link_to_object = attachment.parent_to_child_transform - child.set_pose(link_to_object.to_pose(), set_attachments=False) - child._set_attached_objects_poses(already_moved_objects + [self]) - - def set_position(self, position: Union[Pose, Point], base=False) -> None: - """ - Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position - instead of the origin in the center of the Object. The given position can either be a Pose, - in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. - - :param position: Target position as xyz. - :param base: If the bottom of the Object should be placed or the origin in the center. - """ - pose = Pose() - if isinstance(position, Pose): - target_position = position.position - pose.frame = position.frame - elif isinstance(position, Point): - target_position = position - elif isinstance(position, list): - target_position = position - else: - raise TypeError("The given position has to be a Pose, Point or a list of xyz.") - - pose.position = target_position - pose.orientation = self.get_orientation() - self.set_pose(pose, base=base) - - def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: - """ - Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only - the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. - - :param orientation: Target orientation given as a list of xyzw. - """ - pose = Pose() - if isinstance(orientation, Pose): - target_orientation = orientation.orientation - pose.frame = orientation.frame - else: - target_orientation = orientation - - pose.pose.position = self.get_position() - pose.pose.orientation = target_orientation - self.set_pose(pose) - - def get_joint_id(self, name: str) -> int: - """ - Returns the unique id for a joint name. As used by the world/simulator. - - :param name: The joint name - :return: The unique id - """ - return self.joint_name_to_id[name] - - def get_root_link_description(self) -> LinkDescription: - """ - Returns the root link of the URDF of this object. - :return: The root link as defined in the URDF of this object. - """ - root_link_name = self.description.get_root() - for link_description in self.description.links: - if link_description.name == root_link_name: - return link_description - - @property - def root_link(self) -> Link: - """ - Returns the root link of this object. - :return: The root link of this object. - """ - return self.links[self.description.get_root()] - - @property - def root_link_name(self) -> str: - """ - Returns the name of the root link of this object. - :return: The name of the root link of this object. - """ - return self.description.get_root() - - def get_root_link_id(self) -> int: - """ - Returns the unique id of the root link of this object. - :return: The unique id of the root link of this object. - """ - return self.get_link_id(self.description.get_root()) - - def get_link_id(self, link_name: str) -> int: - """ - Returns a unique id for a link name. - :param link_name: The name of the link. - :return: The unique id of the link. - """ - assert link_name is not None - return self.link_name_to_id[link_name] - - def get_link_by_id(self, link_id: int) -> Link: - """ - Returns the link for a given unique link id - :param link_id: The unique id of the link. - :return: The link object. - """ - return self.links[self.link_id_to_name[link_id]] - - def get_joint_by_id(self, joint_id: int) -> str: - """ - Returns the joint name for a unique world id - - :param joint_id: The world id of for joint - :return: The joint name - """ - return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] - - def reset_all_joints_positions(self) -> None: - """ - Sets the current position of all joints to 0. This is useful if the joints should be reset to their default - """ - joint_names = list(self.joint_name_to_id.keys()) - joint_positions = [0] * len(joint_names) - self.set_joint_positions(dict(zip(joint_names, joint_positions))) - - def set_joint_positions(self, joint_poses: dict) -> None: - """ - Sets the current position of multiple joints at once, this method should be preferred when setting - multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. - - :param joint_poses: - """ - for joint_name, joint_position in joint_poses.items(): - self.joints[joint_name].position = joint_position - # self.update_pose() - self._update_all_links_poses() - self.update_link_transforms() - self._set_attached_objects_poses() - - def set_joint_position(self, joint_name: str, joint_position: float) -> None: - """ - Sets the position of the given joint to the given joint pose and updates the poses of all attached objects. - - :param joint_name: The name of the joint - :param joint_position: The target pose for this joint - """ - self.joints[joint_name].position = joint_position - self._update_all_links_poses() - self.update_link_transforms() - self._set_attached_objects_poses() - - def get_joint_position(self, joint_name: str) -> float: - return self.joints[joint_name].position - - def get_joint_damping(self, joint_name: str) -> float: - return self.joints[joint_name].damping - - def get_joint_upper_limit(self, joint_name: str) -> float: - return self.joints[joint_name].upper_limit - - def get_joint_lower_limit(self, joint_name: str) -> float: - return self.joints[joint_name].lower_limit - - def get_joint_axis(self, joint_name: str) -> Point: - return self.joints[joint_name].axis - - def get_joint_type(self, joint_name: str) -> JointType: - return self.joints[joint_name].type - - def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: - return self.joints[joint_name].limits - - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: - """ - Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. - - :param link_name: AbstractLink name above which the joint should be found - :param joint_type: Joint type that should be searched for - :return: Name of the first joint which has the given type - """ - chain = self.description.get_chain(self.description.get_root(), link_name) - reversed_chain = reversed(chain) - container_joint = None - for element in reversed_chain: - if element in self.joint_name_to_id and self.get_joint_type(element) == joint_type: - container_joint = element - break - if not container_joint: - rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") - return container_joint - - def get_positions_of_all_joints(self) -> Dict[str: float]: - """ - Returns the positions of all joints of the object as a dictionary of joint names and joint positions. - - :return: A dictionary with all joints positions'. - """ - return {j.name: j.position for j in self.joints.values()} - - def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: - """ - Updates the transforms of all links of this object using time 'transform_time' or the current ros time. - """ - for link in self.links.values(): - link.update_transform(transform_time) - - def contact_points(self) -> List: - """ - Returns a list of contact points of this Object with other Objects. - - :return: A list of all contact points with other objects - """ - return self.world.get_object_contact_points(self) - - def contact_points_simulated(self) -> List: - """ - Returns a list of all contact points between this Object and other Objects after stepping the simulation once. - - :return: A list of contact points between this Object and other Objects - """ - state_id = self.world.save_state() - self.world.step() - contact_points = self.contact_points() - self.world.restore_state(state_id) - return contact_points - - def set_color(self, rgba_color: Color) -> None: - """ - Changes the color of this object, the color has to be given as a list - of RGBA values. - - :param rgba_color: The color as Color object with RGBA values between 0 and 1 - """ - # Check if there is only one link, this is the case for primitive - # forms or if loaded from an .stl or .obj file - if self.links != {}: - for link in self.links.values(): - link.color = rgba_color - else: - self.root_link.color = rgba_color - - def get_color(self) -> Union[Color, Dict[str, Color]]: - """ - This method returns the rgba_color of this object. The return is either: - - 1. A Color object with RGBA values, this is the case if the object only has one link (this - happens for example if the object is spawned from a .obj or .stl file) - 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. - Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which - the object is spawned. - - :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and - the rgba_color as value. - """ - link_to_color_dict = self.links_colors - - if len(link_to_color_dict) == 1: - return list(link_to_color_dict.values())[0] - else: - return link_to_color_dict - - @property - def links_colors(self) -> Dict[str, Color]: - """ - The color of each link as a dictionary with link names as keys and RGBA colors as values. - """ - return self.world.get_colors_of_object_links(self) - - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: - """ - :return: The axis aligned bounding box of this object. - """ - return self.world.get_object_axis_aligned_bounding_box(self) - - def get_base_origin(self) -> Pose: - """ - :return: the origin of the base/bottom of this object. - """ - aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() - base_width = np.absolute(aabb.min_x - aabb.max_x) - base_length = np.absolute(aabb.min_y - aabb.max_y) - return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], - self.get_pose().orientation_as_list()) - - -def filter_contact_points(contact_points, exclude_ids) -> List: - """ - Returns a list of contact points where Objects that are in the 'exclude_ids' list are removed. - - :param contact_points: A list of contact points - :param exclude_ids: A list of unique ids of Objects that should be removed from the list - :return: A list containing 'contact_points' without Objects that are in 'exclude_ids' - """ - return list(filter(lambda cp: cp[2] not in exclude_ids, contact_points)) - - -class EntityDescription(ABC): - - @property - @abstractmethod - def origin(self) -> Pose: - """ - Returns the origin of this entity. - """ - pass - - @property - @abstractmethod - def name(self) -> str: - """ - Returns the name of this entity. - """ - pass - - -class LinkDescription(EntityDescription): - """ - A class that represents a link description of an object. - """ - - def __init__(self, parsed_link_description: Any): - self.parsed_description = parsed_link_description - - @property - @abstractmethod - def geometry(self) -> Shape: - """ - Returns the geometry type of the URDF collision element of this link. - """ - pass - - -class JointDescription(EntityDescription): - """ - A class that represents a joint description of a URDF joint. - """ - - def __init__(self, parsed_joint_description: Any): - self.parsed_description = parsed_joint_description - - @property - @abstractmethod - def type(self) -> JointType: - """ - :return: The type of this joint. - """ - pass - - @property - @abstractmethod - def axis(self) -> Point: - """ - :return: The axis of this joint, for example the rotation axis for a revolute joint. - """ - pass - - @property - @abstractmethod - def has_limits(self) -> bool: - """ - Checks if this joint has limits. - :return: True if the joint has limits, False otherwise. - """ - pass - - @property - def limits(self) -> Tuple[float, float]: - """ - :return: The lower and upper limits of this joint. - """ - lower, upper = self.lower_limit, self.upper_limit - if lower > upper: - lower, upper = upper, lower - return lower, upper - - @property - @abstractmethod - def lower_limit(self) -> Union[float, None]: - """ - :return: The lower limit of this joint, or None if the joint has no limits. - """ - pass - - @property - @abstractmethod - def upper_limit(self) -> Union[float, None]: - """ - :return: The upper limit of this joint, or None if the joint has no limits. - """ - pass - - @property - @abstractmethod - def parent_link_name(self) -> str: - """ - :return: The name of the parent link of this joint. - """ - pass - - @property - @abstractmethod - def child_link_name(self) -> str: - """ - :return: The name of the child link of this joint. - """ - pass - - @property - def damping(self) -> float: - """ - :return: The damping of this joint. - """ - raise NotImplementedError - - @property - def friction(self) -> float: - """ - :return: The friction of this joint. - """ - raise NotImplementedError - - -class ObjectEntity(WorldEntity): - """ - An abstract base class that represents a physical part/entity of an Object. - This can be a link or a joint of an Object. - """ - - def __init__(self, _id: int, obj: Object): - WorldEntity.__init__(self, _id, obj.world) - self.object: Object = obj - - @property - @abstractmethod - def pose(self) -> Pose: - """ - :return: The pose of this entity relative to the world frame. - """ - pass - - @property - def transform(self) -> Transform: - """ - Returns the transform of this entity. - - :return: The transform of this entity. - """ - return self.pose.to_transform(self.tf_frame) - - @property - @abstractmethod - def tf_frame(self) -> str: - """ - Returns the tf frame of this entity. - - :return: The tf frame of this entity. - """ - pass - - @property - def object_id(self) -> int: - """ - :return: the id of the object to which this entity belongs. - """ - return self.object.id - - def __repr__(self): - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" for key, value in self.__dict__.items()]) + ")" - - def __str__(self): - return self.__repr__() - - -class AbstractConstraint: - """ - Represents an abstract constraint concept, this could be used to create joints for example or any kind of constraint - between two links in the world. - """ - - def __init__(self, - parent_link: Link, - child_link: Link, - _type: JointType, - parent_to_constraint: Transform, - child_to_constraint: Transform): - self.parent_link: Link = parent_link - self.child_link: Link = child_link - self.type: JointType = _type - self.parent_to_constraint = parent_to_constraint - self.child_to_constraint = child_to_constraint - self._parent_to_child = None - - @property - def parent_to_child_transform(self) -> Union[Transform, None]: - if self._parent_to_child is None: - if self.parent_to_constraint is not None and self.child_to_constraint is not None: - self._parent_to_child = self.parent_to_constraint * self.child_to_constraint.invert() - return self._parent_to_child - - @parent_to_child_transform.setter - def parent_to_child_transform(self, transform: Transform) -> None: - self._parent_to_child = transform - - @property - def parent_object_id(self) -> int: - """ - Returns the id of the parent object of the constraint. - - :return: The id of the parent object of the constraint - """ - return self.parent_link.object_id - - @property - def child_object_id(self) -> int: - """ - Returns the id of the child object of the constraint. - - :return: The id of the child object of the constraint - """ - return self.child_link.object_id - - @property - def parent_link_id(self) -> int: - """ - Returns the id of the parent link of the constraint. - - :return: The id of the parent link of the constraint - """ - return self.parent_link.id - - @property - def child_link_id(self) -> int: - """ - Returns the id of the child link of the constraint. - - :return: The id of the child link of the constraint - """ - return self.child_link.id - - @property - def position_wrt_parent_as_list(self) -> List[float]: - """ - Returns the constraint frame pose with respect to the parent origin as a list. - - :return: The constraint frame pose with respect to the parent origin as a list - """ - return self.pose_wrt_parent.position_as_list() - - @property - def orientation_wrt_parent_as_list(self) -> List[float]: - """ - Returns the constraint frame orientation with respect to the parent origin as a list. - - :return: The constraint frame orientation with respect to the parent origin as a list - """ - return self.pose_wrt_parent.orientation_as_list() - - @property - def pose_wrt_parent(self) -> Pose: - """ - Returns the joint frame pose with respect to the parent origin. - - :return: The joint frame pose with respect to the parent origin - """ - return self.parent_to_constraint.to_pose() - - @property - def position_wrt_child_as_list(self) -> List[float]: - """ - Returns the constraint frame pose with respect to the child origin as a list. - - :return: The constraint frame pose with respect to the child origin as a list - """ - return self.pose_wrt_child.position_as_list() - - @property - def orientation_wrt_child_as_list(self) -> List[float]: - """ - Returns the constraint frame orientation with respect to the child origin as a list. - - :return: The constraint frame orientation with respect to the child origin as a list - """ - return self.pose_wrt_child.orientation_as_list() - - @property - def pose_wrt_child(self) -> Pose: - """ - Returns the joint frame pose with respect to the child origin. - - :return: The joint frame pose with respect to the child origin - """ - return self.child_to_constraint.to_pose() - - -class Constraint(AbstractConstraint): - """ - Represents a constraint between two links in the World. - """ - - def __init__(self, - parent_link: Link, - child_link: Link, - _type: JointType, - axis_in_child_frame: Point, - constraint_to_parent: Transform, - child_to_constraint: Transform): - parent_to_constraint = constraint_to_parent.invert() - AbstractConstraint.__init__(self, parent_link, child_link, _type, parent_to_constraint, child_to_constraint) - self.axis: Point = axis_in_child_frame - - @property - def axis_as_list(self) -> List[float]: - """ - Returns the axis of this constraint as a list. - - :return: The axis of this constraint as a list of xyz - """ - return [self.axis.x, self.axis.y, self.axis.z] - - -class Joint(ObjectEntity, JointDescription, ABC): - """ - Represents a joint of an Object in the World. - """ - - def __init__(self, _id: int, - joint_description: JointDescription, - obj: Object): - ObjectEntity.__init__(self, _id, obj) - JointDescription.__init__(self, joint_description.parsed_description) - self._update_position() - - @property - def tf_frame(self) -> str: - """ - The tf frame of a joint is the tf frame of the child link. - """ - return self.child_link.tf_frame - - @property - def pose(self) -> Pose: - """ - Returns the pose of this joint. The pose is the pose of the child link of this joint. - - :return: The pose of this joint. - """ - return self.child_link.pose - - def _update_position(self) -> None: - """ - Updates the current position of the joint from the physics simulator. - """ - self._current_position = self.world.get_joint_position(self.object, self.name) - - @property - def parent_link(self) -> Link: - """ - Returns the parent link of this joint. - :return: The parent link as a AbstractLink object. - """ - return self.object.links[self.parent_link_name] - - @property - def child_link(self) -> Link: - """ - Returns the child link of this joint. - :return: The child link as a AbstractLink object. - """ - return self.object.links[self.child_link_name] - - @property - def position(self) -> float: - return self._current_position - - def reset_position(self, position: float) -> None: - self.world.reset_joint_position(self.object, self.name, position) - self._update_position() - - def get_object_id(self) -> int: - """ - Returns the id of the object to which this joint belongs. - :return: The integer id of the object to which this joint belongs. - """ - return self.object.id - - @position.setter - def position(self, joint_position: float) -> None: - """ - Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. - - :param joint_position: The target pose for this joint - """ - # TODO Limits for rotational (infinitie) joints are 0 and 1, they should be considered seperatly - if self.has_limits: - low_lim, up_lim = self.limits - if not low_lim <= joint_position <= up_lim: - logging.error( - f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" - f" are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_position}") - # Temporarily disabled because kdl outputs values exciting joint limits - # return - self.reset_position(joint_position) - - def enable_force_torque_sensor(self) -> None: - self.world.enable_joint_force_torque_sensor(self.object, self.id) - - def disable_force_torque_sensor(self) -> None: - self.world.disable_joint_force_torque_sensor(self.object, self.id) - - def get_reaction_force_torque(self) -> List[float]: - return self.world.get_joint_reaction_force_torque(self.object, self.id) - - def get_applied_motor_torque(self) -> float: - return self.world.get_applied_joint_motor_torque(self.object, self.id) - - def restore_state(self, state_id: int) -> None: - self.current_state = self.saved_states[state_id] - - @property - def current_state(self) -> JointState: - return JointState(self.position) - - @current_state.setter - def current_state(self, joint_state: JointState) -> None: - self.position = joint_state.position - - -class Link(ObjectEntity, LinkDescription, ABC): - """ - Represents a link of an Object in the World. - """ - - def __init__(self, _id: int, link_description: LinkDescription, obj: Object): - ObjectEntity.__init__(self, _id, obj) - LinkDescription.__init__(self, link_description.parsed_description) - self.local_transformer: LocalTransformer = LocalTransformer() - self.constraint_ids: Dict[Link, int] = {} - self._update_pose() - - @property - def current_state(self) -> LinkState: - return LinkState(self.constraint_ids.copy()) - - @current_state.setter - def current_state(self, link_state: LinkState) -> None: - self.constraint_ids = link_state.constraint_ids - - def add_fixed_constraint_with_link(self, child_link: Link) -> int: - """ - Adds a fixed constraint between this link and the given link, used to create attachments for example. - :param child_link: The child link to which a fixed constraint should be added. - :return: The unique id of the constraint. - """ - constraint_id = self.world.add_fixed_constraint(self, - child_link, - child_link.get_transform_from_link(self)) - self.constraint_ids[child_link] = constraint_id - child_link.constraint_ids[self] = constraint_id - return constraint_id - - def remove_constraint_with_link(self, child_link: Link) -> None: - """ - Removes the constraint between this link and the given link. - :param child_link: The child link of the constraint that should be removed. - """ - self.world.remove_constraint(self.constraint_ids[child_link]) - del self.constraint_ids[child_link] - del child_link.constraint_ids[self] - - @property - def is_root(self) -> bool: - """ - Returns whether this link is the root link of the object. - :return: True if this link is the root link, False otherwise. - """ - return self.object.get_root_link_id() == self.id - - def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: - """ - Updates the transformation of this link at the given time. - :param transform_time: The time at which the transformation should be updated. - """ - self.local_transformer.update_transforms([self.transform], transform_time) - - def get_transform_to_link(self, link: Link) -> Transform: - """ - Returns the transformation from this link to the given link. - :param link: The link to which the transformation should be returned. - :return: A Transform object with the transformation from this link to the given link. - """ - return link.get_transform_from_link(self) - - def get_transform_from_link(self, link: Link) -> Transform: - """ - Returns the transformation from the given link to this link. - :param link: The link from which the transformation should be returned. - :return: A Transform object with the transformation from the given link to this link. - """ - return self.get_pose_wrt_link(link).to_transform(self.tf_frame) - - def get_pose_wrt_link(self, link: Link) -> Pose: - """ - Returns the pose of this link with respect to the given link. - :param link: The link with respect to which the pose should be returned. - :return: A Pose object with the pose of this link with respect to the given link. - """ - return self.local_transformer.transform_pose(self.pose, link.tf_frame) - - def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: - """ - Returns the axis aligned bounding box of this link. - :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. - """ - return self.world.get_link_axis_aligned_bounding_box(self) - - @property - def position(self) -> Point: - """ - The getter for the position of the link relative to the world frame. - :return: A Point object containing the position of the link relative to the world frame. - """ - return self.pose.position - - @property - def position_as_list(self) -> List[float]: - """ - The getter for the position of the link relative to the world frame as a list. - :return: A list containing the position of the link relative to the world frame. - """ - return self.pose.position_as_list() - - @property - def orientation(self) -> Quaternion: - """ - The getter for the orientation of the link relative to the world frame. - :return: A Quaternion object containing the orientation of the link relative to the world frame. - """ - return self.pose.orientation - - @property - def orientation_as_list(self) -> List[float]: - """ - The getter for the orientation of the link relative to the world frame as a list. - :return: A list containing the orientation of the link relative to the world frame. - """ - return self.pose.orientation_as_list() - - def _update_pose(self) -> None: - """ - Updates the current pose of this link from the world. - """ - self._current_pose = self.world.get_link_pose(self) - - @property - def pose(self) -> Pose: - """ - The pose of the link relative to the world frame. - :return: A Pose object containing the pose of the link relative to the world frame. - """ - return self._current_pose - - @property - def pose_as_list(self) -> List[List[float]]: - """ - The pose of the link relative to the world frame as a list. - :return: A list containing the position and orientation of the link relative to the world frame. - """ - return self.pose.to_list() - - def get_origin_transform(self) -> Transform: - """ - Returns the transformation between the link frame and the origin frame of this link. - """ - return self.origin.to_transform(self.tf_frame) - - @property - def color(self) -> Color: - """ - The getter for the rgba_color of this link. - :return: A Color object containing the rgba_color of this link. - """ - return self.world.get_link_color(self) - - @color.setter - def color(self, color: List[float]) -> None: - """ - The setter for the color of this link, could be rgb or rgba. - :param color: The color as a list of floats, either rgb or rgba. - """ - self.world.set_link_color(self, Color.from_list(color)) - - @property - def origin_transform(self) -> Transform: - """ - :return: The transform from world to origin of entity. - """ - return self.origin.to_transform(self.tf_frame) - - @property - def tf_frame(self) -> str: - """ - The name of the tf frame of this link. - """ - return f"{self.object.tf_frame}/{self.name}" - - -class RootLink(Link, ABC): - """ - Represents the root link of an Object in the World. - It differs from the normal AbstractLink class in that the pose ande the tf_frame is the same as that of the object. - """ - - def __init__(self, obj: Object): - super().__init__(obj.get_root_link_id(), obj.get_root_link_description(), obj) - - @property - def tf_frame(self) -> str: - """ - Returns the tf frame of the root link, which is the same as the tf frame of the object. - """ - return self.object.tf_frame - - def _update_pose(self) -> None: - self._current_pose = self.object.get_pose() - - -class ObjectDescription(EntityDescription): - MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") - - class Link(Link, ABC): - ... - - class RootLink(RootLink, ABC): - ... - - class Joint(Joint, ABC): - ... - - def __init__(self, path: Optional[str] = None): - if path: - self.update_description_from_file(path) - else: - self._parsed_description = None - - def update_description_from_file(self, path: str) -> None: - """ - Updates the description of this object from the file at the given path. - :param path: The path of the file to update from. - """ - self._parsed_description = self.load_description(path) - - @property - def parsed_description(self) -> Any: - """ - Return the object parsed from the description file. - """ - return self._parsed_description - - @parsed_description.setter - def parsed_description(self, parsed_description: Any): - """ - Return the object parsed from the description file. - :param parsed_description: The parsed description object. - """ - self._parsed_description = parsed_description - - @abstractmethod - def load_description(self, path: str) -> Any: - """ - Loads the description from the file at the given path. - :param path: The path to the source file, if only a filename is provided then the resources directories will be - searched. - """ - pass - - def generate_description_from_file(self, path: str, extension: str) -> str: - """ - Generates and preprocesses the description from the file at the given path and returns the preprocessed - description as a string. - :param path: The path of the file to preprocess. - :param extension: The file extension of the file to preprocess. - :return: The processed description string. - """ - - if extension in self.MESH_EXTENSIONS: - description_string = self.generate_from_mesh_file(path) - elif extension == self.get_file_extension(): - description_string = self.generate_from_description_file(path) - else: - # Using the description from the parameter server - description_string = self.generate_from_parameter_server(path) - - return description_string - - def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: str) -> str: - """ - Returns the file name of the description file. - :param path_object: The path object of the description file or the mesh file. - :param extension: The file extension of the description file or the mesh file. - :param object_name: The name of the object. - :return: The file name of the description file. - """ - if extension in self.MESH_EXTENSIONS: - file_name = path_object.stem + self.get_file_extension() - elif extension == self.get_file_extension(): - file_name = path_object.name - else: - file_name = object_name + self.get_file_extension() - - return file_name - - @classmethod - @abstractmethod - def generate_from_mesh_file(cls, path: str) -> str: - """ - Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and - returns the path of the generated file. - :param path: The path to the .obj file. - :return: The path of the generated description file. - """ - pass - - @classmethod - @abstractmethod - def generate_from_description_file(cls, path: str) -> str: - """ - Preprocesses the given file and returns the preprocessed description string. - :param path: The path of the file to preprocess. - :return: The preprocessed description string. - """ - pass - - @classmethod - @abstractmethod - def generate_from_parameter_server(cls, name: str) -> str: - """ - Preprocesses the description from the ROS parameter server and returns the preprocessed description string. - :param name: The name of the description on the parameter server. - :return: The preprocessed description string. - """ - pass - - @property - @abstractmethod - def links(self) -> List[LinkDescription]: - """ - :return: A list of links descriptions of this object. - """ - pass - - @abstractmethod - def get_link_by_name(self, link_name: str) -> LinkDescription: - """ - :return: The link description with the given name. - """ - pass - - @property - @abstractmethod - def joints(self) -> List[JointDescription]: - """ - :return: A list of joints descriptions of this object. - """ - pass - - @abstractmethod - def get_joint_by_name(self, joint_name: str) -> JointDescription: - """ - :return: The joint description with the given name. - """ - pass - - @abstractmethod - def get_root(self) -> str: - """ - :return: the name of the root link of this object. - """ - pass - - @abstractmethod - def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: - """ - :return: the chain of links from 'start_link_name' to 'end_link_name'. - """ - pass - - @staticmethod - @abstractmethod - def get_file_extension() -> str: - """ - :return: The file extension of the description file. - """ - pass - - -class Attachment(AbstractConstraint): - def __init__(self, - parent_link: Link, - child_link: Link, - bidirectional: Optional[bool] = False, - parent_to_child_transform: Optional[Transform] = None, - constraint_id: Optional[int] = None): - """ - Creates an attachment between the parent object link and the child object link. - This could be a bidirectional attachment, meaning that both objects will move when one moves. - :param parent_link: The parent object link. - :param child_link: The child object link. - :param bidirectional: If true, both objects will move when one moves. - :param parent_to_child_transform: The transform from the parent link to the child object link. - :param constraint_id: The id of the constraint in the simulator. - """ - super().__init__(parent_link, child_link, JointType.FIXED, parent_to_child_transform, - Transform(frame=child_link.tf_frame)) - self.id = constraint_id - self.bidirectional: bool = bidirectional - self._loose: bool = False - - if self.parent_to_child_transform is None: - self.update_transform() - - if self.id is None: - self.add_fixed_constraint() - - def update_transform_and_constraint(self) -> None: - """ - Updates the transform and constraint of this attachment. - """ - self.update_transform() - self.update_constraint() - - def update_transform(self) -> None: - """ - Updates the transform of this attachment by calculating the transform from the parent link to the child link. - """ - self.parent_to_child_transform = self.calculate_transform() - - def update_constraint(self) -> None: - """ - Updates the constraint of this attachment by removing the old constraint if one exists and adding a new one. - """ - self.remove_constraint_if_exists() - self.add_fixed_constraint() - - def add_fixed_constraint(self) -> None: - """ - Adds a fixed constraint between the parent link and the child link. - """ - self.id = self.parent_link.add_fixed_constraint_with_link(self.child_link) - - def calculate_transform(self) -> Transform: - """ - Calculates the transform from the parent link to the child link. - """ - return self.parent_link.get_transform_to_link(self.child_link) - - def remove_constraint_if_exists(self) -> None: - """ - Removes the constraint between the parent and the child links if one exists. - """ - if self.child_link in self.parent_link.constraint_ids: - self.parent_link.remove_constraint_with_link(self.child_link) - - def get_inverse(self) -> Attachment: - """ - :return: A new Attachment object with the parent and child links swapped. - """ - attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, - constraint_id=self.id) - attachment.loose = not self._loose - return attachment - - @property - def loose(self) -> bool: - """ - If true, then the child object will not move when parent moves. - """ - return self._loose - - @loose.setter - def loose(self, loose: bool) -> None: - """ - Sets the loose property of this attachment. - :param loose: If true, then the child object will not move when parent moves. - """ - self._loose = loose and not self.bidirectional - - @property - def is_reversed(self) -> bool: - """ - :return: True if the parent and child links are swapped. - """ - return self.loose - - def __del__(self) -> None: - """ - Removes the constraint between the parent and the child links if one exists when the attachment is deleted. - """ - self.remove_constraint_if_exists() - - -class CacheManager: - cache_dir: str = World.cache_dir - """ - The directory where the cached files are stored. - """ - - mesh_extensions: List[str] = [".obj", ".stl"] - """ - The file extensions of mesh files. - """ - - def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, - object_description: ObjectDescription, object_name: str) -> str: - """ - Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. - """ - path_object = pathlib.Path(path) - extension = path_object.suffix - - path = self.look_for_file_in_data_dir(path, path_object) - - self.create_cache_dir_if_not_exists() - - # save correct path in case the file is already in the cache directory - cache_path = self.cache_dir + object_description.get_file_name(path_object, extension, object_name) - - # if file is not yet cached preprocess the description file and save it in the cache directory. - if not self.is_cached(path, object_description) or ignore_cached_files: - self.generate_description_and_write_to_cache(path, extension, cache_path, object_description) - - return cache_path - - def generate_description_and_write_to_cache(self, path: str, extension: str, cache_path: str, - object_description: ObjectDescription) -> None: - """ - Generates the description from the file at the given path and writes it to the cache directory. - :param path: The path of the file to preprocess. - :param extension: The file extension of the file to preprocess. - :param cache_path: The path of the file in the cache directory. - :param object_description: The object description of the file. - """ - description_string = object_description.generate_description_from_file(path, extension) - self.write_to_cache(description_string, cache_path) - - @staticmethod - def write_to_cache(description_string: str, cache_path: str) -> None: - """ - Writes the description string to the cache directory. - :param description_string: The description string to write to the cache directory. - :param cache_path: The path of the file in the cache directory. - """ - with open(cache_path, "w") as file: - file.write(description_string) - - @staticmethod - def look_for_file_in_data_dir(path: str, path_object: pathlib.Path) -> str: - """ - Looks for a file in the data directory of the World. If the file is not found in the data directory, this method - raises a FileNotFoundError. - :param path: The path of the file to look for. - :param path_object: The pathlib object of the file to look for. - """ - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for data_dir in World.data_directory: - for file in os.listdir(data_dir): - if file == path: - return data_dir + f"/{path}" - if path: - break - - if not path: - raise FileNotFoundError( - f"File {path_object.name} could not be found in the resource directory {World.data_directory}") - - return path - - def create_cache_dir_if_not_exists(self): - """ - Creates the cache directory if it does not exist. - """ - if not pathlib.Path(self.cache_dir).exists(): - os.mkdir(self.cache_dir) - - def is_cached(self, path: str, object_description: ObjectDescription) -> bool: - """ - Checks if the file in the given path is already cached or if - there is already a cached file with the given name, this is the case if a .stl, .obj file or a description from - the parameter server is used. - - :param path: The path of the file to check. - :param object_description: The object description of the file. - :return: True if there already exists a cached file, False in any other case. - """ - return True if self.check_with_extension(path) else self.check_without_extension(path, object_description) - - def check_with_extension(self, path: str) -> bool: - """ - Checks if the file in the given ath exists in the cache directory including file extension. - :param path: The path of the file to check. - """ - file_name = pathlib.Path(path).name - full_path = pathlib.Path(self.cache_dir + file_name) - return full_path.exists() - - def check_without_extension(self, path: str, object_description: ObjectDescription) -> bool: - """ - Checks if the file in the given path exists in the cache directory without file extension, - the extension is added after the file name manually in this case. - :param path: The path of the file to check. - :param object_description: The object description of the file. - """ - file_stem = pathlib.Path(path).stem - full_path = pathlib.Path(self.cache_dir + file_stem + object_description.get_file_extension()) - return full_path.exists() diff --git a/src/pycram/world_constraints.py b/src/pycram/world_constraints.py new file mode 100644 index 000000000..f301f0ff9 --- /dev/null +++ b/src/pycram/world_constraints.py @@ -0,0 +1,257 @@ +from geometry_msgs.msg import Point +from typing_extensions import Union, List, Optional + +from pycram.enums import JointType +from pycram.pose import Transform, Pose + + +class AbstractConstraint: + """ + Represents an abstract constraint concept, this could be used to create joints for example or any kind of constraint + between two links in the world. + """ + + def __init__(self, + parent_link: 'Link', + child_link: 'Link', + _type: JointType, + parent_to_constraint: Transform, + child_to_constraint: Transform): + self.parent_link: 'Link' = parent_link + self.child_link: 'Link' = child_link + self.type: JointType = _type + self.parent_to_constraint = parent_to_constraint + self.child_to_constraint = child_to_constraint + self._parent_to_child = None + + @property + def parent_to_child_transform(self) -> Union[Transform, None]: + if self._parent_to_child is None: + if self.parent_to_constraint is not None and self.child_to_constraint is not None: + self._parent_to_child = self.parent_to_constraint * self.child_to_constraint.invert() + return self._parent_to_child + + @parent_to_child_transform.setter + def parent_to_child_transform(self, transform: Transform) -> None: + self._parent_to_child = transform + + @property + def parent_object_id(self) -> int: + """ + Returns the id of the parent object of the constraint. + + :return: The id of the parent object of the constraint + """ + return self.parent_link.object_id + + @property + def child_object_id(self) -> int: + """ + Returns the id of the child object of the constraint. + + :return: The id of the child object of the constraint + """ + return self.child_link.object_id + + @property + def parent_link_id(self) -> int: + """ + Returns the id of the parent link of the constraint. + + :return: The id of the parent link of the constraint + """ + return self.parent_link.id + + @property + def child_link_id(self) -> int: + """ + Returns the id of the child link of the constraint. + + :return: The id of the child link of the constraint + """ + return self.child_link.id + + @property + def position_wrt_parent_as_list(self) -> List[float]: + """ + Returns the constraint frame pose with respect to the parent origin as a list. + + :return: The constraint frame pose with respect to the parent origin as a list + """ + return self.pose_wrt_parent.position_as_list() + + @property + def orientation_wrt_parent_as_list(self) -> List[float]: + """ + Returns the constraint frame orientation with respect to the parent origin as a list. + + :return: The constraint frame orientation with respect to the parent origin as a list + """ + return self.pose_wrt_parent.orientation_as_list() + + @property + def pose_wrt_parent(self) -> Pose: + """ + Returns the joint frame pose with respect to the parent origin. + + :return: The joint frame pose with respect to the parent origin + """ + return self.parent_to_constraint.to_pose() + + @property + def position_wrt_child_as_list(self) -> List[float]: + """ + Returns the constraint frame pose with respect to the child origin as a list. + + :return: The constraint frame pose with respect to the child origin as a list + """ + return self.pose_wrt_child.position_as_list() + + @property + def orientation_wrt_child_as_list(self) -> List[float]: + """ + Returns the constraint frame orientation with respect to the child origin as a list. + + :return: The constraint frame orientation with respect to the child origin as a list + """ + return self.pose_wrt_child.orientation_as_list() + + @property + def pose_wrt_child(self) -> Pose: + """ + Returns the joint frame pose with respect to the child origin. + + :return: The joint frame pose with respect to the child origin + """ + return self.child_to_constraint.to_pose() + + +class Constraint(AbstractConstraint): + """ + Represents a constraint between two links in the World. + """ + + def __init__(self, + parent_link: 'Link', + child_link: 'Link', + _type: JointType, + axis_in_child_frame: Point, + constraint_to_parent: Transform, + child_to_constraint: Transform): + parent_to_constraint = constraint_to_parent.invert() + AbstractConstraint.__init__(self, parent_link, child_link, _type, parent_to_constraint, child_to_constraint) + self.axis: Point = axis_in_child_frame + + @property + def axis_as_list(self) -> List[float]: + """ + Returns the axis of this constraint as a list. + + :return: The axis of this constraint as a list of xyz + """ + return [self.axis.x, self.axis.y, self.axis.z] + + +class Attachment(AbstractConstraint): + def __init__(self, + parent_link: 'Link', + child_link: 'Link', + bidirectional: Optional[bool] = False, + parent_to_child_transform: Optional[Transform] = None, + constraint_id: Optional[int] = None): + """ + Creates an attachment between the parent object link and the child object link. + This could be a bidirectional attachment, meaning that both objects will move when one moves. + :param parent_link: The parent object link. + :param child_link: The child object link. + :param bidirectional: If true, both objects will move when one moves. + :param parent_to_child_transform: The transform from the parent link to the child object link. + :param constraint_id: The id of the constraint in the simulator. + """ + super().__init__(parent_link, child_link, JointType.FIXED, parent_to_child_transform, + Transform(frame=child_link.tf_frame)) + self.id = constraint_id + self.bidirectional: bool = bidirectional + self._loose: bool = False + + if self.parent_to_child_transform is None: + self.update_transform() + + if self.id is None: + self.add_fixed_constraint() + + def update_transform_and_constraint(self) -> None: + """ + Updates the transform and constraint of this attachment. + """ + self.update_transform() + self.update_constraint() + + def update_transform(self) -> None: + """ + Updates the transform of this attachment by calculating the transform from the parent link to the child link. + """ + self.parent_to_child_transform = self.calculate_transform() + + def update_constraint(self) -> None: + """ + Updates the constraint of this attachment by removing the old constraint if one exists and adding a new one. + """ + self.remove_constraint_if_exists() + self.add_fixed_constraint() + + def add_fixed_constraint(self) -> None: + """ + Adds a fixed constraint between the parent link and the child link. + """ + self.id = self.parent_link.add_fixed_constraint_with_link(self.child_link) + + def calculate_transform(self) -> Transform: + """ + Calculates the transform from the parent link to the child link. + """ + return self.parent_link.get_transform_to_link(self.child_link) + + def remove_constraint_if_exists(self) -> None: + """ + Removes the constraint between the parent and the child links if one exists. + """ + if self.child_link in self.parent_link.constraint_ids: + self.parent_link.remove_constraint_with_link(self.child_link) + + def get_inverse(self) -> 'Attachment': + """ + :return: A new Attachment object with the parent and child links swapped. + """ + attachment = Attachment(self.child_link, self.parent_link, self.bidirectional, + constraint_id=self.id) + attachment.loose = not self._loose + return attachment + + @property + def loose(self) -> bool: + """ + If true, then the child object will not move when parent moves. + """ + return self._loose + + @loose.setter + def loose(self, loose: bool) -> None: + """ + Sets the loose property of this attachment. + :param loose: If true, then the child object will not move when parent moves. + """ + self._loose = loose and not self.bidirectional + + @property + def is_reversed(self) -> bool: + """ + :return: True if the parent and child links are swapped. + """ + return self.loose + + def __del__(self) -> None: + """ + Removes the constraint between the parent and the child links if one exists when the attachment is deleted. + """ + self.remove_constraint_if_exists() diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py new file mode 100644 index 000000000..5e2eabf69 --- /dev/null +++ b/src/pycram/world_object.py @@ -0,0 +1,822 @@ +import logging +import os + +import numpy as np +import rospy +from geometry_msgs.msg import Point, Quaternion +from typing_extensions import Type, Optional, Dict, Tuple, List, Union + +from pycram.enums import ObjectType, JointType +from pycram.local_transformer import LocalTransformer +from pycram.pose import Pose +from pycram.robot_descriptions import robot_description +from pycram.world import WorldEntity, World +from pycram.world_constraints import Attachment +from pycram.world_dataclasses import Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox + + +class Object(WorldEntity): + """ + Represents a spawned Object in the World. + """ + + prospection_world_prefix: str = "prospection/" + """ + The ObjectDescription of the object, this contains the name and type of the object as well as the path to the source + file. + """ + + def __init__(self, name: str, obj_type: ObjectType, path: str, + description: Type['ObjectDescription'], + pose: Optional[Pose] = None, + world: Optional[World] = None, + color: Optional[Color] = Color(), + ignore_cached_files: Optional[bool] = False): + """ + The constructor loads the description file into the given World, if no World is specified the + :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. + The rgba_color parameter is only used when loading .stl or .obj files, + for URDFs :func:`~Object.set_color` can be used. + + :param name: The name of the object + :param obj_type: The type of the object as an ObjectType enum. + :param path: The path to the source file, if only a filename is provided then the resources directories will be + searched. + :param description: The ObjectDescription of the object, this contains the joints and links of the object. + :param pose: The pose at which the Object should be spawned + :param world: The World in which the object should be spawned, + if no world is specified the :py:attr:`~World.current_world` will be used. + :param color: The rgba_color with which the object should be spawned. + :param ignore_cached_files: If true the file will be spawned while ignoring cached files. + """ + + super().__init__(-1, world) + + if pose is None: + pose = Pose() + + self.name: str = name + self.obj_type: ObjectType = obj_type + self.color: Color = color + self.description = description() + self.cache_manager = self.world.cache_manager + + self.local_transformer = LocalTransformer() + self.original_pose = self.local_transformer.transform_pose(pose, "map") + self._current_pose = self.original_pose + + self.id, self.path = self._load_object_and_get_id(path, ignore_cached_files) + + self.description.update_description_from_file(self.path) + + self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + + f"{self.name}_{self.id}") + + self._update_object_description_from_file(self.path) + + if self.description.name == robot_description.name: + self.world.set_robot_if_not_set(self) + + self._init_joint_name_and_id_map() + self._init_link_name_and_id_map() + + self._init_links_and_update_transforms() + self._init_joints() + + self.attachments: Dict[Object, Attachment] = {} + + if not self.world.is_prospection_world: + self._add_to_world_sync_obj_queue() + + self.world.objects.append(self) + + def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: + """ + Loads an object to the given World with the given position and orientation. The rgba_color will only be + used when an .obj or .stl file is given. + If a .obj or .stl file is given, before spawning, an urdf file with the .obj or .stl as mesh will be created + and this URDf file will be loaded instead. + When spawning a URDf file a new file will be created in the cache directory, if there exists none. + This new file will have resolved mesh file paths, meaning there will be no references + to ROS packges instead there will be absolute file paths. + + :param ignore_cached_files: Whether to ignore files in the cache directory. + :return: The unique id of the object and the path of the file that was loaded. + """ + + path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) + + try: + obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), + self.get_orientation_as_list())) + return obj_id, path + except Exception as e: + logging.error( + "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" + " the name of an URDF string on the parameter server.") + os.remove(path) + raise (e) + + def _update_object_description_from_file(self, path: str) -> None: + """ + Updates the object description from the given file path. + :param path: The path to the file from which the object description should be updated. + """ + self.description.update_description_from_file(path) + + def _init_joint_name_and_id_map(self) -> None: + """ + Creates a dictionary which maps the joint names to their unique ids and vice versa. + """ + n_joints = len(self.joint_names) + self.joint_name_to_id = dict(zip(self.joint_names, range(n_joints))) + self.joint_id_to_name = dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys())) + + def _init_link_name_and_id_map(self) -> None: + """ + Creates a dictionary which maps the link names to their unique ids and vice versa. + """ + n_links = len(self.link_names) + self.link_name_to_id: Dict[str, int] = dict(zip(self.link_names, range(n_links))) + self.link_name_to_id[self.description.get_root()] = -1 + self.link_id_to_name: Dict[int, str] = dict(zip(self.link_name_to_id.values(), self.link_name_to_id.keys())) + + def _init_links_and_update_transforms(self) -> None: + """ + Initializes the link objects from the URDF file and creates a dictionary which maps the link names to the + corresponding link objects. + """ + self.links = {} + for link_name, link_id in self.link_name_to_id.items(): + link_description = self.description.get_link_by_name(link_name) + if link_name == self.description.get_root(): + self.links[link_name] = self.description.RootLink(self) + else: + self.links[link_name] = self.description.Link(link_id, link_description, self) + + self.update_link_transforms() + + def _init_joints(self): + """ + Initialize the joint objects from the URDF file and creates a dictionary which mas the joint names to the + corresponding joint objects + """ + self.joints = {} + for joint_name, joint_id in self.joint_name_to_id.items(): + joint_description = self.description.get_joint_by_name(joint_name) + self.joints[joint_name] = self.description.Joint(joint_id, joint_description, self) + + def _add_to_world_sync_obj_queue(self) -> None: + """ + Adds this object to the objects queue of the WorldSync object of the World. + """ + self.world.world_sync.add_obj_queue.put( + [self.name, self.obj_type, self.path, type(self.description), self.get_position_as_list(), + self.get_orientation_as_list(), + self.world.prospection_world, self.color, self]) + + @property + def link_names(self) -> List[str]: + """ + :return: The name of each link as a list. + """ + return self.world.get_object_link_names(self) + + @property + def number_of_links(self) -> int: + """ + :return: The number of links of this object. + """ + return len(self.description.links) + + @property + def joint_names(self) -> List[str]: + """ + :return: The name of each joint as a list. + """ + return self.world.get_object_joint_names(self) + + @property + def number_of_joints(self) -> int: + """ + :return: The number of joints of this object. + """ + return len(self.description.joints) + + @property + def base_origin_shift(self) -> np.ndarray: + """ + The shift between the base of the object and the origin of the object. + :return: A numpy array with the shift between the base of the object and the origin of the object. + """ + return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) + + def __repr__(self): + skip_attr = ["links", "joints", "description", "attachments"] + return self.__class__.__qualname__ + f"(" + ', \n'.join( + [f"{key}={value}" if key not in skip_attr else f"{key}: ..." for key, value in self.__dict__.items()]) + ")" + + def remove(self) -> None: + """ + Removes this object from the World it currently resides in. + For the object to be removed it has to be detached from all objects it + is currently attached to. After this is done a call to world remove object is done + to remove this Object from the simulation/world. + """ + self.world.remove_object(self) + + def reset(self, remove_saved_states=True) -> None: + """ + Resets the Object to the state it was first spawned in. + All attached objects will be detached, all joints will be set to the + default position of 0 and the object will be set to the position and + orientation in which it was spawned. + :param remove_saved_states: If True the saved states will be removed. + """ + self.detach_all() + self.reset_all_joints_positions() + self.set_pose(self.original_pose) + if remove_saved_states: + self.remove_saved_states() + + def attach(self, + child_object: 'Object', + parent_link: Optional[str] = None, + child_link: Optional[str] = None, + bidirectional: Optional[bool] = True) -> None: + """ + Attaches another object to this object. This is done by + saving the transformation between the given link, if there is one, and + the base pose of the other object. Additionally, the name of the link, to + which the object is attached, will be saved. + Furthermore, a simulator constraint will be created so the attachment + also works while simulation. + Loose attachments means that the attachment will only be one-directional. For example, if this object moves the + other, attached, object will also move but not the other way around. + + :param child_object: The other object that should be attached. + :param parent_link: The link name of this object. + :param child_link: The link name of the other object. + :param bidirectional: If the attachment should be a loose attachment. + """ + parent_link = self.links[parent_link] if parent_link else self.root_link + child_link = child_object.links[child_link] if child_link else child_object.root_link + + attachment = Attachment(parent_link, child_link, bidirectional) + + self.attachments[child_object] = attachment + child_object.attachments[self] = attachment.get_inverse() + + self.world.attachment_event(self, [self, child_object]) + + def detach(self, child_object: 'Object') -> None: + """ + Detaches another object from this object. This is done by + deleting the attachment from the attachments dictionary of both objects + and deleting the constraint of the simulator. + Afterward the detachment event of the corresponding World will be fired. + + :param child_object: The object which should be detached + """ + del self.attachments[child_object] + del child_object.attachments[self] + + self.world.detachment_event(self, [self, child_object]) + + def detach_all(self) -> None: + """ + Detach all objects attached to this object. + """ + attachments = self.attachments.copy() + for att in attachments.keys(): + self.detach(att) + + def update_attachment_with_object(self, child_object: 'Object'): + self.attachments[child_object].update_transform_and_constraint() + + def get_position(self) -> Point: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_pose().position + + def get_orientation(self) -> Pose.orientation: + """ + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw + """ + return self.get_pose().orientation + + def get_position_as_list(self) -> List[float]: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_pose().position_as_list() + + def get_orientation_as_list(self) -> List[float]: + """ + Returns the orientation of this object as a list of xyzw, representing a quaternion. + + :return: A list of xyzw + """ + return self.get_pose().orientation_as_list() + + def get_pose(self) -> Pose: + """ + Returns the position of this object as a list of xyz. Alias for :func:`~Object.get_position`. + + :return: The current pose of this object + """ + return self._current_pose + + def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Optional[bool] = True) -> None: + """ + Sets the Pose of the object. + + :param pose: New Pose for the object + :param base: If True places the object base instead of origin at the specified position and orientation + :param set_attachments: Whether to set the poses of the attached objects to this object or not. + """ + pose_in_map = self.local_transformer.transform_pose(pose, "map") + if base: + pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift + + self.reset_base_pose(pose_in_map) + + if set_attachments: + self._set_attached_objects_poses() + + def reset_base_pose(self, pose: Pose): + self.world.reset_object_base_pose(self, pose) + self.update_pose() + + def update_pose(self): + """ + Updates the current pose of this object from the world, and updates the poses of all links. + """ + self._current_pose = self.world.get_object_pose(self) + self._update_all_links_poses() + self.update_link_transforms() + + def _update_all_joints_positions(self): + """ + Updates the posisitons of all joints by getting them from the simulator. + """ + for joint in self.joints.values(): + joint._update_position() + + def _update_all_links_poses(self): + """ + Updates the poses of all links by getting them from the simulator. + """ + for link in self.links.values(): + link._update_pose() + + def move_base_to_origin_pos(self) -> None: + """ + Move the object such that its base will be at the current origin position. + This is useful when placing objects on surfaces where you want the object base in contact with the surface. + """ + self.set_pose(self.get_pose(), base=True) + + def save_state(self, state_id) -> None: + """ + Saves the state of this object by saving the state of all links and attachments. + :param state_id: The unique id of the state. + """ + self.save_links_states(state_id) + self.save_joints_states(state_id) + super().save_state(state_id) + + def save_links_states(self, state_id: int) -> None: + """ + Saves the state of all links of this object. + :param state_id: The unique id of the state. + """ + for link in self.links.values(): + link.save_state(state_id) + + def save_joints_states(self, state_id: int) -> None: + """ + Saves the state of all joints of this object. + :param state_id: The unique id of the state. + """ + for joint in self.joints.values(): + joint.save_state(state_id) + + @property + def current_state(self) -> ObjectState: + return ObjectState(self.attachments.copy(), self.link_states, self.joint_states) + + @current_state.setter + def current_state(self, state: ObjectState) -> None: + self.attachments = state.attachments + self.link_states = state.link_states + self.joint_states = state.joint_states + + @property + def link_states(self) -> Dict[int, LinkState]: + """ + Returns the current state of all links of this object. + :return: A dictionary with the link id as key and the current state of the link as value. + """ + return {link.id: link.current_state for link in self.links.values()} + + @link_states.setter + def link_states(self, link_states: Dict[int, LinkState]) -> None: + """ + Sets the current state of all links of this object. + :param link_states: A dictionary with the link id as key and the current state of the link as value. + """ + for link in self.links.values(): + link.current_state = link_states[link.id] + + @property + def joint_states(self) -> Dict[int, JointState]: + """ + Returns the current state of all joints of this object. + :return: A dictionary with the joint id as key and the current state of the joint as value. + """ + return {joint.id: joint.current_state for joint in self.joints.values()} + + @joint_states.setter + def joint_states(self, joint_states: Dict[int, JointState]) -> None: + """ + Sets the current state of all joints of this object. + :param joint_states: A dictionary with the joint id as key and the current state of the joint as value. + """ + for joint in self.joints.values(): + joint.current_state = joint_states[joint.id] + + def restore_state(self, state_id: int) -> None: + """ + Restores the state of this object by restoring the state of all links and attachments. + :param state_id: The unique id of the state. + """ + self.restore_attachments(state_id) + self.restore_links_states(state_id) + self.restore_joints_states(state_id) + + def restore_attachments(self, state_id: int) -> None: + """ + Restores the attachments of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + self.attachments = self.saved_states[state_id].attachments + + def restore_links_states(self, state_id: int) -> None: + """ + Restores the states of all links of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + for link in self.links.values(): + link.restore_state(state_id) + + def restore_joints_states(self, state_id: int) -> None: + """ + Restores the states of all joints of this object from a saved state using the given state id. + :param state_id: The unique id of the state. + """ + for joint in self.joints.values(): + joint.restore_state(state_id) + + def remove_saved_states(self) -> None: + """ + Removes all saved states of this object. + """ + super().remove_saved_states() + self.remove_links_saved_states() + self.remove_joints_saved_states() + + def remove_links_saved_states(self) -> None: + """ + Removes all saved states of the links of this object. + """ + for link in self.links.values(): + link.remove_saved_states() + + def remove_joints_saved_states(self) -> None: + """ + Removes all saved states of the joints of this object. + """ + for joint in self.joints.values(): + joint.remove_saved_states() + + def _set_attached_objects_poses(self, already_moved_objects: Optional[List['Object']] = None) -> None: + """ + Updates the positions of all attached objects. This is done + by calculating the new pose in world coordinate frame and setting the + base pose of the attached objects to this new pose. + After this the _set_attached_objects method of all attached objects + will be called. + + :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent + loops in the update. + """ + + if already_moved_objects is None: + already_moved_objects = [] + + for child in self.attachments: + + if child in already_moved_objects: + continue + + attachment = self.attachments[child] + if not attachment.bidirectional: + self.update_attachment_with_object(child) + child.update_attachment_with_object(self) + + else: + link_to_object = attachment.parent_to_child_transform + child.set_pose(link_to_object.to_pose(), set_attachments=False) + child._set_attached_objects_poses(already_moved_objects + [self]) + + def set_position(self, position: Union[Pose, Point], base=False) -> None: + """ + Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position + instead of the origin in the center of the Object. The given position can either be a Pose, + in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + + :param position: Target position as xyz. + :param base: If the bottom of the Object should be placed or the origin in the center. + """ + pose = Pose() + if isinstance(position, Pose): + target_position = position.position + pose.frame = position.frame + elif isinstance(position, Point): + target_position = position + elif isinstance(position, list): + target_position = position + else: + raise TypeError("The given position has to be a Pose, Point or a list of xyz.") + + pose.position = target_position + pose.orientation = self.get_orientation() + self.set_pose(pose, base=base) + + def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: + """ + Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only + the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. + + :param orientation: Target orientation given as a list of xyzw. + """ + pose = Pose() + if isinstance(orientation, Pose): + target_orientation = orientation.orientation + pose.frame = orientation.frame + else: + target_orientation = orientation + + pose.pose.position = self.get_position() + pose.pose.orientation = target_orientation + self.set_pose(pose) + + def get_joint_id(self, name: str) -> int: + """ + Returns the unique id for a joint name. As used by the world/simulator. + + :param name: The joint name + :return: The unique id + """ + return self.joint_name_to_id[name] + + def get_root_link_description(self) -> 'LinkDescription': + """ + Returns the root link of the URDF of this object. + :return: The root link as defined in the URDF of this object. + """ + root_link_name = self.description.get_root() + for link_description in self.description.links: + if link_description.name == root_link_name: + return link_description + + @property + def root_link(self) -> 'Link': + """ + Returns the root link of this object. + :return: The root link of this object. + """ + return self.links[self.description.get_root()] + + @property + def root_link_name(self) -> str: + """ + Returns the name of the root link of this object. + :return: The name of the root link of this object. + """ + return self.description.get_root() + + def get_root_link_id(self) -> int: + """ + Returns the unique id of the root link of this object. + :return: The unique id of the root link of this object. + """ + return self.get_link_id(self.description.get_root()) + + def get_link_id(self, link_name: str) -> int: + """ + Returns a unique id for a link name. + :param link_name: The name of the link. + :return: The unique id of the link. + """ + return self.link_name_to_id[link_name] + + def get_link_by_id(self, link_id: int) -> 'Link': + """ + Returns the link for a given unique link id + :param link_id: The unique id of the link. + :return: The link object. + """ + return self.links[self.link_id_to_name[link_id]] + + def get_joint_by_id(self, joint_id: int) -> str: + """ + Returns the joint name for a unique world id + + :param joint_id: The world id of for joint + :return: The joint name + """ + return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] + + def reset_all_joints_positions(self) -> None: + """ + Sets the current position of all joints to 0. This is useful if the joints should be reset to their default + """ + joint_names = list(self.joint_name_to_id.keys()) + joint_positions = [0] * len(joint_names) + self.set_joint_positions(dict(zip(joint_names, joint_positions))) + + def set_joint_positions(self, joint_poses: dict) -> None: + """ + Sets the current position of multiple joints at once, this method should be preferred when setting + multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. + + :param joint_poses: + """ + for joint_name, joint_position in joint_poses.items(): + self.joints[joint_name].position = joint_position + # self.update_pose() + self._update_all_links_poses() + self.update_link_transforms() + self._set_attached_objects_poses() + + def set_joint_position(self, joint_name: str, joint_position: float) -> None: + """ + Sets the position of the given joint to the given joint pose and updates the poses of all attached objects. + + :param joint_name: The name of the joint + :param joint_position: The target pose for this joint + """ + self.joints[joint_name].position = joint_position + self._update_all_links_poses() + self.update_link_transforms() + self._set_attached_objects_poses() + + def get_joint_position(self, joint_name: str) -> float: + return self.joints[joint_name].position + + def get_joint_damping(self, joint_name: str) -> float: + return self.joints[joint_name].damping + + def get_joint_upper_limit(self, joint_name: str) -> float: + return self.joints[joint_name].upper_limit + + def get_joint_lower_limit(self, joint_name: str) -> float: + return self.joints[joint_name].lower_limit + + def get_joint_axis(self, joint_name: str) -> Point: + return self.joints[joint_name].axis + + def get_joint_type(self, joint_name: str) -> JointType: + return self.joints[joint_name].type + + def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: + return self.joints[joint_name].limits + + def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + """ + Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. + + :param link_name: AbstractLink name above which the joint should be found + :param joint_type: Joint type that should be searched for + :return: Name of the first joint which has the given type + """ + chain = self.description.get_chain(self.description.get_root(), link_name) + reversed_chain = reversed(chain) + container_joint = None + for element in reversed_chain: + if element in self.joint_name_to_id and self.get_joint_type(element) == joint_type: + container_joint = element + break + if not container_joint: + rospy.logwarn(f"No joint of type {joint_type} found above link {link_name}") + return container_joint + + def get_positions_of_all_joints(self) -> Dict[str, float]: + """ + Returns the positions of all joints of the object as a dictionary of joint names and joint positions. + + :return: A dictionary with all joints positions'. + """ + return {j.name: j.position for j in self.joints.values()} + + def update_link_transforms(self, transform_time: Optional[rospy.Time] = None) -> None: + """ + Updates the transforms of all links of this object using time 'transform_time' or the current ros time. + """ + for link in self.links.values(): + link.update_transform(transform_time) + + def contact_points(self) -> List: + """ + Returns a list of contact points of this Object with other Objects. + + :return: A list of all contact points with other objects + """ + return self.world.get_object_contact_points(self) + + def contact_points_simulated(self) -> List: + """ + Returns a list of all contact points between this Object and other Objects after stepping the simulation once. + + :return: A list of contact points between this Object and other Objects + """ + state_id = self.world.save_state() + self.world.step() + contact_points = self.contact_points() + self.world.restore_state(state_id) + return contact_points + + def set_color(self, rgba_color: Color) -> None: + """ + Changes the color of this object, the color has to be given as a list + of RGBA values. + + :param rgba_color: The color as Color object with RGBA values between 0 and 1 + """ + # Check if there is only one link, this is the case for primitive + # forms or if loaded from an .stl or .obj file + if self.links != {}: + for link in self.links.values(): + link.color = rgba_color + else: + self.root_link.color = rgba_color + + def get_color(self) -> Union[Color, Dict[str, Color]]: + """ + This method returns the rgba_color of this object. The return is either: + + 1. A Color object with RGBA values, this is the case if the object only has one link (this + happens for example if the object is spawned from a .obj or .stl file) + 2. A dict with the link name as key and the rgba_color as value. The rgba_color is given as a Color Object. + Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which + the object is spawned. + + :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and + the rgba_color as value. + """ + link_to_color_dict = self.links_colors + + if len(link_to_color_dict) == 1: + return list(link_to_color_dict.values())[0] + else: + return link_to_color_dict + + @property + def links_colors(self) -> Dict[str, Color]: + """ + The color of each link as a dictionary with link names as keys and RGBA colors as values. + """ + return self.world.get_colors_of_object_links(self) + + def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: + """ + :return: The axis aligned bounding box of this object. + """ + return self.world.get_object_axis_aligned_bounding_box(self) + + def get_base_origin(self) -> Pose: + """ + :return: the origin of the base/bottom of this object. + """ + aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() + base_width = np.absolute(aabb.min_x - aabb.max_x) + base_length = np.absolute(aabb.min_y - aabb.max_y) + return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], + self.get_pose().orientation_as_list()) + + def __copy__(self) -> 'Object': + """ + Returns a copy of this object. The copy will have the same name, type, path, description, pose, world and color. + :return: A copy of this object. + """ + return Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(), + self.world.prospection_world, self.color) diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 9c8f4f764..56da2945f 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -6,8 +6,8 @@ from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp from .pose import Pose, Transform from .robot_descriptions import robot_description -from .world import Object, UseProspectionWorld -from .world import World +from .world_object import Object +from .world import World, UseProspectionWorld def stable(obj: Object) -> bool: diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 9a8f5a808..fa97f3d0a 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -1,6 +1,7 @@ import unittest -from pycram.bullet_world import BulletWorld, Object +from pycram.bullet_world import BulletWorld +from pycram.world_object import Object from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 9542edf98..47ad23064 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -5,7 +5,9 @@ from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose -from pycram.world import Object, ObjectType +from pycram.robot_descriptions import robot_description +from pycram.enums import ObjectType +from pycram.world_object import Object import xml.etree.ElementTree as ET from pycram.urdf_interface import ObjectDescription @@ -56,11 +58,26 @@ def test_get_object_contact_points(self): def test_step_simulation(self): # TODO: kitchen explodes when stepping simulation, fix this + time.sleep(2) self.world.remove_object(self.kitchen) self.milk.set_position(Pose([0, 0, 2])) self.world.simulate(1) self.assertTrue(self.milk.get_position().z < 2) + def test_set_real_time_simulation(self): + # self.world.remove_object(self.kitchen) + self.milk.set_position(Pose([100, 0, 2])) + curr_time = time.time() + self.world.simulate(0.5, real_time=True) + time_elapsed = time.time() - curr_time + self.assertAlmostEqual(time_elapsed, 0.5, delta=0.1) + + def test_create_vis_axis(self): + self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose, 1) + self.assertTrue(len(self.world.vis_axis) == 1) + self.world.remove_vis_axis() + self.assertTrue(len(self.world.vis_axis) == 0) + class XMLTester(unittest.TestCase): diff --git a/test/test_database_merger.py b/test/test_database_merger.py index cbd26b731..6ed3faaf2 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -11,7 +11,8 @@ from pycram.enums import Arms, ObjectType, WorldMode from pycram.task import with_tree import pycram.task -from pycram.bullet_world import Object +from pycram.bullet_world import BulletWorld +from pycram.world_object import Object from pycram.designators.object_designator import * from dataclasses import dataclass, field diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 6df2a71bc..31f4cc28d 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -3,7 +3,7 @@ import sqlalchemy import sqlalchemy.orm import pycram.plan_failures -from pycram.world import Object +from pycram.world_object import Object from pycram import task from pycram.world import World from pycram.designators import action_designator, object_designator diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 4ffad3d4c..b03319785 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -6,7 +6,7 @@ import pycram.plan_failures from pycram.bullet_world import BulletWorld -from pycram.world import Object +from pycram.world_object import Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot diff --git a/test/test_language.py b/test/test_language.py index e4739802a..94cff57a3 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -1,4 +1,5 @@ import threading +import time import unittest from pycram.designators.action_designator import * from pycram.enums import ObjectType, State diff --git a/test/test_links.py b/test/test_links.py index 1205b4e23..a7f37016c 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -1,4 +1,7 @@ +import time + from bullet_world_testcase import BulletWorldTestCase +from pycram.world_dataclasses import Color class TestLinks(BulletWorldTestCase): @@ -25,3 +28,9 @@ def test_transform_link(self): robot_to_milk = robot_link.get_transform_to_link(milk_link) self.assertAlmostEqual(robot_to_milk, milk_to_robot.invert()) + def test_set_color(self): + link = self.robot.links['base_link'] + link.color = Color(1, 0, 0, 1) + self.assertEqual(link.color.get_rgba(), [1, 0, 0, 1]) + + From bfc5134b49ea577e87fd1c2d9b0470f006fc7e17 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 15 Feb 2024 14:45:41 +0100 Subject: [PATCH 084/195] [Abstract World] Added more tests for bullet world, Tests are running. --- src/pycram/bullet_world.py | 63 +++++++++++++++--------------- test/bullet_world_testcase.py | 32 +++++++++++++++- test/test_bullet_world.py | 72 ++++++++++++++++++++++++++++++----- 3 files changed, 123 insertions(+), 44 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 5cb332084..eeef44a64 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -3,20 +3,21 @@ import threading import time -from typing_extensions import List, Optional, Dict import numpy as np import pybullet as p import rosgraph import rospy +from geometry_msgs.msg import Point +from typing_extensions import List, Optional, Dict -from .enums import ObjectType, WorldMode +from .enums import ObjectType, WorldMode, JointType from .pose import Pose +from .urdf_interface import ObjectDescription from .world import World -from .world_object import Object from .world_constraints import Constraint from .world_dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape -from .urdf_interface import ObjectDescription +from .world_object import Object Link = ObjectDescription.Link RootLink = ObjectDescription.RootLink @@ -56,7 +57,7 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo # Needed to let the other thread start the simulation, before Objects are spawned. time.sleep(0.1) - self.vis_axis: List[Object] = [] + self.vis_axis: List[int] = [] # Some default settings self.set_gravity([0, 0, -9.8]) @@ -212,19 +213,15 @@ def add_vis_axis(self, pose: Pose, box_vis_shape = BoxVisualShape(Color(0, 0, 1, 0.8), [0.01, 0.01, length], [0.01, 0.01, length]) vis_z = self.create_visual_shape(box_vis_shape) - obj = p.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=[vis_x, vis_y, vis_z], - basePosition=position, baseOrientation=orientation, - linkPositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkMasses=[1.0, 1.0, 1.0], linkOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkInertialFramePositions=[[0, 0, 0], [0, 0, 0], [0, 0, 0]], - linkInertialFrameOrientations=[[0, 0, 0, 1], [0, 0, 0, 1], [0, 0, 0, 1]], - linkParentIndices=[0, 0, 0], - linkJointTypes=[p.JOINT_FIXED, p.JOINT_FIXED, p.JOINT_FIXED], - linkJointAxis=[[1, 0, 0], [0, 1, 0], [0, 0, 1]], - linkCollisionShapeIndices=[-1, -1, -1], - physicsClientId=self.id) + multibody = MultiBody(base_visual_shape_index=-1, base_pose=pose_in_map, + link_visual_shape_indices=[vis_x, vis_y, vis_z], + link_poses=[Pose(), Pose(), Pose()], link_masses=[1.0, 1.0, 1.0], + link_inertial_frame_poses=[Pose(), Pose(), Pose()], link_parent_indices=[0, 0, 0], + link_joint_types=[JointType.FIXED.value, JointType.FIXED.value, JointType.FIXED.value], + link_joint_axis=[Point(1, 0, 0), Point(0, 1, 0), Point(0, 0, 1)], + link_collision_shape_indices=[-1, -1, -1]) - self.vis_axis.append(obj) + self.vis_axis.append(self.create_multi_body(multibody)) def remove_vis_axis(self) -> None: """ @@ -250,21 +247,21 @@ def create_visual_shape(self, visual_shape: VisualShape) -> int: physicsClientId=self.id, **visual_shape.shape_data()) def create_multi_body(self, multi_body: MultiBody) -> int: - return p.createMultiBody(baseVisualShapeIndex=-MultiBody.base_visual_shape_index, - linkVisualShapeIndices=MultiBody.link_visual_shape_indices, - basePosition=MultiBody.base_pose.position_as_list(), - baseOrientation=MultiBody.base_pose.orientation_as_list(), - linkPositions=[pose.position_as_list() for pose in MultiBody.link_poses], - linkMasses=MultiBody.link_masses, - linkOrientations=[pose.orientation_as_list() for pose in MultiBody.link_poses], + return p.createMultiBody(baseVisualShapeIndex=-multi_body.base_visual_shape_index, + linkVisualShapeIndices=multi_body.link_visual_shape_indices, + basePosition=multi_body.base_pose.position_as_list(), + baseOrientation=multi_body.base_pose.orientation_as_list(), + linkPositions=[pose.position_as_list() for pose in multi_body.link_poses], + linkMasses=multi_body.link_masses, + linkOrientations=[pose.orientation_as_list() for pose in multi_body.link_poses], linkInertialFramePositions=[pose.position_as_list() - for pose in MultiBody.link_inertial_frame_poses], + for pose in multi_body.link_inertial_frame_poses], linkInertialFrameOrientations=[pose.orientation_as_list() - for pose in MultiBody.link_inertial_frame_poses], - linkParentIndices=MultiBody.link_parent_indices, - linkJointTypes=MultiBody.link_joint_types, - linkJointAxis=[[point.x, point.y, point.z] for point in MultiBody.link_joint_axis], - linkCollisionShapeIndices=MultiBody.link_collision_shape_indices) + for pose in multi_body.link_inertial_frame_poses], + linkParentIndices=multi_body.link_parent_indices, + linkJointTypes=multi_body.link_joint_types, + linkJointAxis=[[point.x, point.y, point.z] for point in multi_body.link_joint_axis], + linkCollisionShapeIndices=multi_body.link_collision_shape_indices) def get_images_for_target(self, target_pose: Pose, @@ -299,7 +296,7 @@ def add_text(self, text: str, position: List[float], orientation: Optional[List[ return p.addUserDebugText(text, position, color.get_rgb(), physicsClientId=self.id, **args) def remove_text(self, text_id: Optional[int] = None) -> None: - if text_id: + if text_id is not None: p.removeUserDebugItem(text_id, physicsClientId=self.id) else: p.removeAllUserDebugItems(physicsClientId=self.id) @@ -416,9 +413,9 @@ def run(self): # camera movement when the left mouse button is pressed if mouse_state[0] == 3: - speed_x = abs(old_mouse_x - mouse_x) if (abs(old_mouse_x - mouse_x)) < max_speed\ + speed_x = abs(old_mouse_x - mouse_x) if (abs(old_mouse_x - mouse_x)) < max_speed \ else max_speed - speed_y = abs(old_mouse_y - mouse_y) if (abs(old_mouse_y - mouse_y)) < max_speed\ + speed_y = abs(old_mouse_y - mouse_y) if (abs(old_mouse_y - mouse_y)) < max_speed \ else max_speed # max angle of 89.5 and -89.5 to make sure the camera does not flip (is annoying) diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index fa97f3d0a..99d99f0f8 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -1,3 +1,4 @@ +import time import unittest from pycram.bullet_world import BulletWorld @@ -16,7 +17,7 @@ class BulletWorldTestCase(unittest.TestCase): @classmethod def setUpClass(cls): - cls.world = BulletWorld(WorldMode.DIRECT) + cls.world = BulletWorld(mode=WorldMode.DIRECT) cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + cls.extension, ObjectDescription) @@ -33,6 +34,7 @@ def setUp(self): # Tests in here would not be properly executed in the CI def tearDown(self): + time.sleep(0.1) self.world.reset_world() @classmethod @@ -40,4 +42,32 @@ def tearDownClass(cls): cls.world.exit() +class BulletWorldGUITestCase(unittest.TestCase): + world: BulletWorld + extension: str = ObjectDescription.get_file_extension() + + @classmethod + def setUpClass(cls): + cls.world = BulletWorld(mode=WorldMode.GUI) + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + cls.robot = Object(robot_description.name, ObjectType.ROBOT, + robot_description.name + cls.extension, ObjectDescription) + cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension, ObjectDescription) + cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", + ObjectDescription, pose=Pose([1.3, 0.7, 0.95])) + ProcessModule.execution_delay = False + + def setUp(self): + self.world.reset_world() + + # DO NOT WRITE TESTS HERE!!! + # Test related to the BulletWorld should be written in test_bullet_world.py + # Tests in here would not be properly executed in the CI + + def tearDown(self): + pass + + @classmethod + def tearDownClass(cls): + cls.world.exit() diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 47ad23064..1027b373a 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -1,15 +1,16 @@ import time import unittest +import xml.etree.ElementTree as ET import rospkg -from bullet_world_testcase import BulletWorldTestCase +from bullet_world_testcase import BulletWorldTestCase, BulletWorldGUITestCase +from pycram.enums import ObjectType, WorldMode from pycram.pose import Pose from pycram.robot_descriptions import robot_description -from pycram.enums import ObjectType -from pycram.world_object import Object -import xml.etree.ElementTree as ET from pycram.urdf_interface import ObjectDescription +from pycram.world_dataclasses import Color +from pycram.world_object import Object fix_missing_inertial = ObjectDescription.fix_missing_inertial @@ -41,12 +42,13 @@ def test_save_and_restore_state(self): self.assertTrue(cid == self.robot.attachments[self.milk].id) def test_remove_object(self): - time.sleep(2) + # time.sleep(2) milk_id = self.milk.id self.assertTrue(milk_id in [obj.id for obj in self.world.objects]) self.world.remove_object(self.milk) self.assertTrue(milk_id not in [obj.id for obj in self.world.objects]) - BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", + ObjectDescription, pose=Pose([1.3, 1, 0.9])) def test_get_joint_position(self): self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) @@ -56,24 +58,73 @@ def test_get_object_contact_points(self): self.milk.set_position(self.robot.get_position()) self.assertTrue(len(self.robot.contact_points()) > 0) + +class BulletWorldTestRemove(BulletWorldTestCase): def test_step_simulation(self): # TODO: kitchen explodes when stepping simulation, fix this time.sleep(2) self.world.remove_object(self.kitchen) + time.sleep(2) self.milk.set_position(Pose([0, 0, 2])) self.world.simulate(1) self.assertTrue(self.milk.get_position().z < 2) + # self.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + self.extension, ObjectDescription, + # world=self.world) + # time.sleep(2) def test_set_real_time_simulation(self): - # self.world.remove_object(self.kitchen) self.milk.set_position(Pose([100, 0, 2])) curr_time = time.time() self.world.simulate(0.5, real_time=True) time_elapsed = time.time() - curr_time - self.assertAlmostEqual(time_elapsed, 0.5, delta=0.1) + self.assertAlmostEqual(time_elapsed, 0.5, delta=0.2) - def test_create_vis_axis(self): - self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose, 1) + +class BulletWorldTestVis(BulletWorldTestCase): + def test_add_vis_axis(self): + self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) + self.assertTrue(len(self.world.vis_axis) == 1) + self.world.remove_vis_axis() + self.assertTrue(len(self.world.vis_axis) == 0) + + def test_add_text(self): + link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] + text_id = self.world.add_text("test", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + Color(1, 0, 0, 1), 3, link.object_id, link.id) + if self.world.mode == WorldMode.GUI: + time.sleep(4) + + def test_remove_text(self): + link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] + text_id_1 = self.world.add_text("test 1", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + Color(1, 0, 0, 1), 0, link.object_id, link.id) + text_id = self.world.add_text("test 2", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + Color(0, 1, 0, 1), 0, link.object_id, link.id) + + if self.world.mode == WorldMode.GUI: + time.sleep(2) + self.world.remove_text(text_id_1) + if self.world.mode == WorldMode.GUI: + time.sleep(3) + + def test_remove_all_text(self): + link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] + text_id_1 = self.world.add_text("test 1", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + Color(1, 0, 0, 1), 0, link.object_id, link.id) + text_id = self.world.add_text("test 2", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + Color(0, 1, 0, 1), 0, link.object_id, link.id) + if self.world.mode == WorldMode.GUI: + time.sleep(2) + self.world.remove_text() + if self.world.mode == WorldMode.GUI: + time.sleep(3) + + +@unittest.skip("Not working in CI") +class BulletWorldTestGUI(BulletWorldGUITestCase): + def test_add_vis_axis(self): + time.sleep(10) + self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) self.assertTrue(len(self.world.vis_axis) == 1) self.world.remove_vis_axis() self.assertTrue(len(self.world.vis_axis) == 0) @@ -92,3 +143,4 @@ def test_inertial(self): resulting_tree = ET.ElementTree(ET.fromstring(result)) for element in resulting_tree.iter("link"): self.assertTrue(len([*element.iter("inertial")]) > 0) + From b9f5d86813525b7b3d0189a60bc655ea106d2e35 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 15 Feb 2024 19:35:49 +0100 Subject: [PATCH 085/195] [Abstract World] Added more tests for bullet world, Tests are running. --- src/pycram/bullet_world_reasoning.py | 0 src/pycram/description.py | 21 ++++ src/pycram/designators/object_designator.py | 2 +- .../process_modules/hsr_process_modules.py | 2 +- .../process_modules/pr2_process_modules.py | 4 +- src/pycram/world.py | 68 +++-------- src/pycram/world_constraints.py | 12 ++ src/pycram/world_dataclasses.py | 2 +- src/pycram/world_object.py | 26 +++-- test/bullet_world_testcase.py | 2 +- test/test_bullet_world.py | 107 ++++++++++++++++-- test/test_costmaps.py | 10 +- 12 files changed, 176 insertions(+), 80 deletions(-) delete mode 100644 src/pycram/bullet_world_reasoning.py diff --git a/src/pycram/bullet_world_reasoning.py b/src/pycram/bullet_world_reasoning.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/src/pycram/description.py b/src/pycram/description.py index 8c86a7ea9..3ac66c521 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -370,6 +370,15 @@ def tf_frame(self) -> str: """ return f"{self.object.tf_frame}/{self.name}" + def __eq__(self, other): + return self.id == other.id and self.object == other.object and self.name == other.name + + def __copy__(self): + return Link(self.id, self, self.object) + + def __hash__(self): + return hash((self.id, self.object, self.name)) + class RootLink(Link, ABC): """ @@ -390,6 +399,9 @@ def tf_frame(self) -> str: def _update_pose(self) -> None: self._current_pose = self.object.get_pose() + def __copy__(self): + return RootLink(self.object) + class Joint(ObjectEntity, JointDescription, ABC): """ @@ -499,6 +511,15 @@ def current_state(self) -> JointState: def current_state(self, joint_state: JointState) -> None: self.position = joint_state.position + def __copy__(self): + return Joint(self.id, self, self.object) + + def __eq__(self, other): + return self.id == other.id and self.object == other.object and self.name == other.name + + def __hash__(self): + return hash((self.id, self.object, self.name)) + class ObjectDescription(EntityDescription): MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 23dacdbdf..34975ce1d 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -170,6 +170,6 @@ def __iter__(self): """ object_candidates = query(self) for obj_desig in object_candidates: - for world_obj in World.get_objects_by_type(obj_desig.obj_type): + for world_obj in World.get_object_by_type(obj_desig.obj_type): obj_desig.world_object = world_obj yield obj_desig diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index f0f4d7d1b..0a9936147 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -171,7 +171,7 @@ def _execute(self, desig): cam_frame_name = solution['cam_frame'] front_facing_axis = solution['front_facing_axis'] - objects = World.current_world.get_objects_by_type(object_type) + objects = World.current_world.get_object_by_type(object_type) for obj in objects: if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): return obj diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index aa2c3bc53..1240f7467 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -184,7 +184,7 @@ def _execute(self, desig: DetectingMotion.Motion): # should be [0, 0, 1] front_facing_axis = robot_description.front_facing_axis - objects = World.current_world.get_objects_by_type(object_type) + objects = World.current_world.get_object_by_type(object_type) for obj in objects: if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis): return obj @@ -346,7 +346,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 - world_obj = World.current_world.get_objects_by_type(designator.object_type) + world_obj = World.current_world.get_object_by_type(designator.object_type) if world_obj: world_obj[0].set_pose(obj_pose) return world_obj[0] diff --git a/src/pycram/world.py b/src/pycram/world.py index 463ddf62f..5db837f7e 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -170,6 +170,8 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self._init_events() + self._current_state: Optional[WorldState] = None + def _init_events(self): """ Initializes dynamic events that can be used to react to changes in the World. @@ -244,17 +246,16 @@ def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: """ pass - # TODO: This is not used anywhere, should it be removed? - def get_objects_by_name(self, name: str) -> List['Object']: + def get_object_by_name(self, name: str) -> List['Object']: """ Returns a list of all Objects in this World with the same name as the given one. :param name: The name of the returned Objects. :return: A list of all Objects with the name 'name'. """ - return list(filter(lambda obj: obj.name == name, self.objects)) + return list(filter(lambda obj: obj.name == name, self.objects))[0] - def get_objects_by_type(self, obj_type: ObjectType) -> List['Object']: + def get_object_by_type(self, obj_type: ObjectType) -> List['Object']: """ Returns a list of all Objects which have the type 'obj_type'. @@ -301,7 +302,7 @@ def remove_object(self, obj: 'Object') -> None: self.remove_object_from_simulator(obj) - if World.robot == self: + if World.robot == obj: World.robot = None def add_fixed_constraint(self, parent_link: 'Link', child_link: 'Link', @@ -529,30 +530,6 @@ def get_link_axis_aligned_bounding_box(self, link: 'Link') -> AxisAlignedBoundin """ pass - def get_attachment_event(self) -> Event: - """ - Returns the event reference that is fired if an attachment occurs. - - :return: The reference to the attachment event - """ - return self.attachment_event - - def get_detachment_event(self) -> Event: - """ - Returns the event reference that is fired if a detachment occurs. - - :return: The event reference for the detachment event. - """ - return self.detachment_event - - def get_manipulation_event(self) -> Event: - """ - Returns the event reference that is fired if any manipulation occurs. - - :return: The event reference for the manipulation event. - """ - return self.manipulation_event - @abstractmethod def set_realtime(self, real_time: bool) -> None: """ @@ -666,6 +643,8 @@ def save_state(self, state_id: Optional[int] = None) -> int: @property def current_state(self) -> WorldState: + if self._current_state is None: + self._current_state = WorldState(self.save_physics_simulator_state(), self.object_states) return self._current_state @current_state.setter @@ -674,20 +653,20 @@ def current_state(self, state: WorldState) -> None: self.object_states = state.object_states @property - def object_states(self) -> Dict[int, ObjectState]: + def object_states(self) -> Dict[str, ObjectState]: """ Returns the states of all objects in the World. :return: A dictionary with the object id as key and the object state as value. """ - return {obj.id: obj.current_state for obj in self.objects} + return {obj.name: obj.current_state for obj in self.objects} @object_states.setter - def object_states(self, states: Dict[int, ObjectState]) -> None: + def object_states(self, states: Dict[str, ObjectState]) -> None: """ Sets the states of all objects in the World. """ - for obj_id, obj_state in states.items(): - self.get_object_by_id(obj_id).current_state = obj_state + for obj_name, obj_state in states.items(): + self.get_object_by_name(obj_name).current_state = obj_state def save_objects_state(self, state_id: int) -> None: """ @@ -697,18 +676,6 @@ def save_objects_state(self, state_id: int) -> None: for obj in self.objects: obj.save_state(state_id) - def restore_state(self, state_id) -> None: - """ - Restores the state of the World according to the given state using the unique state id. This includes the state - of the physics simulator and the state of all objects. - However, restore can not respawn objects if there are objects that were deleted between creation of the state - and restoring, they will be skipped. - - :param state_id: The unique id representing the state. - """ - self.restore_physics_simulator_state(state_id) - self.restore_objects_states(state_id) - @abstractmethod def save_physics_simulator_state(self) -> int: """ @@ -893,13 +860,12 @@ def create_multi_body_from_visual_shapes(self, visual_shape_ids: List[int], pose :param pose: The pose of the origin of the multi body relative to the world frame. :return: The unique id of the created multi body. """ - # Dummy parameter since these are needed to spawn visual shapes as a - # multibody. + # Dummy parameter since these are needed to spawn visual shapes as a multibody. num_of_shapes = len(visual_shape_ids) link_poses = [Pose() for _ in range(num_of_shapes)] link_masses = [1.0 for _ in range(num_of_shapes)] link_parent = [0 for _ in range(num_of_shapes)] - link_joints = [JointType.FIXED for _ in range(num_of_shapes)] + link_joints = [JointType.FIXED.value for _ in range(num_of_shapes)] link_collision = [-1 for _ in range(num_of_shapes)] link_joint_axis = [Point(1, 0, 0) for _ in range(num_of_shapes)] @@ -1158,12 +1124,14 @@ def check_for_pause(self) -> None: while self.pause_sync: time.sleep(0.1) - def check_for_equal(self) -> None: + def check_for_equal(self) -> bool: """ Checks if both Worlds have the same state, meaning all objects are in the same position. This is currently not used, but might be used in the future if synchronization issues worsen. + :return: True if both Worlds have the same state, False otherwise. """ eql = True for obj, prospection_obj in self.object_mapping.items(): eql = eql and obj.get_pose() == prospection_obj.get_pose() self.equal_states = eql + return eql diff --git a/src/pycram/world_constraints.py b/src/pycram/world_constraints.py index f301f0ff9..52d8cdd59 100644 --- a/src/pycram/world_constraints.py +++ b/src/pycram/world_constraints.py @@ -255,3 +255,15 @@ def __del__(self) -> None: Removes the constraint between the parent and the child links if one exists when the attachment is deleted. """ self.remove_constraint_if_exists() + + def __copy__(self): + return Attachment(self.parent_link, self.child_link, self.bidirectional, self.parent_to_child_transform, + self.id) + + def __eq__(self, other): + return (self.parent_link == other.parent_link and self.child_link == other.child_link and + self.bidirectional == other.bidirectional and + self.parent_to_child_transform == other.parent_to_child_transform) + + def __hash__(self): + return hash((self.parent_link, self.child_link, self.bidirectional, self.parent_to_child_transform)) diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index e7b0a8692..98b15178a 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -327,7 +327,7 @@ class State(ABC): @dataclass class WorldState(State): simulator_state_id: int - object_states: Dict[int, 'ObjectState'] + object_states: Dict[str, 'ObjectState'] @dataclass diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index 5e2eabf69..c398a1828 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -411,7 +411,7 @@ def save_joints_states(self, state_id: int) -> None: @property def current_state(self) -> ObjectState: - return ObjectState(self.attachments.copy(), self.link_states, self.joint_states) + return ObjectState(self.attachments.copy(), self.link_states.copy(), self.joint_states.copy()) @current_state.setter def current_state(self, state: ObjectState) -> None: @@ -453,15 +453,6 @@ def joint_states(self, joint_states: Dict[int, JointState]) -> None: for joint in self.joints.values(): joint.current_state = joint_states[joint.id] - def restore_state(self, state_id: int) -> None: - """ - Restores the state of this object by restoring the state of all links and attachments. - :param state_id: The unique id of the state. - """ - self.restore_attachments(state_id) - self.restore_links_states(state_id) - self.restore_joints_states(state_id) - def restore_attachments(self, state_id: int) -> None: """ Restores the attachments of this object from a saved state using the given state id. @@ -818,5 +809,16 @@ def __copy__(self) -> 'Object': Returns a copy of this object. The copy will have the same name, type, path, description, pose, world and color. :return: A copy of this object. """ - return Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(), - self.world.prospection_world, self.color) + obj = Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(), + self.world.prospection_world, self.color) + obj.current_state = self.current_state + return obj + + def __eq__(self, other): + if not isinstance(other, Object): + return False + return (self.id == other.id and self.world == other.world and self.name == other.name + and self.obj_type == other.obj_type) + + def __hash__(self): + return hash((self.name, self.obj_type, self.id, self.world.id)) diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 99d99f0f8..4dc7ae2e7 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -34,7 +34,7 @@ def setUp(self): # Tests in here would not be properly executed in the CI def tearDown(self): - time.sleep(0.1) + time.sleep(0.2) self.world.reset_world() @classmethod diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 1027b373a..658138975 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -29,7 +29,10 @@ def test_robot_orientation(self): def test_save_and_restore_state(self): self.robot.attach(self.milk) + self.milk.attach(self.cereal) + all_object_attachments = {obj: obj.attachments.copy() for obj in self.world.objects} state_id = self.world.save_state() + self.milk.detach(self.cereal) robot_link = self.robot.root_link milk_link = self.milk.root_link cid = robot_link.constraint_ids[milk_link] @@ -38,8 +41,11 @@ def test_save_and_restore_state(self): self.world.restore_state(state_id) cid = robot_link.constraint_ids[milk_link] self.assertTrue(milk_link in robot_link.constraint_ids) - self.assertTrue(self.milk in self.robot.attachments) self.assertTrue(cid == self.robot.attachments[self.milk].id) + for obj in self.world.objects: + self.assertTrue(len(obj.attachments) == len(all_object_attachments[obj])) + for att in obj.attachments: + self.assertTrue(att in all_object_attachments[obj]) def test_remove_object(self): # time.sleep(2) @@ -50,6 +56,14 @@ def test_remove_object(self): BulletWorldTest.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + def test_remove_robot(self): + robot_id = self.robot.id + self.assertTrue(robot_id in [obj.id for obj in self.world.objects]) + self.world.remove_object(self.robot) + self.assertTrue(robot_id not in [obj.id for obj in self.world.objects]) + BulletWorldTest.robot = Object(robot_description.name, ObjectType.ROBOT, + robot_description.name + self.extension, ObjectDescription) + def test_get_joint_position(self): self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) @@ -58,19 +72,29 @@ def test_get_object_contact_points(self): self.milk.set_position(self.robot.get_position()) self.assertTrue(len(self.robot.contact_points()) > 0) + def test_enable_joint_force_torque_sensor(self): + self.world.enable_joint_force_torque_sensor(self.robot, self.robot.get_joint_id("head_pan_joint")) + force_torque = self.world.get_joint_reaction_force_torque(self.robot, self.robot.get_joint_id("head_pan_joint")) + # TODO: useless because even if the sensor is disabled, the force_torque is still 0 + for ft in force_torque: + self.assertTrue(ft == 0.0) + + def test_disable_joint_force_torque_sensor(self): + self.world.enable_joint_force_torque_sensor(self.robot, self.robot.get_joint_id("head_pan_joint")) + self.world.disable_joint_force_torque_sensor(self.robot, self.robot.get_joint_id("head_pan_joint")) + force_torque = self.world.get_joint_reaction_force_torque(self.robot, self.robot.get_joint_id("head_pan_joint")) + for ft in force_torque: + self.assertTrue(ft == 0.0) + + def test_get_applied_joint_motor_torque(self): + self.world.get_applied_joint_motor_torque(self.robot, self.robot.get_joint_id("head_pan_joint")) -class BulletWorldTestRemove(BulletWorldTestCase): def test_step_simulation(self): # TODO: kitchen explodes when stepping simulation, fix this - time.sleep(2) - self.world.remove_object(self.kitchen) - time.sleep(2) + self.kitchen.set_position([100, 100, 0]) self.milk.set_position(Pose([0, 0, 2])) self.world.simulate(1) self.assertTrue(self.milk.get_position().z < 2) - # self.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + self.extension, ObjectDescription, - # world=self.world) - # time.sleep(2) def test_set_real_time_simulation(self): self.milk.set_position(Pose([100, 0, 2])) @@ -79,8 +103,72 @@ def test_set_real_time_simulation(self): time_elapsed = time.time() - curr_time self.assertAlmostEqual(time_elapsed, 0.5, delta=0.2) + def test_collision_callback(self): + self.kitchen.set_position([100, 100, 0]) + self.collision_called = False + self.no_collision_called = False + + def collision_callback(): + self.collision_called = True + + def no_collision_callback(): + self.no_collision_called = True + + self.world.register_two_objects_collision_callbacks(self.milk, self.cereal, + collision_callback, no_collision_callback) + + self.world.simulate(1) + self.assertTrue(self.no_collision_called) + self.assertFalse(self.collision_called) + + self.collision_called = False + self.no_collision_called = False + + new_milk_position = self.cereal.get_position() + new_milk_position.z += 0.5 + self.milk.set_position(new_milk_position) + + self.world.simulate(4) + self.assertTrue(self.collision_called) + + def test_equal_world_states(self): + time.sleep(2) + self.robot.set_pose(Pose([1, 0, 0], [0, 0, 0, 1])) + self.assertFalse(self.world.world_sync.check_for_equal()) + self.world.prospection_world.object_states = self.world.current_state.object_states + time.sleep(0.1) + self.assertTrue(self.world.world_sync.check_for_equal()) + + def test_add_resource_path(self): + self.world.add_resource_path("test") + self.assertTrue("test" in self.world.data_directory) + + def test_no_prospection_object_found_for_given_object(self): + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + time.sleep(0.1) + try: + self.world.prospection_world.remove_object(milk_2) + self.assertTrue(milk_2 in self.world.objects) + self.world.get_prospection_object_for_object(milk_2) + self.assertFalse(True) + except ValueError as e: + self.assertTrue(True) + self.world.remove_object(milk_2) + + def test_no_object_found_for_given_prospection_object(self): + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + time.sleep(0.1) + prospection_milk = self.world.get_prospection_object_for_object(milk_2) + self.assertTrue(self.world.get_object_for_prospection_object(prospection_milk) == milk_2) + try: + self.world.remove_object(milk_2) + self.world.get_object_for_prospection_object(prospection_milk) + time.sleep(0.1) + self.assertFalse(True) + except ValueError as e: + self.assertTrue(True) + time.sleep(0.1) -class BulletWorldTestVis(BulletWorldTestCase): def test_add_vis_axis(self): self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) self.assertTrue(len(self.world.vis_axis) == 1) @@ -143,4 +231,3 @@ def test_inertial(self): resulting_tree = ET.ElementTree(ET.fromstring(result)) for element in resulting_tree.iter("link"): self.assertTrue(len([*element.iter("inertial")]) > 0) - diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 457bbd577..ba8c855ff 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -1,7 +1,8 @@ +import numpy as np + from bullet_world_testcase import BulletWorldTestCase from pycram.costmaps import OccupancyCostmap from pycram.pose import Pose -import numpy as np class TestCostmapsCase(BulletWorldTestCase): @@ -16,9 +17,14 @@ def test_attachment_exclusion(self): self.robot.set_pose(Pose([0, 0, 0])) self.milk.set_pose(Pose([0.5, 0, 1])) self.cereal.set_pose(Pose([50, 50, 0])) - o = OccupancyCostmap(0.2, from_ros=False, size=200, resolution=0.02, origin=Pose([0, 0, 0], [0, 0, 0, 1])) + o = OccupancyCostmap(0.2, from_ros=False, size=200, resolution=0.02, + origin=Pose([0, 0, 0], [0, 0, 0, 1])) self.assertEquals(np.sum(o.map[115:135, 90:110]), 0) self.robot.attach(self.milk) self.assertTrue(np.sum(o.map[80:90, 90:110]) != 0) + def test_visualize(self): + o = OccupancyCostmap(0.2, from_ros=False, size=200, resolution=0.02, + origin=Pose([0, 0, 0], [0, 0, 0, 1])) + o.visualize() From 1458e03a4657b8c6595687f997109f35b264b2a0 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 15 Feb 2024 20:54:54 +0100 Subject: [PATCH 086/195] [Abstract World] Added more tests for bullet world, Tests are running. --- src/pycram/world.py | 8 -------- test/test_bullet_world.py | 6 +++--- 2 files changed, 3 insertions(+), 11 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 5db837f7e..9015347d6 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -701,14 +701,6 @@ def restore_physics_simulator_state(self, state_id: int) -> None: """ pass - def restore_objects_states(self, state_id: int) -> None: - """ - Restores the state of all objects in the World according to the given state using the unique state id. - :param state_id: The unique id representing the state. - """ - for obj in self.objects: - obj.restore_state(state_id) - def get_images_for_target(self, target_pose: Pose, cam_pose: Pose, diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 658138975..ff910d877 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -147,13 +147,13 @@ def test_no_prospection_object_found_for_given_object(self): milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) time.sleep(0.1) try: - self.world.prospection_world.remove_object(milk_2) - self.assertTrue(milk_2 in self.world.objects) + prospection_milk_2 = self.world.get_prospection_object_for_object(milk_2) + self.world.remove_object(milk_2) + time.sleep(0.1) self.world.get_prospection_object_for_object(milk_2) self.assertFalse(True) except ValueError as e: self.assertTrue(True) - self.world.remove_object(milk_2) def test_no_object_found_for_given_prospection_object(self): milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) From c49ccc0050648364656d854537dfe7a55c7d2f05 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 16 Feb 2024 17:57:08 +0100 Subject: [PATCH 087/195] [Abstract World] Added more tests for bullet world, Tests are running. Made 'WorldSync' sync objects by equating their current state/ --- src/pycram/bullet_world.py | 6 +- src/pycram/description.py | 22 ++-- src/pycram/designators/location_designator.py | 2 +- src/pycram/pose.py | 4 +- .../process_modules/pr2_process_modules.py | 4 +- src/pycram/world.py | 16 +-- src/pycram/world_dataclasses.py | 1 + src/pycram/world_object.py | 113 +++++------------- test/bullet_world_testcase.py | 2 +- test/test_bullet_world.py | 9 +- test/test_description.py | 25 ++++ test/test_object.py | 110 ++++++++++++++++- 12 files changed, 193 insertions(+), 121 deletions(-) create mode 100644 test/test_description.py diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index eeef44a64..f4fc8c300 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -63,8 +63,8 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo self.set_gravity([0, 0, -9.8]) if not is_prospection_world: - plane = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, ObjectDescription, - world=self) + _ = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, ObjectDescription, + world=self) def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: return p.loadURDF(path, @@ -202,8 +202,6 @@ def add_vis_axis(self, pose: Pose, pose_in_map = self.local_transformer.transform_pose(pose, "map") - position, orientation = pose_in_map.to_list() - box_vis_shape = BoxVisualShape(Color(1, 0, 0, 0.8), [length, 0.01, 0.01], [length, 0.01, 0.01]) vis_x = self.create_visual_shape(box_vis_shape) diff --git a/src/pycram/description.py b/src/pycram/description.py index 3ac66c521..f6bee8ff9 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -184,13 +184,6 @@ def object_id(self) -> int: """ return self.object.id - def __repr__(self): - return self.__class__.__qualname__ + f"(" + ', \n'.join( - [f"{key}={value}" for key, value in self.__dict__.items()]) + ")" - - def __str__(self): - return self.__repr__() - class Link(ObjectEntity, LinkDescription, ABC): """ @@ -509,7 +502,8 @@ def current_state(self) -> JointState: @current_state.setter def current_state(self, joint_state: JointState) -> None: - self.position = joint_state.position + if self._current_position != joint_state.position: + self.position = joint_state.position def __copy__(self): return Joint(self.id, self, self.object) @@ -578,14 +572,22 @@ def generate_description_from_file(self, path: str, extension: str) -> str: :param extension: The file extension of the file to preprocess. :return: The processed description string. """ + description_string = None if extension in self.MESH_EXTENSIONS: description_string = self.generate_from_mesh_file(path) elif extension == self.get_file_extension(): description_string = self.generate_from_description_file(path) else: - # Using the description from the parameter server - description_string = self.generate_from_parameter_server(path) + try: + # Using the description from the parameter server + description_string = self.generate_from_parameter_server(path) + except KeyError: + logging.warning(f"Couldn't find dile data in the ROS parameter server") + if description_string is None: + logging.error(f"Could not find file with path {path} in the resources directory nor" + f" in the ros parameter server.") + raise FileNotFoundError return description_string diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 4b2a0a931..2a087f07f 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -257,7 +257,7 @@ def __iter__(self) -> Location: test_robot = World.current_world.get_prospection_object_for_object(self.robot) # Find a Joint of type prismatic which is above the handle in the URDF tree - container_joint = self.handle.world_object.find_joint_above(self.handle.name, JointType.PRISMATIC) + container_joint = self.handle.world_object.find_joint_above_link(self.handle.name, JointType.PRISMATIC) init_pose = link_pose_for_joint_config(self.handle.world_object, { container_joint: self.handle.world_object.get_joint_limits(container_joint)[0]}, diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 0873883aa..85f85f08a 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -100,8 +100,8 @@ def position(self, value) -> None: """ if (not type(value) == list and not type(value) == tuple and not type(value) == GeoPose and not type(value) == Point): - rospy.logwarn("Position can only be a list or geometry_msgs/Pose") - return + rospy.logerr("Position can only be a list or geometry_msgs/Pose") + raise TypeError("Position can only be a list/tuple or geometry_msgs/Pose") if type(value) == list or type(value) == tuple and len(value) == 3: self.pose.position.x = value[0] self.pose.position.y = value[1] diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 1240f7467..ff5da6a0b 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -244,7 +244,7 @@ class Pr2Open(ProcessModule): def _execute(self, desig: OpeningMotion.Motion): part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) @@ -264,7 +264,7 @@ class Pr2Close(ProcessModule): def _execute(self, desig: ClosingMotion.Motion): part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) diff --git a/src/pycram/world.py b/src/pycram/world.py index 9015347d6..4805c0306 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1076,10 +1076,8 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): # self.equal_states = False for i in range(self.add_obj_queue.qsize()): obj = self.add_obj_queue.get() - # [0:name, 1:type, 2:path, 3:description, 4:position, 5:orientation, - # 6:self.world.prospection_world, 7:rgba_color, 8:world object] # Maps the World object to the prospection world object - self.object_mapping[obj[8]] = copy(obj[8]) + self.object_mapping[obj] = copy(obj) self.add_obj_queue.task_done() for i in range(self.remove_obj_queue.qsize()): obj = self.remove_obj_queue.get() @@ -1090,17 +1088,7 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): self.remove_obj_queue.task_done() for world_obj, prospection_obj in self.object_mapping.items(): - b_pose = world_obj.get_pose() - s_pose = prospection_obj.get_pose() - if b_pose.dist(s_pose) != 0.0: - prospection_obj.set_pose(world_obj.get_pose()) - - # Manage joint positions - if len(world_obj.joint_name_to_id) > 2: - for joint_name in world_obj.joint_name_to_id.keys(): - if prospection_obj.get_joint_position(joint_name) != world_obj.get_joint_position(joint_name): - prospection_obj.set_joint_positions(world_obj.get_positions_of_all_joints()) - break + prospection_obj.current_state = world_obj.current_state self.check_for_pause() # self.check_for_equal() diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 98b15178a..3f0900964 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -332,6 +332,7 @@ class WorldState(State): @dataclass class ObjectState(State): + pose: Pose attachments: Dict['Object', 'Attachment'] link_states: Dict[int, 'LinkState'] joint_states: Dict[int, 'JointState'] diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index c398a1828..1eee6c20d 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -72,8 +72,6 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + f"{self.name}_{self.id}") - self._update_object_description_from_file(self.path) - if self.description.name == robot_description.name: self.world.set_robot_if_not_set(self) @@ -104,7 +102,11 @@ def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, :return: The unique id of the object and the path of the file that was loaded. """ - path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) + try: + path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) + except FileNotFoundError as e: + logging.error("Could not generate description from file.") + raise e try: obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), @@ -115,14 +117,7 @@ def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" " the name of an URDF string on the parameter server.") os.remove(path) - raise (e) - - def _update_object_description_from_file(self, path: str) -> None: - """ - Updates the object description from the given file path. - :param path: The path to the file from which the object description should be updated. - """ - self.description.update_description_from_file(path) + raise e def _init_joint_name_and_id_map(self) -> None: """ @@ -170,10 +165,7 @@ def _add_to_world_sync_obj_queue(self) -> None: """ Adds this object to the objects queue of the WorldSync object of the World. """ - self.world.world_sync.add_obj_queue.put( - [self.name, self.obj_type, self.path, type(self.description), self.get_position_as_list(), - self.get_orientation_as_list(), - self.world.prospection_world, self.color, self]) + self.world.world_sync.add_obj_queue.put(self) @property def link_names(self) -> List[str]: @@ -182,13 +174,6 @@ def link_names(self) -> List[str]: """ return self.world.get_object_link_names(self) - @property - def number_of_links(self) -> int: - """ - :return: The number of links of this object. - """ - return len(self.description.links) - @property def joint_names(self) -> List[str]: """ @@ -196,20 +181,13 @@ def joint_names(self) -> List[str]: """ return self.world.get_object_joint_names(self) - @property - def number_of_joints(self) -> int: - """ - :return: The number of joints of this object. - """ - return len(self.description.joints) - @property def base_origin_shift(self) -> np.ndarray: """ The shift between the base of the object and the origin of the object. :return: A numpy array with the shift between the base of the object and the origin of the object. """ - return np.array(self.get_pose().position_as_list()) - np.array(self.get_base_origin().position_as_list()) + return np.array(self.get_position_as_list()) - np.array(self.get_base_position_as_list()) def __repr__(self): skip_attr = ["links", "joints", "description", "attachments"] @@ -318,6 +296,14 @@ def get_position_as_list(self) -> List[float]: """ return self.get_pose().position_as_list() + def get_base_position_as_list(self) -> List[float]: + """ + Returns the position of this Object as a list of xyz. + + :return: The current position of this object + """ + return self.get_base_origin().position_as_list() + def get_orientation_as_list(self) -> List[float]: """ Returns the orientation of this object as a list of xyzw, representing a quaternion. @@ -344,7 +330,7 @@ def set_pose(self, pose: Pose, base: Optional[bool] = False, set_attachments: Op """ pose_in_map = self.local_transformer.transform_pose(pose, "map") if base: - pose_in_map.position = np.array(pose_in_map.position) + self.base_origin_shift + pose_in_map.position = (np.array(pose_in_map.position_as_list()) + self.base_origin_shift).tolist() self.reset_base_pose(pose_in_map) @@ -363,13 +349,6 @@ def update_pose(self): self._update_all_links_poses() self.update_link_transforms() - def _update_all_joints_positions(self): - """ - Updates the posisitons of all joints by getting them from the simulator. - """ - for joint in self.joints.values(): - joint._update_position() - def _update_all_links_poses(self): """ Updates the poses of all links by getting them from the simulator. @@ -377,7 +356,7 @@ def _update_all_links_poses(self): for link in self.links.values(): link._update_pose() - def move_base_to_origin_pos(self) -> None: + def move_base_to_origin_pose(self) -> None: """ Move the object such that its base will be at the current origin position. This is useful when placing objects on surfaces where you want the object base in contact with the surface. @@ -411,10 +390,12 @@ def save_joints_states(self, state_id: int) -> None: @property def current_state(self) -> ObjectState: - return ObjectState(self.attachments.copy(), self.link_states.copy(), self.joint_states.copy()) + return ObjectState(self.get_pose(), self.attachments.copy(), self.link_states.copy(), self.joint_states.copy()) @current_state.setter def current_state(self, state: ObjectState) -> None: + if self.get_pose().dist(state.pose) != 0.0: + self.set_pose(state.pose, base=False, set_attachments=False) self.attachments = state.attachments self.link_states = state.link_states self.joint_states = state.joint_states @@ -453,29 +434,6 @@ def joint_states(self, joint_states: Dict[int, JointState]) -> None: for joint in self.joints.values(): joint.current_state = joint_states[joint.id] - def restore_attachments(self, state_id: int) -> None: - """ - Restores the attachments of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - self.attachments = self.saved_states[state_id].attachments - - def restore_links_states(self, state_id: int) -> None: - """ - Restores the states of all links of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - for link in self.links.values(): - link.restore_state(state_id) - - def restore_joints_states(self, state_id: int) -> None: - """ - Restores the states of all joints of this object from a saved state using the given state id. - :param state_id: The unique id of the state. - """ - for joint in self.joints.values(): - joint.restore_state(state_id) - def remove_saved_states(self) -> None: """ Removes all saved states of this object. @@ -519,7 +477,7 @@ def _set_attached_objects_poses(self, already_moved_objects: Optional[List['Obje continue attachment = self.attachments[child] - if not attachment.bidirectional: + if attachment.loose: self.update_attachment_with_object(child) child.update_attachment_with_object(self) @@ -552,7 +510,7 @@ def set_position(self, position: Union[Pose, Point], base=False) -> None: pose.orientation = self.get_orientation() self.set_pose(pose, base=base) - def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: + def set_orientation(self, orientation: Union[Pose, Quaternion, List, Tuple, np.ndarray]) -> None: """ Sets the orientation of the Object to the given orientation. Orientation can either be a Pose, in this case only the orientation of this pose is used or a geometry_msgs.msg/Quaternion which is the orientation of a Pose. @@ -563,8 +521,13 @@ def set_orientation(self, orientation: Union[Pose, Quaternion]) -> None: if isinstance(orientation, Pose): target_orientation = orientation.orientation pose.frame = orientation.frame - else: + elif isinstance(orientation, Quaternion): target_orientation = orientation + elif (isinstance(orientation, list) or isinstance(orientation, np.ndarray) or isinstance(orientation, tuple)) \ + and len(orientation) == 4: + target_orientation = Quaternion(*orientation) + else: + raise TypeError("The given orientation has to be a Pose, Quaternion or one of list/tuple/ndarray of xyzw.") pose.pose.position = self.get_position() pose.pose.orientation = target_orientation @@ -584,9 +547,8 @@ def get_root_link_description(self) -> 'LinkDescription': Returns the root link of the URDF of this object. :return: The root link as defined in the URDF of this object. """ - root_link_name = self.description.get_root() for link_description in self.description.links: - if link_description.name == root_link_name: + if link_description.name == self.root_link_name: return link_description @property @@ -628,15 +590,6 @@ def get_link_by_id(self, link_id: int) -> 'Link': """ return self.links[self.link_id_to_name[link_id]] - def get_joint_by_id(self, joint_id: int) -> str: - """ - Returns the joint name for a unique world id - - :param joint_id: The world id of for joint - :return: The joint name - """ - return dict(zip(self.joint_name_to_id.values(), self.joint_name_to_id.keys()))[joint_id] - def reset_all_joints_positions(self) -> None: """ Sets the current position of all joints to 0. This is useful if the joints should be reset to their default @@ -692,7 +645,7 @@ def get_joint_type(self, joint_name: str) -> JointType: def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: return self.joints[joint_name].limits - def find_joint_above(self, link_name: str, joint_type: JointType) -> str: + def find_joint_above_link(self, link_name: str, joint_type: JointType) -> str: """ Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. @@ -798,11 +751,11 @@ def get_base_origin(self) -> Pose: """ :return: the origin of the base/bottom of this object. """ - aabb = self.get_link_by_id(-1).get_axis_aligned_bounding_box() + aabb = self.get_axis_aligned_bounding_box() base_width = np.absolute(aabb.min_x - aabb.max_x) base_length = np.absolute(aabb.min_y - aabb.max_y) return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], - self.get_pose().orientation_as_list()) + self.get_orientation_as_list()) def __copy__(self) -> 'Object': """ diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 4dc7ae2e7..bc0d2cc72 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -34,7 +34,7 @@ def setUp(self): # Tests in here would not be properly executed in the CI def tearDown(self): - time.sleep(0.2) + time.sleep(0.05) self.world.reset_world() @classmethod diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index ff910d877..e68397875 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -48,7 +48,6 @@ def test_save_and_restore_state(self): self.assertTrue(att in all_object_attachments[obj]) def test_remove_object(self): - # time.sleep(2) milk_id = self.milk.id self.assertTrue(milk_id in [obj.id for obj in self.world.objects]) self.world.remove_object(self.milk) @@ -136,7 +135,7 @@ def test_equal_world_states(self): self.robot.set_pose(Pose([1, 0, 0], [0, 0, 0, 1])) self.assertFalse(self.world.world_sync.check_for_equal()) self.world.prospection_world.object_states = self.world.current_state.object_states - time.sleep(0.1) + time.sleep(0.05) self.assertTrue(self.world.world_sync.check_for_equal()) def test_add_resource_path(self): @@ -145,7 +144,7 @@ def test_add_resource_path(self): def test_no_prospection_object_found_for_given_object(self): milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) - time.sleep(0.1) + time.sleep(0.05) try: prospection_milk_2 = self.world.get_prospection_object_for_object(milk_2) self.world.remove_object(milk_2) @@ -157,7 +156,7 @@ def test_no_prospection_object_found_for_given_object(self): def test_no_object_found_for_given_prospection_object(self): milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) - time.sleep(0.1) + time.sleep(0.05) prospection_milk = self.world.get_prospection_object_for_object(milk_2) self.assertTrue(self.world.get_object_for_prospection_object(prospection_milk) == milk_2) try: @@ -167,7 +166,7 @@ def test_no_object_found_for_given_prospection_object(self): self.assertFalse(True) except ValueError as e: self.assertTrue(True) - time.sleep(0.1) + time.sleep(0.05) def test_add_vis_axis(self): self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) diff --git a/test/test_description.py b/test/test_description.py new file mode 100644 index 000000000..8f3afa201 --- /dev/null +++ b/test/test_description.py @@ -0,0 +1,25 @@ +from bullet_world_testcase import BulletWorldTestCase + + +class DescriptionTest(BulletWorldTestCase): + def test_is_root(self): + self.assertTrue(self.robot.root_link.is_root) + self.assertFalse(self.robot.links["base_link"].is_root) + + def test_orientation_as_list(self): + base_link = self.robot.links["base_link"] + self.assertEqual(base_link.orientation_as_list, base_link.pose.orientation_as_list()) + + def test_pose_as_list(self): + base_link = self.robot.links["base_link"] + self.assertEqual(base_link.pose_as_list, base_link.pose.to_list()) + + def test_joint_child_link(self): + self.assertEqual(self.robot.joints["base_footprint_joint"].child_link, self.robot.links["base_link"]) + self.assertEqual(self.robot.joints["base_footprint_joint"].parent_link, self.robot.root_link) + + def test_generate_description_from_mesh(self): + self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.stl", ".stl")) + + def test_generate_description_from_description_file(self): + self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.urdf", ".urdf")) diff --git a/test/test_object.py b/test/test_object.py index ff9361eb5..80a8f98c0 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -1,15 +1,89 @@ +import os + +import numpy as np + from bullet_world_testcase import BulletWorldTestCase -from pycram.enums import JointType + +from pycram.enums import JointType, ObjectType from pycram.pose import Pose -from geometry_msgs.msg import Point +from pycram.world_dataclasses import Color +from pycram.world_object import Object +from pycram.urdf_interface import ObjectDescription + +from geometry_msgs.msg import Point, Quaternion class TestObject(BulletWorldTestCase): + def test_wrong_object_description_path(self): + with self.assertRaises(FileNotFoundError): + milk = Object("milk2", ObjectType.MILK, "wrong_path.sk", ObjectDescription) + + def test_malformed_object_description(self): + malformed_file = "../resources/cached/malformed_description.urdf" + with open(malformed_file, "w") as file: + file.write("malformed") + with self.assertRaises(Exception): + Object("milk2", ObjectType.MILK, malformed_file, ObjectDescription) + + def test_move_base_to_origin_pose(self): + self.milk.set_position(Point(1, 2, 3), base=False) + self.milk.move_base_to_origin_pose() + self.assertEqual(self.milk.get_base_position_as_list(), [1, 2, 3]) + def test_set_position_as_point(self): self.milk.set_position(Point(1, 2, 3)) self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) + def test_uni_direction_attachment(self): + self.milk.attach(self.cereal, bidirectional=False) + + milk_position = self.milk.get_position_as_list() + cereal_position = self.cereal.get_position_as_list() + + def move_milk_and_assert_cereal_moved(): + milk_position[0] += 1 + cereal_position[0] += 1 + self.milk.set_position(milk_position) + + new_cereal_position = self.cereal.get_position_as_list() + self.assertEqual(new_cereal_position, cereal_position) + + def move_cereal_and_assert_milk_not_moved(): + cereal_position[0] += 1 + self.cereal.set_position(cereal_position) + + new_milk_position = self.milk.get_position_as_list() + self.assertEqual(new_milk_position, milk_position) + + # move twice to test updated attachment at the new cereal position + for _ in range(2): + move_milk_and_assert_cereal_moved() + move_cereal_and_assert_milk_not_moved() + + def test_setting_wrong_position_type(self): + with self.assertRaises(TypeError): + self.milk.set_position(np.array([1, 2, 3])) + + with self.assertRaises(TypeError): + self.milk.get_pose().position = np.array([1, 2, 3]) + + def test_set_orientation_as_list(self): + self.milk.set_orientation([1, 0, 0, 0]) + self.assertEqual(self.milk.get_orientation_as_list(), [1, 0, 0, 0]) + + def test_set_orientation_as_quaternion(self): + self.milk.set_orientation(Quaternion(*[1, 0, 0, 0])) + self.assertEqual(self.milk.get_orientation_as_list(), [1, 0, 0, 0]) + + def test_set_orientation_as_ndarray(self): + self.milk.set_orientation(np.array([1, 0, 0, 0])) + self.assertEqual(self.milk.get_orientation_as_list(), [1, 0, 0, 0]) + + def test_set_wrong_orientation_type(self): + with self.assertRaises(TypeError): + self.milk.set_orientation(1) + def test_set_position_as_pose(self): self.milk.set_position(Pose([1, 2, 3])) self.assertEqual(self.milk.get_position_as_list(), [1, 2, 3]) @@ -56,3 +130,35 @@ def test_restore_state(self): saved_state = link.saved_states[1] self.assertEqual(curr_state, saved_state) self.assertEqual(curr_state.constraint_ids, saved_state.constraint_ids) + + def test_get_link_by_id(self): + self.assertEqual(self.robot.get_link_by_id(-1), self.robot.root_link) + + def test_find_joint_above_link(self): + self.assertEqual(self.robot.find_joint_above_link("head_pan_link", JointType.REVOLUTE), "head_pan_joint") + + def test_wrong_joint_type_for_joint_above_link(self): + container_joint = self.robot.find_joint_above_link("head_pan_link", JointType.CONTINUOUS) + self.assertTrue(container_joint is None) + + def test_contact_points_simulated(self): + self.milk.set_position([0, 0, 100]) + contact_points = self.milk.contact_points_simulated() + self.assertFalse(contact_points) + self.milk.set_position(self.cereal.get_position_as_list(), base=True) + contact_points = self.milk.contact_points_simulated() + self.assertTrue(contact_points) + + def test_set_color(self): + self.milk.set_color(Color(1, 0, 0, 1)) + self.assertEqual(self.milk.get_color(), Color(1, 0, 0, 1)) + self.robot.set_color(Color(0, 1, 0, 1)) + for color in self.robot.get_color().values(): + self.assertEqual(color, Color(0, 1, 0, 1)) + + def test_object_equal(self): + milk2 = Object("milk2", ObjectType.MILK, "milk.stl", ObjectDescription) + self.assertNotEqual(self.milk, milk2) + self.assertEqual(self.milk, self.milk) + self.assertNotEqual(self.milk, self.cereal) + self.assertNotEqual(self.milk, self.world) From bba4c4fec79134afb3da4ce97fde600b31f45d6b Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 16 Feb 2024 18:10:28 +0100 Subject: [PATCH 088/195] [Abstract World] Added more tests for bullet world, Tests are running. --- src/pycram/world_dataclasses.py | 61 --------------------------------- test/test_cache_manager.py | 17 +++++++++ 2 files changed, 17 insertions(+), 61 deletions(-) create mode 100644 test/test_cache_manager.py diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 3f0900964..54b04876a 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -76,67 +76,6 @@ def get_rgb(self) -> List[float]: return [self.R, self.G, self.B] -@dataclass -class Constraint: - """ - Dataclass for storing a constraint between two objects. - """ - parent_link: 'Link' - child_link: 'Link' - joint_type: JointType - joint_axis_in_child_link_frame: Point - joint_frame_pose_wrt_parent_origin: Pose - joint_frame_pose_wrt_child_origin: Pose - - def get_parent_object_id(self) -> int: - """ - Returns the id of the parent object of the constraint. - - :return: The id of the parent object of the constraint - """ - return self.parent_link.object.id - - def get_child_object_id(self) -> int: - """ - Returns the id of the child object of the constraint. - - :return: The id of the child object of the constraint - """ - return self.child_link.object.id - - def get_parent_link_id(self) -> int: - """ - Returns the id of the parent link of the constraint. - - :return: The id of the parent link of the constraint - """ - return self.parent_link.id - - def get_child_link_id(self) -> int: - """ - Returns the id of the child link of the constraint. - - :return: The id of the child link of the constraint - """ - return self.child_link.id - - def get_joint_axis_as_list(self) -> List[float]: - """ - Returns the joint axis of the constraint as a list. - - :return: The joint axis of the constraint as a list - """ - return get_point_as_list(self.joint_axis_in_child_link_frame) - - def get_joint_position_wrt_parent_as_list(self) -> List[float]: - """ - Returns the joint frame pose with respect to the parent origin as a list. - - :return: The joint frame pose with respect to the parent origin as a list - """ - return self.joint_frame_pose_wrt_parent_origin.position_as_list() - - @dataclass class AxisAlignedBoundingBox: """ diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py new file mode 100644 index 000000000..c69e1ea9f --- /dev/null +++ b/test/test_cache_manager.py @@ -0,0 +1,17 @@ +from bullet_world_testcase import BulletWorldTestCase +from pycram.enums import ObjectType +from pycram.urdf_interface import ObjectDescription +from pycram.world_object import Object + + +class TestCacheManager(BulletWorldTestCase): + + def test_generate_description_and_write_to_cache(self): + cache_manager = self.world.cache_manager + path = "../resources/apartment.urdf" + extension = ".urdf" + cache_path = self.world.cache_dir + "apartment.urdf" + apartment = Object("apartment", ObjectType.ENVIRONMENT, path, ObjectDescription) + cache_manager.generate_description_and_write_to_cache(path, extension, cache_path, + apartment.description) + self.assertTrue(cache_manager.is_cached(path, apartment.description)) From f4fa6d672be5043170eff06fda9c775fd762e462 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Tue, 20 Feb 2024 11:00:19 +0100 Subject: [PATCH 089/195] [designator] added auto inserts to action designators --- src/pycram/designators/actions/actions.py | 267 +++++++------------- src/pycram/designators/motion_designator.py | 6 +- 2 files changed, 93 insertions(+), 180 deletions(-) diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 83ca6c29f..ff83245c1 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -1,5 +1,6 @@ import abc -from typing_extensions import Union +import inspect +from typing_extensions import Union, Type from pycram.designator import ActionDesignatorDescription from pycram.designators.motion_designator import * from pycram.enums import Arms @@ -10,7 +11,9 @@ from ...bullet_world import BulletWorld from ...helper import multiply_quaternions from ...local_transformer import LocalTransformer -from ...orm.base import Base +from ...orm.base import Base, Pose as ORMPose +from ...orm.object_designator import Object as ORMObject, ObjectPart as ORMObjectPart +from ...orm.action_designator import Action as ORMAction from ...plan_failures import ObjectUnfetchable, ReachabilityFailure from ...robot_descriptions import robot_description from ...orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, @@ -24,6 +27,11 @@ @dataclass class ActionAbstract(ActionDesignatorDescription.Action, abc.ABC): """Base class for performable actions.""" + orm_class: Type[ORMAction] = field(init=False, default=None) + """ + The ORM class that is used to insert this action into the database. Must be overwritten by every action in order to + be able to insert the action into the database. + """ @abc.abstractmethod def perform(self) -> None: @@ -32,14 +40,24 @@ def perform(self) -> None: """ pass - @abc.abstractmethod def to_sql(self) -> Action: """ Convert this action to its ORM equivalent. Will be overwritten by each action. """ - pass + # get all class parameters (ignore inherited ones) + class_variables = {key: value for key, value in vars(self).items() + if key in inspect.getfullargspec(self.__init__).args} + + # get all orm class parameters (ignore inherited ones) + orm_class_variables = inspect.getfullargspec(self.orm_class.__init__).args + + # list of parameters that will be passed to the ORM class. If the name does not match the orm_class equivalent + # or if it is a type that needs to be inserted into the session manually, it will not be added to the list + parameters = [value for key, value in class_variables.items() if key in orm_class_variables + and not isinstance(value, (ObjectDesignatorDescription.Object, Pose))] + + return self.orm_class(*parameters) - @abc.abstractmethod def insert(self, session: Session, **kwargs) -> Action: """ Insert this action into the database. @@ -50,6 +68,25 @@ def insert(self, session: Session, **kwargs) -> Action: """ action = super().insert(session) + + # get all class parameters (ignore inherited ones) + class_variables = {key: value for key, value in vars(self).items() + if key in inspect.getfullargspec(self.__init__).args} + + # get all orm class parameters (ignore inherited ones) + orm_class_variables = inspect.getfullargspec(self.orm_class.__init__).args + + # loop through all class parameters and insert them into the session unless they are already added by the ORM + for key, value in class_variables.items(): + if key not in orm_class_variables: + variable = value.insert(session) + if isinstance(variable, ORMObject): + action.object_id = variable.id + elif isinstance(variable, ORMPose): + action.pose_id = variable.id + + session.add(action) + session.commit() return action @@ -63,20 +100,15 @@ class MoveTorsoActionPerformable(ActionAbstract): """ Target position of the torso joint """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMMoveTorsoAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: MoveJointsMotion([robot_description.torso_joint], [self.position]).perform() - def to_sql(self) -> ORMMoveTorsoAction: - return ORMMoveTorsoAction(self.position) - - def insert(self, session: Session, **kwargs) -> ORMMoveTorsoAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - @dataclass class SetGripperActionPerformable(ActionAbstract): @@ -92,20 +124,15 @@ class SetGripperActionPerformable(ActionAbstract): """ The motion that should be set on the gripper """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMSetGripperAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: MoveGripperMotion(gripper=self.gripper, motion=self.motion).perform() - def to_sql(self) -> ORMSetGripperAction: - return ORMSetGripperAction(self.gripper, self.motion) - - def insert(self, session: Session, *args, **kwargs) -> ORMSetGripperAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - @dataclass class ReleaseActionPerformable(ActionAbstract): @@ -122,12 +149,6 @@ class ReleaseActionPerformable(ActionAbstract): def perform(self) -> None: raise NotImplementedError - def to_sql(self) -> ORMParkArmsAction: - raise NotImplementedError - - def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: - raise NotImplementedError - @dataclass class GripActionPerformable(ActionAbstract): @@ -145,12 +166,6 @@ class GripActionPerformable(ActionAbstract): def perform(self) -> None: raise NotImplementedError() - def to_sql(self) -> Base: - raise NotImplementedError() - - def insert(self, session: Session, *args, **kwargs) -> Base: - raise NotImplementedError() - @dataclass class ParkArmsActionPerformable(ActionAbstract): @@ -162,6 +177,10 @@ class ParkArmsActionPerformable(ActionAbstract): """ Entry from the enum for which arm should be parked """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMParkArmsAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -182,15 +201,6 @@ def perform(self) -> None: MoveArmJointsMotion(left_poses, right_poses).perform() - def to_sql(self) -> ORMParkArmsAction: - return ORMParkArmsAction(self.arm.name) - - def insert(self, session: Session, **kwargs) -> ORMParkArmsAction: - action = super().insert(session) - session.add(action) - session.commit() - return action - @dataclass class PickUpActionPerformable(ActionAbstract): @@ -218,6 +228,10 @@ class PickUpActionPerformable(ActionAbstract): The object at the time this Action got created. It is used to be a static, information holding entity. It is not updated when the BulletWorld object is changed. """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMPickUpAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -285,20 +299,6 @@ def perform(self) -> None: # Remove the vis axis from the world BulletWorld.current_bullet_world.remove_vis_axis() - def to_sql(self) -> ORMPickUpAction: - return ORMPickUpAction(self.arm, self.grasp) - - def insert(self, session: Session, **kwargs) -> ORMPickUpAction: - action = super().insert(session) - - od = self.object_at_execution.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action - @dataclass class PlaceActionPerformable(ActionAbstract): @@ -318,6 +318,10 @@ class PlaceActionPerformable(ActionAbstract): """ Pose in the world at which the object should be placed """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMPlaceAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -339,23 +343,6 @@ def perform(self) -> None: retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).perform() - def to_sql(self) -> ORMPlaceAction: - return ORMPlaceAction(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMPlaceAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - @dataclass class NavigateActionPerformable(ActionAbstract): @@ -367,25 +354,15 @@ class NavigateActionPerformable(ActionAbstract): """ Location to which the robot should be navigated """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMNavigateAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: MoveMotion(self.target_location).perform() - def to_sql(self) -> ORMNavigateAction: - return ORMNavigateAction() - - def insert(self, session: Session, *args, **kwargs) -> ORMNavigateAction: - action = super().insert(session) - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - @dataclass class TransportActionPerformable(ActionAbstract): @@ -405,11 +382,14 @@ class TransportActionPerformable(ActionAbstract): """ Target Location to which the object should be transported """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMTransportAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: robot_desig = BelieveObject(names=[robot_description.name]) - # ParkArmsAction.Action(Arms.BOTH).perform() ParkArmsActionPerformable(Arms.BOTH).perform() pickup_loc = CostmapLocation(target=self.object_designator, reachable_for=robot_desig.resolve(), reachable_arm=self.arm) @@ -425,7 +405,6 @@ def perform(self) -> None: NavigateActionPerformable(pickup_pose.pose).perform() PickUpActionPerformable(self.object_designator, self.arm, "front").perform() - # ParkArmsAction.Action(Arms.BOTH).perform() ParkArmsActionPerformable(Arms.BOTH).perform() try: place_loc = CostmapLocation(target=self.target_location, reachable_for=robot_desig.resolve(), @@ -437,23 +416,6 @@ def perform(self) -> None: PlaceActionPerformable(self.object_designator, self.arm, self.target_location).perform() ParkArmsActionPerformable(Arms.BOTH).perform() - def to_sql(self) -> ORMTransportAction: - return ORMTransportAction(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMTransportAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - pose = self.target_location.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - - return action - @dataclass class LookAtActionPerformable(ActionAbstract): @@ -465,24 +427,15 @@ class LookAtActionPerformable(ActionAbstract): """ Position at which the robot should look, given as 6D pose """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMLookAtAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: LookingMotion(target=self.target).perform() - def to_sql(self) -> ORMLookAtAction: - return ORMLookAtAction() - - def insert(self, session: Session, *args, **kwargs) -> ORMLookAtAction: - action = super().insert(session) - - pose = self.target.insert(session) - action.pose_id = pose.id - - session.add(action) - session.commit() - return action - @dataclass class DetectActionPerformable(ActionAbstract): @@ -494,25 +447,15 @@ class DetectActionPerformable(ActionAbstract): """ Object designator loosely describing the object, e.g. only type. """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMDetectAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: return DetectingMotion(object_type=self.object_designator.type).perform() - def to_sql(self) -> ORMDetectAction: - return ORMDetectAction() - - def insert(self, session: Session, *args, **kwargs) -> ORMDetectAction: - action = super().insert(session) - - od = self.object_designator.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action - @dataclass class OpenActionPerformable(ActionAbstract): @@ -528,6 +471,10 @@ class OpenActionPerformable(ActionAbstract): """ Arm that should be used for opening the container """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMOpenAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -536,20 +483,6 @@ def perform(self) -> None: MoveGripperMotion("open", self.arm, allow_gripper_collision=True).perform() - def to_sql(self) -> ORMOpenAction: - return ORMOpenAction(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMOpenAction: - action = super().insert(session) - - op = self.object_designator.insert(session) - action.object_id = op.id - - session.add(action) - session.commit() - - return action - @dataclass class CloseActionPerformable(ActionAbstract): @@ -565,6 +498,10 @@ class CloseActionPerformable(ActionAbstract): """ Arm that should be used for closing """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMCloseAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -573,20 +510,6 @@ def perform(self) -> None: MoveGripperMotion("open", self.arm, allow_gripper_collision=True).perform() - def to_sql(self) -> ORMCloseAction: - return ORMCloseAction(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMCloseAction: - action = super().insert(session) - - op = self.object_designator.insert(session) - action.object_id = op.id - - session.add(action) - session.commit() - - return action - @dataclass class GraspingActionPerformable(ActionAbstract): @@ -602,6 +525,10 @@ class GraspingActionPerformable(ActionAbstract): """ Object Designator for the object that should be grasped """ + orm_class: Type[ActionAbstract] = field(init=False, default=ORMGraspingAction) + """ + The ORM class that is used to insert this action into the database + """ @with_tree def perform(self) -> None: @@ -623,17 +550,3 @@ def perform(self) -> None: MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).perform() MoveGripperMotion("close", self.arm, allow_gripper_collision=True).perform() - - def to_sql(self) -> ORMGraspingAction: - return ORMGraspingAction(self.arm) - - def insert(self, session: Session, *args, **kwargs) -> ORMGraspingAction: - action = super().insert(session) - - od = self.object_desig.insert(session) - action.object_id = od.id - - session.add(action) - session.commit() - - return action diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 31c163e0f..b6779c300 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -260,11 +260,11 @@ class MoveArmJointsMotion(BaseMotion): Moves the joints of each arm into the given position """ - left_arm_poses: Optional[Dict[str, float]] + left_arm_poses: Optional[Dict[str, float]] = None """ Target positions for the left arm joints """ - right_arm_poses: Optional[Dict[str, float]] + right_arm_poses: Optional[Dict[str, float]] = None """ Target positions for the right arm joints """ @@ -286,7 +286,7 @@ class WorldStateDetectingMotion(BaseMotion): Detects an object based on the world state. """ - object_type: str + object_type: ObjectType """ Object type that should be detected """ From 9e39552e7e87b7acf7a2d0dccd438ee262cd35c6 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 20 Feb 2024 20:35:51 +0100 Subject: [PATCH 090/195] [Abstract World] Tried importing annotations from __future__ but Fails due to circular imports. --- demos/pycram_bullet_world_demo/demo.py | 4 +- doc/source/notebooks/bullet_world.ipynb | 21 +-- doc/source/notebooks/intro.ipynb | 2 +- examples/bullet_world.ipynb | 21 ++- examples/cram_plan_tutorial.ipynb | 6 +- examples/intro.ipynb | 2 +- examples/local_transformer.ipynb | 2 +- src/neem_interface_python | 2 +- src/pycram/costmaps.py | 4 +- src/pycram/description.py | 22 +-- src/pycram/designators/action_designator.py | 8 +- src/pycram/designators/object_designator.py | 2 +- src/pycram/external_interfaces/giskard.py | 7 +- src/pycram/external_interfaces/ik.py | 4 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/helper.py | 2 +- src/pycram/pose_generator_and_validator.py | 4 +- .../process_modules/boxy_process_modules.py | 6 +- .../default_process_modules.py | 4 +- .../process_modules/donbot_process_modules.py | 6 +- .../process_modules/hsr_process_modules.py | 6 +- .../process_modules/pr2_process_modules.py | 10 +- src/pycram/ros/tf_broadcaster.py | 4 +- src/pycram/ros/viz_marker_publisher.py | 23 +-- src/pycram/world.py | 96 ++++++----- src/pycram/world_constraints.py | 24 +-- src/pycram/world_dataclasses.py | 41 +++-- src/pycram/world_object.py | 160 ++++++++++++++++-- src/pycram/world_reasoning.py | 4 +- test/test_action_designator.py | 4 +- test/test_bullet_world.py | 16 +- test/test_bullet_world_reasoning.py | 10 +- test/test_description.py | 4 +- test/test_links.py | 2 +- test/test_task_tree.py | 2 +- 35 files changed, 347 insertions(+), 190 deletions(-) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 24917d05d..f37015e4f 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -6,7 +6,7 @@ from pycram.pose import Pose from pycram.process_module import simulated_robot, with_simulated_robot from pycram.urdf_interface import ObjectDescription -from pycram.world import Object +from pycram.world_object import Object from pycram.world_dataclasses import Color extension = ObjectDescription.get_file_extension() @@ -70,7 +70,7 @@ def move_and_detect(obj_type): spoon.detach(apartment) # Detect and pickup the spoon - LookAtAction([apartment.links["handle_cab10_t"].pose]).resolve().perform() + LookAtAction([apartment.get_link_pose("handle_cab10_t")]).resolve().perform() spoon_desig = DetectAction(BelieveObject(types=[ObjectType.SPOON])).resolve().perform() diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index c9a0def28..cc8874cec 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -141,9 +141,10 @@ }, "outputs": [], "source": [ - "from pycram.world import Object\n", + "from pycram.world_object import Object\n", + "from pycram.urdf_interface import ObjectDescription\n", "\n", - "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([0, 0, 1]))" + "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", ObjectDescription, pose=Pose([0, 0, 1]))" ] }, { @@ -292,7 +293,7 @@ }, "outputs": [], "source": [ - "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", pose=Pose([1, 0, 1]))" + "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", ObjectDescription, pose=Pose([1, 0, 1]))" ] }, { @@ -395,7 +396,7 @@ } ], "source": [ - "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\")\n", + "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\", ObjectDescription)\n", "print(pr2.links)" ] }, @@ -452,11 +453,11 @@ } ], "source": [ - "print(f\"Position: \\n{pr2.links['torso_lift_link'].position}\")\n", + "print(f\"Position: \\n{pr2.get_link_position('torso_lift_link')}\")\n", "\n", - "print(f\"Orientation: \\n{pr2.links['torso_lift_link'].orientation}\")\n", + "print(f\"Orientation: \\n{pr2.get_link_orientation('torso_lift_link')}\")\n", "\n", - "print(f\"Pose: \\n{pr2.links['torso_lift_link'].pose}\")" + "print(f\"Pose: \\n{pr2.get_link_pose('torso_lift_link')}\")" ] }, { @@ -533,7 +534,7 @@ } ], "source": [ - "print(f\"Pr2 forearm color: {pr2.links['r_forearm_link'].color}\")" + "print(f\"Pr2 forearm color: {pr2.get_link_color('r_forearm_link')}\")" ] }, { @@ -548,7 +549,7 @@ }, "outputs": [], "source": [ - "pr2.links[\"r_forearm_link\"].color = [1, 0, 0, 1]" + "pr2.set_link_color(\"r_forearm_link\", [1, 0, 0, 1])" ] }, { @@ -580,7 +581,7 @@ } ], "source": [ - "pr2.get_aabb()" + "pr2.get_axis_aligned_bounding_box()" ] }, { diff --git a/doc/source/notebooks/intro.ipynb b/doc/source/notebooks/intro.ipynb index d38e92ecc..86a479e1e 100644 --- a/doc/source/notebooks/intro.ipynb +++ b/doc/source/notebooks/intro.ipynb @@ -489,7 +489,7 @@ ], "source": [ "milk.set_position(Pose([1,0,1]))\n", - "visible = btr.visible(milk, pr2.links[\"wide_stereo_optical_frame\"].pose)\n", + "visible = btr.visible(milk, pr2.get_link_pose(\"wide_stereo_optical_frame\"))\n", "print(f\"Milk visible: {visible}\")" ] }, diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index 6a7423953..33a3da4d7 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -355,6 +355,15 @@ "print(pr2.links)" ] }, + { + "cell_type": "code", + "outputs": [], + "source": [], + "metadata": { + "collapsed": false + }, + "id": "e896223230860878" + }, { "cell_type": "markdown", "id": "e157eb6f", @@ -408,11 +417,11 @@ } ], "source": [ - "print(f\"Position: \\n{pr2.links['torso_lift_link'].position}\")\n", + "print(f\"Position: \\n{pr2.get_link_position('torso_lift_link')}\")\n", "\n", - "print(f\"Orientation: \\n{pr2.links['torso_lift_link'].orientation}\")\n", + "print(f\"Orientation: \\n{pr2.get_link_orientation('torso_lift_link')}\")\n", "\n", - "print(f\"Pose: \\n{pr2.links['torso_lift_link'].pose}\")" + "print(f\"Pose: \\n{pr2.get_link_pose('torso_lift_link')}\")" ] }, { @@ -489,7 +498,7 @@ } ], "source": [ - "print(f\"Pr2 forearm color: {pr2.links['r_forearm_link'].color}\")" + "print(f\"Pr2 forearm color: {pr2.get_link_color('r_forearm_link')}\")" ] }, { @@ -504,7 +513,7 @@ }, "outputs": [], "source": [ - "pr2.links[\"r_forearm_link\"].color = [1, 0, 0]" + "pr2.set_link_color(\"r_forearm_link\", [1, 0, 0])" ] }, { @@ -536,7 +545,7 @@ } ], "source": [ - "pr2.get_aabb()" + "pr2.get_axis_aligned_bounding_box()" ] } ], diff --git a/examples/cram_plan_tutorial.ipynb b/examples/cram_plan_tutorial.ipynb index 2297b6cb5..1427b2915 100644 --- a/examples/cram_plan_tutorial.ipynb +++ b/examples/cram_plan_tutorial.ipynb @@ -81,7 +81,7 @@ "robot_desig = ObjectDesignatorDescription(names=['pr2']).resolve()\n", "apartment = Object(\"apartment\", \"environment\", \"/home/abassi/cram_ws/src/iai_maps/iai_apartment/urdf/apartment.urdf\", position=[-1.5, -2.5, 0])\n", "apartment_desig = ObjectDesignatorDescription(names=['apartment']).resolve()\n", - "table_top = apartment.links[\"cooktop\"].position\n", + "table_top = apartment.get_link_position(\"cooktop\")\n", "# milk = Object(\"milk\", \"milk\", \"milk.stl\", position=[table_top[0]-0.15, table_top[1], table_top[2]])\n", "# milk.set_position(position=milk.get_position(), base=True)\n", "# cereal = Object(\"cereal\", \"cereal\", \"breakfast_cereal.stl\", position=table_top)\n", @@ -213,8 +213,8 @@ "source": [ "import pybullet as p\n", "for link_name in apartment.links.keys():\n", - " world.add_vis_axis(apartment.links[link_name].pose)\n", - " p.addUserDebugText(link_name, apartment.links[link_name].position)" + " world.add_vis_axis(apartment.get_link_pose(link_name))\n", + " p.addUserDebugText(link_name, apartment.get_link_position(link_name))" ] }, { diff --git a/examples/intro.ipynb b/examples/intro.ipynb index 44d3ad652..ba33eab21 100644 --- a/examples/intro.ipynb +++ b/examples/intro.ipynb @@ -489,7 +489,7 @@ ], "source": [ "milk.set_position(Pose([1,0,1]))\n", - "visible = btr.visible(milk, pr2.links[\"wide_stereo_optical_frame\"].pose)\n", + "visible = btr.visible(milk, pr2.get_link_pose(\"wide_stereo_optical_frame\"))\n", "print(f\"Milk visible: {visible}\")" ] }, diff --git a/examples/local_transformer.ipynb b/examples/local_transformer.ipynb index 4ff40178e..f71431ec0 100644 --- a/examples/local_transformer.ipynb +++ b/examples/local_transformer.ipynb @@ -319,7 +319,7 @@ "source": [ "print(milk.tf_frame)\n", "\n", - "print(kitchen.links[\"kitchen_island_surface\"].tf_frame)" + "print(kitchen.get_link_tf_frame(\"kitchen_island_surface\"))" ] } ], diff --git a/src/neem_interface_python b/src/neem_interface_python index 05ad42c41..182daab69 160000 --- a/src/neem_interface_python +++ b/src/neem_interface_python @@ -1 +1 @@ -Subproject commit 05ad42c41042335dd2287d865f6a37c115ea8ffe +Subproject commit 182daab69cb2e4dab23fbf5c9b9d1146837d8102 diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 11ae3ab0f..01b9820db 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -680,9 +680,9 @@ def __init__(self, object, urdf_link_name, size=100, resolution=0.02, world=None """ self.world: World = world if world else World.current_world self.object: Object = object - self.link: Link = object.links[urdf_link_name] + self.link: Link = object.get_link(urdf_link_name) self.resolution: float = resolution - self.origin: Pose = object.links[urdf_link_name].pose + self.origin: Pose = object.get_link_pose(urdf_link_name) self.height: int = 0 self.width: int = 0 self.map: np.ndarray = [] diff --git a/src/pycram/description.py b/src/pycram/description.py index f6bee8ff9..93513b8aa 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -1,17 +1,19 @@ +from __future__ import annotations + +import logging import pathlib from abc import ABC, abstractmethod -import logging import rospy from geometry_msgs.msg import Point, Quaternion from typing_extensions import Tuple, Union, Any, List, Optional, Dict -from pycram.enums import Shape, JointType -from pycram.local_transformer import LocalTransformer -from pycram.pose import Pose, Transform -from pycram.world import WorldEntity -from pycram.world_object import Object -from pycram.world_dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState +from .enums import JointType +from .local_transformer import LocalTransformer +from .pose import Pose, Transform +from .world import WorldEntity +from .world_dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape +from .world_object import Object class EntityDescription(ABC): @@ -43,7 +45,7 @@ def __init__(self, parsed_link_description: Any): @property @abstractmethod - def geometry(self) -> Shape: + def geometry(self) -> VisualShape: """ Returns the geometry type of the URDF collision element of this link. """ @@ -436,7 +438,7 @@ def parent_link(self) -> Link: Returns the parent link of this joint. :return: The parent link as a AbstractLink object. """ - return self.object.links[self.parent_link_name] + return self.object.get_link(self.parent_link_name) @property def child_link(self) -> Link: @@ -444,7 +446,7 @@ def child_link(self) -> Link: Returns the child link of this joint. :return: The child link as a AbstractLink object. """ - return self.object.links[self.child_link_name] + return self.object.get_link(self.child_link_name) @property def position(self) -> float: diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index beea5f255..d701b2bb0 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -326,7 +326,7 @@ def perform(self) -> None: # prepose depending on the gripper (its annoying we have to put pr2_1 here tbh # gripper_frame = "pr2_1/l_gripper_tool_frame" if self.arm == "left" else "pr2_1/r_gripper_tool_frame" - gripper_frame = robot.links[robot_description.get_tool_frame(self.arm)].tf_frame + gripper_frame = robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm)) # First rotate the gripper, so the further calculations makes sense tmp_for_rotate_pose = object.local_transformer.transform_pose(adjusted_oTm, gripper_frame) tmp_for_rotate_pose.pose.position.x = 0 @@ -436,7 +436,7 @@ def perform(self) -> None: # Transformations such that the target position is the position of the object and not the tcp tool_name = robot_description.get_tool_frame(self.arm) tcp_to_object = local_tf.transform_pose(object_pose, - World.robot.links[tool_name].tf_frame) + World.robot.get_link_tf_frame(tool_name)) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() @@ -445,7 +445,7 @@ def perform(self) -> None: World.robot.detach(self.object_designator.world_object) retract_pose = local_tf.transform_pose( target_diff, - World.robot.links[robot_description.get_tool_frame(self.arm)].tf_frame) + World.robot.get_link_tf_frame(robot_description.get_tool_frame(self.arm))) retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).resolve().perform() @@ -887,7 +887,7 @@ def perform(self) -> Any: gripper_name = robot_description.get_tool_frame(self.arm) object_pose_in_gripper = lt.transform_pose(object_pose, - World.robot.links[gripper_name].tf_frame) + World.robot.get_link_tf_frame(gripper_name)) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 34975ce1d..bd24a86a3 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -97,7 +97,7 @@ def __iter__(self): for name in self.names: if name in self.part_of.world_object.link_name_to_id.keys(): yield self.Object(name, self.type, self.part_of.world_object, - self.part_of.world_object.links[name].pose) + self.part_of.world_object.get_link_pose(name)) class LocatedObject(ObjectDesignatorDescription): diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index d2c83e8e4..1d60c5a09 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -12,6 +12,7 @@ from ..pose import Pose from ..robot_descriptions import robot_description from ..world import World +from ..world_dataclasses import MeshVisualShape from ..world_object import Object from ..robot_description import ManipulatorDescription @@ -160,9 +161,9 @@ def spawn_object(object: Object) -> None: :param object: World object that should be spawned """ if len(object.link_name_to_id) == 1: - geometry = object.description.link_map[object.description.get_root()].collision.geometry - if isinstance(geometry, urdf_parser_py.urdf.Mesh): - filename = geometry.filename + geometry = object.get_link_geometry(object.root_link_name) + if isinstance(geometry, MeshVisualShape): + filename = geometry.file_name spawn_mesh(object.name + "_" + str(object.id), filename, object.get_pose()) else: spawn_urdf(object.name + "_" + str(object.id), object.path, object.get_pose()) diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 4d60d7d52..2f1b2c184 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -29,7 +29,7 @@ def _make_request_msg(root_link: str, tip_link: str, target_pose: Pose, robot_ob :return: A moveit_msgs/PositionIKRequest message containing all the information from the parameter """ local_transformer = LocalTransformer() - target_pose = local_transformer.transform_pose(target_pose, robot_object.links[root_link].tf_frame) + target_pose = local_transformer.transform_pose(target_pose, robot_object.get_link_tf_frame(root_link)) robot_state = RobotState() joint_state = JointState() @@ -164,7 +164,7 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str # Get link after last joint in chain end_effector = robot_description.get_child(joints[-1]) - target_torso = local_transformer.transform_pose(target_pose, robot.links[base_link].tf_frame) + target_torso = local_transformer.transform_pose(target_pose, robot.get_link_tf_frame(base_link)) diff = calculate_wrist_tool_offset(end_effector, gripper, robot) target_diff = target_torso.to_transform("target").inverse_times(diff).to_pose() diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index 4ecc35085..0497c04f1 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -125,7 +125,7 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti for i in range(0, len(query_result.res[0].pose)): pose = Pose.from_pose_stamped(query_result.res[0].pose[i]) - pose.frame = World.current_world.robot.links[pose.frame].tf_frame # TODO: pose.frame is a link name? + pose.frame = World.current_world.robot.get_link_tf_frame(pose.frame) # TODO: pose.frame is a link name? source = query_result.res[0].poseSource[i] lt = LocalTransformer() diff --git a/src/pycram/helper.py b/src/pycram/helper.py index a0c9fb4ae..bb171a0b1 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -55,7 +55,7 @@ def _apply_ik(robot: WorldObject, joint_poses: List[float], joints: List[str]) - def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: WorldObject) -> Transform: - return robot.links[wrist_frame].get_transform_to_link(robot.links[tool_frame]) + return robot.get_transfrom_between_links(wrist_frame, tool_frame) def transform(pose: List[float], diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index a1bc00019..994ff234d 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -95,13 +95,13 @@ def visibility_validator(pose: Pose, robot_pose = robot.get_pose() if isinstance(object_or_pose, Object): robot.set_pose(pose) - camera_pose = robot.links[robot_description.get_camera_frame()].pose + camera_pose = robot.get_link_pose(robot_description.get_camera_frame()) robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) ray = world.ray_test(camera_pose.position_as_list(), object_or_pose.get_position_as_list()) res = ray == object_or_pose.id else: robot.set_pose(pose) - camera_pose = robot.links[robot_description.get_camera_frame()].pose + camera_pose = robot.get_link_pose(robot_description.get_camera_frame()) robot.set_pose(Pose([100, 100, 0], [0, 0, 0, 1])) # TODO: Check if this is correct ray = world.ray_test(camera_pose.position_as_list(), object_or_pose) diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index e5930b694..3b4fa4698 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -33,7 +33,7 @@ def _execute(self, desig: PlaceMotion.Motion): object_pose = obj.get_pose() local_tf = LocalTransformer() tcp_to_object = local_tf.transform_pose(object_pose, - robot.links[robot_description.get_tool_frame(arm)].tf_frame) + robot.get_link_tf_frame(robot_description.get_tool_frame(arm))) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) @@ -64,7 +64,7 @@ def _execute(self, desig): local_transformer = LocalTransformer() - pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) + pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("neck_shoulder_link")) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "front")) @@ -75,7 +75,7 @@ def _execute(self, desig): if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): robot.set_joint_positions(robot_description.get_static_joint_chain("neck", "neck_left")) - pose_in_shoulder = local_transformer.transform_pose(target, robot.links["neck_shoulder_link"].tf_frame) + pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("neck_shoulder_link")) new_pan = np.arctan2(pose_in_shoulder.position.y, pose_in_shoulder.position.x) diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index ba763b7c7..19faebb29 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -30,8 +30,8 @@ def _execute(self, desig: LookingMotion.Motion): pan_joint = robot_description.chains["neck"].joints[0] tilt_joint = robot_description.chains["neck"].joints[1] - pose_in_pan = local_transformer.transform_pose(target, robot.links[pan_link].tf_frame) - pose_in_tilt = local_transformer.transform_pose(target, robot.links[tilt_link].tf_frame) + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame(pan_link)) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame(tilt_link)) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 4b9979cd5..5833d0513 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -56,7 +56,7 @@ def _execute(self, desig): object_pose = obj.get_pose() local_tf = LocalTransformer() tcp_to_object = local_tf.transform_pose(object_pose, - robot.links[robot_description.get_tool_frame("left")].tf_frame) + robot.get_link_tf_frame(robot_description.get_tool_frame("left"))) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, "left") @@ -75,7 +75,7 @@ def _execute(self, desig): local_transformer = LocalTransformer() - pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) + pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("ur5_shoulder_link")) if pose_in_shoulder.position.x >= 0 and pose_in_shoulder.position.x >= abs(pose_in_shoulder.position.y): robot.set_joint_positions(robot_description.get_static_joint_chain("left", "front")) @@ -86,7 +86,7 @@ def _execute(self, desig): if pose_in_shoulder.position.y <= 0 and abs(pose_in_shoulder.position.y) > abs(pose_in_shoulder.position.x): robot.set_joint_positions(robot_description.get_static_joint_chain("left", "arm_left")) - pose_in_shoulder = local_transformer.transform_pose(target, robot.links["ur5_shoulder_link"].tf_frame) + pose_in_shoulder = local_transformer.transform_pose(target, robot.get_link_tf_frame("ur5_shoulder_link")) new_pan = np.arctan2(pose_in_shoulder.position.y, pose_in_shoulder.position.x) diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 0a9936147..0b4e11512 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -101,9 +101,9 @@ def _execute(self, desig): drawer_handle = solution['drawer_handle'] drawer_joint = solution['drawer_joint'] dis = solution['distance'] - calculate_and_apply_ik(robot, gripper, kitchen.links[drawer_handle].position) + calculate_and_apply_ik(robot, gripper, kitchen.get_link_position(drawer_handle)) time.sleep(0.2) - han_pose = kitchen.links[drawer_handle].position + han_pose = kitchen.get_link_position(drawer_handle) new_p = Point(han_pose[0] - dis, han_pose[1], han_pose[2]) calculate_and_apply_ik(robot, gripper, new_p) kitchen.set_joint_position(drawer_joint, 0.3) @@ -173,7 +173,7 @@ def _execute(self, desig): objects = World.current_world.get_object_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis, 0.5): + if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis, 0.5): return obj diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index ff5da6a0b..34e367404 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -99,7 +99,7 @@ def _execute(self, desig: PlaceMotion.Motion): object_pose = obj.get_pose() local_tf = LocalTransformer() tool_name = robot_description.get_tool_frame(arm) - tcp_to_object = local_tf.transform_pose(object_pose, robot.links[tool_name].tf_frame) + tcp_to_object = local_tf.transform_pose(object_pose, robot.get_link_tf_frame(tool_name)) target_diff = desig.target.to_transform("target").inverse_times(tcp_to_object.to_transform("object")).to_pose() _move_arm_tcp(target_diff, robot, arm) @@ -124,8 +124,8 @@ def get_pan_and_tilt_goals(self, desig: LookingMotion.Motion) -> Tuple[float, fl target = desig.target local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, self.robot.links["head_pan_link"].tf_frame) - pose_in_tilt = local_transformer.transform_pose(target, self.robot.links["head_tilt_link"].tf_frame) + pose_in_pan = local_transformer.transform_pose(target, self.robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose(target, self.robot.get_link_tf_frame("head_tilt_link")) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 @@ -186,7 +186,7 @@ def _execute(self, desig: DetectingMotion.Motion): objects = World.current_world.get_object_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.links[cam_frame_name].pose, front_facing_axis): + if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): return obj @@ -342,7 +342,7 @@ def _execute(self, designator: DetectingMotion.Motion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose(obj_pose, World.robot.links["torso_lift_link"].tf_frame) + obj_pose = lt.transform_pose(obj_pose, World.robot.get_link_tf_frame("torso_lift_link")) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index e3be3bc6d..a727e75bb 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -55,9 +55,9 @@ def _update_objects(self) -> None: pose.header.stamp = rospy.Time.now() self._publish_pose(obj.tf_frame, pose) for link in obj.link_name_to_id.keys(): - link_pose = obj.links[link].pose + link_pose = obj.get_link_pose(link) link_pose.header.stamp = rospy.Time.now() - self._publish_pose(obj.links[link].tf_frame, link_pose) + self._publish_pose(obj.get_link_tf_frame(link), link_pose) def _update_static_odom(self) -> None: """ diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index d47279a90..8213b1b73 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -11,12 +11,14 @@ import urdf_parser_py from pycram.pose import Transform +from ..world_dataclasses import MeshVisualShape, CylinderVisualShape, BoxVisualShape, SphereVisualShape class VizMarkerPublisher: """ Publishes an Array of visualization marker which represent the situation in the World """ + def __init__(self, topic_name="/pycram/viz_marker", interval=0.1): """ The Publisher creates an Array of Visualization marker with a Marker for each link of each Object in the @@ -59,7 +61,7 @@ def _make_marker_array(self) -> MarkerArray: if obj.name == "floor": continue for link in obj.link_name_to_id.keys(): - geom = obj.links[link].get_geometry() + geom = obj.get_link_geometry(link) if not geom: continue msg = Marker() @@ -68,9 +70,9 @@ def _make_marker_array(self) -> MarkerArray: msg.id = obj.link_name_to_id[link] msg.type = Marker.MESH_RESOURCE msg.action = Marker.ADD - link_pose = obj.links[link].transform - if obj.links[link].origin: - link_origin = obj.links[link].get_origin_transform() + link_pose = obj.get_link_transform(link) + if obj.get_link_origin(link): + link_origin = obj.get_link_origin_transform(link) else: link_origin = Transform() link_pose_with_origin = link_pose * link_origin @@ -81,19 +83,19 @@ def _make_marker_array(self) -> MarkerArray: msg.color = ColorRGBA(*color) msg.lifetime = rospy.Duration(1) - if type(geom) == urdf_parser_py.urdf.Mesh: + if isinstance(geom, MeshVisualShape): msg.type = Marker.MESH_RESOURCE - msg.mesh_resource = "file://" + geom.filename + msg.mesh_resource = "file://" + geom.file_name msg.scale = Vector3(1, 1, 1) msg.mesh_use_embedded_materials = True - elif type(geom) == urdf_parser_py.urdf.Cylinder: + elif isinstance(geom, CylinderVisualShape): msg.type = Marker.CYLINDER msg.scale = Vector3(geom.radius * 2, geom.radius * 2, geom.length) - elif type(geom) == urdf_parser_py.urdf.Box: + elif isinstance(geom, BoxVisualShape): msg.type = Marker.CUBE msg.scale = Vector3(*geom.size) - elif type(geom) == urdf_parser_py.urdf.Sphere: - msg.type == Marker.SPHERE + elif isinstance(geom, SphereVisualShape): + msg.type = Marker.SPHERE msg.scale = Vector3(geom.radius * 2, geom.radius * 2, geom.radius * 2) marker_array.markers.append(msg) @@ -105,4 +107,3 @@ def _stop_publishing(self) -> None: """ self.kill_event.set() self.thread.join() - diff --git a/src/pycram/world.py b/src/pycram/world.py index 4805c0306..67e7efc7a 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -24,6 +24,8 @@ MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, ObjectState, State, WorldState) +from .world_object import Object +from .description import Link class StateEntity: @@ -117,9 +119,9 @@ class World(StateEntity, ABC): used at the moment. """ - robot: Optional['Object'] = None + robot: Optional[Object] = None """ - Global reference to the spawned 'Object'that represents the robot. The robot is identified by checking the name in + Global reference to the spawned Object that represents the robot. The robot is identified by checking the name in the URDF with the name of the URDF on the parameter server. """ @@ -157,7 +159,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.local_transformer = LocalTransformer() self._update_local_transformer_worlds() - self.objects: List['Object'] = [] + self.objects: List[Object] = [] # List of all Objects in the World self.id: int = -1 @@ -166,7 +168,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.mode: WorldMode = mode # The mode of the simulation, can be "GUI" or "DIRECT" - self.coll_callbacks: Dict[Tuple['Object', 'Object'], CollisionCallbacks] = {} + self.coll_callbacks: Dict[Tuple[Object, Object], CollisionCallbacks] = {} self._init_events() @@ -218,7 +220,7 @@ def _sync_prospection_world(self): self.world_sync.start() def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, - obj: 'Object') -> str: + obj: Object) -> str: """ Updates the cache directory with the given object. @@ -246,7 +248,7 @@ def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: """ pass - def get_object_by_name(self, name: str) -> List['Object']: + def get_object_by_name(self, name: str) -> List[Object]: """ Returns a list of all Objects in this World with the same name as the given one. @@ -255,7 +257,7 @@ def get_object_by_name(self, name: str) -> List['Object']: """ return list(filter(lambda obj: obj.name == name, self.objects))[0] - def get_object_by_type(self, obj_type: ObjectType) -> List['Object']: + def get_object_by_type(self, obj_type: ObjectType) -> List[Object]: """ Returns a list of all Objects which have the type 'obj_type'. @@ -264,29 +266,29 @@ def get_object_by_type(self, obj_type: ObjectType) -> List['Object']: """ return list(filter(lambda obj: obj.obj_type == obj_type, self.objects)) - def get_object_by_id(self, obj_id: int) -> 'Object': + def get_object_by_id(self, obj_id: int) -> Object: """ - Returns the single 'Object'that has the unique id. + Returns the single Object that has the unique id. - :param obj_id: The unique id for which the 'Object'should be returned. - :return: The 'Object'with the id 'id'. + :param obj_id: The unique id for which the Object should be returned. + :return: The Object with the id 'id'. """ return list(filter(lambda obj: obj.id == obj_id, self.objects))[0] @abstractmethod - def remove_object_from_simulator(self, obj: 'Object') -> None: + def remove_object_from_simulator(self, obj: Object) -> None: """ Removes an object from the physics simulator. :param obj: The object to be removed. """ pass - def remove_object(self, obj: 'Object') -> None: + def remove_object(self, obj: Object) -> None: """ Removes this object from the current world. For the object to be removed it has to be detached from all objects it is currently attached to. After this is done a call to world remove object is done - to remove this 'Object'from the simulation/world. + to remove this Object from the simulation/world. :param obj: The object to be removed. """ @@ -305,7 +307,7 @@ def remove_object(self, obj: 'Object') -> None: if World.robot == obj: World.robot = None - def add_fixed_constraint(self, parent_link: 'Link', child_link: 'Link', + def add_fixed_constraint(self, parent_link: Link, child_link: Link, child_to_parent_transform: Transform) -> int: """ Creates a fixed joint constraint between the given parent and child links, @@ -347,7 +349,7 @@ def remove_constraint(self, constraint_id) -> None: pass @abstractmethod - def get_joint_position(self, obj: 'Object', joint_name: str) -> float: + def get_joint_position(self, obj: Object, joint_name: str) -> float: """ Get the position of a joint of an articulated object @@ -358,7 +360,7 @@ def get_joint_position(self, obj: 'Object', joint_name: str) -> float: pass @abstractmethod - def get_object_joint_names(self, obj: 'Object') -> List[str]: + def get_object_joint_names(self, obj: Object) -> List[str]: """ Returns the names of all joints of this object. @@ -368,7 +370,7 @@ def get_object_joint_names(self, obj: 'Object') -> List[str]: pass @abstractmethod - def get_link_pose(self, link: 'Link') -> Pose: + def get_link_pose(self, link: Link) -> Pose: """ Get the pose of a link of an articulated object with respect to the world frame. @@ -378,7 +380,7 @@ def get_link_pose(self, link: 'Link') -> Pose: pass @abstractmethod - def get_object_link_names(self, obj: 'Object') -> List[str]: + def get_object_link_names(self, obj: Object) -> List[str]: """ Returns the names of all links of this object. :param obj: The object. @@ -419,7 +421,7 @@ def update_all_objects_poses(self) -> None: obj.update_pose() @abstractmethod - def get_object_pose(self, obj: 'Object') -> Pose: + def get_object_pose(self, obj: Object) -> Pose: """ Get the pose of an object in the world frame from the current object pose in the simulator. """ @@ -433,9 +435,9 @@ def perform_collision_detection(self) -> None: pass @abstractmethod - def get_object_contact_points(self, obj: 'Object') -> List: + def get_object_contact_points(self, obj: Object) -> List: """ - Returns a list of contact points of this 'Object'with all other Objects. + Returns a list of contact points of this Object with all other Objects. :param obj: The object. :return: A list of all contact points with other objects @@ -443,7 +445,7 @@ def get_object_contact_points(self, obj: 'Object') -> List: pass @abstractmethod - def get_contact_points_between_two_objects(self, obj1: 'Object', obj2: 'Object') -> List: + def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> List: """ Returns a list of contact points between obj1 and obj2. @@ -454,7 +456,7 @@ def get_contact_points_between_two_objects(self, obj1: 'Object', obj2: 'Object') pass @abstractmethod - def reset_joint_position(self, obj: 'Object', joint_name: str, joint_pose: float) -> None: + def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: """ Reset the joint position instantly without physics simulation @@ -465,7 +467,7 @@ def reset_joint_position(self, obj: 'Object', joint_name: str, joint_pose: float pass @abstractmethod - def reset_object_base_pose(self, obj: 'Object', pose: Pose): + def reset_object_base_pose(self, obj: Object, pose: Pose): """ Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation. @@ -483,7 +485,7 @@ def step(self): pass @abstractmethod - def set_link_color(self, link: 'Link', rgba_color: Color): + def set_link_color(self, link: Link, rgba_color: Color): """ Changes the rgba_color of a link of this object, the rgba_color has to be given as Color object. @@ -493,7 +495,7 @@ def set_link_color(self, link: 'Link', rgba_color: Color): pass @abstractmethod - def get_link_color(self, link: 'Link') -> Color: + def get_link_color(self, link: Link) -> Color: """ This method returns the rgba_color of this link. :param link: The link for which the rgba_color should be returned. @@ -502,7 +504,7 @@ def get_link_color(self, link: 'Link') -> Color: pass @abstractmethod - def get_colors_of_object_links(self, obj: 'Object') -> Dict[str, Color]: + def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: """ Get the RGBA colors of each link in the object as a dictionary from link name to rgba_color. @@ -512,7 +514,7 @@ def get_colors_of_object_links(self, obj: 'Object') -> Dict[str, Color]: pass @abstractmethod - def get_object_axis_aligned_bounding_box(self, obj: 'Object') -> AxisAlignedBoundingBox: + def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this object. The return of this method are two points in world coordinate frame which define a bounding box. @@ -523,7 +525,7 @@ def get_object_axis_aligned_bounding_box(self, obj: 'Object') -> AxisAlignedBoun pass @abstractmethod - def get_link_axis_aligned_bounding_box(self, link: 'Link') -> AxisAlignedBoundingBox: + def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link. The return of this method are two points in world coordinate frame which define a bounding box. @@ -550,21 +552,21 @@ def set_gravity(self, gravity_vector: List[float]) -> None: """ pass - def set_robot_if_not_set(self, robot: 'Object') -> None: + def set_robot_if_not_set(self, robot: Object) -> None: """ Sets the robot if it is not set yet. - :param robot: The 'Object'reference to the 'Object'representing the robot. + :param robot: The Object reference to the Object representing the robot. """ if not self.robot_is_set(): self.set_robot(robot) @staticmethod - def set_robot(robot: Union['Object', None]) -> None: + def set_robot(robot: Union[Object, None]) -> None: """ - Sets the global variable for the robot 'Object' This should be set on spawning the robot. + Sets the global variable for the robot Object This should be set on spawning the robot. - :param robot: The 'Object'reference to the 'Object'representing the robot. + :param robot: The Object reference to the Object representing the robot. """ World.robot = robot @@ -710,7 +712,7 @@ def get_images_for_target(self, 1. An RGB image 2. A depth image - 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible 'Object' + 3. A segmentation Mask, the segmentation mask indicates for every pixel the visible Object :param target_pose: The pose to which the camera should point. :param cam_pose: The pose of the camera. @@ -720,8 +722,8 @@ def get_images_for_target(self, pass def register_two_objects_collision_callbacks(self, - object_a: 'Object', - object_b: 'Object', + object_a: Object, + object_b: Object, on_collision_callback: Callable, on_collision_removal_callback: Optional[Callable] = None) -> None: """ @@ -740,16 +742,16 @@ def register_two_objects_collision_callbacks(self, def add_resource_path(cls, path: str) -> None: """ Adds a resource path in which the World will search for files. This resource directory is searched if an - 'Object'is spawned only with a filename. + Object is spawned only with a filename. :param path: A path in the filesystem in which to search for files. """ cls.data_directory.append(path) - def get_prospection_object_for_object(self, obj: 'Object') -> 'Object': + def get_prospection_object_for_object(self, obj: Object) -> Object: """ Returns the corresponding object from the prospection world for a given object in the main world. - If the given 'Object'is already in the prospection world, it is returned. + If the given Object is already in the prospection world, it is returned. :param obj: The object for which the corresponding object in the prospection World should be found. :return: The corresponding object in the prospection world. @@ -766,7 +768,7 @@ def get_prospection_object_for_object(self, obj: 'Object') -> 'Object': f" the object isn't anymore in the main (graphical) World" f" or if the given object is already a prospection object. ") - def get_object_for_prospection_object(self, prospection_object: 'Object') -> 'Object': + def get_object_for_prospection_object(self, prospection_object: Object) -> Object: """ Returns the corresponding object from the main World for a given object in the prospection world. If the given object is not in the prospection @@ -960,7 +962,7 @@ def remove_text(self, text_id: Optional[int] = None) -> None: """ raise NotImplementedError - def enable_joint_force_torque_sensor(self, obj: 'Object', fts_joint_idx: int) -> None: + def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> None: """ You can enable a joint force/torque sensor in each joint. Once enabled, if you perform a simulation step, the get_joint_reaction_force_torque will report the joint reaction forces in @@ -972,7 +974,7 @@ def enable_joint_force_torque_sensor(self, obj: 'Object', fts_joint_idx: int) -> """ raise NotImplementedError - def disable_joint_force_torque_sensor(self, obj: 'Object', joint_id: int) -> None: + def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: """ Disables the force torque sensor of a joint. :param obj: The object in which the joint is located. @@ -980,7 +982,7 @@ def disable_joint_force_torque_sensor(self, obj: 'Object', joint_id: int) -> Non """ raise NotImplementedError - def get_joint_reaction_force_torque(self, obj: 'Object', joint_id: int) -> List[float]: + def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: """ Returns the joint reaction forces and torques of the specified joint. :param obj: The object in which the joint is located. @@ -989,7 +991,7 @@ def get_joint_reaction_force_torque(self, obj: 'Object', joint_id: int) -> List[ """ raise NotImplementedError - def get_applied_joint_motor_torque(self, obj: 'Object', joint_id: int) -> float: + def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: """ Returns the applied torque by a joint motor. :param obj: The object in which the joint is located. @@ -1057,7 +1059,7 @@ def __init__(self, world: World, prospection_world: World): self.remove_obj_queue: Queue = Queue() self.pause_sync: bool = False # Maps world to prospection world objects - self.object_mapping: Dict['Object', 'Object'] = {} + self.object_mapping: Dict[Object, Object] = {} self.equal_states = False def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): diff --git a/src/pycram/world_constraints.py b/src/pycram/world_constraints.py index 52d8cdd59..de2ba2b62 100644 --- a/src/pycram/world_constraints.py +++ b/src/pycram/world_constraints.py @@ -1,8 +1,12 @@ +from __future__ import annotations + from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional -from pycram.enums import JointType -from pycram.pose import Transform, Pose +from .enums import JointType +from .pose import Transform, Pose + +from .description import Link class AbstractConstraint: @@ -12,13 +16,13 @@ class AbstractConstraint: """ def __init__(self, - parent_link: 'Link', - child_link: 'Link', + parent_link: Link, + child_link: Link, _type: JointType, parent_to_constraint: Transform, child_to_constraint: Transform): - self.parent_link: 'Link' = parent_link - self.child_link: 'Link' = child_link + self.parent_link: Link = parent_link + self.child_link: Link = child_link self.type: JointType = _type self.parent_to_constraint = parent_to_constraint self.child_to_constraint = child_to_constraint @@ -132,8 +136,8 @@ class Constraint(AbstractConstraint): """ def __init__(self, - parent_link: 'Link', - child_link: 'Link', + parent_link: Link, + child_link: Link, _type: JointType, axis_in_child_frame: Point, constraint_to_parent: Transform, @@ -154,8 +158,8 @@ def axis_as_list(self) -> List[float]: class Attachment(AbstractConstraint): def __init__(self, - parent_link: 'Link', - child_link: 'Link', + parent_link: Link, + child_link: Link, bidirectional: Optional[bool] = False, parent_to_child_transform: Optional[Transform] = None, constraint_id: Optional[int] = None): diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 54b04876a..55f335f53 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,15 +1,20 @@ +from __future__ import annotations + from dataclasses import dataclass from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union from .enums import JointType, Shape from .pose import Pose, Point from abc import ABC, abstractmethod +from .description import Link +from .world_object import Object +from .world_constraints import Attachment def get_point_as_list(point: Point) -> List[float]: """ Returns the point as a list. - :param point: The point + :param point: The point. :return: The point as a list """ return [point.x, point.y, point.z] @@ -199,6 +204,10 @@ def shape_data(self) -> Dict[str, List[float]]: def visual_geometry_type(self) -> Shape: return Shape.BOX + @property + def size(self) -> List[float]: + return self.half_extents + @dataclass class SphereVisualShape(VisualShape): @@ -235,11 +244,11 @@ def visual_geometry_type(self) -> Shape: @dataclass class MeshVisualShape(VisualShape): - mesh_scale: List[float] - mesh_file_name: str + scale: List[float] + file_name: str def shape_data(self) -> Dict[str, Union[List[float], str]]: - return {"meshScale": self.mesh_scale, "meshFileName": self.mesh_file_name} + return {"meshScale": self.scale, "meshFileName": self.file_name} @property def visual_geometry_type(self) -> Shape: @@ -264,24 +273,24 @@ class State(ABC): @dataclass -class WorldState(State): - simulator_state_id: int - object_states: Dict[str, 'ObjectState'] +class LinkState(State): + constraint_ids: Dict[Link, int] @dataclass -class ObjectState(State): - pose: Pose - attachments: Dict['Object', 'Attachment'] - link_states: Dict[int, 'LinkState'] - joint_states: Dict[int, 'JointState'] +class JointState(State): + position: float @dataclass -class LinkState(State): - constraint_ids: Dict['Link', int] +class ObjectState(State): + pose: Pose + attachments: Dict[Object, Attachment] + link_states: Dict[int, LinkState] + joint_states: Dict[int, JointState] @dataclass -class JointState(State): - position: float +class WorldState(State): + simulator_state_id: int + object_states: Dict[str, ObjectState] diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index 1eee6c20d..791e71b90 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import logging import os @@ -6,13 +8,16 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Type, Optional, Dict, Tuple, List, Union -from pycram.enums import ObjectType, JointType -from pycram.local_transformer import LocalTransformer -from pycram.pose import Pose -from pycram.robot_descriptions import robot_description -from pycram.world import WorldEntity, World -from pycram.world_constraints import Attachment -from pycram.world_dataclasses import Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox +from .enums import ObjectType, JointType +from .local_transformer import LocalTransformer +from .pose import Pose, Transform +from .robot_descriptions import robot_description +from .world import WorldEntity, World +from .world_constraints import Attachment +from .world_dataclasses import Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape +from .description import ObjectDescription, LinkDescription + +Link = ObjectDescription.Link class Object(WorldEntity): @@ -27,7 +32,7 @@ class Object(WorldEntity): """ def __init__(self, name: str, obj_type: ObjectType, path: str, - description: Type['ObjectDescription'], + description: Type[ObjectDescription], pose: Optional[Pose] = None, world: Optional[World] = None, color: Optional[Color] = Color(), @@ -181,6 +186,126 @@ def joint_names(self) -> List[str]: """ return self.world.get_object_joint_names(self) + def get_link(self, link_name: str) -> Link: + """ + Returns the link object with the given name. + :param link_name: The name of the link. + :return: The link object. + """ + return self.links[link_name] + + def get_link_pose(self, link_name: str) -> Pose: + """ + Returns the pose of the link with the given name. + :param link_name: The name of the link. + :return: The pose of the link. + """ + return self.links[link_name].pose + + def get_link_position(self, link_name: str) -> Point: + """ + Returns the position of the link with the given name. + :param link_name: The name of the link. + :return: The position of the link. + """ + return self.links[link_name].position + + def get_link_position_as_list(self, link_name: str) -> List[float]: + """ + Returns the position of the link with the given name. + :param link_name: The name of the link. + :return: The position of the link. + """ + return self.links[link_name].position_as_list + + def get_link_orientation(self, link_name: str) -> Quaternion: + """ + Returns the orientation of the link with the given name. + :param link_name: The name of the link. + :return: The orientation of the link. + """ + return self.links[link_name].orientation + + def get_link_orientation_as_list(self, link_name: str) -> List[float]: + """ + Returns the orientation of the link with the given name. + :param link_name: The name of the link. + :return: The orientation of the link. + """ + return self.links[link_name].orientation_as_list + + def get_link_tf_frame(self, link_name: str) -> str: + """ + Returns the tf frame of the link with the given name. + :param link_name: The name of the link. + :return: The tf frame of the link. + """ + return self.links[link_name].tf_frame + + def get_link_axis_aligned_bounding_box(self, link_name: str) -> AxisAlignedBoundingBox: + """ + Returns the axis aligned bounding box of the link with the given name. + :param link_name: The name of the link. + :return: The axis aligned bounding box of the link. + """ + return self.links[link_name].get_axis_aligned_bounding_box() + + def get_transform_between_links(self, from_link: str, to_link: str) -> Transform: + """ + Returns the transform between two links. + :param from_link: The name of the link from which the transform should be calculated. + :param to_link: The name of the link to which the transform should be calculated. + """ + return self.links[from_link].get_transform_to_link(self.links[to_link]) + + def get_link_color(self, link_name: str) -> Color: + """ + Returns the color of the link with the given name. + :param link_name: The name of the link. + :return: The color of the link. + """ + return self.links[link_name].color + + def set_link_color(self, link_name: str, color: List[float]) -> None: + """ + Sets the color of the link with the given name. + :param link_name: The name of the link. + :param color: The new color of the link. + """ + self.links[link_name].color = Color.from_list(color) + + def get_link_geometry(self, link_name: str) -> VisualShape: + """ + Returns the geometry of the link with the given name. + :param link_name: The name of the link. + :return: The geometry of the link. + """ + return self.links[link_name].geometry + + def get_link_transform(self, link_name: str) -> Transform: + """ + Returns the transform of the link with the given name. + :param link_name: The name of the link. + :return: The transform of the link. + """ + return self.links[link_name].transform + + def get_link_origin(self, link_name: str) -> Pose: + """ + Returns the origin of the link with the given name. + :param link_name: The name of the link. + :return: The origin of the link as a 'Pose'. + """ + return self.links[link_name].origin + + def get_link_origin_transform(self, link_name: str) -> Transform: + """ + Returns the origin transform of the link with the given name. + :param link_name: The name of the link. + :return: The origin transform of the link. + """ + return self.links[link_name].origin_transform + @property def base_origin_shift(self) -> np.ndarray: """ @@ -218,7 +343,7 @@ def reset(self, remove_saved_states=True) -> None: self.remove_saved_states() def attach(self, - child_object: 'Object', + child_object: Object, parent_link: Optional[str] = None, child_link: Optional[str] = None, bidirectional: Optional[bool] = True) -> None: @@ -247,7 +372,7 @@ def attach(self, self.world.attachment_event(self, [self, child_object]) - def detach(self, child_object: 'Object') -> None: + def detach(self, child_object: Object) -> None: """ Detaches another object from this object. This is done by deleting the attachment from the attachments dictionary of both objects @@ -269,7 +394,7 @@ def detach_all(self) -> None: for att in attachments.keys(): self.detach(att) - def update_attachment_with_object(self, child_object: 'Object'): + def update_attachment_with_object(self, child_object: Object): self.attachments[child_object].update_transform_and_constraint() def get_position(self) -> Point: @@ -456,7 +581,7 @@ def remove_joints_saved_states(self) -> None: for joint in self.joints.values(): joint.remove_saved_states() - def _set_attached_objects_poses(self, already_moved_objects: Optional[List['Object']] = None) -> None: + def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Object]] = None) -> None: """ Updates the positions of all attached objects. This is done by calculating the new pose in world coordinate frame and setting the @@ -542,7 +667,7 @@ def get_joint_id(self, name: str) -> int: """ return self.joint_name_to_id[name] - def get_root_link_description(self) -> 'LinkDescription': + def get_root_link_description(self) -> LinkDescription: """ Returns the root link of the URDF of this object. :return: The root link as defined in the URDF of this object. @@ -552,7 +677,7 @@ def get_root_link_description(self) -> 'LinkDescription': return link_description @property - def root_link(self) -> 'Link': + def root_link(self) -> Link: """ Returns the root link of this object. :return: The root link of this object. @@ -582,7 +707,7 @@ def get_link_id(self, link_name: str) -> int: """ return self.link_name_to_id[link_name] - def get_link_by_id(self, link_id: int) -> 'Link': + def get_link_by_id(self, link_id: int) -> Link: """ Returns the link for a given unique link id :param link_id: The unique id of the link. @@ -645,6 +770,9 @@ def get_joint_type(self, joint_name: str) -> JointType: def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: return self.joints[joint_name].limits + def get_joint_child_link(self, joint_name: str) -> Link: + return self.joints[joint_name].child_link + def find_joint_above_link(self, link_name: str, joint_type: JointType) -> str: """ Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. @@ -757,7 +885,7 @@ def get_base_origin(self) -> Pose: return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], self.get_orientation_as_list()) - def __copy__(self) -> 'Object': + def __copy__(self) -> Object: """ Returns a copy of this object. The copy will have the same name, type, path, description, pose, world and color. :return: A copy of this object. diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 56da2945f..2e9103084 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -202,7 +202,7 @@ def reachable( if not target_pose: return False - gripper_pose = prospection_robot.links[gripper_name].pose + gripper_pose = prospection_robot.get_link_pose(gripper_name) diff = target_pose.dist(gripper_pose) return diff < threshold @@ -273,4 +273,4 @@ def link_pose_for_joint_config( with UseProspectionWorld(): for joint, pose in joint_config.items(): prospection_object.set_joint_position(joint, pose) - return prospection_object.links[link_name].pose + return prospection_object.get_link_pose(link_name) diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 37a5f13d4..d972aa0c0 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -131,8 +131,8 @@ def test_grasping(self): with simulated_robot: description.resolve().perform() dist = np.linalg.norm( - np.array(self.robot.links[robot_description.get_tool_frame("right")].position_as_list) - - np.array(self.milk.get_pose().position_as_list())) + np.array(self.robot.get_link_position_as_list(robot_description.get_tool_frame("right"))) - + np.array(self.milk.get_position_as_list())) self.assertTrue(dist < 0.01) diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index e68397875..2c1bf0682 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -23,9 +23,9 @@ def test_object_movement(self): def test_robot_orientation(self): self.robot.set_pose(Pose([0, 1, 1])) - head_position = self.robot.links['head_pan_link'].position.z + head_position = self.robot.get_link_position('head_pan_link').z self.robot.set_orientation(Pose(orientation=[0, 0, 1, 1])) - self.assertEqual(self.robot.links['head_pan_link'].position.z, head_position) + self.assertEqual(self.robot.get_link_position('head_pan_link').z, head_position) def test_save_and_restore_state(self): self.robot.attach(self.milk) @@ -169,20 +169,20 @@ def test_no_object_found_for_given_prospection_object(self): time.sleep(0.05) def test_add_vis_axis(self): - self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) + self.world.add_vis_axis(self.robot.get_link_pose(robot_description.get_camera_frame())) self.assertTrue(len(self.world.vis_axis) == 1) self.world.remove_vis_axis() self.assertTrue(len(self.world.vis_axis) == 0) def test_add_text(self): - link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] - text_id = self.world.add_text("test", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, + link: ObjectDescription.Link = self.robot.get_link(robot_description.get_camera_frame()) + text_id = self.world.add_text("test", link.position_as_list, link.orientation_as_list, 1, Color(1, 0, 0, 1), 3, link.object_id, link.id) if self.world.mode == WorldMode.GUI: time.sleep(4) def test_remove_text(self): - link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] + link: ObjectDescription.Link = self.robot.get_link(robot_description.get_camera_frame()) text_id_1 = self.world.add_text("test 1", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, Color(1, 0, 0, 1), 0, link.object_id, link.id) text_id = self.world.add_text("test 2", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, @@ -195,7 +195,7 @@ def test_remove_text(self): time.sleep(3) def test_remove_all_text(self): - link: ObjectDescription.Link = self.robot.links[robot_description.get_camera_frame()] + link: ObjectDescription.Link = self.robot.get_link(robot_description.get_camera_frame()) text_id_1 = self.world.add_text("test 1", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, Color(1, 0, 0, 1), 0, link.object_id, link.id) text_id = self.world.add_text("test 2", link.pose.position_as_list(), link.pose.orientation_as_list(), 1, @@ -211,7 +211,7 @@ def test_remove_all_text(self): class BulletWorldTestGUI(BulletWorldGUITestCase): def test_add_vis_axis(self): time.sleep(10) - self.world.add_vis_axis(self.robot.links[robot_description.get_camera_frame()].pose) + self.world.add_vis_axis(self.robot.get_link_pose(robot_description.get_camera_frame())) self.assertTrue(len(self.world.vis_axis) == 1) self.world.remove_vis_axis() self.assertTrue(len(self.world.vis_axis) == 0) diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index 2643eb40e..db81af34f 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -1,7 +1,7 @@ import time -from bullet_world_testcase import BulletWorldTestCase import pycram.world_reasoning as btr +from bullet_world_testcase import BulletWorldTestCase from pycram.pose import Pose from pycram.robot_descriptions import robot_description @@ -21,15 +21,15 @@ def test_visible(self): self.robot.set_pose(Pose()) time.sleep(1) camera_frame = robot_description.get_camera_frame() - self.world.add_vis_axis(self.robot.links[camera_frame].pose) - self.assertTrue(btr.visible(self.milk, self.robot.links[camera_frame].pose, + self.world.add_vis_axis(self.robot.get_link_pose(camera_frame)) + self.assertTrue(btr.visible(self.milk, self.robot.get_link_pose(camera_frame), robot_description.front_facing_axis)) def test_occluding(self): self.milk.set_pose(Pose([3, 0, 1.2])) self.robot.set_pose(Pose()) - self.assertTrue(btr.occluding(self.milk, self.robot.links[robot_description.get_camera_frame()].pose, - robot_description.front_facing_axis) != []) + self.assertTrue(btr.occluding(self.milk, self.robot.get_link_pose(robot_description.get_camera_frame()), + robot_description.front_facing_axis) != []) def test_reachable(self): self.robot.set_pose(Pose()) diff --git a/test/test_description.py b/test/test_description.py index 8f3afa201..0d427717c 100644 --- a/test/test_description.py +++ b/test/test_description.py @@ -15,8 +15,8 @@ def test_pose_as_list(self): self.assertEqual(base_link.pose_as_list, base_link.pose.to_list()) def test_joint_child_link(self): - self.assertEqual(self.robot.joints["base_footprint_joint"].child_link, self.robot.links["base_link"]) - self.assertEqual(self.robot.joints["base_footprint_joint"].parent_link, self.robot.root_link) + self.assertEqual(self.robot.get_joint_child_link("base_footprint_joint"), self.robot.get_link("base_link")) + self.assertEqual(self.robot.get_joint_parent_link("base_footprint_joint"), self.robot.root_link) def test_generate_description_from_mesh(self): self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.stl", ".stl")) diff --git a/test/test_links.py b/test/test_links.py index a7f37016c..af26bb39e 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -29,7 +29,7 @@ def test_transform_link(self): self.assertAlmostEqual(robot_to_milk, milk_to_robot.invert()) def test_set_color(self): - link = self.robot.links['base_link'] + link = self.robot.get_link('base_link') link.color = Color(1, 0, 0, 1) self.assertEqual(link.color.get_rgba(), [1, 0, 0, 1]) diff --git a/test/test_task_tree.py b/test/test_task_tree.py index 1635974a0..36d994663 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -4,7 +4,7 @@ from pycram.task import with_tree import unittest import anytree -from bullet_world_testcase import BulletWorldTestCase +from bullet_world_testcase import BulletWorldTestCase import pycram.plan_failures from pycram.designators import object_designator, action_designator From 92d7bea2e09b9ff34aac64173a323d87be352c3a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Fri, 23 Feb 2024 11:33:20 +0100 Subject: [PATCH 091/195] [resolver] fixed querying from occupancy costmap --- src/pycram/resolver/location/database_location.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index d613b99a3..c0427de82 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -45,12 +45,12 @@ def create_query_from_occupancy_costmap(self) -> Select: # query all relative robot positions in regard to an objects position # make sure to order the joins() correctly - query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, Position.x, Position.y) + query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, robot_pos.x, robot_pos.y) .join(TaskTreeNode.code) .join(Code.designator.of_type(PickUpAction)) .join(PickUpAction.robot_state) .join(RobotState.pose) - .join(orm.base.Pose.position) + .join(robot_pos) .join(PickUpAction.object).where(Object.type == self.target.type) .where(TaskTreeNode.status == "SUCCEEDED")) From 8462338eafb5c9f6044ff68ccd8a061cf320c6ef Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 23 Feb 2024 15:21:07 +0100 Subject: [PATCH 092/195] [Abstract World] Solved cyclic imports problem. --- src/pycram/description.py | 6 +++-- src/pycram/helper.py | 2 +- src/pycram/urdf_interface.py | 8 +++---- src/pycram/world.py | 8 ++++--- src/pycram/world_constraints.py | 5 +++-- src/pycram/world_dataclasses.py | 10 +++++---- src/pycram/world_object.py | 39 +++++++++++++++++++++++++++++++++ 7 files changed, 62 insertions(+), 16 deletions(-) diff --git a/src/pycram/description.py b/src/pycram/description.py index 93513b8aa..3d91601e2 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -6,14 +6,16 @@ import rospy from geometry_msgs.msg import Point, Quaternion -from typing_extensions import Tuple, Union, Any, List, Optional, Dict +from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING from .enums import JointType from .local_transformer import LocalTransformer from .pose import Pose, Transform from .world import WorldEntity from .world_dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape -from .world_object import Object + +if TYPE_CHECKING: + from .world_object import Object class EntityDescription(ABC): diff --git a/src/pycram/helper.py b/src/pycram/helper.py index bb171a0b1..3b07ce6e3 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -55,7 +55,7 @@ def _apply_ik(robot: WorldObject, joint_poses: List[float], joints: List[str]) - def calculate_wrist_tool_offset(wrist_frame: str, tool_frame: str, robot: WorldObject) -> Transform: - return robot.get_transfrom_between_links(wrist_frame, tool_frame) + return robot.get_transform_between_links(wrist_frame, tool_frame) def transform(pose: List[float], diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index 51ce8c3b3..e33ad8d09 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -10,11 +10,11 @@ from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, Sphere as URDF_Sphere, Mesh as URDF_Mesh) -from pycram.enums import JointType, Shape -from pycram.pose import Pose -from pycram.description import JointDescription as AbstractJointDescription, \ +from .enums import JointType, Shape +from .pose import Pose +from .description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription -from pycram.world_dataclasses import Color +from .world_dataclasses import Color class LinkDescription(AbstractLinkDescription): diff --git a/src/pycram/world.py b/src/pycram/world.py index 67e7efc7a..96294fc08 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -11,7 +11,7 @@ import numpy as np import rospy from geometry_msgs.msg import Point -from typing_extensions import List, Optional, Dict, Tuple, Callable +from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING from typing_extensions import Union from .cache_manager import CacheManager @@ -24,8 +24,10 @@ MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, ObjectState, State, WorldState) -from .world_object import Object -from .description import Link + +if TYPE_CHECKING: + from .world_object import Object + from .description import Link class StateEntity: diff --git a/src/pycram/world_constraints.py b/src/pycram/world_constraints.py index de2ba2b62..6dc75e33b 100644 --- a/src/pycram/world_constraints.py +++ b/src/pycram/world_constraints.py @@ -1,12 +1,13 @@ from __future__ import annotations from geometry_msgs.msg import Point -from typing_extensions import Union, List, Optional +from typing_extensions import Union, List, Optional, TYPE_CHECKING from .enums import JointType from .pose import Transform, Pose -from .description import Link +if TYPE_CHECKING: + from .description import Link class AbstractConstraint: diff --git a/src/pycram/world_dataclasses.py b/src/pycram/world_dataclasses.py index 55f335f53..7aea14338 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/world_dataclasses.py @@ -1,13 +1,15 @@ from __future__ import annotations from dataclasses import dataclass -from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union +from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING from .enums import JointType, Shape from .pose import Pose, Point from abc import ABC, abstractmethod -from .description import Link -from .world_object import Object -from .world_constraints import Attachment + +if TYPE_CHECKING: + from .description import Link + from .world_object import Object + from .world_constraints import Attachment def get_point_as_list(point: Point) -> List[float]: diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index 791e71b90..ba31d8dc2 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -750,29 +750,68 @@ def set_joint_position(self, joint_name: str, joint_position: float) -> None: self._set_attached_objects_poses() def get_joint_position(self, joint_name: str) -> float: + """ + :param joint_name: The name of the joint + :return: The current position of the given joint + """ return self.joints[joint_name].position def get_joint_damping(self, joint_name: str) -> float: + """ + :param joint_name: The name of the joint + :return: The damping of the given joint + """ return self.joints[joint_name].damping def get_joint_upper_limit(self, joint_name: str) -> float: + """ + :param joint_name: The name of the joint + :return: The upper limit of the given joint + """ return self.joints[joint_name].upper_limit def get_joint_lower_limit(self, joint_name: str) -> float: + """ + :param joint_name: The name of the joint + :return: The lower limit of the given joint + """ return self.joints[joint_name].lower_limit def get_joint_axis(self, joint_name: str) -> Point: + """ + :param joint_name: The name of the joint + :return: The axis of the given joint + """ return self.joints[joint_name].axis def get_joint_type(self, joint_name: str) -> JointType: + """ + :param joint_name: The name of the joint + :return: The type of the given joint + """ return self.joints[joint_name].type def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: + """ + :param joint_name: The name of the joint + :return: The lower and upper limits of the given joint + """ return self.joints[joint_name].limits def get_joint_child_link(self, joint_name: str) -> Link: + """ + :param joint_name: The name of the joint + :return: The child link of the given joint + """ return self.joints[joint_name].child_link + def get_joint_parent_link(self, joint_name: str) -> Link: + """ + :param joint_name: The name of the joint + :return: The parent link of the given joint + """ + return self.joints[joint_name].parent_link + def find_joint_above_link(self, link_name: str, joint_type: JointType) -> str: """ Traverses the chain from 'link' to the URDF origin and returns the first joint that is of type 'joint_type'. From 7b8afe664df3d92dc612d7c1c4b0911b7c6cd01a Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 23 Feb 2024 17:45:04 +0100 Subject: [PATCH 093/195] [Abstract World] Resolved requested changes. --- src/pycram/cache_manager.py | 22 +++++++++++--- src/pycram/description.py | 45 ++++++++++++++++++---------- src/pycram/pose.py | 59 +++++++++++++++++++++---------------- src/pycram/world.py | 12 ++++++-- 4 files changed, 91 insertions(+), 47 deletions(-) diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py index 24d3989e7..ae3ea3c68 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/cache_manager.py @@ -2,27 +2,41 @@ import pathlib import re -from typing_extensions import List +from typing_extensions import List, TYPE_CHECKING + +if TYPE_CHECKING: + from .description import ObjectDescription class CacheManager: + """ + The CacheManager is responsible for caching object description files and managing the cache directory. + """ + mesh_extensions: List[str] = [".obj", ".stl"] """ The file extensions of mesh files. """ def __init__(self, cache_dir: str, data_directory: List[str]): + """ + Initializes the CacheManager. + :param cache_dir: The directory where the cached files are stored. + :param data_directory: The directory where all resource files are stored. + """ self.cache_dir = cache_dir - # The directory where the cached files are stored. - self.data_directory = data_directory - # The directory where all resource files are stored. def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, object_description: 'ObjectDescription', object_name: str) -> str: """ Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + :param path: The path of the file to preprocess and save in the cache directory. + :param ignore_cached_files: If True, the file will be preprocessed and saved in the cache directory even if it + is already cached. + :param object_description: The object description of the file. + :param object_name: The name of the object. """ path_object = pathlib.Path(path) extension = path_object.suffix diff --git a/src/pycram/description.py b/src/pycram/description.py index 3d91601e2..7286a7e78 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -20,6 +20,10 @@ class EntityDescription(ABC): + """ + A class that represents a description of an entity. This can be a link, joint or object description. + """ + @property @abstractmethod def origin(self) -> Pose: @@ -49,14 +53,14 @@ def __init__(self, parsed_link_description: Any): @abstractmethod def geometry(self) -> VisualShape: """ - Returns the geometry type of the URDF collision element of this link. + Returns the geometry type of the collision element of this link. """ pass class JointDescription(EntityDescription): """ - A class that represents a joint description of a URDF joint. + A class that represents the description of a joint. """ def __init__(self, parsed_joint_description: Any): @@ -468,8 +472,8 @@ def get_object_id(self) -> int: @position.setter def position(self, joint_position: float) -> None: """ - Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, as stated - in the URDF, an error will be printed. However, the joint will be set either way. + Sets the position of the given joint to the given joint pose. If the pose is outside the joint limits, + an error will be printed. However, the joint will be set either way. :param joint_position: The target pose for this joint """ @@ -477,10 +481,10 @@ def position(self, joint_position: float) -> None: if self.has_limits: low_lim, up_lim = self.limits if not low_lim <= joint_position <= up_lim: - logging.error( + logging.warning( f"The joint position has to be within the limits of the joint. The joint limits for {self.name}" f" are {low_lim} and {up_lim}") - logging.error(f"The given joint position was: {joint_position}") + logging.warning(f"The given joint position was: {joint_position}") # Temporarily disabled because kdl outputs values exciting joint limits # return self.reset_position(joint_position) @@ -497,15 +501,16 @@ def get_reaction_force_torque(self) -> List[float]: def get_applied_motor_torque(self) -> float: return self.world.get_applied_joint_motor_torque(self.object, self.id) - def restore_state(self, state_id: int) -> None: - self.current_state = self.saved_states[state_id] - @property def current_state(self) -> JointState: return JointState(self.position) @current_state.setter def current_state(self, joint_state: JointState) -> None: + """ + Updates the current state of this joint from the given joint state if the position is different. + :param joint_state: The joint state to update from. + """ if self._current_position != joint_state.position: self.position = joint_state.position @@ -520,7 +525,15 @@ def __hash__(self): class ObjectDescription(EntityDescription): - MESH_EXTENSIONS: Tuple[str] = (".obj", ".stl") + + """ + A class that represents the description of an object. + """ + + mesh_extensions: Tuple[str] = (".obj", ".stl") + """ + The file extensions of the mesh files that can be used to generate a description file. + """ class Link(Link, ABC): ... @@ -532,6 +545,9 @@ class Joint(Joint, ABC): ... def __init__(self, path: Optional[str] = None): + """ + :param path: The path of the file to update the description data from. + """ if path: self.update_description_from_file(path) else: @@ -554,8 +570,7 @@ def parsed_description(self) -> Any: @parsed_description.setter def parsed_description(self, parsed_description: Any): """ - Return the object parsed from the description file. - :param parsed_description: The parsed description object. + :param parsed_description: The parsed description object (depends on the description file type). """ self._parsed_description = parsed_description @@ -578,7 +593,7 @@ def generate_description_from_file(self, path: str, extension: str) -> str: """ description_string = None - if extension in self.MESH_EXTENSIONS: + if extension in self.mesh_extensions: description_string = self.generate_from_mesh_file(path) elif extension == self.get_file_extension(): description_string = self.generate_from_description_file(path) @@ -603,7 +618,7 @@ def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: :param object_name: The name of the object. :return: The file name of the description file. """ - if extension in self.MESH_EXTENSIONS: + if extension in self.mesh_extensions: file_name = path_object.stem + self.get_file_extension() elif extension == self.get_file_extension(): file_name = path_object.name @@ -616,7 +631,7 @@ def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: @abstractmethod def generate_from_mesh_file(cls, path: str) -> str: """ - Generates a description file from one of the mesh types defined in the MESH_EXTENSIONS and + Generates a description file from one of the mesh types defined in the mesh_extensions and returns the path of the generated file. :param path: The path to the .obj file. :return: The path of the generated description file. diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 85f85f08a..74bda8b8d 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -14,6 +14,25 @@ from .orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData +def get_normalized_quaternion(quaternion: np.ndarray) -> GeoQuaternion: + """ + Normalizes a given quaternion such that it has a magnitude of 1. + + :param quaternion: The quaternion that should be normalized + :return: The normalized quaternion + """ + mag = math.sqrt(sum(v**2 for v in quaternion)) + normed_rotation = quaternion / mag + + geo_quaternion = GeoQuaternion() + geo_quaternion.x = normed_rotation[0] + geo_quaternion.y = normed_rotation[1] + geo_quaternion.z = normed_rotation[2] + geo_quaternion.w = normed_rotation[3] + + return geo_quaternion + + class Pose(PoseStamped): """ Pose representation for PyCRAM, this class extends the PoseStamped ROS message from geometry_msgs. Thus making it @@ -98,11 +117,11 @@ def position(self, value) -> None: :param value: List or geometry_msgs/Pose message for the position """ - if (not type(value) == list and not type(value) == tuple and not type(value) == GeoPose - and not type(value) == Point): + if (not isinstance(value, list) and not isinstance(value, tuple) and not isinstance(value, GeoPose) + and not isinstance(value, Point)): rospy.logerr("Position can only be a list or geometry_msgs/Pose") raise TypeError("Position can only be a list/tuple or geometry_msgs/Pose") - if type(value) == list or type(value) == tuple and len(value) == 3: + if isinstance(value, list) or isinstance(value, tuple) and len(value) == 3: self.pose.position.x = value[0] self.pose.position.y = value[1] self.pose.position.z = value[2] @@ -125,22 +144,16 @@ def orientation(self, value) -> None: :param value: New orientation, either a list or geometry_msgs/Quaternion """ - if not type(value) == list and not type(value) == tuple and not type(value) == GeoQuaternion: + if not isinstance(value, list) and not isinstance(value, tuple) and not isinstance(value, GeoQuaternion): rospy.logwarn("Orientation can only be a list or geometry_msgs/Quaternion") return - if type(value) == list or type(value) == tuple and len(value) == 4: + if isinstance(value, list) or isinstance(value, tuple) and len(value) == 4: orientation = np.array(value) else: orientation = np.array([value.x, value.y, value.z, value.w]) # This is used instead of np.linalg.norm since numpy is too slow on small arrays - mag = math.sqrt(sum(v**2 for v in orientation)) - normed_orientation = orientation / mag - - self.pose.orientation.x = normed_orientation[0] - self.pose.orientation.y = normed_orientation[1] - self.pose.orientation.z = normed_orientation[2] - self.pose.orientation.w = normed_orientation[3] + self.pose.orientation = get_normalized_quaternion(orientation) def to_list(self) -> List[List[float]]: """ @@ -207,7 +220,7 @@ def __eq__(self, other: Pose) -> bool: :param other: Other pose which should be compared :return: True if both Poses have the same position, orientation and frame. False otherwise """ - if not type(other) == Pose: + if not isinstance(other, Pose): return False self_position = self.position_as_list() other_position = other.position_as_list() @@ -354,10 +367,10 @@ def translation(self, value) -> None: :param value: The new value for the translation, either a list or geometry_msgs/Vector3 """ - if not type(value) == list and not type(value) == Vector3: + if not isinstance(value, list) and not isinstance(value, Vector3): rospy.logwarn("Value of a translation can only be a list of a geometry_msgs/Vector3") return - if type(value) == list and len(value) == 3: + if isinstance(value, list) and len(value) == 3: self.transform.translation.x = value[0] self.transform.translation.y = value[1] self.transform.translation.z = value[2] @@ -379,22 +392,16 @@ def rotation(self, value): :param value: The new value for the rotation, either a list or geometry_msgs/Quaternion """ - if not type(value) == list and not type(value) == GeoQuaternion: + if not isinstance(value, list) and not isinstance(value, GeoQuaternion): rospy.logwarn("Value of the rotation can only be a list or a geometry.msgs/Quaternion") return - if type(value) == list and len(value) == 4: + if isinstance(value, list) and len(value) == 4: rotation = np.array(value) else: rotation = np.array([value.x, value.y, value.z, value.w]) # This is used instead of np.linalg.norm since numpy is too slow on small arrays - mag = math.sqrt(sum(v**2 for v in rotation)) - normed_rotation = rotation / mag - - self.transform.rotation.x = normed_rotation[0] - self.transform.rotation.y = normed_rotation[1] - self.transform.rotation.z = normed_rotation[2] - self.transform.rotation.w = normed_rotation[3] + self.transform.rotation = get_normalized_quaternion(rotation) def copy(self) -> Transform: """ @@ -453,7 +460,7 @@ def __mul__(self, other: Transform) -> Union[Transform, None]: :param other: The Transform which should be multiplied with this one. :return: The resulting Transform from the multiplication """ - if not type(other) == Transform: + if not isinstance(other, Transform): rospy.logerr(f"Can only multiply two Transforms") return self_trans = transformations.translation_matrix(self.translation_as_list()) @@ -487,7 +494,7 @@ def __eq__(self, other: Transform) -> bool: :param other: Other pose which should be compared :return: True if both Transforms have the same translation, rotation, frame and child frame. False otherwise """ - if not type(other) == Transform: + if not isinstance(other, Transform): return False self_position = self.translation_as_list() other_position = other.translation_as_list() diff --git a/src/pycram/world.py b/src/pycram/world.py index 96294fc08..cc1f6fde2 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -164,7 +164,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.objects: List[Object] = [] # List of all Objects in the World - self.id: int = -1 + self.id: Optional[int] = -1 # This is used to connect to the physics server (allows multiple clients) self.mode: WorldMode = mode @@ -1002,6 +1002,9 @@ def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: """ raise NotImplementedError + def __del__(self): + self.exit() + class UseProspectionWorld: """ @@ -1013,6 +1016,11 @@ class UseProspectionWorld: NavigateAction.Action([[1, 0, 0], [0, 0, 0, 1]]).perform() """ + WAIT_TIME_FOR_ADDING_QUEUE = 20 + """ + The time in seconds to wait for the adding queue to be ready. + """ + def __init__(self): self.prev_world: Optional[World] = None # The previous world is saved to restore it after the with block is exited. @@ -1022,7 +1030,7 @@ def __enter__(self): This method is called when entering the with block, it will set the current world to the prospection world """ if not World.current_world.is_prospection_world: - time.sleep(20 * World.current_world.simulation_time_step) + time.sleep(self.WAIT_TIME_FOR_ADDING_QUEUE * World.current_world.simulation_time_step) # blocks until the adding queue is ready World.current_world.world_sync.add_obj_queue.join() From c85cb9115eb44b51992e85ac93f4be79bf02b90b Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Sun, 25 Feb 2024 17:43:02 +0100 Subject: [PATCH 094/195] [AbstractWorld] refactored joint position getting and setting to use joint class. --- src/pycram/bullet_world.py | 8 ++++---- src/pycram/description.py | 4 ++-- src/pycram/world.py | 14 ++++++-------- 3 files changed, 12 insertions(+), 14 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index f4fc8c300..f5083f6c4 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -92,8 +92,8 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): p.removeConstraint(constraint_id, physicsClientId=self.id) - def get_joint_position(self, obj: Object, joint_name: str) -> float: - return p.getJointState(obj.id, obj.joint_name_to_id[joint_name], physicsClientId=self.id)[0] + def get_joint_position(self, joint: Joint) -> float: + return p.getJointState(joint.object_id, joint.id, physicsClientId=self.id)[0] def get_object_joint_names(self, obj: Object) -> List[str]: return [p.getJointInfo(obj.id, i, physicsClientId=self.id)[1].decode('utf-8') @@ -129,8 +129,8 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> self.perform_collision_detection() return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.id) - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: - p.resetJointState(obj.id, obj.joint_name_to_id[joint_name], joint_pose, physicsClientId=self.id) + def reset_joint_position(self, joint: Joint, joint_position: str) -> None: + p.resetJointState(joint.object_id, joint.id, joint_position, physicsClientId=self.id) def reset_object_base_pose(self, obj: Object, pose: Pose) -> None: p.resetBasePositionAndOrientation(obj.id, pose.position_as_list(), pose.orientation_as_list(), diff --git a/src/pycram/description.py b/src/pycram/description.py index 7286a7e78..04b3dd667 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -436,7 +436,7 @@ def _update_position(self) -> None: """ Updates the current position of the joint from the physics simulator. """ - self._current_position = self.world.get_joint_position(self.object, self.name) + self._current_position = self.world.get_joint_position(self) @property def parent_link(self) -> Link: @@ -459,7 +459,7 @@ def position(self) -> float: return self._current_position def reset_position(self, position: float) -> None: - self.world.reset_joint_position(self.object, self.name, position) + self.world.reset_joint_position(self, position) self._update_position() def get_object_id(self) -> int: diff --git a/src/pycram/world.py b/src/pycram/world.py index cc1f6fde2..dc93a2c2f 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -27,7 +27,7 @@ if TYPE_CHECKING: from .world_object import Object - from .description import Link + from .description import Link, Joint class StateEntity: @@ -351,12 +351,11 @@ def remove_constraint(self, constraint_id) -> None: pass @abstractmethod - def get_joint_position(self, obj: Object, joint_name: str) -> float: + def get_joint_position(self, joint: Joint) -> float: """ Get the position of a joint of an articulated object - :param obj: The object. - :param joint_name: The name of the joint. + :param joint: The joint to get the position for. :return: The joint position as a float. """ pass @@ -458,13 +457,12 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> pass @abstractmethod - def reset_joint_position(self, obj: Object, joint_name: str, joint_pose: float) -> None: + def reset_joint_position(self, joint: Joint, joint_position: float) -> None: """ Reset the joint position instantly without physics simulation - :param obj: The object - :param joint_name: The name of the joint - :param joint_pose: The new joint pose + :param joint: The joint to reset the position for. + :param joint_position: The new joint pose. """ pass From 8b813538a756156408737c59c1892f4795542d13 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Tue, 27 Feb 2024 08:30:34 +0100 Subject: [PATCH 095/195] [AbstractWorld] allowing not object description for initializing objects. still in development. --- src/neem_interface_python | 2 +- src/pycram/bullet_world.py | 9 ++++++++- src/pycram/cache_manager.py | 16 ++++++---------- src/pycram/description.py | 8 +++++--- src/pycram/urdf_interface.py | 5 +++-- src/pycram/world.py | 9 +++++---- src/pycram/world_object.py | 26 +++++++++++++++----------- 7 files changed, 43 insertions(+), 32 deletions(-) diff --git a/src/neem_interface_python b/src/neem_interface_python index 182daab69..05ad42c41 160000 --- a/src/neem_interface_python +++ b/src/neem_interface_python @@ -1 +1 @@ -Subproject commit 182daab69cb2e4dab23fbf5c9b9d1146837d8102 +Subproject commit 05ad42c41042335dd2287d865f6a37c115ea8ffe diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index f5083f6c4..67536bcf1 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -66,7 +66,14 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo _ = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, ObjectDescription, world=self) - def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_object_and_get_id(self, path: Optional[str] = None, pose: Optional[Pose] = None) -> int: + if pose is None: + pose = Pose() + return self._load_object_and_get_id(path, pose) + + def _load_object_and_get_id(self, path: str, pose: Pose) -> int: + if path is None: + raise ValueError("Path to the object file is required.") return p.loadURDF(path, basePosition=pose.position_as_list(), baseOrientation=pose.orientation_as_list(), physicsClientId=self.id) diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py index ae3ea3c68..835c07cef 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/cache_manager.py @@ -50,20 +50,21 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, # if file is not yet cached preprocess the description file and save it in the cache directory. if not self.is_cached(path, object_description) or ignore_cached_files: - self.generate_description_and_write_to_cache(path, extension, cache_path, object_description) + self.generate_description_and_write_to_cache(path, object_name, extension, cache_path, object_description) return cache_path - def generate_description_and_write_to_cache(self, path: str, extension: str, cache_path: str, + def generate_description_and_write_to_cache(self, path: str, name: str, extension: str, cache_path: str, object_description: 'ObjectDescription') -> None: """ Generates the description from the file at the given path and writes it to the cache directory. :param path: The path of the file to preprocess. + :param name: The name of the object. :param extension: The file extension of the file to preprocess. :param cache_path: The path of the file in the cache directory. :param object_description: The object description of the file. """ - description_string = object_description.generate_description_from_file(path, extension) + description_string = object_description.generate_description_from_file(path, name, extension) self.write_to_cache(description_string, cache_path) @staticmethod @@ -88,14 +89,9 @@ def look_for_file_in_data_dir(self, path: str, path_object: pathlib.Path) -> str for file in os.listdir(data_dir): if file == path: return data_dir + f"/{path}" - if path: - break - if not path: - raise FileNotFoundError( - f"File {path_object.name} could not be found in the resource directory {self.data_directory}") - - return path + raise FileNotFoundError( + f"File {path_object.name} could not be found in the resource directory {self.data_directory}") def create_cache_dir_if_not_exists(self): """ diff --git a/src/pycram/description.py b/src/pycram/description.py index 04b3dd667..e0b9ecc1e 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -583,18 +583,19 @@ def load_description(self, path: str) -> Any: """ pass - def generate_description_from_file(self, path: str, extension: str) -> str: + def generate_description_from_file(self, path: str, name: str, extension: str) -> str: """ Generates and preprocesses the description from the file at the given path and returns the preprocessed description as a string. :param path: The path of the file to preprocess. + :param name: The name of the object. :param extension: The file extension of the file to preprocess. :return: The processed description string. """ description_string = None if extension in self.mesh_extensions: - description_string = self.generate_from_mesh_file(path) + description_string = self.generate_from_mesh_file(path, name) elif extension == self.get_file_extension(): description_string = self.generate_from_description_file(path) else: @@ -629,11 +630,12 @@ def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: @classmethod @abstractmethod - def generate_from_mesh_file(cls, path: str) -> str: + def generate_from_mesh_file(cls, path: str, name: str) -> str: """ Generates a description file from one of the mesh types defined in the mesh_extensions and returns the path of the generated file. :param path: The path to the .obj file. + :param name: The name of the object. :return: The path of the generated description file. """ pass diff --git a/src/pycram/urdf_interface.py b/src/pycram/urdf_interface.py index e33ad8d09..4dc1abe11 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/urdf_interface.py @@ -158,12 +158,13 @@ def load_description(self, path) -> URDF: with open(path, 'r') as file: return URDF.from_xml_string(file.read()) - def generate_from_mesh_file(self, path, color: Optional[Color] = Color()) -> str: + def generate_from_mesh_file(self, path: str, name: str, color: Optional[Color] = Color()) -> str: """ Generates an URDf file with the given .obj or .stl file as mesh. In addition, the given rgba_color will be used to create a material tag in the URDF. :param path: The path to the mesh file. + :param name: The name of the object. :param color: The color of the object. :return: The absolute path of the created file """ @@ -189,7 +190,7 @@ def generate_from_mesh_file(self, path, color: Optional[Color] = Color()) -> str rgb = " ".join(list(map(str, color.get_rgba()))) pathlib_obj = pathlib.Path(path) path = str(pathlib_obj.resolve()) - content = urdf_template.replace("~a", self.name).replace("~b", path).replace("~c", rgb) + content = urdf_template.replace("~a", name).replace("~b", path).replace("~c", rgb) return content def generate_from_description_file(self, path: str) -> str: diff --git a/src/pycram/world.py b/src/pycram/world.py index dc93a2c2f..722325501 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -129,12 +129,13 @@ class World(StateEntity, ABC): data_directory: List[str] = [os.path.join(os.path.dirname(__file__), '..', '..', 'resources')] """ - Global reference for the data directories, this is used to search for the URDF files of the robot and the objects. + Global reference for the data directories, this is used to search for the description files of the robot + and the objects. """ cache_dir = data_directory[0] + '/cached/' """ - Global reference for the cache directory, this is used to cache the URDF files of the robot and the objects. + Global reference for the cache directory, this is used to cache the description files of the robot and the objects. """ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequency: float): @@ -240,11 +241,11 @@ def simulation_time_step(self): return 1 / World.simulation_frequency @abstractmethod - def load_description_and_get_object_id(self, path: str, pose: Pose) -> int: + def load_object_and_get_id(self, path: Optional[str] = None, pose: Optional[Pose] = None) -> int: """ Loads a description file (e.g. URDF) at the given pose and returns the id of the loaded object. - :param path: The path to the description file. + :param path: The path to the description file, if None the description file is assumed to be already loaded. :param pose: The pose at which the object should be loaded. :return: The id of the loaded object. """ diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index ba31d8dc2..8206b21e8 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -77,8 +77,9 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.tf_frame = ((self.prospection_world_prefix if self.world.is_prospection_world else "") + f"{self.name}_{self.id}") - if self.description.name == robot_description.name: - self.world.set_robot_if_not_set(self) + if robot_description is not None: + if self.description.name == robot_description.name: + self.world.set_robot_if_not_set(self) self._init_joint_name_and_id_map() self._init_link_name_and_id_map() @@ -93,7 +94,8 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.objects.append(self) - def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, str]: + def _load_object_and_get_id(self, path: Optional[str] = None, + ignore_cached_files: Optional[bool] = False) -> Tuple[int, Union[str, None]]: """ Loads an object to the given World with the given position and orientation. The rgba_color will only be used when an .obj or .stl file is given. @@ -103,19 +105,21 @@ def _load_object_and_get_id(self, path, ignore_cached_files: bool) -> Tuple[int, This new file will have resolved mesh file paths, meaning there will be no references to ROS packges instead there will be absolute file paths. + :param path: The path to the description file, if None then no file will be loaded, this is useful when the + PyCRAM is not responsible for loading the file but another system is. :param ignore_cached_files: Whether to ignore files in the cache directory. :return: The unique id of the object and the path of the file that was loaded. """ + if path is not None: + try: + path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) + except FileNotFoundError as e: + logging.error("Could not generate description from file.") + raise e try: - path = self.world.update_cache_dir_with_object(path, ignore_cached_files, self) - except FileNotFoundError as e: - logging.error("Could not generate description from file.") - raise e - - try: - obj_id = self.world.load_description_and_get_object_id(path, Pose(self.get_position_as_list(), - self.get_orientation_as_list())) + obj_id = self.world.load_object_and_get_id(path, Pose(self.get_position_as_list(), + self.get_orientation_as_list())) return obj_id, path except Exception as e: logging.error( From 9afff12b08d282974ce7844150e46c7cafaf3812 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 27 Feb 2024 15:19:01 +0100 Subject: [PATCH 096/195] [pms] Added new Process modules for HSR --- src/pycram/process_modules/__init__.py | 4 +- .../process_modules/hsr_process_modules.py | 618 +++++++++++++----- 2 files changed, 463 insertions(+), 159 deletions(-) diff --git a/src/pycram/process_modules/__init__.py b/src/pycram/process_modules/__init__.py index e6b5fdc67..8349b3ec5 100644 --- a/src/pycram/process_modules/__init__.py +++ b/src/pycram/process_modules/__init__.py @@ -1,11 +1,11 @@ from .pr2_process_modules import Pr2Manager from .boxy_process_modules import BoxyManager from .donbot_process_modules import DonbotManager -from .hsr_process_modules import HSRManager +from .hsr_process_modules import HSRBManager from .default_process_modules import DefaultManager Pr2Manager() BoxyManager() DonbotManager() -HSRManager() +HSRBManager() DefaultManager() diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index e3df9dba1..208dfe59f 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -1,18 +1,28 @@ from threading import Lock +from threading import Lock +from typing import Any + +import numpy as np +import rospy +# from tmc_control_msgs.msg import GripperApplyEffortActionGoal +# from tmc_msgs.msg import Voice +import pycram.bullet_world_reasoning as btr +from ..designators.motion_designator import * +from ..bullet_world import BulletWorld, Object from ..robot_descriptions import robot_description -from ..process_module import ProcessModule, ProcessModuleManager -from ..bullet_world import BulletWorld +from ..enums import JointType, ObjectType +from ..external_interfaces import giskard +from ..external_interfaces.ik import request_ik +# from ..external_interfaces.robokudo import queryEmpty, queryHuman, stop_queryHuman from ..helper import _apply_ik -import pycram.bullet_world_reasoning as btr -import pybullet as p -import logging -import time +from ..local_transformer import LocalTransformer +from ..process_module import ProcessModule def _park_arms(arm): """ - Defines the joint poses for the parking positions of the arm of HSR and applies them to the + Defines the joint poses for the parking positions of the arms of HSRB and applies them to the in the BulletWorld defined robot. :return: None """ @@ -23,200 +33,445 @@ def _park_arms(arm): robot.set_joint_state(joint, pose) -class HSRNavigation(ProcessModule): +class HSRBNavigation(ProcessModule): """ The process module to move the robot from one position to another. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == 'navigate': - robot = BulletWorld.robot - robot.set_position_and_orientation(solution['target'], solution['orientation']) + def _execute(self, desig: MoveMotion): + robot = BulletWorld.robot + robot.set_pose(desig.target) -class HSRPickUp(ProcessModule): +class HSRBMoveHead(ProcessModule): """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. + This process module moves the head to look at a specific point in the world coordinate frame. + This point can either be a position or an object. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == 'pick': - object = solution['object'] - robot = BulletWorld.robot - target = object.get_position() - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(solution['gripper']), target, - maxNumIterations=100) - _apply_ik(robot, inv) - robot.attach(object, solution['gripper']) - time.sleep(0.5) + def _execute(self, desig: LookingMotion): + target = desig.target + robot = BulletWorld.robot + local_transformer = LocalTransformer() + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) -class HSRPlace(ProcessModule): + new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) + new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 + + current_pan = robot.get_joint_state("head_pan_joint") + current_tilt = robot.get_joint_state("head_tilt_joint") + + robot.set_joint_state("head_pan_joint", new_pan + current_pan) + robot.set_joint_state("head_tilt_joint", new_tilt + current_tilt) + + +class HSRBMoveGripper(ProcessModule): """ - This process module places an object at the given position in world coordinate frame. + This process module controls the gripper of the robot. They can either be opened or closed. + Furthermore, it can only moved one gripper at a time. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == 'place': - object = solution['object'] - robot = BulletWorld.robot - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(solution['gripper']), solution['target'], - maxNumIterations=100) - _apply_ik(robot, inv) - robot.detach(object) - time.sleep(0.5) + def _execute(self, desig: MoveGripperMotion): + robot = BulletWorld.robot + gripper = desig.gripper + motion = desig.motion + for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): + robot.set_joint_state(joint, state) -class HSRAccessing(ProcessModule): +class HSRBDetecting(ProcessModule): """ - This process module responsible for opening drawers to access the objects inside. This works by firstly moving - the end effector to the handle of the drawer. Next, the end effector is moved the respective distance to the back. - This provides the illusion the robot would open the drawer by himself. - Then the drawer will be opened by setting the joint pose of the drawer joint. + This process module tries to detect an object with the given type. To be detected the object has to be in + the field of view of the robot. + """ + + def _execute(self, desig: DetectingMotion): + rospy.loginfo("Detecting technique: {}".format(desig.technique)) + robot = BulletWorld.robot + object_type = desig.object_type + # Should be "wide_stereo_optical_frame" + cam_frame_name = robot_description.get_camera_frame() + # should be [0, 0, 1] + front_facing_axis = robot_description.front_facing_axis + # if desig.technique == 'all': + # rospy.loginfo("Fake detecting all generic objects") + # objects = BulletWorld.current_bullet_world.get_all_objets_not_robot() + # elif desig.technique == 'human': + # rospy.loginfo("Fake detecting human -> spawn 0,0,0") + # human = [] + # human.append(Object("human", ObjectType.HUMAN, "human_male.stl", pose=Pose([0, 0, 0]))) + # object_dict = {} + # + # # Iterate over the list of objects and store each one in the dictionary + # for i, obj in enumerate(human): + # object_dict[obj.name] = obj + # return object_dict + # + # else: + # rospy.loginfo("Fake -> Detecting specific object type") + objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + + object_dict = {} + + perceived_objects = [] + for obj in objects: + if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): + return obj + + +class HSRBMoveTCP(ProcessModule): + """ + This process moves the tool center point of either the right or the left arm. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == 'access': - kitchen = solution['part_of'] - robot = BulletWorld.robot - gripper = solution['gripper'] - drawer_handle = solution['drawer_handle'] - drawer_joint = solution['drawer_joint'] - dis = solution['distance'] - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), - kitchen.get_link_position(drawer_handle)) - _apply_ik(robot, inv) - time.sleep(0.2) - han_pose = kitchen.get_link_position(drawer_handle) - new_p = [han_pose[0] - dis, han_pose[1], han_pose[2]] - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), new_p) - _apply_ik(robot, inv) - kitchen.set_joint_state(drawer_joint, 0.3) - time.sleep(0.5) + def _execute(self, desig: MoveTCPMotion): + target = desig.target + robot = BulletWorld.robot + _move_arm_tcp(target, robot, desig.arm) -class HSRParkArms(ProcessModule): + +class HSRBMoveArmJoints(ProcessModule): """ - This process module is for moving the arms in a parking position. - It is currently not used. + This process modules moves the joints of either the right or the left arm. The joint states can be given as + list that should be applied or a pre-defined position can be used, such as "parking" """ - def _execute(self, desig): - solutions = desig.reference() - if solutions['cmd'] == 'park': - _park_arms() + def _execute(self, desig: MoveArmJointsMotion): + robot = BulletWorld.robot + if desig.right_arm_poses: + robot.set_joint_states(desig.right_arm_poses) + if desig.left_arm_poses: + robot.set_joint_states(desig.left_arm_poses) -class HSRMoveHead(ProcessModule): + +class HSRBMoveJoints(ProcessModule): """ - This process module moves the head to look at a specific point in the world coordinate frame. - This point can either be a position or an object. + Process Module for generic joint movements, is not confined to the arms but can move any joint of the robot """ - def _execute(self, desig): - solutions = desig.reference() - if solutions['cmd'] == 'looking': - target = solutions['target'] - if target == 'forward' or target == 'down': - robot = BulletWorld.robot - for joint, state in robot_description.get_static_joint_chain("neck", target).items(): - robot.set_joint_state(joint, state) - else: - logging.error("There is no target position defined with the target %s.", target) + def _execute(self, desig: MoveJointsMotion): + robot = BulletWorld.robot + robot.set_joint_states(dict(zip(desig.names, desig.positions))) -class HSRMoveGripper(ProcessModule): +class HSRBWorldStateDetecting(ProcessModule): """ - This process module controls the gripper of the robot. They can either be opened or closed. - Furthermore, it can only moved one gripper at a time. + This process module detectes an object even if it is not in the field of view of the robot. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == "move-gripper": - robot = BulletWorld.robot - gripper = solution['gripper'] - motion = solution['motion'] - for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): - robot.set_joint_state(joint, state) - time.sleep(0.5) + def _execute(self, desig: WorldStateDetectingMotion): + obj_type = desig.object_type + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] -class HSRDetecting(ProcessModule): +class HSRBOpen(ProcessModule): """ - This process module tries to detect an object with the given type. To be detected the object has to be in - the field of view of the robot. + Low-level implementation of opening a container in the simulation. Assumes the handle is already grasped. """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == "detecting": - robot = BulletWorld.robot - object_type = solution['object_type'] - cam_frame_name = solution['cam_frame'] - front_facing_axis = solution['front_facing_axis'] + def _execute(self, desig: OpeningMotion): + part_of_object = desig.object_part.bullet_world_object + + container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) - for obj in objects: - if btr.visible(obj, robot.get_link_position_and_orientation(cam_frame_name), front_facing_axis, 0.5): - return obj + goal_pose = btr.link_pose_for_joint_config(part_of_object, { + container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) + _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) -class HSRMoveTCP(ProcessModule): + desig.object_part.bullet_world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits(container_joint)[1]) + + +class HSRBClose(ProcessModule): """ - This process moves the tool center point of either the right or the left arm. + Low-level implementation that lets the robot close a grasped container, in simulation """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == "move-tcp": - target = solution['target'] - gripper = solution['gripper'] - robot = BulletWorld.robot - inv = p.calculateInverseKinematics(robot.id, robot.get_link_id(gripper), target) - _apply_ik(robot, inv) - time.sleep(0.5) + def _execute(self, desig: ClosingMotion): + part_of_object = desig.object_part.bullet_world_object + + container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + + goal_pose = btr.link_pose_for_joint_config(part_of_object, { + container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) + + _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + desig.object_part.bullet_world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits(container_joint)[0]) -class HSRMoveJoints(ProcessModule): + +def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: + gripper = robot_description.get_tool_frame(arm) + + joints = robot_description.chains[arm].joints + + inv = request_ik(target, robot, joints, gripper) + _apply_ik(robot, inv, joints) + + +########################################################### +########## Process Modules for the Real HSRB ############### +########################################################### + + +class HSRBNavigationReal(ProcessModule): """ - This process modules moves the joints of either the right or the left arm. The joint states can be given as - list that should be applied or a pre-defined position can be used, such as "parking" + Process module for the real HSRB that sends a cartesian goal to giskard to move the robot base """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == "move-arm-joints": - robot = BulletWorld.robot - left_arm_poses = solution['left_arm_poses'] + def _execute(self, designator: MoveMotion) -> Any: + rospy.logdebug(f"Sending goal to giskard to Move the robot") + # giskard.achieve_cartesian_goal(designator.target, robot_description.base_link, "map") + queryPoseNav(designator.target) - if type(left_arm_poses) == dict: - for joint, pose in left_arm_poses.items(): - robot.set_joint_state(joint, pose) - elif type(left_arm_poses) == str and left_arm_poses == "park": - _park_arms("left") - time.sleep(0.5) +class HSRBNavigationSemiReal(ProcessModule): + """ + Process module for the real HSRB that sends a cartesian goal to giskard to move the robot base + """ + def _execute(self, designator: MoveMotion) -> Any: + rospy.logdebug(f"Sending goal to giskard to Move the robot") + giskard.achieve_cartesian_goal(designator.target, robot_description.base_link, "map") + # queryPoseNav(designator.target) -class HSRWorldStateDetecting(ProcessModule): + +class HSRBMoveHeadReal(ProcessModule): """ - This process module detectes an object even if it is not in the field of view of the robot. + Process module for the real robot to move that such that it looks at the given position. Uses the same calculation + as the simulated one + """ + + def _execute(self, desig: LookingMotion): + target = desig.target + robot = BulletWorld.robot + + local_transformer = LocalTransformer() + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) + + new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) + new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x + pose_in_tilt.position.y) + + current_pan = robot.get_joint_state("head_pan_joint") + current_tilt = robot.get_joint_state("head_tilt_joint") + + giskard.avoid_all_collisions() + giskard.achieve_joint_goal( + {"head_pan_joint": new_pan + current_pan, "head_tilt_joint": new_tilt + current_tilt}) + giskard.achieve_joint_goal( + {"head_pan_joint": new_pan + current_pan, "head_tilt_joint": new_tilt + current_tilt}) + + +class HSRBDetectingReal(ProcessModule): + """ + Process Module for the real HSRB that tries to detect an object fitting the given object description. Uses Robokudo + for perception of the environment. + """ + + def _execute(self, desig: DetectingMotion) -> Any: + # todo at the moment perception ignores searching for a specific object type so we do as well on real + if desig.technique == 'human' and (desig.state == "start" or desig.state == None): + human_pose = queryHuman() + pose = Pose.from_pose_stamped(human_pose) + pose.position.z = 0 + human = [] + human.append(Object("human", ObjectType.HUMAN, "human_male.stl", pose=pose)) + object_dict = {} + + # Iterate over the list of objects and store each one in the dictionary + for i, obj in enumerate(human): + object_dict[obj.name] = obj + return object_dict + + return human_pose + elif desig.technique == 'human' and desig.state == "stop": + stop_queryHuman() + return "stopped" + + query_result = queryEmpty(ObjectDesignatorDescription(types=[desig.object_type])) + perceived_objects = [] + for i in range(0, len(query_result.res)): + # this has to be pose from pose stamped since we spawn the object with given header + obj_pose = Pose.from_pose_stamped(query_result.res[i].pose[0]) + # obj_pose.orientation = [0, 0, 0, 1] + # obj_pose_tmp = query_result.res[i].pose[0] + obj_type = query_result.res[i].type + obj_size = query_result.res[i].shape_size + obj_color = query_result.res[i].color[0] + color_switch = { + "red": [1, 0, 0, 1], + "green": [0, 1, 0, 1], + "blue": [0, 0, 1, 1], + "black": [0, 0, 0, 1], + "white": [1, 1, 1, 1], + # add more colors if needed + } + color = color_switch.get(obj_color) + if color is None: + color = [0, 0, 0, 1] + + # atm this is the string size that describes the object but it is not the shape size thats why string + def extract_xyz_values(input_string): + # Split the input string by commas and colon to separate key-value pairs + # key_value_pairs = input_string.split(', ') + + # Initialize variables to store the X, Y, and Z values + x_value = None + y_value = None + z_value = None + + for key in input_string: + x_value = key.dimensions.x + y_value = key.dimensions.y + z_value = key.dimensions.z + + # + # # Iterate through the key-value pairs to extract the values + # for pair in key_value_pairs: + # key, value = pair.split(': ') + # if key == 'x': + # x_value = float(value) + # elif key == 'y': + # y_value = float(value) + # elif key == 'z': + # z_value = float(value) + + return x_value, y_value, z_value + + x, y, z = extract_xyz_values(obj_size) + size = (x, z / 2, y) + size_box = (x / 2, z / 2, y / 2) + hard_size = (0.02, 0.02, 0.03) + id = BulletWorld.current_bullet_world.add_rigid_box(obj_pose, hard_size, color) + box_object = Object(obj_type + "_" + str(rospy.get_time()), obj_type, pose=obj_pose, color=color, id=id, + customGeom={"size": [hard_size[0], hard_size[1], hard_size[2]]}) + box_object.set_pose(obj_pose) + box_desig = ObjectDesignatorDescription.Object(box_object.name, box_object.type, box_object) + + perceived_objects.append(box_desig) + + object_dict = {} + + # Iterate over the list of objects and store each one in the dictionary + for i, obj in enumerate(perceived_objects): + object_dict[obj.name] = obj + return object_dict + + +class HSRBMoveTCPReal(ProcessModule): + """ + Moves the tool center point of the real HSRB while avoiding all collisions + """ + + def _execute(self, designator: MoveTCPMotion) -> Any: + lt = LocalTransformer() + pose_in_map = lt.transform_pose(designator.target, "map") + giskard.avoid_all_collisions() + if designator.allow_gripper_collision: + giskard.allow_gripper_collision(designator.arm) + giskard.achieve_cartesian_goal(pose_in_map, robot_description.get_tool_frame(designator.arm), + "map") + + +class HSRBMoveArmJointsReal(ProcessModule): + """ + Moves the arm joints of the real HSRB to the given configuration while avoiding all collisions + """ + + def _execute(self, designator: MoveArmJointsMotion) -> Any: + joint_goals = {} + if designator.left_arm_poses: + joint_goals.update(designator.left_arm_poses) + giskard.avoid_all_collisions() + giskard.achieve_joint_goal(joint_goals) + + +class HSRBMoveJointsReal(ProcessModule): + """ + Moves any joint using giskard, avoids all collisions while doint this. + """ + + def _execute(self, designator: MoveJointsMotion) -> Any: + name_to_position = dict(zip(designator.names, designator.positions)) + giskard.avoid_all_collisions() + giskard.achieve_joint_goal(name_to_position) + + +class HSRBMoveGripperReal(ProcessModule): + """ + Opens or closes the gripper of the real HSRB with the help of giskard. + """ + + def _execute(self, designator: MoveGripperMotion) -> Any: + if (designator.motion == "open"): + pub_gripper = rospy.Publisher('/hsrb/gripper_controller/grasp/goal', GripperApplyEffortActionGoal, + queue_size=10) + rate = rospy.Rate(10) + rospy.sleep(2) + msg = GripperApplyEffortActionGoal() # sprechen joint gripper_controll_manager an, indem wir goal publishen type den giskard fürs greifen erwartet + msg.goal.effort = 0.8 + pub_gripper.publish(msg) + + elif (designator.motion == "close"): + pub_gripper = rospy.Publisher('/hsrb/gripper_controller/grasp/goal', GripperApplyEffortActionGoal, + queue_size=10) + rate = rospy.Rate(10) + rospy.sleep(2) + msg = GripperApplyEffortActionGoal() + msg.goal.effort = -0.8 + pub_gripper.publish(msg) + + # if designator.allow_gripper_collision: + # giskard.allow_gripper_collision("left") + # giskard.achieve_gripper_motion_goal(designator.motion) + + +class HSRBOpenReal(ProcessModule): + """ + Tries to open an already grasped container + """ + + def _execute(self, designator: OpeningMotion) -> Any: + giskard.achieve_open_container_goal(robot_description.get_tool_frame(designator.arm), + designator.object_part.name) + + +class HSRBCloseReal(ProcessModule): + """ + Tries to close an already grasped container """ - def _execute(self, desig): - solution = desig.reference() - if solution['cmd'] == "world-state-detecting": - obj_type = solution['object_type'] - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + def _execute(self, designator: ClosingMotion) -> Any: + giskard.achieve_close_container_goal(robot_description.get_tool_frame(designator.arm), + designator.object_part.name) -class HSRManager(ProcessModuleManager): +# class HSRBTalkReal(ProcessModule): +# """ +# Tries to close an already grasped container +# """ +# +# def _execute(self, designator: TalkingMotion.Motion) -> Any: +# pub = rospy.Publisher('/talk_request', Voice, queue_size=10) +# +# # fill message of type Voice with required data: +# texttospeech = Voice() +# # language 1 = english (0 = japanese) +# texttospeech.language = 1 +# texttospeech.sentence = designator.cmd +# +# rospy.sleep(1) +# pub.publish(texttospeech) + + +class HSRBManager(ProcessModuleManager): def __init__(self): super().__init__("hsrb") @@ -232,39 +487,88 @@ def __init__(self): self._move_gripper_lock = Lock() self._open_lock = Lock() self._close_lock = Lock() + self._talk_lock = Lock() def navigate(self): if ProcessModuleManager.execution_type == "simulated": - return HSRNavigation(self._navigate_lock) - - def pick_up(self): - if ProcessModuleManager.execution_type == "simulated": - return HSRPickUp(self._pick_up_lock) - - def place(self): - if ProcessModuleManager.execution_type == "simulated": - return HSRPlace(self._place_lock) + return HSRBNavigation(self._navigate_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBNavigationReal(self._navigate_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBNavigationSemiReal(self._navigate_lock) def looking(self): if ProcessModuleManager.execution_type == "simulated": - return HSRMoveHead(self._looking_lock) + return HSRBMoveHead(self._looking_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBMoveHeadReal(self._looking_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBMoveHeadReal(self._looking_lock) def detecting(self): if ProcessModuleManager.execution_type == "simulated": - return HSRDetecting(self._detecting_lock) + return HSRBDetecting(self._detecting_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBDetectingReal(self._detecting_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBDetecting(self._detecting_lock) def move_tcp(self): if ProcessModuleManager.execution_type == "simulated": - return HSRMoveTCP(self._move_tcp_lock) + return HSRBMoveTCP(self._move_tcp_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBMoveTCPReal(self._move_tcp_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBMoveTCPReal(self._move_tcp_lock) def move_arm_joints(self): if ProcessModuleManager.execution_type == "simulated": - return HSRMoveJoints(self._move_arm_joints_lock) + return HSRBMoveArmJoints(self._move_arm_joints_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBMoveArmJointsReal(self._move_arm_joints_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBMoveArmJointsReal(self._move_arm_joints_lock) def world_state_detecting(self): + if ProcessModuleManager.execution_type == "simulated" or ProcessModuleManager.execution_type == "real": + return HSRBWorldStateDetecting(self._world_state_detecting_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBWorldStateDetecting(self._world_state_detecting_lock) + + def move_joints(self): if ProcessModuleManager.execution_type == "simulated": - return HSRWorldStateDetecting(self._world_state_detecting_lock) + return HSRBMoveJoints(self._move_joints_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBMoveJointsReal(self._move_joints_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBMoveJointsReal(self._move_joints_lock) def move_gripper(self): if ProcessModuleManager.execution_type == "simulated": - return HSRMoveGripper(self._move_gripper_lock) + return HSRBMoveGripper(self._move_gripper_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBMoveGripperReal(self._move_gripper_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBMoveGripperReal(self._move_gripper_lock) + + def open(self): + if ProcessModuleManager.execution_type == "simulated": + return HSRBOpen(self._open_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBOpenReal(self._open_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBOpenReal(self._open_lock) + + def close(self): + if ProcessModuleManager.execution_type == "simulated": + return HSRBClose(self._close_lock) + elif ProcessModuleManager.execution_type == "real": + return HSRBCloseReal(self._close_lock) + elif ProcessModuleManager.execution_type == "semi_real": + return HSRBCloseReal(self._close_lock) + + # def talk(self): + # if ProcessModuleManager.execution_type == "real": + # return HSRBTalkReal(self._talk_lock) + # elif ProcessModuleManager.execution_type == "semi_real": + # return HSRBTalkReal(self._talk_lock) From b4a384f89ee8d49c62564249837bde4939bd35c6 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 27 Feb 2024 16:34:37 +0100 Subject: [PATCH 097/195] [Abstract World] solved cache search problem, tests are passing. --- src/pycram/cache_manager.py | 21 ++++++++++----------- test/test_cache_manager.py | 6 ++++-- test/test_description.py | 6 ++++-- 3 files changed, 18 insertions(+), 15 deletions(-) diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py index 835c07cef..2dc479d8d 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/cache_manager.py @@ -41,15 +41,14 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, path_object = pathlib.Path(path) extension = path_object.suffix - path = self.look_for_file_in_data_dir(path, path_object) - self.create_cache_dir_if_not_exists() # save correct path in case the file is already in the cache directory cache_path = self.cache_dir + object_description.get_file_name(path_object, extension, object_name) - # if file is not yet cached preprocess the description file and save it in the cache directory. if not self.is_cached(path, object_description) or ignore_cached_files: + # if file is not yet cached preprocess the description file and save it in the cache directory. + path = self.look_for_file_in_data_dir(path_object) self.generate_description_and_write_to_cache(path, object_name, extension, cache_path, object_description) return cache_path @@ -77,21 +76,21 @@ def write_to_cache(description_string: str, cache_path: str) -> None: with open(cache_path, "w") as file: file.write(description_string) - def look_for_file_in_data_dir(self, path: str, path_object: pathlib.Path) -> str: + def look_for_file_in_data_dir(self, path_object: pathlib.Path) -> str: """ Looks for a file in the data directory of the World. If the file is not found in the data directory, this method raises a FileNotFoundError. - :param path: The path of the file to look for. :param path_object: The pathlib object of the file to look for. """ - if re.match("[a-zA-Z_0-9].[a-zA-Z0-9]", path): - for data_dir in self.data_directory: - for file in os.listdir(data_dir): - if file == path: - return data_dir + f"/{path}" + + name = path_object.name + for data_dir in self.data_directory: + for file in os.listdir(data_dir): + if file == name: + return data_dir + f"/{name}" raise FileNotFoundError( - f"File {path_object.name} could not be found in the resource directory {self.data_directory}") + f"File {name} could not be found in the resource directory {self.data_directory}") def create_cache_dir_if_not_exists(self): """ diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py index c69e1ea9f..bbdf686d3 100644 --- a/test/test_cache_manager.py +++ b/test/test_cache_manager.py @@ -1,3 +1,5 @@ +from pathlib import Path + from bullet_world_testcase import BulletWorldTestCase from pycram.enums import ObjectType from pycram.urdf_interface import ObjectDescription @@ -9,9 +11,9 @@ class TestCacheManager(BulletWorldTestCase): def test_generate_description_and_write_to_cache(self): cache_manager = self.world.cache_manager path = "../resources/apartment.urdf" - extension = ".urdf" + extension = Path(path).suffix cache_path = self.world.cache_dir + "apartment.urdf" apartment = Object("apartment", ObjectType.ENVIRONMENT, path, ObjectDescription) - cache_manager.generate_description_and_write_to_cache(path, extension, cache_path, + cache_manager.generate_description_and_write_to_cache(path, apartment.name, extension, cache_path, apartment.description) self.assertTrue(cache_manager.is_cached(path, apartment.description)) diff --git a/test/test_description.py b/test/test_description.py index 0d427717c..e1c62ccbf 100644 --- a/test/test_description.py +++ b/test/test_description.py @@ -19,7 +19,9 @@ def test_joint_child_link(self): self.assertEqual(self.robot.get_joint_parent_link("base_footprint_joint"), self.robot.root_link) def test_generate_description_from_mesh(self): - self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.stl", ".stl")) + self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.stl", + "milk", ".stl")) def test_generate_description_from_description_file(self): - self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.urdf", ".urdf")) + self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.urdf", + "milk", ".urdf")) From 953f31238d60efc1bff58dec43218243e3f936b1 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 27 Feb 2024 17:10:27 +0100 Subject: [PATCH 098/195] [Abstract World] Defualted description type to URDF as it as it is currently the only used/implement description. --- demos/pycram_bullet_world_demo/demo.py | 12 ++++++------ doc/source/notebooks/bullet_world.ipynb | 6 +++--- src/pycram/bullet_world.py | 2 +- src/pycram/world_object.py | 3 ++- test/bullet_world_testcase.py | 12 ++++++------ test/test_bullet_world.py | 6 +++--- test/test_cache_manager.py | 2 +- test/test_object.py | 6 +++--- 8 files changed, 25 insertions(+), 24 deletions(-) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index f37015e4f..22aa7c54d 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -12,16 +12,16 @@ extension = ObjectDescription.get_file_extension() world = BulletWorld() -robot = Object("pr2", ObjectType.ROBOT, f"pr2{extension}", ObjectDescription, pose=Pose([1, 2, 0])) -apartment = Object("apartment", ObjectType.ENVIRONMENT, f"apartment{extension}", ObjectDescription) +robot = Object("pr2", ObjectType.ROBOT, f"pr2{extension}", pose=Pose([1, 2, 0])) +apartment = Object("apartment", ObjectType.ENVIRONMENT, f"apartment{extension}") -milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([2.5, 2, 1.02]), +milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([2.5, 2, 1.02]), color=Color(1, 0, 0, 1)) -cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", ObjectDescription, +cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([2.5, 2.3, 1.05]), color=Color(0, 1, 0, 1)) -spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", ObjectDescription, pose=Pose([2.4, 2.2, 0.85]), +spoon = Object("spoon", ObjectType.SPOON, "spoon.stl", pose=Pose([2.4, 2.2, 0.85]), color=Color(0, 0, 1, 1)) -bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", ObjectDescription, pose=Pose([2.5, 2.2, 1.02]), +bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=Pose([2.5, 2.2, 1.02]), color=Color(1, 1, 0, 1)) apartment.attach(spoon, 'cabinet10_drawer_top') diff --git a/doc/source/notebooks/bullet_world.ipynb b/doc/source/notebooks/bullet_world.ipynb index cc8874cec..18bdb9814 100644 --- a/doc/source/notebooks/bullet_world.ipynb +++ b/doc/source/notebooks/bullet_world.ipynb @@ -144,7 +144,7 @@ "from pycram.world_object import Object\n", "from pycram.urdf_interface import ObjectDescription\n", "\n", - "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", ObjectDescription, pose=Pose([0, 0, 1]))" + "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([0, 0, 1]))" ] }, { @@ -293,7 +293,7 @@ }, "outputs": [], "source": [ - "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", ObjectDescription, pose=Pose([1, 0, 1]))" + "cereal = Object(\"cereal\", ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\", pose=Pose([1, 0, 1]))" ] }, { @@ -396,7 +396,7 @@ } ], "source": [ - "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\", ObjectDescription)\n", + "pr2 = Object(\"pr2\", ObjectType.ROBOT, \"pr2.urdf\")\n", "print(pr2.links)" ] }, diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index 67536bcf1..15d1cf329 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -63,7 +63,7 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo self.set_gravity([0, 0, -9.8]) if not is_prospection_world: - _ = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, ObjectDescription, + _ = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, world=self) def load_object_and_get_id(self, path: Optional[str] = None, pose: Optional[Pose] = None) -> int: diff --git a/src/pycram/world_object.py b/src/pycram/world_object.py index 8206b21e8..55d15890a 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/world_object.py @@ -16,6 +16,7 @@ from .world_constraints import Attachment from .world_dataclasses import Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape from .description import ObjectDescription, LinkDescription +from .urdf_interface import ObjectDescription as URDF Link = ObjectDescription.Link @@ -32,7 +33,7 @@ class Object(WorldEntity): """ def __init__(self, name: str, obj_type: ObjectType, path: str, - description: Type[ObjectDescription], + description: Optional[Type[ObjectDescription]] = URDF, pose: Optional[Pose] = None, world: Optional[World] = None, color: Optional[Color] = Color(), diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index bc0d2cc72..525832ba6 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -18,10 +18,10 @@ class BulletWorldTestCase(unittest.TestCase): @classmethod def setUpClass(cls): cls.world = BulletWorld(mode=WorldMode.DIRECT) - cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, - robot_description.name + cls.extension, ObjectDescription) - cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension, ObjectDescription) + robot_description.name + cls.extension) + cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension) cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", ObjectDescription, pose=Pose([1.3, 0.7, 0.95])) ProcessModule.execution_delay = False @@ -50,10 +50,10 @@ class BulletWorldGUITestCase(unittest.TestCase): @classmethod def setUpClass(cls): cls.world = BulletWorld(mode=WorldMode.GUI) - cls.milk = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, - robot_description.name + cls.extension, ObjectDescription) - cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension, ObjectDescription) + robot_description.name + cls.extension) + cls.kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen" + cls.extension) cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", ObjectDescription, pose=Pose([1.3, 0.7, 0.95])) ProcessModule.execution_delay = False diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 2c1bf0682..059c27f8d 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -61,7 +61,7 @@ def test_remove_robot(self): self.world.remove_object(self.robot) self.assertTrue(robot_id not in [obj.id for obj in self.world.objects]) BulletWorldTest.robot = Object(robot_description.name, ObjectType.ROBOT, - robot_description.name + self.extension, ObjectDescription) + robot_description.name + self.extension) def test_get_joint_position(self): self.assertEqual(self.robot.get_joint_position("head_pan_joint"), 0.0) @@ -143,7 +143,7 @@ def test_add_resource_path(self): self.assertTrue("test" in self.world.data_directory) def test_no_prospection_object_found_for_given_object(self): - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) time.sleep(0.05) try: prospection_milk_2 = self.world.get_prospection_object_for_object(milk_2) @@ -155,7 +155,7 @@ def test_no_prospection_object_found_for_given_object(self): self.assertTrue(True) def test_no_object_found_for_given_prospection_object(self): - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", ObjectDescription, pose=Pose([1.3, 1, 0.9])) + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) time.sleep(0.05) prospection_milk = self.world.get_prospection_object_for_object(milk_2) self.assertTrue(self.world.get_object_for_prospection_object(prospection_milk) == milk_2) diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py index bbdf686d3..3df0e3484 100644 --- a/test/test_cache_manager.py +++ b/test/test_cache_manager.py @@ -13,7 +13,7 @@ def test_generate_description_and_write_to_cache(self): path = "../resources/apartment.urdf" extension = Path(path).suffix cache_path = self.world.cache_dir + "apartment.urdf" - apartment = Object("apartment", ObjectType.ENVIRONMENT, path, ObjectDescription) + apartment = Object("apartment", ObjectType.ENVIRONMENT, path) cache_manager.generate_description_and_write_to_cache(path, apartment.name, extension, cache_path, apartment.description) self.assertTrue(cache_manager.is_cached(path, apartment.description)) diff --git a/test/test_object.py b/test/test_object.py index 80a8f98c0..9ef50883c 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -17,14 +17,14 @@ class TestObject(BulletWorldTestCase): def test_wrong_object_description_path(self): with self.assertRaises(FileNotFoundError): - milk = Object("milk2", ObjectType.MILK, "wrong_path.sk", ObjectDescription) + milk = Object("milk2", ObjectType.MILK, "wrong_path.sk") def test_malformed_object_description(self): malformed_file = "../resources/cached/malformed_description.urdf" with open(malformed_file, "w") as file: file.write("malformed") with self.assertRaises(Exception): - Object("milk2", ObjectType.MILK, malformed_file, ObjectDescription) + Object("milk2", ObjectType.MILK, malformed_file) def test_move_base_to_origin_pose(self): self.milk.set_position(Point(1, 2, 3), base=False) @@ -157,7 +157,7 @@ def test_set_color(self): self.assertEqual(color, Color(0, 1, 0, 1)) def test_object_equal(self): - milk2 = Object("milk2", ObjectType.MILK, "milk.stl", ObjectDescription) + milk2 = Object("milk2", ObjectType.MILK, "milk.stl") self.assertNotEqual(self.milk, milk2) self.assertEqual(self.milk, self.milk) self.assertNotEqual(self.milk, self.cereal) From b6a512e77eb89e90dec166fd0a909705d18e4ef7 Mon Sep 17 00:00:00 2001 From: A_Bassiouny Date: Tue, 27 Feb 2024 22:12:09 +0100 Subject: [PATCH 099/195] [AbstractWorld] Restructured files. --- demos/pycram_bullet_world_demo/demo.py | 12 +- demos/pycram_ur5_demo/demo.py | 5 +- resources/ur5e_without_gripper.urdf | 191 ++++++++++++++++++ src/neem_interface_python | 2 +- src/pycram/__init__.py | 2 +- src/pycram/description.py | 12 +- src/pycram/designator.py | 10 +- src/pycram/designators/action_designator.py | 8 +- src/pycram/designators/location_designator.py | 12 +- src/pycram/designators/motion_designator.py | 8 +- src/pycram/designators/object_designator.py | 6 +- src/pycram/external_interfaces/giskard.py | 14 +- src/pycram/external_interfaces/ik.py | 6 +- src/pycram/external_interfaces/robokudo.py | 9 +- src/pycram/helper.py | 4 +- src/pycram/language.py | 4 +- src/pycram/object_descriptors/__init__.py | 0 .../urdf.py} | 8 +- src/pycram/orm/action_designator.py | 2 +- src/pycram/orm/base.py | 2 +- src/pycram/orm/motion_designator.py | 4 +- src/pycram/orm/object_designator.py | 2 +- src/pycram/orm/task.py | 6 +- src/pycram/orm/utils.py | 6 - src/pycram/pose_generator_and_validator.py | 18 +- .../process_modules/boxy_process_modules.py | 7 +- .../default_process_modules.py | 4 +- .../process_modules/donbot_process_modules.py | 4 +- .../process_modules/hsr_process_modules.py | 4 +- .../process_modules/pr2_process_modules.py | 10 +- .../resolver/location/database_location.py | 8 +- .../resolver/location/giskard_location.py | 6 +- src/pycram/resolver/location/jpt_location.py | 8 +- src/pycram/robot_description.py | 2 +- src/pycram/ros/force_torque_sensor.py | 2 +- src/pycram/ros/joint_state_publisher.py | 2 +- src/pycram/ros/robot_state_updater.py | 4 +- src/pycram/ros/tf_broadcaster.py | 4 +- src/pycram/ros/viz_marker_publisher.py | 7 +- src/pycram/task.py | 6 +- src/pycram/world.py | 24 +-- src/pycram/world_reasoning.py | 10 +- src/pycram/worlds/__init__.py | 0 src/pycram/{ => worlds}/bullet_world.py | 14 +- src/pycram/worlds/concepts/__init__.py | 0 .../{ => worlds/concepts}/cache_manager.py | 3 +- .../concepts/constraints.py} | 6 +- src/pycram/{ => worlds/concepts}/costmaps.py | 14 +- src/pycram/{ => worlds/concepts}/event.py | 0 .../{ => worlds/concepts}/world_object.py | 31 +-- src/pycram/worlds/datastructures/__init__.py | 0 .../datastructures/dataclasses.py} | 10 +- .../{ => worlds/datastructures}/enums.py | 0 .../datastructures}/local_transformer.py | 2 +- .../{ => worlds/datastructures}/pose.py | 2 +- test/bullet_world_testcase.py | 10 +- test/test_action_designator.py | 9 +- test/test_bullet_world.py | 10 +- test/test_bullet_world_reasoning.py | 2 +- test/test_cache_manager.py | 5 +- test/test_costmaps.py | 4 +- test/test_database_merger.py | 6 +- test/test_database_resolver.py | 6 +- test/test_failure_handling.py | 6 +- test/test_jpt_resolver.py | 8 +- test/test_language.py | 6 +- test/test_links.py | 4 +- test/test_local_transformer.py | 4 +- test/test_location_designator.py | 6 +- test/test_object.py | 11 +- test/test_object_designator.py | 2 +- test/test_orm.py | 3 +- test/test_pose.py | 2 +- test/test_task_tree.py | 2 +- 74 files changed, 411 insertions(+), 242 deletions(-) create mode 100644 resources/ur5e_without_gripper.urdf create mode 100644 src/pycram/object_descriptors/__init__.py rename src/pycram/{urdf_interface.py => object_descriptors/urdf.py} (98%) create mode 100644 src/pycram/worlds/__init__.py rename src/pycram/{ => worlds}/bullet_world.py (98%) create mode 100644 src/pycram/worlds/concepts/__init__.py rename src/pycram/{ => worlds/concepts}/cache_manager.py (99%) rename src/pycram/{world_constraints.py => worlds/concepts/constraints.py} (98%) rename src/pycram/{ => worlds/concepts}/costmaps.py (98%) rename src/pycram/{ => worlds/concepts}/event.py (100%) rename src/pycram/{ => worlds/concepts}/world_object.py (97%) create mode 100644 src/pycram/worlds/datastructures/__init__.py rename src/pycram/{world_dataclasses.py => worlds/datastructures/dataclasses.py} (96%) rename src/pycram/{ => worlds/datastructures}/enums.py (100%) rename src/pycram/{ => worlds/datastructures}/local_transformer.py (98%) rename src/pycram/{ => worlds/datastructures}/pose.py (99%) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 22aa7c54d..188eb1baa 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -1,13 +1,13 @@ -from pycram.bullet_world import BulletWorld +from pycram.worlds.bullet_world import BulletWorld from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.designators.object_designator import * -from pycram.enums import ObjectType -from pycram.pose import Pose +from pycram.worlds.datastructures.enums import ObjectType +from pycram.worlds.datastructures.pose import Pose from pycram.process_module import simulated_robot, with_simulated_robot -from pycram.urdf_interface import ObjectDescription -from pycram.world_object import Object -from pycram.world_dataclasses import Color +from pycram.object_descriptors.urdf import ObjectDescription +from pycram.worlds.concepts.world_object import Object +from pycram.worlds.datastructures.dataclasses import Color extension = ObjectDescription.get_file_extension() diff --git a/demos/pycram_ur5_demo/demo.py b/demos/pycram_ur5_demo/demo.py index b54b5b6d7..b0cc4358e 100644 --- a/demos/pycram_ur5_demo/demo.py +++ b/demos/pycram_ur5_demo/demo.py @@ -4,10 +4,9 @@ from rospkg import RosPack import pybullet as pb -from pycram import robot_description -from pycram.bullet_world import BulletWorld +from pycram.worlds.bullet_world import BulletWorld from pycram.world import Object -from pycram.pose import Pose +from pycram.worlds.datastructures.pose import Pose from pycram.ros.force_torque_sensor import ForceTorqueSensor from pycram.ros.joint_state_publisher import JointStatePublisher from pycram.ros.tf_broadcaster import TFBroadcaster diff --git a/resources/ur5e_without_gripper.urdf b/resources/ur5e_without_gripper.urdf new file mode 100644 index 000000000..7ecbb9659 --- /dev/null +++ b/resources/ur5e_without_gripper.urdf @@ -0,0 +1,191 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/neem_interface_python b/src/neem_interface_python index 05ad42c41..285033958 160000 --- a/src/neem_interface_python +++ b/src/neem_interface_python @@ -1 +1 @@ -Subproject commit 05ad42c41042335dd2287d865f6a37c115ea8ffe +Subproject commit 28503395862f676fc2ad19877559673bd988fd07 diff --git a/src/pycram/__init__.py b/src/pycram/__init__.py index a081b74a1..878e37441 100644 --- a/src/pycram/__init__.py +++ b/src/pycram/__init__.py @@ -23,7 +23,7 @@ import logging import logging.config -# with utils.suppress_stdout_stderr(): +# with datastructures.suppress_stdout_stderr(): # import pycram.process_modules import pycram.process_modules diff --git a/src/pycram/description.py b/src/pycram/description.py index e0b9ecc1e..dc11387ea 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -8,14 +8,14 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING -from .enums import JointType -from .local_transformer import LocalTransformer -from .pose import Pose, Transform -from .world import WorldEntity -from .world_dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape +from pycram.worlds.datastructures.enums import JointType +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.world import WorldEntity +from pycram.worlds.datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape if TYPE_CHECKING: - from .world_object import Object + from pycram.worlds.concepts.world_object import Object class EntityDescription(ABC): diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 4dc524b4e..6b1743d64 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -8,18 +8,18 @@ from sqlalchemy.orm.session import Session import rospy -from .world import World -from .world_object import Object as WorldObject +from pycram.world import World +from pycram.worlds.concepts.world_object import Object as WorldObject from .helper import GeneratorList, bcolors from threading import Lock from time import time from typing_extensions import List, Dict, Any, Optional, Union, get_type_hints, Callable, Iterable -from .local_transformer import LocalTransformer +from pycram.worlds.datastructures.local_transformer import LocalTransformer from .language import Language -from .pose import Pose +from pycram.worlds.datastructures.pose import Pose from .robot_descriptions import robot_description -from .enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType import logging diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index d701b2bb0..987a787a2 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -6,7 +6,7 @@ from .location_designator import CostmapLocation from .motion_designator import * from .object_designator import ObjectDesignatorDescription, BelieveObject, ObjectPart -from ..local_transformer import LocalTransformer +from pycram.worlds.datastructures.local_transformer import LocalTransformer from ..orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, PickUpAction as ORMPickUpAction, PlaceAction as ORMPlaceAction, MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, @@ -19,10 +19,10 @@ from ..plan_failures import ObjectUnfetchable, ReachabilityFailure from ..robot_descriptions import robot_description from ..task import with_tree -from ..enums import Arms +from pycram.worlds.datastructures.enums import Arms from ..designator import ActionDesignatorDescription -from ..world import World -from ..pose import Pose +from pycram.world import World +from pycram.worlds.datastructures.pose import Pose from ..helper import multiply_quaternions diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 2a087f07f..cc78cedc5 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -2,17 +2,17 @@ from typing_extensions import List, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..world import World, UseProspectionWorld -from ..world_reasoning import link_pose_for_joint_config +from pycram.world import World, UseProspectionWorld +from pycram.world_reasoning import link_pose_for_joint_config from ..designator import DesignatorError, LocationDesignatorDescription -from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap +from pycram.worlds.concepts.costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap from ..robot_descriptions import robot_description -from ..enums import JointType +from pycram.worlds.datastructures.enums import JointType from ..helper import transform -from ..pose_generator_and_validator import pose_generator, visibility_validator, reachability_validator, \ +from pycram.pose_generator_and_validator import pose_generator, visibility_validator, reachability_validator, \ generate_orientation from ..robot_description import ManipulatorDescription -from ..pose import Pose +from pycram.worlds.datastructures.pose import Pose class Location(LocationDesignatorDescription): diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index 88604d71f..f24cb0f05 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -2,8 +2,8 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject -from ..world import World -from ..world_object import Object +from pycram.world import World +from pycram.worlds.concepts.world_object import Object from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager @@ -13,10 +13,10 @@ MoveTCPMotion as ORMMoveTCPMotion, LookingMotion as ORMLookingMotion, MoveGripperMotion as ORMMoveGripperMotion, DetectingMotion as ORMDetectingMotion, OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion) -from ..enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType from typing_extensions import List, Dict, Callable, Optional -from ..pose import Pose +from pycram.worlds.datastructures.pose import Pose from ..task import with_tree diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index bd24a86a3..6826eef00 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -1,12 +1,12 @@ import dataclasses from typing_extensions import List, Optional, Callable import sqlalchemy.orm -from ..world import World -from ..world_object import Object as WorldObject +from pycram.world import World +from pycram.worlds.concepts.world_object import Object as WorldObject from ..designator import ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) -from ..pose import Pose +from pycram.worlds.datastructures.pose import Pose from ..external_interfaces.robokudo import query diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index 1d60c5a09..ce1afabec 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -1,22 +1,18 @@ import json import threading -import rosnode import rospy import sys import rosnode -import urdf_parser_py - -import traceback -from ..pose import Pose +from pycram.worlds.datastructures.pose import Pose from ..robot_descriptions import robot_description -from ..world import World -from ..world_dataclasses import MeshVisualShape -from ..world_object import Object +from pycram.world import World +from pycram.worlds.datastructures.dataclasses import MeshVisualShape +from pycram.worlds.concepts.world_object import Object from ..robot_description import ManipulatorDescription -from typing_extensions import List, Tuple, Dict, Callable, Optional +from typing_extensions import List, Dict, Callable, Optional from geometry_msgs.msg import PoseStamped, PointStamped, QuaternionStamped, Vector3Stamped from threading import Lock, RLock diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 2f1b2c184..c70a6469c 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -6,10 +6,10 @@ from moveit_msgs.srv import GetPositionIK from sensor_msgs.msg import JointState -from ..world_object import Object +from pycram.worlds.concepts.world_object import Object from ..helper import calculate_wrist_tool_offset, _apply_ik -from ..local_transformer import LocalTransformer -from ..pose import Pose +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose from ..robot_descriptions import robot_description from ..plan_failures import IKError diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index 0497c04f1..531c0eb6f 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -1,16 +1,15 @@ import sys from typing_extensions import Callable -import rosnode import rospy import actionlib import rosnode from ..designator import ObjectDesignatorDescription -from ..pose import Pose -from ..local_transformer import LocalTransformer -from ..world import World -from ..enums import ObjectType +from pycram.worlds.datastructures.pose import Pose +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.world import World +from pycram.worlds.datastructures.enums import ObjectType try: from robokudo_msgs.msg import ObjectDesignator as robokudo_ObjetDesignator diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 3b07ce6e3..0da52632a 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -13,8 +13,8 @@ from pytransform3d.rotations import quaternion_wxyz_from_xyzw, quaternion_xyzw_from_wxyz from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform -from .world_object import Object as WorldObject -from .pose import Transform, Pose +from pycram.worlds.concepts.world_object import Object as WorldObject +from pycram.worlds.datastructures.pose import Transform, Pose import math diff --git a/src/pycram/language.py b/src/pycram/language.py index 80948cc8d..310f8ce1b 100644 --- a/src/pycram/language.py +++ b/src/pycram/language.py @@ -3,9 +3,9 @@ import time from typing_extensions import Iterable, Optional, Callable, Dict, Any, List, Union -from anytree import NodeMixin, Node, PreOrderIter, RenderTree +from anytree import NodeMixin, Node, PreOrderIter -from .enums import State +from pycram.worlds.datastructures.enums import State import threading from .fluent import Fluent diff --git a/src/pycram/object_descriptors/__init__.py b/src/pycram/object_descriptors/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/urdf_interface.py b/src/pycram/object_descriptors/urdf.py similarity index 98% rename from src/pycram/urdf_interface.py rename to src/pycram/object_descriptors/urdf.py index 4dc1abe11..b2905e170 100644 --- a/src/pycram/urdf_interface.py +++ b/src/pycram/object_descriptors/urdf.py @@ -10,11 +10,11 @@ from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, Sphere as URDF_Sphere, Mesh as URDF_Mesh) -from .enums import JointType, Shape -from .pose import Pose -from .description import JointDescription as AbstractJointDescription, \ +from pycram.worlds.datastructures.enums import JointType, Shape +from pycram.worlds.datastructures.pose import Pose +from pycram.description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription -from .world_dataclasses import Color +from pycram.worlds.datastructures.dataclasses import Color class LinkDescription(AbstractLinkDescription): diff --git a/src/pycram/orm/action_designator.py b/src/pycram/orm/action_designator.py index d27642cf7..7bbaa0525 100644 --- a/src/pycram/orm/action_designator.py +++ b/src/pycram/orm/action_designator.py @@ -2,7 +2,7 @@ from .base import RobotState, Designator, MapperArgsMixin, PoseMixin from .object_designator import ObjectMixin -from ..enums import Arms +from pycram.worlds.datastructures.enums import Arms from sqlalchemy.orm import Mapped, mapped_column, relationship from sqlalchemy import ForeignKey diff --git a/src/pycram/orm/base.py b/src/pycram/orm/base.py index 407270a17..61a6ab39a 100644 --- a/src/pycram/orm/base.py +++ b/src/pycram/orm/base.py @@ -10,7 +10,7 @@ from sqlalchemy.orm import DeclarativeBase, Mapped, MappedAsDataclass, mapped_column, Session, relationship, \ declared_attr -from ..enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType def get_pycram_version_from_git() -> Optional[str]: diff --git a/src/pycram/orm/motion_designator.py b/src/pycram/orm/motion_designator.py index 44624d33d..af67aeb9e 100644 --- a/src/pycram/orm/motion_designator.py +++ b/src/pycram/orm/motion_designator.py @@ -8,11 +8,11 @@ from typing_extensions import Optional from .base import MapperArgsMixin, Designator, PoseMixin -from .object_designator import Object, ObjectMixin +from .object_designator import Object from sqlalchemy.orm import Mapped, mapped_column, relationship from sqlalchemy import ForeignKey -from ..enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType class Motion(MapperArgsMixin, Designator): diff --git a/src/pycram/orm/object_designator.py b/src/pycram/orm/object_designator.py index fad1d3c6e..776ab59ce 100644 --- a/src/pycram/orm/object_designator.py +++ b/src/pycram/orm/object_designator.py @@ -2,7 +2,7 @@ from pycram.orm.base import Base, MapperArgsMixin, PoseMixin from sqlalchemy.orm import Mapped, mapped_column, declared_attr, relationship from sqlalchemy import ForeignKey -from ..enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType class ObjectMixin: """ diff --git a/src/pycram/orm/task.py b/src/pycram/orm/task.py index 333bd5d8e..d821a2a5d 100644 --- a/src/pycram/orm/task.py +++ b/src/pycram/orm/task.py @@ -1,11 +1,9 @@ """Implementation of ORM classes associated with pycram.task.""" from typing_extensions import Optional from sqlalchemy import ForeignKey -from sqlalchemy.orm import MappedAsDataclass, Mapped, mapped_column, relationship -from .action_designator import Action +from sqlalchemy.orm import Mapped, mapped_column, relationship from .base import Base, Designator -from .motion_designator import Motion -from ..enums import TaskStatus +from pycram.worlds.datastructures.enums import TaskStatus import datetime diff --git a/src/pycram/orm/utils.py b/src/pycram/orm/utils.py index 5efe3a2e6..624773a88 100644 --- a/src/pycram/orm/utils.py +++ b/src/pycram/orm/utils.py @@ -1,17 +1,11 @@ import traceback -from anytree import Node, RenderTree, LevelOrderIter import rospy import sqlalchemy import pycram.orm.base -from pycram.designators.action_designator import * from pycram.designators.object_designator import * import json from pycram.designators.action_designator import * -from pycram.designators.location_designator import * -from pycram.process_module import simulated_robot -from pycram.enums import Arms, ObjectType -from pycram.task import with_tree import pycram.orm diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 994ff234d..96f1bf26f 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -1,15 +1,15 @@ import tf import numpy as np -from .world import World -from .world_object import Object -from .world_reasoning import contact -from .costmaps import Costmap -from .pose import Pose, Transform -from .robot_descriptions import robot_description -from .external_interfaces.ik import request_ik -from .plan_failures import IKError -from .helper import _apply_ik +from pycram.world import World +from pycram.worlds.concepts.world_object import Object +from pycram.world_reasoning import contact +from pycram.worlds.concepts.costmaps import Costmap +from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.robot_descriptions import robot_description +from pycram.external_interfaces.ik import request_ik +from pycram.plan_failures import IKError +from pycram.helper import _apply_ik from typing_extensions import Tuple, List, Union, Dict, Iterable diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 3b4fa4698..f0aecef08 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -2,14 +2,13 @@ import numpy as np -from ..world import World +from pycram.world import World from ..designators.motion_designator import PlaceMotion -from ..local_transformer import LocalTransformer +from pycram.worlds.datastructures.local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description from ..process_modules.pr2_process_modules import (_park_arms, Pr2Navigation as BoxyNavigation, - Pr2PickUp as BoxyPickUp, Pr2Open as BoxyOpen, - Pr2Close as BoxyClose, Pr2Detecting as BoxyDetecting, + Pr2PickUp as BoxyPickUp, Pr2Detecting as BoxyDetecting, Pr2MoveTCP as BoxyMoveTCP, Pr2MoveArmJoints as BoxyMoveArmJoints, Pr2WorldStateDetecting as BoxyWorldStateDetecting, _move_arm_tcp) diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 19faebb29..8993b10d2 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -8,8 +8,8 @@ Pr2Close as DefaultClose, Pr2MoveGripper as DefaultMoveGripper, Pr2Detecting as DefaultDetecting, \ Pr2MoveTCP as DefaultMoveTCP from ..robot_descriptions import robot_description -from ..world import World -from ..local_transformer import LocalTransformer +from pycram.world import World +from pycram.worlds.datastructures.local_transformer import LocalTransformer from ..designators.motion_designator import LookingMotion, MoveArmJointsMotion, MoveJointsMotion diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 5833d0513..41a8704b9 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -3,9 +3,9 @@ import numpy as np from typing_extensions import Optional -from ..bullet_world import World +from pycram.worlds.bullet_world import World from ..designators.motion_designator import MoveArmJointsMotion, WorldStateDetectingMotion -from ..local_transformer import LocalTransformer +from pycram.worlds.datastructures.local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description from ..process_modules.pr2_process_modules import Pr2PickUp, Pr2Detecting as DonbotDetecting, _move_arm_tcp diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 0b4e11512..75cb82e72 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -3,8 +3,8 @@ from typing_extensions import Optional from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager -from ..world import World -from ..pose import Pose, Point +from pycram.world import World +from pycram.worlds.datastructures.pose import Pose, Point from ..helper import _apply_ik from ..external_interfaces.ik import request_ik from .. import world_reasoning as btr diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 34e367404..204b3d1b8 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -12,16 +12,16 @@ from ..process_module import ProcessModule, ProcessModuleManager from ..external_interfaces.ik import request_ik from ..helper import _apply_ik -from ..local_transformer import LocalTransformer +from pycram.worlds.datastructures.local_transformer import LocalTransformer from ..designators.object_designator import ObjectDesignatorDescription from ..designators.motion_designator import MoveMotion, PickUpMotion, PlaceMotion, LookingMotion, \ DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ MoveGripperMotion, OpeningMotion, ClosingMotion, MotionDesignatorDescription from ..robot_descriptions import robot_description -from ..world import World -from ..world_object import Object -from ..pose import Pose -from ..enums import JointType, ObjectType +from pycram.world import World +from pycram.worlds.concepts.world_object import Object +from pycram.worlds.datastructures.pose import Pose +from pycram.worlds.datastructures.enums import JointType, ObjectType from ..external_interfaces import giskard from ..external_interfaces.robokudo import query diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index f8bb9ef96..4c205bbbb 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -4,14 +4,14 @@ from tf import transformations import pycram.designators.location_designator import pycram.task -from pycram.costmaps import OccupancyCostmap -from pycram.orm.action_designator import PickUpAction, Action +from pycram.worlds.concepts.costmaps import OccupancyCostmap +from pycram.orm.action_designator import PickUpAction from pycram.orm.object_designator import Object -from pycram.orm.base import Position, RobotState, Designator, Base +from pycram.orm.base import Position, RobotState from pycram.orm.task import TaskTreeNode, Code from .jpt_location import JPTCostmapLocation from ... import orm -from ...pose import Pose +from pycram.worlds.datastructures.pose import Pose class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation): diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index add24a41c..506e3503c 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,9 +1,9 @@ from ...external_interfaces.giskard import achieve_cartesian_goal from ...designators.location_designator import CostmapLocation -from ...world import UseProspectionWorld, World -from ...pose import Pose +from pycram.world import UseProspectionWorld, World +from pycram.worlds.datastructures.pose import Pose from ...robot_descriptions import robot_description -from ...pose_generator_and_validator import reachability_validator +from pycram.pose_generator_and_validator import reachability_validator from typing_extensions import Tuple, Dict import tf diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 5161ee014..73aa3a6f7 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -6,10 +6,10 @@ import tf from ...designators import location_designator -from ...costmaps import OccupancyCostmap -from ...pose import Pose -from ...world import Object, World -from ...world_dataclasses import BoxVisualShape, Color +from pycram.worlds.concepts.costmaps import OccupancyCostmap +from pycram.worlds.datastructures.pose import Pose +from pycram.world import Object, World +from pycram.worlds.datastructures.dataclasses import BoxVisualShape, Color class JPTCostmapLocation(location_designator.CostmapLocation): diff --git a/src/pycram/robot_description.py b/src/pycram/robot_description.py index 795330b90..462777364 100644 --- a/src/pycram/robot_description.py +++ b/src/pycram/robot_description.py @@ -139,7 +139,7 @@ class ManipulatorDescription(InteractionDescription): This class allows with the given interaction description to include a gripper description which is placed between the last link of the interaction description and the rest of it. - Independently from that a tool frame can be saved, which allows to use objects + Independently of that a tool frame can be saved, which allows to use objects to manipulate the environment:: |--> (tool_frame) diff --git a/src/pycram/ros/force_torque_sensor.py b/src/pycram/ros/force_torque_sensor.py index b2d07b2c6..aee3b8f46 100644 --- a/src/pycram/ros/force_torque_sensor.py +++ b/src/pycram/ros/force_torque_sensor.py @@ -6,7 +6,7 @@ from geometry_msgs.msg import WrenchStamped from std_msgs.msg import Header -from ..world import World +from pycram.world import World class ForceTorqueSensor: diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index 75e4c084c..45f89bf54 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -6,7 +6,7 @@ from sensor_msgs.msg import JointState from std_msgs.msg import Header -from ..world import World +from pycram.world import World class JointStatePublisher: diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index 93ab7ecce..e1400fb5b 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -5,9 +5,9 @@ from geometry_msgs.msg import TransformStamped from sensor_msgs.msg import JointState -from ..world import World +from pycram.world import World from ..robot_descriptions import robot_description -from ..pose import Pose +from pycram.worlds.datastructures.pose import Pose class RobotStateUpdater: diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index a727e75bb..c698f9b8b 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -3,8 +3,8 @@ import threading import atexit -from ..pose import Pose -from ..world import World +from pycram.worlds.datastructures.pose import Pose +from pycram.world import World from tf2_msgs.msg import TFMessage diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 8213b1b73..317af4724 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -5,13 +5,12 @@ from geometry_msgs.msg import Vector3 from std_msgs.msg import ColorRGBA -from ..world import World +from pycram.world import World from visualization_msgs.msg import MarkerArray, Marker import rospy -import urdf_parser_py -from pycram.pose import Transform -from ..world_dataclasses import MeshVisualShape, CylinderVisualShape, BoxVisualShape, SphereVisualShape +from pycram.worlds.datastructures.pose import Transform +from pycram.worlds.datastructures.dataclasses import MeshVisualShape, CylinderVisualShape, BoxVisualShape, SphereVisualShape class VizMarkerPublisher: diff --git a/src/pycram/task.py b/src/pycram/task.py index b8baacbe0..de870493f 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -13,13 +13,13 @@ import sqlalchemy.orm.session import tqdm -from .world import World +from pycram.world import World from .orm.task import (Code as ORMCode, TaskTreeNode as ORMTaskTreeNode) from .orm.base import ProcessMetaData from .plan_failures import PlanFailure from .language import Code -from .enums import TaskStatus -from .world_dataclasses import Color +from pycram.worlds.datastructures.enums import TaskStatus +from pycram.worlds.datastructures.dataclasses import Color class TaskCode(Code): diff --git a/src/pycram/world.py b/src/pycram/world.py index 722325501..3df891777 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -14,20 +14,20 @@ from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING from typing_extensions import Union -from .cache_manager import CacheManager -from .enums import JointType, ObjectType, WorldMode -from .event import Event -from .local_transformer import LocalTransformer -from .pose import Pose, Transform -from .world_constraints import Constraint -from .world_dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, - MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, - CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, - ObjectState, State, WorldState) +from pycram.worlds.concepts.cache_manager import CacheManager +from pycram.worlds.datastructures.enums import JointType, ObjectType, WorldMode +from pycram.worlds.concepts.event import Event +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.worlds.concepts.constraints import Constraint +from pycram.worlds.datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, + MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, + CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, + ObjectState, State, WorldState) if TYPE_CHECKING: - from .world_object import Object - from .description import Link, Joint + from pycram.worlds.concepts.world_object import Object + from pycram.description import Link, Joint class StateEntity: diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 2e9103084..27111daa7 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -3,11 +3,11 @@ import numpy as np -from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp -from .pose import Pose, Transform -from .robot_descriptions import robot_description -from .world_object import Object -from .world import World, UseProspectionWorld +from pycram.external_interfaces.ik import try_to_reach, try_to_reach_with_grasp +from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.robot_descriptions import robot_description +from pycram.worlds.concepts.world_object import Object +from pycram.world import World, UseProspectionWorld def stable(obj: Object) -> bool: diff --git a/src/pycram/worlds/__init__.py b/src/pycram/worlds/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/bullet_world.py b/src/pycram/worlds/bullet_world.py similarity index 98% rename from src/pycram/bullet_world.py rename to src/pycram/worlds/bullet_world.py index 15d1cf329..addb57190 100755 --- a/src/pycram/bullet_world.py +++ b/src/pycram/worlds/bullet_world.py @@ -11,13 +11,13 @@ from geometry_msgs.msg import Point from typing_extensions import List, Optional, Dict -from .enums import ObjectType, WorldMode, JointType -from .pose import Pose -from .urdf_interface import ObjectDescription -from .world import World -from .world_constraints import Constraint -from .world_dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape -from .world_object import Object +from pycram.worlds.datastructures.enums import ObjectType, WorldMode, JointType +from pycram.worlds.datastructures.pose import Pose +from pycram.object_descriptors.urdf import ObjectDescription +from pycram.world import World +from pycram.worlds.concepts.constraints import Constraint +from pycram.worlds.datastructures.dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape +from pycram.worlds.concepts.world_object import Object Link = ObjectDescription.Link RootLink = ObjectDescription.RootLink diff --git a/src/pycram/worlds/concepts/__init__.py b/src/pycram/worlds/concepts/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/cache_manager.py b/src/pycram/worlds/concepts/cache_manager.py similarity index 99% rename from src/pycram/cache_manager.py rename to src/pycram/worlds/concepts/cache_manager.py index 2dc479d8d..a8995636b 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/worlds/concepts/cache_manager.py @@ -1,11 +1,10 @@ import os import pathlib -import re from typing_extensions import List, TYPE_CHECKING if TYPE_CHECKING: - from .description import ObjectDescription + from pycram.description import ObjectDescription class CacheManager: diff --git a/src/pycram/world_constraints.py b/src/pycram/worlds/concepts/constraints.py similarity index 98% rename from src/pycram/world_constraints.py rename to src/pycram/worlds/concepts/constraints.py index 6dc75e33b..c36b733a2 100644 --- a/src/pycram/world_constraints.py +++ b/src/pycram/worlds/concepts/constraints.py @@ -3,11 +3,11 @@ from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional, TYPE_CHECKING -from .enums import JointType -from .pose import Transform, Pose +from pycram.worlds.datastructures.enums import JointType +from pycram.worlds.datastructures.pose import Transform, Pose if TYPE_CHECKING: - from .description import Link + from pycram.description import Link class AbstractConstraint: diff --git a/src/pycram/costmaps.py b/src/pycram/worlds/concepts/costmaps.py similarity index 98% rename from src/pycram/costmaps.py rename to src/pycram/worlds/concepts/costmaps.py index 01b9820db..8411e5fa0 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/worlds/concepts/costmaps.py @@ -10,13 +10,13 @@ from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData -from .world import UseProspectionWorld -from .world_object import Object -from .description import Link -from .local_transformer import LocalTransformer -from .pose import Pose, Transform -from .world import World -from .world_dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color +from pycram.world import UseProspectionWorld +from pycram.worlds.concepts.world_object import Object +from pycram.description import Link +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.world import World +from pycram.worlds.datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color class Costmap: diff --git a/src/pycram/event.py b/src/pycram/worlds/concepts/event.py similarity index 100% rename from src/pycram/event.py rename to src/pycram/worlds/concepts/event.py diff --git a/src/pycram/world_object.py b/src/pycram/worlds/concepts/world_object.py similarity index 97% rename from src/pycram/world_object.py rename to src/pycram/worlds/concepts/world_object.py index 55d15890a..71b05579c 100644 --- a/src/pycram/world_object.py +++ b/src/pycram/worlds/concepts/world_object.py @@ -8,15 +8,16 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Type, Optional, Dict, Tuple, List, Union -from .enums import ObjectType, JointType -from .local_transformer import LocalTransformer -from .pose import Pose, Transform -from .robot_descriptions import robot_description -from .world import WorldEntity, World -from .world_constraints import Attachment -from .world_dataclasses import Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape -from .description import ObjectDescription, LinkDescription -from .urdf_interface import ObjectDescription as URDF +from pycram.description import ObjectDescription, LinkDescription +from pycram.object_descriptors.urdf import ObjectDescription as URDFObject +from pycram.robot_descriptions import robot_description +from pycram.world import WorldEntity, World +from pycram.worlds.concepts.constraints import Attachment +from pycram.worlds.datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, + AxisAlignedBoundingBox, VisualShape) +from pycram.worlds.datastructures.enums import ObjectType, JointType +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose, Transform Link = ObjectDescription.Link @@ -33,7 +34,7 @@ class Object(WorldEntity): """ def __init__(self, name: str, obj_type: ObjectType, path: str, - description: Optional[Type[ObjectDescription]] = URDF, + description: Optional[Type[ObjectDescription]] = URDFObject, pose: Optional[Pose] = None, world: Optional[World] = None, color: Optional[Color] = Color(), @@ -119,9 +120,15 @@ def _load_object_and_get_id(self, path: Optional[str] = None, raise e try: - obj_id = self.world.load_object_and_get_id(path, Pose(self.get_position_as_list(), - self.get_orientation_as_list())) + simulator_object_path = path + if simulator_object_path is None: + # This is useful when the object is already loaded in the simulator so it would use its name instead of + # its path + simulator_object_path = self.name + obj_id = self.world.load_object_and_get_id(simulator_object_path, Pose(self.get_position_as_list(), + self.get_orientation_as_list())) return obj_id, path + except Exception as e: logging.error( "The File could not be loaded. Please note that the path has to be either a URDF, stl or obj file or" diff --git a/src/pycram/worlds/datastructures/__init__.py b/src/pycram/worlds/datastructures/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/world_dataclasses.py b/src/pycram/worlds/datastructures/dataclasses.py similarity index 96% rename from src/pycram/world_dataclasses.py rename to src/pycram/worlds/datastructures/dataclasses.py index 7aea14338..c41a41b50 100644 --- a/src/pycram/world_dataclasses.py +++ b/src/pycram/worlds/datastructures/dataclasses.py @@ -2,14 +2,14 @@ from dataclasses import dataclass from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING -from .enums import JointType, Shape -from .pose import Pose, Point +from pycram.worlds.datastructures.enums import JointType, Shape +from pycram.worlds.datastructures.pose import Pose, Point from abc import ABC, abstractmethod if TYPE_CHECKING: - from .description import Link - from .world_object import Object - from .world_constraints import Attachment + from pycram.description import Link + from pycram.worlds.concepts.world_object import Object + from pycram.worlds.concepts.constraints import Attachment def get_point_as_list(point: Point) -> List[float]: diff --git a/src/pycram/enums.py b/src/pycram/worlds/datastructures/enums.py similarity index 100% rename from src/pycram/enums.py rename to src/pycram/worlds/datastructures/enums.py diff --git a/src/pycram/local_transformer.py b/src/pycram/worlds/datastructures/local_transformer.py similarity index 98% rename from src/pycram/local_transformer.py rename to src/pycram/worlds/datastructures/local_transformer.py index 3ea74dea2..635a6fa38 100644 --- a/src/pycram/local_transformer.py +++ b/src/pycram/worlds/datastructures/local_transformer.py @@ -9,7 +9,7 @@ from rospy import Duration from geometry_msgs.msg import TransformStamped -from .pose import Pose, Transform +from pycram.worlds.datastructures.pose import Pose, Transform from typing_extensions import List, Optional, Union, Iterable diff --git a/src/pycram/pose.py b/src/pycram/worlds/datastructures/pose.py similarity index 99% rename from src/pycram/pose.py rename to src/pycram/worlds/datastructures/pose.py index 74bda8b8d..79eadaeef 100644 --- a/src/pycram/pose.py +++ b/src/pycram/worlds/datastructures/pose.py @@ -11,7 +11,7 @@ from geometry_msgs.msg import PoseStamped, TransformStamped, Vector3, Point from geometry_msgs.msg import (Pose as GeoPose, Quaternion as GeoQuaternion) from tf import transformations -from .orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData +from pycram.orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData def get_normalized_quaternion(quaternion: np.ndarray) -> GeoQuaternion: diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 525832ba6..46144af36 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -1,13 +1,13 @@ import time import unittest -from pycram.bullet_world import BulletWorld -from pycram.world_object import Object -from pycram.pose import Pose +from pycram.worlds.bullet_world import BulletWorld +from pycram.worlds.concepts.world_object import Object +from pycram.worlds.datastructures.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule -from pycram.enums import ObjectType, WorldMode -from pycram.urdf_interface import ObjectDescription +from pycram.worlds.datastructures.enums import ObjectType, WorldMode +from pycram.object_descriptors.urdf import ObjectDescription class BulletWorldTestCase(unittest.TestCase): diff --git a/test/test_action_designator.py b/test/test_action_designator.py index d972aa0c0..656df74b8 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -2,9 +2,8 @@ from pycram.designators import action_designator, object_designator from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot -from pycram.pose import Pose -from pycram.enums import ObjectType -import pycram.enums +from pycram.worlds.datastructures.pose import Pose +from pycram.worlds.datastructures.enums import ObjectType, Arms from bullet_world_testcase import BulletWorldTestCase import numpy as np @@ -42,8 +41,8 @@ def test_grip(self): self.assertEqual(description.ground().object_designator.name, "milk") def test_park_arms(self): - description = action_designator.ParkArmsAction([pycram.enums.Arms.BOTH]) - self.assertEqual(description.ground().arm, pycram.enums.Arms.BOTH) + description = action_designator.ParkArmsAction([Arms.BOTH]) + self.assertEqual(description.ground().arm, Arms.BOTH) with simulated_robot: description.resolve().perform() for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 059c27f8d..058adb0c4 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -5,12 +5,12 @@ import rospkg from bullet_world_testcase import BulletWorldTestCase, BulletWorldGUITestCase -from pycram.enums import ObjectType, WorldMode -from pycram.pose import Pose +from pycram.worlds.datastructures.enums import ObjectType, WorldMode +from pycram.worlds.datastructures.pose import Pose from pycram.robot_descriptions import robot_description -from pycram.urdf_interface import ObjectDescription -from pycram.world_dataclasses import Color -from pycram.world_object import Object +from pycram.object_descriptors.urdf import ObjectDescription +from pycram.worlds.datastructures.dataclasses import Color +from pycram.worlds.concepts.world_object import Object fix_missing_inertial = ObjectDescription.fix_missing_inertial diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index db81af34f..4438d37ce 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -2,7 +2,7 @@ import pycram.world_reasoning as btr from bullet_world_testcase import BulletWorldTestCase -from pycram.pose import Pose +from pycram.worlds.datastructures.pose import Pose from pycram.robot_descriptions import robot_description use_new = True diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py index 3df0e3484..ef126f2eb 100644 --- a/test/test_cache_manager.py +++ b/test/test_cache_manager.py @@ -1,9 +1,8 @@ from pathlib import Path from bullet_world_testcase import BulletWorldTestCase -from pycram.enums import ObjectType -from pycram.urdf_interface import ObjectDescription -from pycram.world_object import Object +from pycram.worlds.datastructures.enums import ObjectType +from pycram.worlds.concepts.world_object import Object class TestCacheManager(BulletWorldTestCase): diff --git a/test/test_costmaps.py b/test/test_costmaps.py index ba8c855ff..1bffb32c2 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -1,8 +1,8 @@ import numpy as np from bullet_world_testcase import BulletWorldTestCase -from pycram.costmaps import OccupancyCostmap -from pycram.pose import Pose +from pycram.worlds.concepts.costmaps import OccupancyCostmap +from pycram.worlds.datastructures.pose import Pose class TestCostmapsCase(BulletWorldTestCase): diff --git a/test/test_database_merger.py b/test/test_database_merger.py index 6ed3faaf2..fbe396431 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -8,11 +8,11 @@ from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.process_module import simulated_robot -from pycram.enums import Arms, ObjectType, WorldMode +from pycram.worlds.datastructures.enums import Arms, ObjectType, WorldMode from pycram.task import with_tree import pycram.task -from pycram.bullet_world import BulletWorld -from pycram.world_object import Object +from pycram.worlds.bullet_world import BulletWorld +from pycram.worlds.concepts.world_object import Object from pycram.designators.object_designator import * from dataclasses import dataclass, field diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 31f4cc28d..2809396d2 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -3,17 +3,17 @@ import sqlalchemy import sqlalchemy.orm import pycram.plan_failures -from pycram.world_object import Object +from pycram.worlds.concepts.world_object import Object from pycram import task from pycram.world import World from pycram.designators import action_designator, object_designator from pycram.orm.base import Base from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot -from pycram.pose import Pose +from pycram.worlds.datastructures.pose import Pose from pycram.robot_descriptions import robot_description from pycram.task import with_tree -from pycram.enums import ObjectType, WorldMode +from pycram.worlds.datastructures.enums import ObjectType, WorldMode # check if jpt is installed jpt_installed = True diff --git a/test/test_failure_handling.py b/test/test_failure_handling.py index cc9e7fd5e..bd7f36258 100644 --- a/test/test_failure_handling.py +++ b/test/test_failure_handling.py @@ -2,15 +2,15 @@ import roslaunch -from pycram.bullet_world import BulletWorld, Object +from pycram.worlds.bullet_world import BulletWorld, Object from pycram.designator import ActionDesignatorDescription from pycram.designators.action_designator import ParkArmsAction -from pycram.enums import ObjectType, Arms, WorldMode +from pycram.worlds.datastructures.enums import ObjectType, Arms, WorldMode from pycram.failure_handling import Retry from pycram.plan_failures import PlanFailure from pycram.process_module import ProcessModule, simulated_robot from pycram.robot_descriptions import robot_description -from pycram.urdf_interface import ObjectDescription +from pycram.object_descriptors.urdf import ObjectDescription extension = ObjectDescription.get_file_extension() diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index b03319785..534d6e4e3 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -5,14 +5,14 @@ import requests import pycram.plan_failures -from pycram.bullet_world import BulletWorld -from pycram.world_object import Object +from pycram.worlds.bullet_world import BulletWorld +from pycram.worlds.concepts.world_object import Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description -from pycram.pose import Pose -from pycram.enums import WorldMode +from pycram.worlds.datastructures.pose import Pose +from pycram.worlds.datastructures.enums import WorldMode # check if jpt is installed jpt_installed = True diff --git a/test/test_language.py b/test/test_language.py index 94cff57a3..458fbe0ac 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -2,11 +2,11 @@ import time import unittest from pycram.designators.action_designator import * -from pycram.enums import ObjectType, State +from pycram.worlds.datastructures.enums import ObjectType, State from pycram.fluent import Fluent from pycram.plan_failures import PlanFailure -from pycram.pose import Pose -from pycram.language import Sequential, Language, Parallel, TryAll, TryInOrder, Monitor, Repeat, Code, RenderTree +from pycram.worlds.datastructures.pose import Pose +from pycram.language import Sequential, Language, Parallel, TryAll, TryInOrder, Monitor, Code from pycram.process_module import simulated_robot from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_links.py b/test/test_links.py index af26bb39e..f737a55ce 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -1,7 +1,5 @@ -import time - from bullet_world_testcase import BulletWorldTestCase -from pycram.world_dataclasses import Color +from pycram.worlds.datastructures.dataclasses import Color class TestLinks(BulletWorldTestCase): diff --git a/test/test_local_transformer.py b/test/test_local_transformer.py index 4cad086e7..afaac7a71 100644 --- a/test/test_local_transformer.py +++ b/test/test_local_transformer.py @@ -1,8 +1,8 @@ import rospy -from pycram.local_transformer import LocalTransformer -from pycram.pose import Pose, Transform +from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.worlds.datastructures.pose import Pose, Transform from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_location_designator.py b/test/test_location_designator.py index 11ea179c0..54860a746 100644 --- a/test/test_location_designator.py +++ b/test/test_location_designator.py @@ -1,10 +1,6 @@ -import unittest from pycram.designators.location_designator import * -from pycram.designators import action_designator, object_designator from pycram.robot_descriptions import robot_description -from pycram.process_module import simulated_robot -from pycram.pose import Pose -import pycram.enums +from pycram.worlds.datastructures.pose import Pose from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_object.py b/test/test_object.py index 9ef50883c..d0c0ee12b 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -1,14 +1,11 @@ -import os - import numpy as np from bullet_world_testcase import BulletWorldTestCase -from pycram.enums import JointType, ObjectType -from pycram.pose import Pose -from pycram.world_dataclasses import Color -from pycram.world_object import Object -from pycram.urdf_interface import ObjectDescription +from pycram.worlds.datastructures.enums import JointType, ObjectType +from pycram.worlds.datastructures.pose import Pose +from pycram.worlds.datastructures.dataclasses import Color +from pycram.worlds.concepts.world_object import Object from geometry_msgs.msg import Point, Quaternion diff --git a/test/test_object_designator.py b/test/test_object_designator.py index f203a514d..695fc6b84 100644 --- a/test/test_object_designator.py +++ b/test/test_object_designator.py @@ -1,7 +1,7 @@ import unittest from bullet_world_testcase import BulletWorldTestCase from pycram.designators.object_designator import * -from pycram.enums import ObjectType +from pycram.worlds.datastructures.enums import ObjectType class TestObjectDesignator(BulletWorldTestCase): diff --git a/test/test_orm.py b/test/test_orm.py index ceec18c5d..f8697b78e 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -1,4 +1,3 @@ -import os import unittest import sqlalchemy @@ -14,7 +13,7 @@ from bullet_world_testcase import BulletWorldTestCase import test_task_tree from pycram.designators import action_designator, object_designator -from pycram.pose import Pose +from pycram.worlds.datastructures.pose import Pose from pycram.process_module import simulated_robot from pycram.task import with_tree diff --git a/test/test_pose.py b/test/test_pose.py index 97064a56d..c6ce5a63e 100644 --- a/test/test_pose.py +++ b/test/test_pose.py @@ -1,6 +1,6 @@ import unittest -from pycram.pose import Pose, Transform +from pycram.worlds.datastructures.pose import Pose, Transform class TestPose(unittest.TestCase): diff --git a/test/test_task_tree.py b/test/test_task_tree.py index 36d994663..ee06fd717 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -1,4 +1,4 @@ -from pycram.pose import Pose +from pycram.worlds.datastructures.pose import Pose from pycram.process_module import simulated_robot import pycram.task from pycram.task import with_tree From dfd48cd08594022282714d5f1173e5351e1a3c31 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Sun, 3 Mar 2024 16:55:30 +0100 Subject: [PATCH 100/195] [resolver] fixed querying from occupancy costmap II --- .../resolver/location/database_location.py | 70 ++++++------ test/test_database_resolver.py | 104 +++++++++++++++--- 2 files changed, 125 insertions(+), 49 deletions(-) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index c0427de82..1d0b056ff 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -2,16 +2,14 @@ import sqlalchemy.orm import sqlalchemy.sql from sqlalchemy import select, Select -from tf import transformations import pycram.designators.location_designator import pycram.task from pycram.costmaps import OccupancyCostmap from pycram.orm.action_designator import PickUpAction, Action from pycram.orm.object_designator import Object -from pycram.orm.base import Position, RobotState, Designator, Base +from pycram.orm.base import Position, RobotState, Pose as ORMPose, Quaternion from pycram.orm.task import TaskTreeNode, Code from .jpt_location import JPTCostmapLocation -from ... import orm from ...pose import Pose @@ -42,26 +40,31 @@ def create_query_from_occupancy_costmap(self) -> Select: """ robot_pos = sqlalchemy.orm.aliased(Position) + robot_pose = sqlalchemy.orm.aliased(ORMPose) + object_pos = sqlalchemy.orm.aliased(Position) + relative_x = robot_pos.x - object_pos.x + relative_y = robot_pos.y - object_pos.y # query all relative robot positions in regard to an objects position # make sure to order the joins() correctly - query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, robot_pos.x, robot_pos.y) + query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, relative_x, relative_y, + Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() .join(TaskTreeNode.code) .join(Code.designator.of_type(PickUpAction)) .join(PickUpAction.robot_state) - .join(RobotState.pose) - .join(robot_pos) - .join(PickUpAction.object).where(Object.type == self.target.type) - .where(TaskTreeNode.status == "SUCCEEDED")) + .join(robot_pose, RobotState.pose) + .join(robot_pos, robot_pose.position) + .join(ORMPose.orientation) + .join(PickUpAction.object) + .join(Object.pose) + .join(object_pos, ORMPose.position).where(Object.type == self.target.type) + .where(TaskTreeNode.status == "SUCCEEDED")) # create Occupancy costmap for the target object - position, orientation = self.target.pose.to_list() - position = list(position) - position[-1] = 0 ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, - origin=Pose(position, orientation)) - # ocm.visualize() + origin=self.target.pose) + ocm.visualize() # working on a copy of the costmap, since found rectangles are deleted map = np.copy(ocm.map) @@ -70,29 +73,22 @@ def create_query_from_occupancy_costmap(self) -> Select: filters = [] - # for every index pair (i, j) in the occupancy map for i in range(0, map.shape[0]): for j in range(0, map.shape[1]): - - # if this index has not been used yet if map[i][j] > 0: - # get consecutive box - width = ocm._find_consectuive_line((i, j), map) - height = ocm._find_max_box_height((i, j), width, map) + curr_width = ocm._find_consectuive_line((i, j), map) + curr_pose = (i, j) + curr_height = ocm._find_max_box_height((i, j), curr_width, map) - # mark box as used - map[i:i + height, j:j + width] = 0 + x_lower = (curr_pose[0] - origin[0]) * ocm.resolution + x_upper = (curr_pose[0] + curr_width - origin[0]) * ocm.resolution + y_lower = (curr_pose[1] - origin[1]) * ocm.resolution + y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution - # calculate to coordinates relative to the objects pose - pose = np.array([i, j]) - lower_corner = (pose - origin) * ocm.resolution - upper_corner = (pose - origin + np.array([height, width])) * ocm.resolution - rectangle = np.array([lower_corner, upper_corner]).T + map[i:i + curr_height, j:j + curr_width] = 0 - # transform to jpt query - filters.append(sqlalchemy.and_(robot_pos.x >= rectangle[0][0], robot_pos.x < rectangle[0][1], - robot_pos.y >= rectangle[1][0], robot_pos.y < rectangle[1][1])) - # query = self.model.bind({"x": list(rectangle[0]), "y": list(rectangle[1])}) + filters.append(sqlalchemy.and_(relative_x >= x_lower, relative_x < x_upper, + relative_y >= y_lower, relative_y < y_upper)) return query.where(sqlalchemy.or_(*filters)) @@ -104,15 +100,17 @@ def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLoc :return: The costmap location """ target_x, target_y, target_z = self.target.pose.position_as_list() - pose = [target_x + sample.x, target_y + sample.y, 0] - angle = np.arctan2(pose[1] - target_y, pose[0] - target_x) + np.pi - orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) + position = [target_x + sample[3], target_y + sample[4], 0] + orientation = [sample[5], sample[6], sample[7], sample[8]] - result = JPTCostmapLocation.Location(Pose(pose, orientation), sample.arm, sample.torso_height, sample.grasp) + result = JPTCostmapLocation.Location(Pose(position, orientation), sample.arm, sample.torso_height, sample.grasp) return result def __iter__(self) -> JPTCostmapLocation.Location: statement = self.create_query_from_occupancy_costmap().limit(200) samples = self.session.execute(statement).all() - for sample in samples: - yield self.sample_to_location(sample) + if samples: + for sample in samples: + yield self.sample_to_location(sample) + else: + raise ValueError("No samples found") diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index e03f6d5db..cc78537f4 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -7,7 +7,7 @@ from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ - NavigateActionPerformable + NavigateActionPerformable, PlaceActionPerformable from pycram.orm.base import Base from pycram.designators.object_designator import ObjectDesignatorDescription from pycram.process_module import ProcessModule @@ -88,31 +88,109 @@ def test_costmap_no_obstacles(self): sample = next(iter(cml)) with simulated_robot: - # action_designator.NavigateAction.Action(sample.pose).perform() MoveTorsoActionPerformable(sample.torso_height).perform() PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() - @unittest.skip def test_costmap_with_obstacles(self): kitchen = Object("kitchen", "environment", "kitchen.urdf") + self.plan() + pycram.orm.base.ProcessMetaData().description = "costmap_with_obstacles_test" + pycram.task.task_tree.root.insert(self.session) + self.world.reset_bullet_world() + + cml = DatabaseCostmapLocation(self.milk, self.session, reachable_for=self.robot) + sample = next(iter(cml)) + + with simulated_robot: + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() + try: + PickUpActionPerformable( + ObjectDesignatorDescription(types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + except pycram.plan_failures.PlanFailure as p: + kitchen.remove() + raise p + kitchen.remove() + + def test_object_at_different_location(self): + kitchen = Object("kitchen", "environment", "kitchen.urdf") + self.plan() + + pycram.orm.base.ProcessMetaData().description = "object_at_different_location_test" + pycram.task.task_tree.root.insert(self.session) + self.world.reset_bullet_world() + + new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + cml = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) + + sample = next(iter(cml)) + with simulated_robot: + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() + try: + PickUpActionPerformable( + ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + except pycram.plan_failures.PlanFailure as p: + new_milk.remove() + kitchen.remove() + raise p + PlaceActionPerformable(ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + arm=sample.reachable_arm, target_location=Pose([-1.45, 2.5, 0.95])).perform() + new_milk.remove() + kitchen.remove() + + def test_multiple_objects(self): + kitchen = Object("kitchen", "environment", "kitchen.urdf") + new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.9])) + + object_description = ObjectDesignatorDescription(names=["milk"]) + object_description_new_milk = ObjectDesignatorDescription(names=["new_milk"]) + description = action_designator.PlaceAction(object_description_new_milk, [Pose([-1.45, 2.5, 0.9], [0, 0, 0, 1])], ["left"]) + with simulated_robot: + NavigateActionPerformable(Pose([1, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + PlaceActionPerformable(object_description.resolve(), "left", Pose([1.3, 1, 0.9], [0, 0, 0, 1])).perform() + NavigateActionPerformable(Pose([-1.75, 1.9, 0], [0, 0, 0, 1])).perform() + PickUpActionPerformable(object_description_new_milk.resolve(), "left", "front").perform() + description.resolve().perform() + + pycram.orm.base.ProcessMetaData().description = "multiple_objects_test" + pycram.task.task_tree.root.insert(self.session) + self.world.reset_bullet_world() cml = DatabaseCostmapLocation(self.milk, self.session, reachable_for=self.robot) + cml_new_milk = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) - for i in range(20): - sample = next(iter(cml)) - with simulated_robot: + dcls = [cml, cml_new_milk] + for dcl in dcls: + sample = next(iter(dcl)) + with (simulated_robot): NavigateActionPerformable(sample.pose).perform() MoveTorsoActionPerformable(sample.torso_height).perform() try: - PickUpActionPerformable( - ObjectDesignatorDescription(types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() - except pycram.plan_failures.PlanFailure: - continue - return + if dcl.target.name == "milk": + PickUpActionPerformable( + ObjectDesignatorDescription(names=["milk"], types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + else: + PickUpActionPerformable( + ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + except pycram.plan_failures.PlanFailure as p: + new_milk.remove() + kitchen.remove() + raise p + PlaceActionPerformable(ObjectDesignatorDescription(names=[dcl.target.name], types=["milk"]).resolve(), + arm=sample.reachable_arm, target_location=Pose([dcl.target.pose.position.x, + dcl.target.pose.position.y, + dcl.target.pose.position.z]) + ).perform() + new_milk.remove() kitchen.remove() - raise pycram.plan_failures.PlanFailure() if __name__ == '__main__': From f118e7d14715a164aeb2d72af1297855f95061db Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Sun, 3 Mar 2024 17:20:56 +0100 Subject: [PATCH 101/195] [resolver] updated DatabaseCostmapLocation documentation --- src/pycram/resolver/location/database_location.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 1d0b056ff..9fcbce9fb 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -5,7 +5,7 @@ import pycram.designators.location_designator import pycram.task from pycram.costmaps import OccupancyCostmap -from pycram.orm.action_designator import PickUpAction, Action +from pycram.orm.action_designator import PickUpAction from pycram.orm.object_designator import Object from pycram.orm.base import Position, RobotState, Pose as ORMPose, Quaternion from pycram.orm.task import TaskTreeNode, Code @@ -39,9 +39,12 @@ def create_query_from_occupancy_costmap(self) -> Select: OccupancyCostmap. """ + # create aliases for the Position and Pose tables, since they are used multiple times robot_pos = sqlalchemy.orm.aliased(Position) robot_pose = sqlalchemy.orm.aliased(ORMPose) object_pos = sqlalchemy.orm.aliased(Position) + + # calculate the relative position of the robot to the object relative_x = robot_pos.x - object_pos.x relative_y = robot_pos.y - object_pos.y @@ -61,10 +64,8 @@ def create_query_from_occupancy_costmap(self) -> Select: .where(TaskTreeNode.status == "SUCCEEDED")) # create Occupancy costmap for the target object - ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, origin=self.target.pose) - ocm.visualize() # working on a copy of the costmap, since found rectangles are deleted map = np.copy(ocm.map) @@ -73,20 +74,26 @@ def create_query_from_occupancy_costmap(self) -> Select: filters = [] + # for every index pair (i, j) in the occupancy costmap for i in range(0, map.shape[0]): for j in range(0, map.shape[1]): + + # if this index has not been used yet if map[i][j] > 0: curr_width = ocm._find_consectuive_line((i, j), map) curr_pose = (i, j) curr_height = ocm._find_max_box_height((i, j), curr_width, map) + # calculate the rectangle in the costmap x_lower = (curr_pose[0] - origin[0]) * ocm.resolution x_upper = (curr_pose[0] + curr_width - origin[0]) * ocm.resolution y_lower = (curr_pose[1] - origin[1]) * ocm.resolution y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution + # mark the found rectangle as occupied map[i:i + curr_height, j:j + curr_width] = 0 + # transform to jpt query filters.append(sqlalchemy.and_(relative_x >= x_lower, relative_x < x_upper, relative_y >= y_lower, relative_y < y_upper)) @@ -99,6 +106,7 @@ def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLoc :param sample: The database row. :return: The costmap location """ + target_x, target_y, target_z = self.target.pose.position_as_list() position = [target_x + sample[3], target_y + sample[4], 0] orientation = [sample[5], sample[6], sample[7], sample[8]] From 833b15840db145e3efda96a47dd3413ed3acdbca Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 5 Mar 2024 10:50:45 +0100 Subject: [PATCH 102/195] [ROS] fixed bullet world reference in VizMarkerPublisher --- src/pycram/ros/viz_marker_publisher.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 52bfe879c..b36773f1a 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -18,6 +18,7 @@ class VizMarkerPublisher: """ Publishes an Array of visualization marker which represent the situation in the Bullet World """ + def __init__(self, topic_name="/pycram/viz_marker", interval=0.1): """ The Publisher creates an Array of Visualization marker with a Marker for each link of each Object in the Bullet @@ -33,8 +34,9 @@ def __init__(self, topic_name="/pycram/viz_marker", interval=0.1): self.thread = threading.Thread(target=self._publish) self.kill_event = threading.Event() - self.thread.start() + self.main_world = BulletWorld.current_bullet_world if not BulletWorld.current_bullet_world.is_shadow_world else BulletWorld.current_bullet_world.world_sync.world + self.thread.start() atexit.register(self._stop_publishing) def _publish(self) -> None: @@ -56,7 +58,7 @@ def _make_marker_array(self) -> MarkerArray: :return: An Array of Visualization Marker """ marker_array = MarkerArray() - for obj in BulletWorld.current_bullet_world.objects: + for obj in self.main_world.objects: if obj.name == "floor": continue for link in obj.links.keys(): @@ -72,7 +74,8 @@ def _make_marker_array(self) -> MarkerArray: link_pose = obj.get_link_pose(link).to_transform(link) if obj.urdf_object.link_map[link].collision.origin: link_origin = Transform(obj.urdf_object.link_map[link].collision.origin.xyz, - list(quaternion_from_euler(*obj.urdf_object.link_map[link].collision.origin.rpy))) + list(quaternion_from_euler( + *obj.urdf_object.link_map[link].collision.origin.rpy))) else: link_origin = Transform() link_pose_with_origin = link_pose * link_origin @@ -107,4 +110,3 @@ def _stop_publishing(self) -> None: """ self.kill_event.set() self.thread.join() - From 0f7cea4d89c375cca4281af16caaef08b1a045f5 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 5 Mar 2024 17:25:30 +0100 Subject: [PATCH 103/195] [Costmaps] Started to refactor JPT and Database costmaps. --- examples/custom_resolver.ipynb | 257 +++++++++--------- .../resolver/location/database_location.py | 106 +++++--- src/pycram/resolver/location/jpt_location.py | 67 +++-- test/test_database_resolver.py | 1 + test/test_jpt_resolver.py | 121 ++++----- 5 files changed, 315 insertions(+), 237 deletions(-) diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb index ef4413897..55f1f8161 100644 --- a/examples/custom_resolver.ipynb +++ b/examples/custom_resolver.ipynb @@ -20,58 +20,44 @@ }, { "cell_type": "code", - "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:05:37.443271489Z", - "start_time": "2024-01-29T16:05:35.328010988Z" + "end_time": "2024-03-05T13:45:12.736132Z", + "start_time": "2024-03-05T13:45:11.708013Z" } }, + "source": [ + "!pip install --upgrade probabilistic_model" + ], "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Requirement already up-to-date: probabilistic_model in /home/dprueser/.local/lib/python3.8/site-packages (1.6.20)\r\n", - "Requirement already satisfied, skipping upgrade: random-events>=1.2.5 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", - "Requirement already satisfied, skipping upgrade: anytree>=2.9.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.9.0)\r\n", - "Requirement already satisfied, skipping upgrade: portion>=2.4.1 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (2.4.1)\r\n", - "Requirement already satisfied, skipping upgrade: plotly>=5.18.0 in /home/dprueser/.local/lib/python3.8/site-packages (from probabilistic_model) (5.18.0)\r\n", - "Requirement already satisfied, skipping upgrade: six in /usr/local/lib/python3.8/dist-packages (from anytree>=2.9.0->probabilistic_model) (1.16.0)\r\n", - "Requirement already satisfied, skipping upgrade: sortedcontainers~=2.2 in /home/dprueser/.local/lib/python3.8/site-packages (from portion>=2.4.1->probabilistic_model) (2.4.0)\r\n", - "Requirement already satisfied, skipping upgrade: tenacity>=6.2.0 in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (8.2.3)\r\n", - "Requirement already satisfied, skipping upgrade: packaging in /home/dprueser/.local/lib/python3.8/site-packages (from plotly>=5.18.0->probabilistic_model) (23.2)\r\n" + "Requirement already satisfied: probabilistic_model in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (3.3.3)\r\n", + "Requirement already satisfied: random-events>=1.2.5 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", + "Requirement already satisfied: networkx>=3.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (3.1)\r\n", + "Requirement already satisfied: portion>=2.4.2 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (2.4.2)\r\n", + "Requirement already satisfied: plotly>=5.19.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (5.19.0)\r\n", + "Requirement already satisfied: scipy>=1.10.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.10.1)\r\n", + "Requirement already satisfied: typing-extensions>=4.9.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (4.10.0)\r\n", + "Requirement already satisfied: numpy>=1.24.4 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.24.4)\r\n", + "Requirement already satisfied: tenacity>=6.2.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from plotly>=5.19.0->probabilistic_model) (8.2.2)\r\n", + "Requirement already satisfied: packaging in /usr/lib/python3/dist-packages (from plotly>=5.19.0->probabilistic_model) (20.3)\r\n", + "Requirement already satisfied: sortedcontainers~=2.2 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from portion>=2.4.2->probabilistic_model) (2.4.0)\r\n" ] } ], - "source": [ - "!pip install --upgrade probabilistic_model" - ] + "execution_count": 1 }, { "cell_type": "code", - "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:05:38.648889392Z", - "start_time": "2024-01-29T16:05:37.442437872Z" + "end_time": "2024-03-05T13:45:14.170210Z", + "start_time": "2024-03-05T13:45:12.740951Z" } }, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "pybullet build time: May 20 2022 19:44:17\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1706544338.060994]: Failed to import Giskard messages\n", - "[WARN] [1706544338.065403]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" - ] - } - ], "source": [ "from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable\n", "from tf import transformations\n", @@ -97,6 +83,8 @@ "import sqlalchemy.sql\n", "import pandas as pd\n", "from pycram.pose import Pose\n", + "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", + " \n", "\n", "np.random.seed(420)\n", "\n", @@ -154,8 +142,11 @@ " # create progress bar\n", " progress_bar = tqdm.tqdm(\n", " total=np.prod([len(p) for p in self.hyper_parameters]) * self.samples_per_scenario)\n", - " \n", + "\n", " self.world = BulletWorld(\"DIRECT\")\n", + " \n", + " v = VizMarkerPublisher()\n", + "\n", "\n", " # for every robot\n", " for robot, robot_urdf in self.robots:\n", @@ -226,7 +217,21 @@ " robot.remove()\n", "\n", " self.world.exit()" - ] + ], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1709646313.790492]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + ] + } + ], + "execution_count": 2 }, { "cell_type": "markdown", @@ -238,14 +243,22 @@ }, { "cell_type": "code", - "execution_count": 3, "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-01-29T16:07:21.351710589Z", - "start_time": "2024-01-29T16:05:38.643086881Z" + "end_time": "2024-03-05T13:47:04.916953Z", + "start_time": "2024-03-05T13:45:14.170956Z" } }, + "source": [ + "engine = sqlalchemy.create_engine(\"sqlite+pysqlite:///:memory:\")\n", + "session = sqlalchemy.orm.Session(bind=engine)\n", + "pycram.orm.base.Base.metadata.create_all(bind=engine)\n", + "session.commit()\n", + "\n", + "explorer = GraspingExplorer(samples_per_scenario=30)\n", + "explorer.perform(session)" + ], "outputs": [ { "name": "stderr", @@ -263,21 +276,11 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - " 96%|█████████▌| 923/960 [01:38<00:03, 9.52it/s, success_rate=0.0845]Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame spoon_2 (parent map) at time 1706544437.280444 according to authority default_authority\n", - " at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp\n", - "100%|██████████| 960/960 [01:42<00:00, 10.12it/s, success_rate=0.0854]" + "100%|██████████| 960/960 [01:50<00:00, 9.53it/s, success_rate=0.0854]" ] } ], - "source": [ - "engine = sqlalchemy.create_engine(\"sqlite+pysqlite:///:memory:\")\n", - "session = sqlalchemy.orm.Session(bind=engine)\n", - "pycram.orm.base.Base.metadata.create_all(bind=engine)\n", - "session.commit()\n", - "\n", - "explorer = GraspingExplorer(samples_per_scenario=30)\n", - "explorer.perform(session)" - ] + "execution_count": 3 }, { "cell_type": "markdown", @@ -288,14 +291,12 @@ }, { "cell_type": "code", - "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:07:21.445516208Z", - "start_time": "2024-01-29T16:07:21.396046276Z" + "end_time": "2024-03-05T13:47:05.027887Z", + "start_time": "2024-03-05T13:47:04.920018Z" } }, - "outputs": [], "source": [ "import os\n", "con = engine.raw_connection()\n", @@ -303,7 +304,9 @@ "with open(os.path.join(os.path. expanduser('~'), \"Documents\", \"costmap.dump\"), 'w') as f:\n", " for line in con.iterdump():\n", " f.write('%s\\n' % line)" - ] + ], + "outputs": [], + "execution_count": 4 }, { "cell_type": "markdown", @@ -314,15 +317,13 @@ }, { "cell_type": "code", - "execution_count": 5, "metadata": { "scrolled": true, "ExecuteTime": { - "end_time": "2024-01-29T16:07:21.541375696Z", - "start_time": "2024-01-29T16:07:21.448402324Z" + "end_time": "2024-03-05T13:47:05.175078Z", + "start_time": "2024-03-05T13:47:05.028832Z" } }, - "outputs": [], "source": [ "import os\n", "\n", @@ -336,7 +337,9 @@ " raw_connection = engine.raw_connection()\n", " # raw_cursor = raw_connection()\n", " raw_connection.executescript(file.read())" - ] + ], + "outputs": [], + "execution_count": 5 }, { "cell_type": "markdown", @@ -354,14 +357,40 @@ }, { "cell_type": "code", - "execution_count": 6, "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-01-29T16:07:21.605599589Z", - "start_time": "2024-01-29T16:07:21.552928567Z" + "end_time": "2024-03-05T13:47:05.196323Z", + "start_time": "2024-03-05T13:47:05.175819Z" } }, + "source": [ + "from sqlalchemy import select\n", + "from pycram.orm.base import Pose as ORMPose\n", + "\n", + "robot_pose = sqlalchemy.orm.aliased(ORMPose)\n", + "object_pose = sqlalchemy.orm.aliased(ORMPose)\n", + "robot_pos = sqlalchemy.orm.aliased(Position)\n", + "object_pos = sqlalchemy.orm.aliased(Position)\n", + "\n", + "query = (select(TaskTreeNode.status, Object.type, ORMPickUpAction.arm, ORMPickUpAction.grasp,\n", + " sqlalchemy.label(\"relative torso height\", object_pos.z - RobotState.torso_height),\n", + " sqlalchemy.label(\"x\", robot_pos.x - object_pos.x), \n", + " sqlalchemy.label(\"y\", robot_pos.y - object_pos.y))\n", + " .join(TaskTreeNode.code)\n", + " .join(Code.designator.of_type(ORMPickUpAction))\n", + " .join(ORMPickUpAction.robot_state)\n", + " .join(robot_pose, RobotState.pose)\n", + " .join(robot_pos, robot_pose.position)\n", + " .join(ORMPickUpAction.object)\n", + " .join(object_pose, Object.pose)\n", + " .join(object_pos, object_pose.position))\n", + "print(query)\n", + "\n", + "df = pd.read_sql(query, session.get_bind())\n", + "df[\"status\"] = df[\"status\"].apply(lambda x: str(x.name))\n", + "print(df)" + ], "outputs": [ { "name": "stdout", @@ -399,33 +428,7 @@ ] } ], - "source": [ - "from sqlalchemy import select\n", - "from pycram.orm.base import Pose as ORMPose\n", - "\n", - "robot_pose = sqlalchemy.orm.aliased(ORMPose)\n", - "object_pose = sqlalchemy.orm.aliased(ORMPose)\n", - "robot_pos = sqlalchemy.orm.aliased(Position)\n", - "object_pos = sqlalchemy.orm.aliased(Position)\n", - "\n", - "query = (select(TaskTreeNode.status, Object.type, ORMPickUpAction.arm, ORMPickUpAction.grasp,\n", - " sqlalchemy.label(\"relative torso height\", object_pos.z - RobotState.torso_height),\n", - " sqlalchemy.label(\"x\", robot_pos.x - object_pos.x), \n", - " sqlalchemy.label(\"y\", robot_pos.y - object_pos.y))\n", - " .join(TaskTreeNode.code)\n", - " .join(Code.designator.of_type(ORMPickUpAction))\n", - " .join(ORMPickUpAction.robot_state)\n", - " .join(robot_pose, RobotState.pose)\n", - " .join(robot_pos, robot_pose.position)\n", - " .join(ORMPickUpAction.object)\n", - " .join(object_pose, Object.pose)\n", - " .join(object_pos, object_pose.position))\n", - "print(query)\n", - "\n", - "df = pd.read_sql(query, session.get_bind())\n", - "df[\"status\"] = df[\"status\"].apply(lambda x: str(x.name))\n", - "print(df)" - ] + "execution_count": 6 }, { "cell_type": "markdown", @@ -436,19 +439,25 @@ }, { "cell_type": "code", - "execution_count": 7, "metadata": { "ExecuteTime": { - "end_time": "2024-01-29T16:07:21.939517021Z", - "start_time": "2024-01-29T16:07:21.601075366Z" + "end_time": "2024-03-05T13:47:05.494943Z", + "start_time": "2024-03-05T13:47:05.197022Z" } }, + "source": [ + "import jpt\n", + "\n", + "model = jpt.trees.JPT(variables=jpt.infer_from_dataframe(df, scale_numeric_types=False, precision=0.05),\n", + " min_samples_leaf=10, min_impurity_improvement=0.01)\n", + "model.fit(df)" + ], "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ - "100%|██████████| 960/960 [01:43<00:00, 9.32it/s, success_rate=0.0854]\n" + "100%|██████████| 960/960 [01:51<00:00, 8.63it/s, success_rate=0.0854]\n" ] }, { @@ -460,13 +469,7 @@ "output_type": "execute_result" } ], - "source": [ - "import jpt\n", - "\n", - "model = jpt.trees.JPT(variables=jpt.infer_from_dataframe(df, scale_numeric_types=False, precision=0.05),\n", - " min_samples_leaf=10, min_impurity_improvement=0.01)\n", - "model.fit(df)" - ] + "execution_count": 7 }, { "cell_type": "markdown", @@ -477,34 +480,13 @@ }, { "cell_type": "code", - "execution_count": 8, "metadata": { "collapsed": false, + "is_executing": true, "ExecuteTime": { - "end_time": "2024-01-29T16:13:01.579305735Z", - "start_time": "2024-01-29T16:07:21.942920319Z" + "start_time": "2024-03-05T13:47:05.495621Z" } }, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" - ] - } - ], "source": [ "from pycram.designators.actions.actions import NavigateActionPerformable, PickUpActionPerformable\n", "from pycram.resolver import JPTCostmapLocation\n", @@ -531,7 +513,28 @@ " continue\n", " break\n", "world.exit()" - ] + ], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" + ] + } + ], + "execution_count": null }, { "cell_type": "markdown", @@ -544,9 +547,9 @@ ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "pycram", "language": "python", - "name": "python3" + "name": "pycram" }, "language_info": { "codemirror_mode": { diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 9fcbce9fb..3474ab862 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -1,19 +1,79 @@ +from dataclasses import dataclass + import numpy as np import sqlalchemy.orm import sqlalchemy.sql -from sqlalchemy import select, Select +from sqlalchemy import select, Select, join +from sqlalchemy.sql.elements import BinaryExpression + +from typing_extensions import Tuple + import pycram.designators.location_designator import pycram.task from pycram.costmaps import OccupancyCostmap -from pycram.orm.action_designator import PickUpAction +from pycram.orm.action_designator import PickUpAction, Action from pycram.orm.object_designator import Object from pycram.orm.base import Position, RobotState, Pose as ORMPose, Quaternion from pycram.orm.task import TaskTreeNode, Code -from .jpt_location import JPTCostmapLocation from ...pose import Pose -class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation): +@dataclass +class Location(pycram.designators.location_designator.LocationDesignatorDescription.Location): + """ + A location that is described by a pose, a reachable arm, a torso height and a grasp. + """ + pose: Pose + reachable_arm: str + torso_height: float + grasp: str + + +class RequiresDatabase: + """ + Mixin class that provides a database session. + """ + + robot_pos = sqlalchemy.orm.aliased(Position) + """3D Vector of robot position""" + robot_pose = sqlalchemy.orm.aliased(ORMPose) + object_pos = sqlalchemy.orm.aliased(Position) + relative_x = robot_pos.x - object_pos.x + relative_y = robot_pos.y - object_pos.y + + def __init__(self, session: sqlalchemy.orm.Session = None): + """ + Create a new RequiresDatabase instance. + + :param session: The database session + """ + self.session = session + + def create_query(self) -> Select: + """ + Create a query that queries the database for all pick up actions with context. + """ + + # query all relative robot positions in regard to an objects position + # make sure to order the joins() correctly + query = self.join_statement(self.select_statement()) + return query + + def select_statement(self): + return select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, self.relative_y, + Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() + def join_statement(self, query: Select): + return (query.join(TaskTreeNode.code). + join(Code.designator.of_type(PickUpAction)).join(PickUpAction.robot_state) + .join(self.robot_pose, RobotState.pose) + .join(self.robot_pos, self.robot_pose.position) + .join(ORMPose.orientation) + .join(PickUpAction.object) + .join(Object.pose) + .join(self.object_pos, ORMPose.position)) + + +class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation, RequiresDatabase): """ Class that represents costmap locations from a given Database. The database has to have a schema that is compatible with the pycram.orm package. @@ -31,7 +91,7 @@ def __init__(self, target, session: sqlalchemy.orm.Session = None, """ super().__init__(target, reachable_for, None, reachable_arm, resolver) - self.session = session + RequiresDatabase.__init__(self, session) def create_query_from_occupancy_costmap(self) -> Select: """ @@ -39,29 +99,11 @@ def create_query_from_occupancy_costmap(self) -> Select: OccupancyCostmap. """ - # create aliases for the Position and Pose tables, since they are used multiple times - robot_pos = sqlalchemy.orm.aliased(Position) - robot_pose = sqlalchemy.orm.aliased(ORMPose) - object_pos = sqlalchemy.orm.aliased(Position) + # get query + query = self.create_query() - # calculate the relative position of the robot to the object - relative_x = robot_pos.x - object_pos.x - relative_y = robot_pos.y - object_pos.y - - # query all relative robot positions in regard to an objects position - # make sure to order the joins() correctly - query = (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, relative_x, relative_y, - Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() - .join(TaskTreeNode.code) - .join(Code.designator.of_type(PickUpAction)) - .join(PickUpAction.robot_state) - .join(robot_pose, RobotState.pose) - .join(robot_pos, robot_pose.position) - .join(ORMPose.orientation) - .join(PickUpAction.object) - .join(Object.pose) - .join(object_pos, ORMPose.position).where(Object.type == self.target.type) - .where(TaskTreeNode.status == "SUCCEEDED")) + # constraint query to correct object type and successful task status + query = query.where(Object.type == self.target.type).where(TaskTreeNode.status == "SUCCEEDED") # create Occupancy costmap for the target object ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, @@ -94,12 +136,12 @@ def create_query_from_occupancy_costmap(self) -> Select: map[i:i + curr_height, j:j + curr_width] = 0 # transform to jpt query - filters.append(sqlalchemy.and_(relative_x >= x_lower, relative_x < x_upper, - relative_y >= y_lower, relative_y < y_upper)) + filters.append(sqlalchemy.and_(self.relative_x >= x_lower, self.relative_x < x_upper, + self.relative_y >= y_lower, self.relative_y < y_upper)) return query.where(sqlalchemy.or_(*filters)) - def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLocation.Location: + def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> Location: """ Convert a database row to a costmap location. @@ -111,10 +153,10 @@ def sample_to_location(self, sample: sqlalchemy.engine.row.Row) -> JPTCostmapLoc position = [target_x + sample[3], target_y + sample[4], 0] orientation = [sample[5], sample[6], sample[7], sample[8]] - result = JPTCostmapLocation.Location(Pose(position, orientation), sample.arm, sample.torso_height, sample.grasp) + result = Location(Pose(position, orientation), sample.arm, sample.torso_height, sample.grasp) return result - def __iter__(self) -> JPTCostmapLocation.Location: + def __iter__(self) -> Location: statement = self.create_query_from_occupancy_costmap().limit(200) samples = self.session.execute(statement).all() if samples: diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 2f728d14c..b84542c62 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -1,11 +1,18 @@ import dataclasses +import json import time from typing import Optional, List, Tuple -import jpt +import sqlalchemy +import sqlalchemy.orm + +from probabilistic_model.learning.jpt.jpt import JPT +from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe +from random_events.events import Event import numpy as np import pybullet import tf +from sqlalchemy import select import pycram.designators.location_designator import pycram.task @@ -14,23 +21,25 @@ from ...pose import Pose from pycram.bullet_world import BulletWorld, Object +from ...orm.action_designator import PickUpAction +from ...orm.object_designator import Object +from ...orm.base import Position, RobotState, Pose as ORMPose, Quaternion +from ...orm.task import TaskTreeNode, Code +from .database_location import Location, RequiresDatabase + +import pandas as pd -class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): - """Costmap Locations using Joint Probability Trees (JPTs). + +class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation, RequiresDatabase): + """ + Costmap Locations using Joint Probability Trees (JPTs). JPT costmaps are trained to model the dependency with a robot position relative to the object, the robots type, the objects type, the robot torso height, and the grasp parameters. Solutions to the problem definitions are chosen in such a way that the success probability is highest. """ - @dataclasses.dataclass - class Location(pycram.designators.location_designator.LocationDesignatorDescription.Location): - pose: Pose - reachable_arm: str - torso_height: float - grasp: str - def __init__(self, target: Object, reachable_for=None, reachable_arm=None, - model: Optional[jpt.trees.JPT] = None, path: Optional[str] = None, resolver=None): + model: Optional[JPT] = None, path: Optional[str] = None): """ Create a JPT Costmap @@ -40,7 +49,7 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, :param model: The JPT model as a loaded tree in memory, either model or path must be set :param path: The path to the JPT model, either model or path must be set """ - super().__init__(target, reachable_for, None, reachable_arm, resolver) + super().__init__(target, reachable_for, None, reachable_arm, None) # check if arguments are plausible if (not model and not path) or (model and path): raise ValueError("Either model or path must be set.") @@ -51,12 +60,36 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, # load model from path if path: - self.model = jpt.trees.JPT.load(path) + with open(path, "r") as f: + json_dict = json.load(f) + self.model = JPT.from_json(json_dict) # initialize member for visualized objects self.visual_ids: List[int] = [] + self.arm, self.grasp, self.relative_x, self.relative_y, self.torso_height, self.w, self.x, self.y, self.z = ( + self.model.variables) + + @classmethod + def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False): + """ + Fit a JPT to become a location designator using the data from the database that is reachable via the session. - def evidence_from_occupancy_costmap(self) -> List[jpt.variables.LabelAssignment]: + :param session: + :param success_only: + :return: + """ + query, _, _ = RequiresDatabase.create_query() + if success_only: + query = query.where(TaskTreeNode.status == "SUCCEEDED") + + samples = pd.read_sql(query, session.bind) + samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) + variables = infer_variables_from_dataframe(samples) + model = JPT(variables, min_samples_leaf=0.1) + model.fit(samples) + return model + + def evidence_from_occupancy_costmap(self) -> List[Event]: """ Create a list of boxes that can be used as evidences for a jpt. The list of boxes describe areas where the robot can stand. @@ -102,12 +135,12 @@ def evidence_from_occupancy_costmap(self) -> List[jpt.variables.LabelAssignment] rectangle = np.array([lower_corner, upper_corner]).T # transform to jpt query - query = self.model.bind({"x": list(rectangle[0]), "y": list(rectangle[1])}) + query = Event({self.x: list(rectangle[0]), self.y: list(rectangle[1])}) queries.append(query) return queries - def create_evidence(self, use_success=True) -> jpt.variables.LabelAssignment: + def create_evidence(self, use_success=True) -> Event: """ Create evidence usable for JPTs where type and status are set if wanted. @@ -121,7 +154,7 @@ def create_evidence(self, use_success=True) -> jpt.variables.LabelAssignment: if use_success: evidence["status"] = {"SUCCEEDED"} - return self.model.bind(evidence) + return evidence def sample(self, amount: int = 1) -> np.ndarray: """ diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index cc78537f4..4a298fe5d 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -1,4 +1,5 @@ import os +import time import unittest import sqlalchemy import sqlalchemy.orm diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 9979d4a62..e22c02369 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -1,9 +1,7 @@ import os import unittest -import numpy as np -import requests - +import enums import pycram.plan_failures from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator, object_designator @@ -13,90 +11,91 @@ from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description from pycram.pose import Pose +from pycram.enums import ObjectType +import pycram.orm +import pycram.task +from pycram.task import with_tree +from pycram.designators.object_designator import ObjectDesignatorDescription + +import sqlalchemy +import sqlalchemy.orm # check if jpt is installed jpt_installed = True try: - import jpt + from probabilistic_model.learning.jpt.jpt import JPT + from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe from pycram.resolver.location.jpt_location import JPTCostmapLocation except ImportError: jpt_installed = False -# check if mlflow is installed -mlflow_installed = True -try: - import mlflow -except ImportError: - mlflow_installed = False - -mlflow_uri = os.getenv('MLFLOW_TRACKING_URI') -if mlflow_uri is None: - mlflow_uri = "http://127.0.0.1:5000" - -try: - response = requests.get(mlflow_uri, timeout=2) -except requests.exceptions.ConnectionError: - response = None - - -@unittest.skipIf(response is None or (response.status_code != requests.codes.ok), "mlflow server is not available.") -@unittest.skipIf(not jpt_installed, "jpt is not installed. Install via 'pip install pyjpt'") -@unittest.skipIf(not mlflow_installed, "mlflow is not installed. Install via 'pip install mlflow'") +pycrorm_uri = os.getenv('PYCRORM_URI') +if pycrorm_uri: + pycrorm_uri = "mysql+pymysql://" + pycrorm_uri +@unittest.skipIf(not jpt_installed, "probabilistic model is not installed. " + "Install via 'pip install probabilistic_model") class JPTResolverTestCase(unittest.TestCase): world: BulletWorld milk: Object robot: Object - model: 'jpt.JPT' + engine: sqlalchemy.engine.Engine + session: sqlalchemy.orm.Session + model: JPT @classmethod def setUpClass(cls) -> None: - np.random.seed(420) - cls.model = mlflow.pyfunc.load_model( - model_uri="mlflow-artifacts:/0/9150dd1fb353494d807261928cea6e8c/artifacts/grasping").unwrap_python_model() \ - .model + global pycrorm_uri cls.world = BulletWorld("DIRECT") - cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([3, 3, 0.75])) - cls.robot = Object(robot_description.name, "pr2", robot_description.name + ".urdf") + cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False + cls.engine = sqlalchemy.create_engine(pycrorm_uri) - def test_costmap_no_obstacles(self): - """Check if grasping a milk in the air works.""" - cml = JPTCostmapLocation(self.milk, reachable_for=self.robot, model=self.model) - sample = next(iter(cml)) - - with simulated_robot: - NavigateActionPerformable(sample.pose).perform() - MoveTorsoActionPerformable(sample.torso_height).perform() - PickUpActionPerformable( - object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() - - def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") - self.milk.set_pose(Pose([-1.2, 1, 0.98])) - cml = JPTCostmapLocation(self.milk, reachable_for=self.robot, model=self.model) - - for i in range(20): - sample = next(iter(cml)) - with simulated_robot: - NavigateActionPerformable(sample.pose).perform() - MoveTorsoActionPerformable(sample.torso_height).perform() - try: - PickUpActionPerformable( - object_designator.ObjectDesignatorDescription(types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() - except pycram.plan_failures.PlanFailure: - continue - return - raise pycram.plan_failures.PlanFailure() + def setUp(self) -> None: + self.world.reset_bullet_world() + pycram.orm.base.Base.metadata.create_all(self.engine) + self.session = sqlalchemy.orm.Session(bind=self.engine) + self.session.commit() + self.learn_model() def tearDown(self) -> None: self.world.reset_bullet_world() + pycram.task.reset_tree() + pycram.orm.base.ProcessMetaData.reset() + self.session.rollback() + pycram.orm.base.Base.metadata.drop_all(self.engine) + self.session.close() @classmethod def tearDownClass(cls) -> None: cls.world.exit() + @with_tree + def plan(self): + object_description = ObjectDesignatorDescription(types=["milk"]) + description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) + with simulated_robot: + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + description.resolve().perform() + + def learn_model(self): + self.plan() + pycram.orm.base.ProcessMetaData().description = "costmap_no_obstacles_test" + pycram.task.task_tree.root.insert(self.session) + self.model = JPTCostmapLocation.fit_from_database(self.session) + + def test_costmap_no_obstacles(self): + """Check if grasping a milk in the air works.""" + cml = JPTCostmapLocation(self.milk, model=self.model) + sample = next(iter(cml)) + + with simulated_robot: + MoveTorsoActionPerformable(sample.torso_height).perform() + PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, + grasp=sample.grasp).perform() + if __name__ == '__main__': unittest.main() From 128e1d17f383ceb47ce0872614ebae95dc4c64be Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Wed, 6 Mar 2024 09:43:01 +0100 Subject: [PATCH 104/195] [Costmap] Refactored JPT Costmap Locations --- .../resolver/location/database_location.py | 16 +- src/pycram/resolver/location/jpt_location.py | 137 ++++++++---------- test/test_jpt_resolver.py | 2 +- 3 files changed, 68 insertions(+), 87 deletions(-) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 3474ab862..36d898618 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -63,14 +63,14 @@ def select_statement(self): return select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, self.relative_y, Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() def join_statement(self, query: Select): - return (query.join(TaskTreeNode.code). - join(Code.designator.of_type(PickUpAction)).join(PickUpAction.robot_state) - .join(self.robot_pose, RobotState.pose) - .join(self.robot_pos, self.robot_pose.position) - .join(ORMPose.orientation) - .join(PickUpAction.object) - .join(Object.pose) - .join(self.object_pos, ORMPose.position)) + return (query.join(TaskTreeNode.code).join(Code.designator.of_type(PickUpAction)). + join(PickUpAction.robot_state) + .join(self.robot_pose, RobotState.pose) + .join(self.robot_pos, self.robot_pose.position) + .join(ORMPose.orientation) + .join(PickUpAction.object) + .join(Object.pose) + .join(self.object_pos, ORMPose.position)) class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation, RequiresDatabase): diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index b84542c62..cda1a6c38 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -3,6 +3,7 @@ import time from typing import Optional, List, Tuple +import portion import sqlalchemy import sqlalchemy.orm @@ -11,7 +12,7 @@ from random_events.events import Event import numpy as np import pybullet -import tf +import tf.transformations from sqlalchemy import select import pycram.designators.location_designator @@ -26,11 +27,21 @@ from ...orm.base import Position, RobotState, Pose as ORMPose, Quaternion from ...orm.task import TaskTreeNode, Code from .database_location import Location, RequiresDatabase +from ...enums import TaskStatus import pandas as pd +from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit -class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation, RequiresDatabase): + +class QueryBuilder(RequiresDatabase): + + def select_statement(self): + return (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, + self.relative_y, TaskTreeNode.status)) + + +class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): """ Costmap Locations using Joint Probability Trees (JPTs). JPT costmaps are trained to model the dependency with a robot position relative to the object, the robots type, @@ -66,7 +77,7 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, # initialize member for visualized objects self.visual_ids: List[int] = [] - self.arm, self.grasp, self.relative_x, self.relative_y, self.torso_height, self.w, self.x, self.y, self.z = ( + self.arm, self.grasp, self.relative_x, self.relative_y, self.status, self.torso_height = ( self.model.variables) @classmethod @@ -78,18 +89,19 @@ def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only :param success_only: :return: """ - query, _, _ = RequiresDatabase.create_query() + query_builder = QueryBuilder(session) + query = query_builder.create_query() if success_only: - query = query.where(TaskTreeNode.status == "SUCCEEDED") + query = query.where(TaskTreeNode.status == TaskStatus.SUCCEEDED) samples = pd.read_sql(query, session.bind) samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) - variables = infer_variables_from_dataframe(samples) + variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) model = JPT(variables, min_samples_leaf=0.1) model.fit(samples) return model - def evidence_from_occupancy_costmap(self) -> List[Event]: + def events_from_occupancy_costmap(self) -> List[Event]: """ Create a list of boxes that can be used as evidences for a jpt. The list of boxes describe areas where the robot can stand. @@ -109,90 +121,55 @@ def evidence_from_occupancy_costmap(self) -> List[Event]: # working on a copy of the costmap, since found rectangles are deleted map = np.copy(ocm.map) - # initialize result - queries = [] + origin = np.array([ocm.height / 2, ocm.width / 2]) - origin = np.array([ocm.height/2, ocm.width/2]) + events = [] - # for every index pair (i, j) in the occupancy map + # for every index pair (i, j) in the occupancy costmap for i in range(0, map.shape[0]): for j in range(0, map.shape[1]): # if this index has not been used yet if map[i][j] > 0: + curr_width = ocm._find_consectuive_line((i, j), map) + curr_pose = (i, j) + curr_height = ocm._find_max_box_height((i, j), curr_width, map) - # get consecutive box - width = ocm._find_consectuive_line((i, j), map) - height = ocm._find_max_box_height((i, j), width, map) + # calculate the rectangle in the costmap + x_lower = (curr_pose[0] - origin[0]) * ocm.resolution + x_upper = (curr_pose[0] + curr_width - origin[0]) * ocm.resolution + y_lower = (curr_pose[1] - origin[1]) * ocm.resolution + y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution - # mark box as used - map[i:i+height, j:j+width] = 0 + # mark the found rectangle as occupied + map[i:i + curr_height, j:j + curr_width] = 0 - # calculate to coordinates relative to the objects pose - pose = np.array([i, j]) - lower_corner = (pose - origin) * ocm.resolution - upper_corner = (pose - origin + np.array([height, width])) * ocm.resolution - rectangle = np.array([lower_corner, upper_corner]).T + event = Event({self.relative_x: portion.closedopen(x_lower, x_upper), + self.relative_y: portion.closedopen(y_lower, y_upper)}) - # transform to jpt query - query = Event({self.x: list(rectangle[0]), self.y: list(rectangle[1])}) - queries.append(query) + events.append(event) - return queries + return events - def create_evidence(self, use_success=True) -> Event: + def ground_model(self) -> DeterministicSumUnit: """ - Create evidence usable for JPTs where type and status are set if wanted. - - :param use_success: Rather to set success or not - :return: The usable label-assignment + Ground the model to the current evidence. """ - evidence = dict() - - evidence["type"] = {self.target.type} - - if use_success: - evidence["status"] = {"SUCCEEDED"} - return evidence + locations = self.events_from_occupancy_costmap() - def sample(self, amount: int = 1) -> np.ndarray: - """ - Sample from the locations that fit the CostMap and are not occupied. + model = DeterministicSumUnit() - :param amount: The amount of samples to draw - :return: A numpy array containing the samples drawn from the tree. - """ - evidence = self.create_evidence() + for location in locations: + conditional, probability = self.model.conditional(location) + if probability > 0: + model.add_subcircuit(conditional, probability) - locations = self.evidence_from_occupancy_costmap() - solutions = [] + if len(model.subcircuits) == 0: + raise PlanFailure("No possible locations found") - for location in locations: - for variable, value in evidence.items(): - location[variable] = value - - for leaf in self.model.apply(location): - if leaf.probability(location) == 0: - continue - altered_leaf = leaf.conditional_leaf(location) - # success_probability = altered_leaf.probability(location) - success_probability = altered_leaf.probability(self.model.bind({"status": "SUCCEEDED"})) - - mpe_state, _ = altered_leaf.mpe(self.model.minimal_distances) - location["grasp"] = mpe_state["grasp"] - location["arm"] = mpe_state["arm"] - location["relative torso height"] = mpe_state["relative torso height"] - location["x"] = mpe_state["x"] - location["y"] = mpe_state["y"] - solutions.append((location, success_probability, leaf.prior)) - - solutions = sorted(solutions, key=lambda x: x[1], reverse=True) - best_solution = solutions[0] - conditional_model = self.model.conditional_jpt(best_solution[0]) - - # conditional_model.plot(plotvars=conditional_model.variables) - return conditional_model.sample(amount) + model.normalize() + return model def sample_to_location(self, sample: np.ndarray) -> Location: """ @@ -201,21 +178,25 @@ def sample_to_location(self, sample: np.ndarray) -> Location: :param sample: The drawn sample :return: The usable costmap-location """ - sample_dict = {variable.name: value for variable, value in zip(self.model.variables, sample)} + sample_dict = {variable: value for variable, value in zip(self.model.variables, sample)} target_x, target_y, target_z = self.target.pose.position_as_list() - pose = [target_x + sample_dict["x"], target_y + sample_dict["y"], 0] + pose = [target_x + sample_dict[self.relative_x], target_y + sample_dict[self.relative_y], 0] angle = np.arctan2(pose[1] - target_y, pose[0] - target_x) + np.pi orientation = list(tf.transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) - torso_height = np.clip(target_z - sample_dict["relative torso height"], 0, 0.33) - result = self.Location(Pose(pose, orientation), sample_dict["arm"], torso_height, sample_dict["grasp"]) + torso_height = np.clip(target_z - sample_dict[self.torso_height], 0, 0.33) + result = Location(Pose(pose, orientation), sample_dict[self.arm], torso_height, sample_dict[self.grasp]) return result def __iter__(self): - samples = self.sample(200) - for sample in samples: - yield self.sample_to_location(sample) + + model = self.ground_model() + + for _ in range(20): + sample = model.sample(1) + print(sample) + yield self.sample_to_location(sample[0]) def visualize(self): """ diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index e22c02369..545a36003 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -1,7 +1,6 @@ import os import unittest -import enums import pycram.plan_failures from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator, object_designator @@ -32,6 +31,7 @@ pycrorm_uri = os.getenv('PYCRORM_URI') if pycrorm_uri: pycrorm_uri = "mysql+pymysql://" + pycrorm_uri + @unittest.skipIf(not jpt_installed, "probabilistic model is not installed. " "Install via 'pip install probabilistic_model") class JPTResolverTestCase(unittest.TestCase): From 1ff82cb8acb778a7d6fa35cbebb6f994c519b588 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Wed, 6 Mar 2024 10:24:03 +0100 Subject: [PATCH 105/195] [Costmap] More tests for JPT Costmap locations. --- src/pycram/resolver/location/jpt_location.py | 11 ++--- test/test_jpt_resolver.py | 44 ++++++++++++++++++++ 2 files changed, 47 insertions(+), 8 deletions(-) diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index cda1a6c38..911e1fb3e 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -81,7 +81,7 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, self.model.variables) @classmethod - def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False): + def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False) -> JPT: """ Fit a JPT to become a location designator using the data from the database that is reachable via the session. @@ -93,7 +93,6 @@ def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only query = query_builder.create_query() if success_only: query = query.where(TaskTreeNode.status == TaskStatus.SUCCEEDED) - samples = pd.read_sql(query, session.bind) samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) @@ -181,11 +180,8 @@ def sample_to_location(self, sample: np.ndarray) -> Location: sample_dict = {variable: value for variable, value in zip(self.model.variables, sample)} target_x, target_y, target_z = self.target.pose.position_as_list() pose = [target_x + sample_dict[self.relative_x], target_y + sample_dict[self.relative_y], 0] - - angle = np.arctan2(pose[1] - target_y, pose[0] - target_x) + np.pi - - orientation = list(tf.transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) - torso_height = np.clip(target_z - sample_dict[self.torso_height], 0, 0.33) + orientation = [0, 0, 0, 1] + torso_height = sample_dict[self.torso_height] result = Location(Pose(pose, orientation), sample_dict[self.arm], torso_height, sample_dict[self.grasp]) return result @@ -195,7 +191,6 @@ def __iter__(self): for _ in range(20): sample = model.sample(1) - print(sample) yield self.sample_to_location(sample[0]) def visualize(self): diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 545a36003..521dccc0d 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -1,4 +1,5 @@ import os +import time import unittest import pycram.plan_failures @@ -15,6 +16,8 @@ import pycram.task from pycram.task import with_tree from pycram.designators.object_designator import ObjectDesignatorDescription +from pycram.ros.viz_marker_publisher import VizMarkerPublisher + import sqlalchemy import sqlalchemy.orm @@ -46,6 +49,7 @@ class JPTResolverTestCase(unittest.TestCase): def setUpClass(cls) -> None: global pycrorm_uri cls.world = BulletWorld("DIRECT") + # VizMarkerPublisher(interval=0.1) cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False @@ -96,6 +100,46 @@ def test_costmap_no_obstacles(self): PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() + def test_costmap_with_obstacles(self): + kitchen = Object("kitchen", "environment", "kitchen.urdf") + self.world.reset_bullet_world() + + cml = JPTCostmapLocation(self.milk, model=self.model) + sample = next(iter(cml)) + + with simulated_robot: + NavigateActionPerformable(sample.pose).perform() + + MoveTorsoActionPerformable(sample.torso_height).perform() + + try: + PickUpActionPerformable( + ObjectDesignatorDescription(types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + + except pycram.plan_failures.PlanFailure as p: + kitchen.remove() + raise p + kitchen.remove() + + def test_object_at_different_location(self): + kitchen = Object("kitchen", "environment", "kitchen.urdf") + self.world.reset_bullet_world() + + new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + cml = JPTCostmapLocation(new_milk, model=self.model) + + sample = next(iter(cml)) + with simulated_robot: + NavigateActionPerformable(sample.pose).perform() + MoveTorsoActionPerformable(sample.torso_height).perform() + try: + PickUpActionPerformable( + ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + arm=sample.reachable_arm, grasp=sample.grasp).perform() + except pycram.plan_failures.PlanFailure as p: + raise p + if __name__ == '__main__': unittest.main() From 682e7a32c85bd66fb62f25f654a849b8d14f74a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Wed, 6 Mar 2024 17:57:46 +0100 Subject: [PATCH 106/195] [designator] updated action designator documentation --- src/pycram/designators/actions/actions.py | 51 ++++++----------------- 1 file changed, 12 insertions(+), 39 deletions(-) diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index ff83245c1..71e781afc 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -36,13 +36,19 @@ class ActionAbstract(ActionDesignatorDescription.Action, abc.ABC): @abc.abstractmethod def perform(self) -> None: """ - Perform the action. Will be overwritten by each action. + Perform the action. + + Will be overwritten by each action. """ pass def to_sql(self) -> Action: """ - Convert this action to its ORM equivalent. Will be overwritten by each action. + Convert this action to its ORM equivalent. + + Needs to be overwritten by an action if it didn't overwrite the orm_class attribute with its ORM equivalent. + + :return: An instance of the ORM equivalent of the action with the parameters set """ # get all class parameters (ignore inherited ones) class_variables = {key: value for key, value in vars(self).items() @@ -62,9 +68,12 @@ def insert(self, session: Session, **kwargs) -> Action: """ Insert this action into the database. + Needs to be overwritten by an action if the action has attributes that do not exist in the orm class + equivalent. In that case, the attributes need to be inserted into the session manually. + :param session: Session with a database that is used to add and commit the objects :param kwargs: Possible extra keyword arguments - :return: The completely instanced ORM object + :return: The completely instanced ORM action that was inserted into the database """ action = super().insert(session) @@ -101,9 +110,6 @@ class MoveTorsoActionPerformable(ActionAbstract): Target position of the torso joint """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMMoveTorsoAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -125,9 +131,6 @@ class SetGripperActionPerformable(ActionAbstract): The motion that should be set on the gripper """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMSetGripperAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -178,9 +181,6 @@ class ParkArmsActionPerformable(ActionAbstract): Entry from the enum for which arm should be parked """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMParkArmsAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -229,9 +229,6 @@ class PickUpActionPerformable(ActionAbstract): not updated when the BulletWorld object is changed. """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMPickUpAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -319,9 +316,6 @@ class PlaceActionPerformable(ActionAbstract): Pose in the world at which the object should be placed """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMPlaceAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -355,9 +349,6 @@ class NavigateActionPerformable(ActionAbstract): Location to which the robot should be navigated """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMNavigateAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -383,9 +374,6 @@ class TransportActionPerformable(ActionAbstract): Target Location to which the object should be transported """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMTransportAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -428,9 +416,6 @@ class LookAtActionPerformable(ActionAbstract): Position at which the robot should look, given as 6D pose """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMLookAtAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -448,9 +433,6 @@ class DetectActionPerformable(ActionAbstract): Object designator loosely describing the object, e.g. only type. """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMDetectAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -472,9 +454,6 @@ class OpenActionPerformable(ActionAbstract): Arm that should be used for opening the container """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMOpenAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -499,9 +478,6 @@ class CloseActionPerformable(ActionAbstract): Arm that should be used for closing """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMCloseAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: @@ -526,9 +502,6 @@ class GraspingActionPerformable(ActionAbstract): Object Designator for the object that should be grasped """ orm_class: Type[ActionAbstract] = field(init=False, default=ORMGraspingAction) - """ - The ORM class that is used to insert this action into the database - """ @with_tree def perform(self) -> None: From 93a94dc82ec787f46004fa78de74d95d75532500 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Thu, 7 Mar 2024 13:50:46 +0100 Subject: [PATCH 107/195] [Task] Refactored task.py and remove the useless Code class. --- src/pycram/orm/task.py | 15 +- src/pycram/resolver/__init__.py | 1 - .../resolver/location/database_location.py | 162 +++++++++++------ src/pycram/resolver/location/jpt_location.py | 70 ++------ src/pycram/task.py | 168 +++++++----------- test/test_database_resolver.py | 12 +- test/test_orm.py | 13 +- test/test_task_tree.py | 23 ++- 8 files changed, 205 insertions(+), 259 deletions(-) diff --git a/src/pycram/orm/task.py b/src/pycram/orm/task.py index 5d2152c1f..9a5669890 100644 --- a/src/pycram/orm/task.py +++ b/src/pycram/orm/task.py @@ -13,22 +13,17 @@ class TaskTreeNode(Base): """ORM equivalent of pycram.task.TaskTreeNode.""" id: Mapped[int] = mapped_column(autoincrement=True, primary_key=True, init=False) - """id overriden in order to be able to set the remote_side of the parent attribute""" - code_id: Mapped[int] = mapped_column(ForeignKey("Code.id"), default=None) - code: Mapped["Code"] = relationship(init=False) + action_id: Mapped[Optional[int]] = mapped_column(ForeignKey(f'{Designator.__tablename__}.id'), default=None) + action: Mapped[Optional[Designator]] = relationship(init=False) + start_time: Mapped[datetime.datetime] = mapped_column(default=None) end_time: Mapped[Optional[datetime.datetime]] = mapped_column(default=None) + status: Mapped[TaskStatus] = mapped_column(default=None) reason: Mapped[Optional[str]] = mapped_column(default=None) + parent_id: Mapped[Optional[int]] = mapped_column(ForeignKey("TaskTreeNode.id"), default=None) parent: Mapped["TaskTreeNode"] = relationship(foreign_keys=[parent_id], init=False, remote_side=[id]) -class Code(Base): - """ORM equivalent of pycram.task.Code.""" - - function: Mapped[str] = mapped_column(default=None) - designator_id: Mapped[Optional[int]] = mapped_column(ForeignKey(f'{Designator.__tablename__}.id'), default=None) - designator: Mapped[Designator] = relationship(init=False) - diff --git a/src/pycram/resolver/__init__.py b/src/pycram/resolver/__init__.py index 82926eded..e69de29bb 100644 --- a/src/pycram/resolver/__init__.py +++ b/src/pycram/resolver/__init__.py @@ -1 +0,0 @@ -from .location.jpt_location import JPTCostmapLocation \ No newline at end of file diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 36d898618..06717c76d 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -3,18 +3,16 @@ import numpy as np import sqlalchemy.orm import sqlalchemy.sql -from sqlalchemy import select, Select, join -from sqlalchemy.sql.elements import BinaryExpression - -from typing_extensions import Tuple +from sqlalchemy import select, Select +from typing_extensions import List import pycram.designators.location_designator import pycram.task from pycram.costmaps import OccupancyCostmap -from pycram.orm.action_designator import PickUpAction, Action -from pycram.orm.object_designator import Object +from pycram.orm.action_designator import PickUpAction from pycram.orm.base import Position, RobotState, Pose as ORMPose, Quaternion -from pycram.orm.task import TaskTreeNode, Code +from pycram.orm.object_designator import Object +from pycram.orm.task import TaskTreeNode from ...pose import Pose @@ -29,17 +27,46 @@ class Location(pycram.designators.location_designator.LocationDesignatorDescript grasp: str +@dataclass +class Rectangle: + """ + A rectangle that is described by a lower and upper x and y value. + """ + x_lower: float + x_upper: float + y_lower: float + y_upper: float + + class RequiresDatabase: """ Mixin class that provides a database session. """ - robot_pos = sqlalchemy.orm.aliased(Position) - """3D Vector of robot position""" + robot_position = sqlalchemy.orm.aliased(Position) + """ + 3D Vector of robot position + """ + robot_pose = sqlalchemy.orm.aliased(ORMPose) - object_pos = sqlalchemy.orm.aliased(Position) - relative_x = robot_pos.x - object_pos.x - relative_y = robot_pos.y - object_pos.y + """ + Complete robot pose + """ + + object_position = sqlalchemy.orm.aliased(Position) + """ + 3D Vector for object position + """ + + relative_x = robot_position.x - object_position.x + """ + Distance on x axis between robot and object + """ + + relative_y = robot_position.y - object_position.y + """ + Distance on y axis between robot and object + """ def __init__(self, session: sqlalchemy.orm.Session = None): """ @@ -53,78 +80,59 @@ def create_query(self) -> Select: """ Create a query that queries the database for all pick up actions with context. """ - - # query all relative robot positions in regard to an objects position - # make sure to order the joins() correctly query = self.join_statement(self.select_statement()) return query def select_statement(self): return select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, self.relative_y, - Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() + Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() + def join_statement(self, query: Select): - return (query.join(TaskTreeNode.code).join(Code.designator.of_type(PickUpAction)). - join(PickUpAction.robot_state) - .join(self.robot_pose, RobotState.pose) - .join(self.robot_pos, self.robot_pose.position) + return (query.join(TaskTreeNode).join(TaskTreeNode.action.of_type(PickUpAction)) + .join(PickUpAction.robot_state).join(self.robot_pose, RobotState.pose) + .join(self.robot_position, self.robot_pose.position) .join(ORMPose.orientation) .join(PickUpAction.object) - .join(Object.pose) - .join(self.object_pos, ORMPose.position)) + .join(Object.pose).join(self.object_position, ORMPose.position)) -class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation, RequiresDatabase): +class AbstractCostmapLocation(pycram.designators.location_designator.CostmapLocation): """ - Class that represents costmap locations from a given Database. - The database has to have a schema that is compatible with the pycram.orm package. + Abstract Class for JPT and Database costmaps. """ - def __init__(self, target, session: sqlalchemy.orm.Session = None, - reachable_for=None, reachable_arm=None, resolver=None): + def __init__(self, target, reachable_for=None, reachable_arm=None): """ - Create a Database Costmap - + Create a new AbstractCostmapLocation instance. :param target: The target object - :param session: A session that can be used to execute queries - :param reachable_for: The robot to grab the object with - :param reachable_arm: The arm to use - + :param reachable_for: + :param reachable_arm: """ - super().__init__(target, reachable_for, None, reachable_arm, resolver) - RequiresDatabase.__init__(self, session) + super().__init__(target, reachable_for, None, reachable_arm, None) - def create_query_from_occupancy_costmap(self) -> Select: + def create_occupancy_rectangles(self) -> List[Rectangle]: """ - Create a query that queries all relative robot positions from an object that are not occluded using an - OccupancyCostmap. + :return: A list of rectangles that represent the occupied space of the target object. """ - - # get query - query = self.create_query() - - # constraint query to correct object type and successful task status - query = query.where(Object.type == self.target.type).where(TaskTreeNode.status == "SUCCEEDED") - # create Occupancy costmap for the target object ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, origin=self.target.pose) # working on a copy of the costmap, since found rectangles are deleted - map = np.copy(ocm.map) + ocm_map = np.copy(ocm.map) origin = np.array([ocm.height / 2, ocm.width / 2]) - - filters = [] + rectangles = [] # for every index pair (i, j) in the occupancy costmap - for i in range(0, map.shape[0]): - for j in range(0, map.shape[1]): + for i in range(0, ocm_map.shape[0]): + for j in range(0, ocm_map.shape[1]): # if this index has not been used yet - if map[i][j] > 0: - curr_width = ocm._find_consectuive_line((i, j), map) + if ocm_map[i][j] > 0: + curr_width = ocm._find_consectuive_line((i, j), ocm_map) curr_pose = (i, j) - curr_height = ocm._find_max_box_height((i, j), curr_width, map) + curr_height = ocm._find_max_box_height((i, j), curr_width, ocm_map) # calculate the rectangle in the costmap x_lower = (curr_pose[0] - origin[0]) * ocm.resolution @@ -133,11 +141,51 @@ def create_query_from_occupancy_costmap(self) -> Select: y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution # mark the found rectangle as occupied - map[i:i + curr_height, j:j + curr_width] = 0 + ocm_map[i:i + curr_height, j:j + curr_width] = 0 + + rectangles.append(Rectangle(x_lower, x_upper, y_lower, y_upper)) + + return rectangles + + +class DatabaseCostmapLocation(AbstractCostmapLocation, RequiresDatabase): + """ + Class that represents costmap locations from a given Database. + The database has to have a schema that is compatible with the pycram.orm package. + """ + + def __init__(self, target, session: sqlalchemy.orm.Session = None, reachable_for=None, reachable_arm=None): + """ + Create a Database Costmap + + :param target: The target object + :param session: A session that can be used to execute queries + :param reachable_for: The robot to grab the object with + :param reachable_arm: The arm to use + + """ + super().__init__(target, reachable_for, reachable_arm) + RequiresDatabase.__init__(self, session) + + def create_query_from_occupancy_costmap(self) -> Select: + """ + Create a query that queries all relative robot positions from an object that are not occluded using an + OccupancyCostmap. + """ + + # get query + query = self.create_query() + + # constraint query to correct object type and successful task status + query = query.where(Object.type == self.target.type).where(TaskTreeNode.status == "SUCCEEDED") + + filters = [] - # transform to jpt query - filters.append(sqlalchemy.and_(self.relative_x >= x_lower, self.relative_x < x_upper, - self.relative_y >= y_lower, self.relative_y < y_upper)) + # for every rectangle + for rectangle in self.create_occupancy_rectangles(): + # add sql filter + filters.append(sqlalchemy.and_(self.relative_x >= rectangle.x_lower, self.relative_x < rectangle.x_upper, + self.relative_y >= rectangle.y_lower, self.relative_y < rectangle.y_upper)) return query.where(sqlalchemy.or_(*filters)) diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 911e1fb3e..a35d200f5 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -25,8 +25,8 @@ from ...orm.action_designator import PickUpAction from ...orm.object_designator import Object from ...orm.base import Position, RobotState, Pose as ORMPose, Quaternion -from ...orm.task import TaskTreeNode, Code -from .database_location import Location, RequiresDatabase +from ...orm.task import TaskTreeNode +from .database_location import Location, RequiresDatabase, Rectangle, AbstractCostmapLocation from ...enums import TaskStatus import pandas as pd @@ -41,7 +41,7 @@ def select_statement(self): self.relative_y, TaskTreeNode.status)) -class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation): +class JPTCostmapLocation(AbstractCostmapLocation): """ Costmap Locations using Joint Probability Trees (JPTs). JPT costmaps are trained to model the dependency with a robot position relative to the object, the robots type, @@ -50,7 +50,7 @@ class JPTCostmapLocation(pycram.designators.location_designator.CostmapLocation) """ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, - model: Optional[JPT] = None, path: Optional[str] = None): + model: Optional[JPT] = None): """ Create a JPT Costmap @@ -58,25 +58,14 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, :param reachable_for: The robot to grab the object with :param reachable_arm: The arm to use :param model: The JPT model as a loaded tree in memory, either model or path must be set - :param path: The path to the JPT model, either model or path must be set """ - super().__init__(target, reachable_for, None, reachable_arm, None) - # check if arguments are plausible - if (not model and not path) or (model and path): - raise ValueError("Either model or path must be set.") - - # set model - if model: - self.model = model - - # load model from path - if path: - with open(path, "r") as f: - json_dict = json.load(f) - self.model = JPT.from_json(json_dict) + super().__init__(target, reachable_for, reachable_arm) + self.model = model # initialize member for visualized objects self.visual_ids: List[int] = [] + + # easy access to models variables self.arm, self.grasp, self.relative_x, self.relative_y, self.status, self.torso_height = ( self.model.variables) @@ -108,45 +97,12 @@ def events_from_occupancy_costmap(self) -> List[Event]: :return: List of evidences describing the found boxes """ - # create Occupancy costmap for the target object - position, orientation = self.target.pose.to_list() - position = list(position) - position[-1] = 0 - - ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, - origin=Pose(position, orientation)) - # ocm.visualize() - - # working on a copy of the costmap, since found rectangles are deleted - map = np.copy(ocm.map) - - origin = np.array([ocm.height / 2, ocm.width / 2]) - events = [] - - # for every index pair (i, j) in the occupancy costmap - for i in range(0, map.shape[0]): - for j in range(0, map.shape[1]): - - # if this index has not been used yet - if map[i][j] > 0: - curr_width = ocm._find_consectuive_line((i, j), map) - curr_pose = (i, j) - curr_height = ocm._find_max_box_height((i, j), curr_width, map) - - # calculate the rectangle in the costmap - x_lower = (curr_pose[0] - origin[0]) * ocm.resolution - x_upper = (curr_pose[0] + curr_width - origin[0]) * ocm.resolution - y_lower = (curr_pose[1] - origin[1]) * ocm.resolution - y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution - - # mark the found rectangle as occupied - map[i:i + curr_height, j:j + curr_width] = 0 - - event = Event({self.relative_x: portion.closedopen(x_lower, x_upper), - self.relative_y: portion.closedopen(y_lower, y_upper)}) - - events.append(event) + for rectangle in self.create_occupancy_rectangles(): + # get the occupancy costmap + event = Event({self.relative_x: portion.closedopen(rectangle.x_lower, rectangle.x_upper), + self.relative_y: portion.closedopen(rectangle.y_lower, rectangle.y_upper)}) + events.append(event) return events diff --git a/src/pycram/task.py b/src/pycram/task.py index e6323fd0c..2477c1880 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -3,6 +3,8 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations +from typing_extensions import TYPE_CHECKING + import datetime import inspect import json @@ -15,110 +17,72 @@ import tqdm from .bullet_world import BulletWorld -from .orm.task import (Code as ORMCode, TaskTreeNode as ORMTaskTreeNode) +from .orm.task import TaskTreeNode as ORMTaskTreeNode from .orm.base import ProcessMetaData from .plan_failures import PlanFailure -from .language import Code from .enums import TaskStatus +if TYPE_CHECKING: + from .designators.actions import Action -class TaskCode(Code): - def __str__(self) -> str: - if "self" in self.kwargs: - class_name = self.kwargs["self"].__class__.__name__ - else: - class_name = "" - function_name = self.function.__name__ - - return f"{function_name}({class_name})" - - def __eq__(self, other): - return isinstance(other, Code) and other.function.__name__ == self.function.__name__ \ - and other.kwargs == self.kwargs - - def to_json(self) -> Dict: - """Create a dictionary that can be json serialized.""" - return {"function": self.function.__name__, "kwargs": self.kwargs_to_json()} - - def kwargs_to_json(self): - """Try to parse the keyword arguments to json. Checks if the objects given as arguments can be serialized - as standard object or have a to_json method. If not they are skipped. """ - result = dict() - for keyword, argument in self.kwargs.items(): - to_json_method = getattr(argument, 'to_json', None) - - if to_json_method: - result[keyword] = argument.to_json() - - else: - try: - argument_ = json.loads(json.dumps(argument)) - result[keyword] = argument_ - except (TypeError, OverflowError): - logging.warning("Object of type %s cannot be JSON serialized. Skipping..." % type(argument)) - - return result - - def to_sql(self) -> ORMCode: - return ORMCode(self.function.__name__) - def insert(self, session: sqlalchemy.orm.session.Session) -> ORMCode: - code = self.to_sql() +class NoOperation: - # set foreign key to designator if present - self_ = self.kwargs.get("self") + def perform(self): + ... - if self_ and getattr(self_, "insert", None): - designator = self_.insert(session) - code.designator_id = designator.id - - # get and set metadata - metadata = ProcessMetaData().insert(session) - code.process_metadata_id = metadata.id - - session.add(code) - session.commit() - return code + def __repr__(self): + return "NoOperation" -class NoOperation(TaskCode): +class TaskTreeNode(anytree.NodeMixin): """ - Convenience class that represents no operation as code. + TaskTreeNode represents one function that was called during a pycram plan. + Additionally, meta information is stored. """ - def __init__(self): - # default no operation - def no_operation(): return None + action: Optional[Action] + """ + The action and that is performed or None if nothing was performed + """ - # initialize a code block that does nothing - super().__init__(no_operation) + status: TaskStatus + """ + The status of the node from the TaskStatus enum. + """ + start_time: Optional[datetime.datetime] + """ + The starting time of the function, optional + """ -class TaskTreeNode(anytree.NodeMixin): - """TaskTreeNode represents one function that was called during a pycram plan. - Additionally, meta information is stored. + end_time: Optional[datetime.datetime] + """ + The ending time of the function, optional + """ - :ivar code: The function that was executed as Code object. - :ivar status: The status of the node from the TaskStatus enum. - :ivar start_time: The starting time of the function, optional - :ivar end_time: The ending time of the function, optional - :ivar reason: The reason why this task failed, optional + """ + The reason why this task failed, optional """ - def __init__(self, code: TaskCode = NoOperation(), parent: Optional[TaskTreeNode] = None, + def __init__(self, action: Optional[Action] = NoOperation(), parent: Optional[TaskTreeNode] = None, children: Optional[List[TaskTreeNode]] = None, reason: Optional[Exception] = None): """ Create a TaskTreeNode - :param code: The function and its arguments that got called as TaskCode object, defaults to NoOperation() + :param action: The action and that is performed, defaults to None :param parent: The parent function of this function. None if this the parent, optional :param children: An iterable of TaskTreeNode with the ordered children, optional """ super().__init__() - self.code: TaskCode = code - self.status: TaskStatus = TaskStatus.CREATED - self.start_time: Optional[datetime.datetime] = None - self.end_time: Optional[datetime.datetime] = None + + if action is None: + action = NoOperation() + + self.action = action + self.status = TaskStatus.CREATED + self.start_time = None + self.end_time = None self.parent = parent self.reason: Optional[Exception] = reason @@ -129,24 +93,15 @@ def __init__(self, code: TaskCode = NoOperation(), parent: Optional[TaskTreeNode def name(self): return str(self) - def to_json(self): - return {"code": self.code.to_json(), - "status": self.status.name, - "start_time": self.start_time.isoformat() if self.start_time else None, - "end_time": self.end_time.isoformat() if self.end_time else None, - "id": id(self), - "parent_id": id(self.parent) if self.parent else None - } - def __str__(self): return "Code: %s \n " \ - "start_time: %s \n " \ "Status: %s \n " \ + "start_time: %s \n " \ "end_time: %s \n " \ - "" % (str(self.code), self.start_time, self.status, self.end_time) + "" % (str(self.action), self.start_time, self.status, self.end_time) def __repr__(self): - return str(self.code) + return str(self.action.__class__.__name__) def __len__(self): """Get the number of nodes that are in this subtree.""" @@ -186,12 +141,16 @@ def insert(self, session: sqlalchemy.orm.session.Session, recursive: bool = True progress_bar = tqdm.tqdm(desc="Inserting TaskTree into database", leave=True, position=0, total=len(self) if recursive else 1) - # insert code - code = self.code.insert(session) - # convert self to orm object node = self.to_sql() - node.code_id = code.id + + # insert action if possible + if getattr(self.action, "insert", None): + action = self.action.insert(session) + node.action_id = action.id + else: + action = None + node.action_id = None # get and set metadata metadata = ProcessMetaData().insert(session) @@ -223,11 +182,9 @@ def __enter__(self): Fresh structures are then available inside the with statement.""" global task_tree - def simulation(): return None - self.suspended_tree = task_tree self.world_state, self.objects2attached = BulletWorld.current_bullet_world.save_state() - self.simulated_root = TaskTreeNode(code=TaskCode(simulation)) + self.simulated_root = TaskTreeNode() task_tree = self.simulated_root pybullet.addUserDebugText("Simulating...", [0, 0, 1.75], textColorRGB=[0, 0, 0], parentObjectUniqueId=1, lifeTime=0) @@ -252,7 +209,7 @@ def reset_tree() -> None: Reset the current task tree to an empty root (NoOperation) node. """ global task_tree - task_tree = TaskTreeNode(NoOperation()) + task_tree = TaskTreeNode() task_tree.start_time = datetime.datetime.now() task_tree.status = TaskStatus.RUNNING @@ -261,7 +218,8 @@ def reset_tree() -> None: def with_tree(fun: Callable) -> Callable: - """Decorator that records the function name, arguments and execution metadata in the task tree. + """ + Decorator that records the function name, arguments and execution metadata in the task tree. :param fun: The function to record the data from. """ @@ -271,16 +229,20 @@ def handle_tree(*args, **kwargs): # get the task tree global task_tree - # create the code object that gets executed - code = TaskCode(fun, inspect.getcallargs(fun, *args, **kwargs)) + # parse keyword arguments + keyword_arguments = inspect.getcallargs(fun, *args, **kwargs) + + # try to get self object since this represents the action object + action = keyword_arguments.get("self", None) - task_tree = TaskTreeNode(code, parent=task_tree) + # create the task tree node + task_tree = TaskTreeNode(action, parent=task_tree) # Try to execute the task try: task_tree.status = TaskStatus.CREATED task_tree.start_time = datetime.datetime.now() - result = task_tree.code.execute() + result = fun(*args, **kwargs) # if it succeeded set the flag task_tree.status = TaskStatus.SUCCEEDED @@ -289,7 +251,7 @@ def handle_tree(*args, **kwargs): except PlanFailure as e: # log the error and set the flag - logging.exception("Task execution failed at %s. Reason %s" % (str(task_tree.code), e)) + logging.exception("Task execution failed at %s. Reason %s" % (repr(task_tree), e)) task_tree.reason = e task_tree.status = TaskStatus.FAILED raise e diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 4a298fe5d..c6697fa58 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -17,15 +17,7 @@ from pycram.robot_descriptions import robot_description from pycram.task import with_tree from pycram.enums import ObjectType - -# check if jpt is installed -jpt_installed = True -try: - import jpt - from pycram.resolver.location.database_location import DatabaseCostmapLocation -except ImportError: - jpt_installed = False - +from pycram.resolver.location.database_location import DatabaseCostmapLocation pycrorm_uri = os.getenv('PYCRORM_URI') if pycrorm_uri: @@ -33,8 +25,6 @@ @unittest.skipIf(pycrorm_uri is None, "pycrorm database is not available.") -@unittest.skipIf(not jpt_installed, "jpt is not installed but needed for the definition of DatabaseCostmapLocations. " - "Install via 'pip install pyjpt'") class DatabaseResolverTestCase(unittest.TestCase,): world: BulletWorld milk: Object diff --git a/test/test_orm.py b/test/test_orm.py index 4c5063fc7..23150b9be 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -1,5 +1,7 @@ import os import unittest + +import anytree from sqlalchemy import select import sqlalchemy.orm import pycram.orm.action_designator @@ -54,7 +56,6 @@ def test_schema_creation(self): self.assertTrue("Position" in tables) self.assertTrue("Quaternion" in tables) self.assertTrue("TaskTreeNode" in tables) - self.assertTrue("Code" in tables) self.assertTrue("Action" in tables) self.assertTrue("ParkArmsAction" in tables) self.assertTrue("NavigateAction" in tables) @@ -93,9 +94,6 @@ def test_node(self): node_results = self.session.scalars(select(pycram.orm.task.TaskTreeNode)).all() self.assertEqual(len(node_results), len(pycram.task.task_tree.root)) - code_results = self.session.scalars(select(pycram.orm.task.Code)).all() - self.assertEqual(len(code_results), len(pycram.task.task_tree.root)) - position_results = self.session.scalars(select(pycram.orm.base.Position)).all() self.assertEqual(14, len(position_results)) @@ -205,9 +203,10 @@ def test_code_designator_type(self): action.perform() pycram.orm.base.ProcessMetaData().description = "code_designator_type_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.scalars(select(pycram.orm.task.Code).where(pycram.orm.task.Code.function == "perform")).all() - self.assertEqual(result[0].designator.dtype, action_designator.NavigateAction.__name__) - self.assertEqual(result[1].designator.dtype, motion_designator.MoveMotion.__name__) + result = self.session.scalars(select(pycram.orm.task.TaskTreeNode).where(pycram.orm.task.TaskTreeNode. + action_id.isnot(None))).all() + self.assertEqual(result[0].action.dtype, action_designator.NavigateAction.__name__) + self.assertEqual(result[1].action.dtype, motion_designator.MoveMotion.__name__) def test_parkArmsAction(self): action = ParkArmsActionPerformable(pycram.enums.Arms.BOTH) diff --git a/test/test_task_tree.py b/test/test_task_tree.py index 3c534ba7d..0827a07f8 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -34,18 +34,12 @@ def test_tree_creation(self): # self.tearDownBulletWorld() tt = pycram.task.task_tree - # print(anytree.RenderTree(tt)) - self.assertEqual(15, len(tt.root)) self.assertEqual(10, len(tt.root.leaves)) - names = [node.code.function.__name__ for node in anytree.PreOrderIter(tt.root)] - self.assertEqual(names, ["no_operation", "plan", "perform", "perform", "perform", "perform", "perform", - "perform", "perform", "perform", "perform", "perform", "perform", "perform", "perform"] - ) # check that all nodes succeeded for node in anytree.PreOrderIter(tt.root): - if node.code != pycram.task.NoOperation(): + if not isinstance(node.action, pycram.task.NoOperation): self.assertEqual(node.status, pycram.task.TaskStatus.SUCCEEDED) def test_exception(self): @@ -54,6 +48,7 @@ def test_exception(self): @with_tree def failing_plan(): raise pycram.plan_failures.PlanFailure("PlanFailure for UnitTesting") + pycram.task.reset_tree() self.assertRaises(pycram.plan_failures.PlanFailure, failing_plan) @@ -61,7 +56,7 @@ def failing_plan(): tt = pycram.task.task_tree for node in anytree.PreOrderIter(tt.root): - if node.code != pycram.task.NoOperation(): + if not isinstance(node.action, pycram.task.NoOperation): self.assertEqual(node.status, pycram.task.TaskStatus.FAILED) self.assertEqual(pycram.plan_failures.PlanFailure, type(node.reason)) @@ -71,7 +66,7 @@ def test_execution(self): tt = pycram.task.task_tree # self.setUpBulletWorld(False) with simulated_robot: - [node.code.execute() for node in tt.root.leaves] + [node.action.perform() for node in tt.root.leaves] def test_simulated_tree(self): with pycram.task.SimulatedTaskTree() as st: @@ -80,13 +75,15 @@ def test_simulated_tree(self): self.assertEqual(15, len(tt.root)) self.assertEqual(10, len(tt.root.leaves)) - names = [node.code.function.__name__ for node in anytree.PreOrderIter(tt.root)] - self.assertEqual(names, ["simulation", "plan", "perform", "perform", "perform", "perform", "perform", - "perform", "perform", "perform", "perform", "perform", "perform", "perform", - "perform"]) self.assertEqual(len(pycram.task.task_tree), 1) + def test_to_sql(self): + self.plan() + tt = pycram.task.task_tree + result = tt.root.to_sql() + self.assertIsNotNone(result) + if __name__ == '__main__': unittest.main() From 8bb33038f2b066bd710b1bcb3826ece2c5a03749 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Thu, 7 Mar 2024 15:08:28 +0100 Subject: [PATCH 108/195] [Task] Updated custom resolver tutorial code --- examples/custom_resolver.ipynb | 227 ++++++------------- src/pycram/resolver/location/jpt_location.py | 8 +- 2 files changed, 79 insertions(+), 156 deletions(-) diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb index 55f1f8161..966f2a2fe 100644 --- a/examples/custom_resolver.ipynb +++ b/examples/custom_resolver.ipynb @@ -22,8 +22,8 @@ "cell_type": "code", "metadata": { "ExecuteTime": { - "end_time": "2024-03-05T13:45:12.736132Z", - "start_time": "2024-03-05T13:45:11.708013Z" + "end_time": "2024-03-07T14:07:44.495616Z", + "start_time": "2024-03-07T14:07:43.418329Z" } }, "source": [ @@ -34,7 +34,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "Requirement already satisfied: probabilistic_model in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (3.3.3)\r\n", + "Requirement already satisfied: probabilistic_model in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (3.3.4)\r\n", "Requirement already satisfied: random-events>=1.2.5 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", "Requirement already satisfied: networkx>=3.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (3.1)\r\n", "Requirement already satisfied: portion>=2.4.2 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (2.4.2)\r\n", @@ -54,8 +54,8 @@ "cell_type": "code", "metadata": { "ExecuteTime": { - "end_time": "2024-03-05T13:45:14.170210Z", - "start_time": "2024-03-05T13:45:12.740951Z" + "end_time": "2024-03-07T14:07:45.728089Z", + "start_time": "2024-03-07T14:07:44.501390Z" } }, "source": [ @@ -69,19 +69,15 @@ "import pycram.orm.base\n", "import pycram.task\n", "from pycram.bullet_world import BulletWorld, Object as BulletWorldObject\n", - "from pycram.designators.action_designator import MoveTorsoAction, PickUpAction, NavigateAction, ParkArmsAction\n", + "from pycram.designators.action_designator import PickUpAction, NavigateAction\n", "from pycram.designators.object_designator import ObjectDesignatorDescription\n", "import pycram.enums\n", "from pycram.plan_failures import PlanFailure\n", "from pycram.process_module import ProcessModule\n", "from pycram.process_module import simulated_robot\n", "import pycram.orm\n", - "from pycram.orm.base import Position, RobotState\n", - "from pycram.orm.task import TaskTreeNode, Code\n", - "from pycram.orm.action_designator import PickUpAction as ORMPickUpAction \n", - "from pycram.orm.object_designator import Object \n", + "\n", "import sqlalchemy.sql\n", - "import pandas as pd\n", "from pycram.pose import Pose\n", "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", " \n", @@ -227,7 +223,7 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1709646313.790492]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + "[WARN] [1709820465.515996]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -246,8 +242,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-03-05T13:47:04.916953Z", - "start_time": "2024-03-05T13:45:14.170956Z" + "end_time": "2024-03-07T14:07:45.744134Z", + "start_time": "2024-03-07T14:07:45.728897Z" } }, "source": [ @@ -257,29 +253,9 @@ "session.commit()\n", "\n", "explorer = GraspingExplorer(samples_per_scenario=30)\n", - "explorer.perform(session)" - ], - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - " 0%| | 0/960 [00:00" - }, - "execution_count": 7, - "metadata": {}, - "output_type": "execute_result" - } + "from pycram.resolver.location.jpt_location import JPTCostmapLocation\n", + "model = JPTCostmapLocation.fit_from_database(session, success_only=True)" ], - "execution_count": 7 + "outputs": [], + "execution_count": 6 }, { "cell_type": "markdown", @@ -482,36 +377,42 @@ "cell_type": "code", "metadata": { "collapsed": false, - "is_executing": true, "ExecuteTime": { - "start_time": "2024-03-05T13:47:05.495621Z" + "end_time": "2024-03-07T14:07:57.592487Z", + "start_time": "2024-03-07T14:07:46.224148Z" } }, "source": [ + "import random\n", "from pycram.designators.actions.actions import NavigateActionPerformable, PickUpActionPerformable\n", - "from pycram.resolver import JPTCostmapLocation\n", - "\n", + "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", + "from pycram.designators.actions.actions import LookAtActionPerformable\n", + "import time\n", "\n", "ProcessModule.execution_delay = True\n", "\n", - "world = BulletWorld(\"GUI\")\n", + "world = BulletWorld(\"DIRECT\")\n", + "VizMarkerPublisher(interval=0.1)\n", "robot = BulletWorldObject(\"pr2\", pycram.enums.ObjectType.ROBOT, \"pr2.urdf\")\n", "\n", - "cereal = BulletWorldObject(\"milk\", pycram.enums.ObjectType.MILK, \"milk.stl\", pose=Pose([1, 0, 0.75], [0,0,0,1]))\n", + "milk = BulletWorldObject(\"milk\", pycram.enums.ObjectType.MILK, \"milk.stl\", pose=Pose([1, 0, 0.75], [0,0,0,1]))\n", + "random.seed(420)\n", "np.random.seed(420)\n", - "cml = JPTCostmapLocation(cereal, reachable_for=robot, model=model)\n", - "cml.visualize()\n", + "cml = JPTCostmapLocation(milk, reachable_for=robot, model=model)\n", + "\n", + "# cml.visualize()\n", "with simulated_robot:\n", " for sample in iter(cml):\n", " ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform()\n", " NavigateActionPerformable(sample.pose).perform()\n", " MoveTorsoActionPerformable(sample.torso_height).perform()\n", + " time.sleep(1)\n", " try:\n", - " PickUpActionPerformable(ObjectDesignatorDescription(types=[pycram.enums.ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform()\n", - " # time.sleep(5)\n", + " PickUpActionPerformable(ObjectDesignatorDescription(types=[milk.type]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform()\n", + " break\n", " except pycram.plan_failures.PlanFailure as p:\n", " continue\n", - " break\n", + "time.sleep(5)\n", "world.exit()" ], "outputs": [ @@ -519,22 +420,44 @@ "name": "stderr", "output_type": "stream", "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "header: \n", + " seq: 0\n", + " stamp: \n", + " secs: 1709820467\n", + " nsecs: 175542593\n", + " frame_id: \"map\"\n", + "pose: \n", + " position: \n", + " x: 1.5083740789539029\n", + " y: -0.3709888064438581\n", + " z: 0\n", + " orientation: \n", + " x: 0.0\n", + " y: 0.0\n", + " z: 0.6691405836012501\n", + " w: 0.7431358418067174\n" + ] } ], - "execution_count": null + "execution_count": 7 }, { "cell_type": "markdown", diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index a35d200f5..e6db72347 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -38,7 +38,7 @@ class QueryBuilder(RequiresDatabase): def select_statement(self): return (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, - self.relative_y, TaskTreeNode.status)) + self.relative_y, Quaternion.x, Quaternion.y, Quaternion.z, TaskTreeNode.status)).distinct() class JPTCostmapLocation(AbstractCostmapLocation): @@ -66,8 +66,8 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, self.visual_ids: List[int] = [] # easy access to models variables - self.arm, self.grasp, self.relative_x, self.relative_y, self.status, self.torso_height = ( - self.model.variables) + (self.arm, self.grasp, self.relative_x, self.relative_y, self.status, self.torso_height, self.qx, self.qy, + self.qz) = self.model.variables @classmethod def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False) -> JPT: @@ -136,7 +136,7 @@ def sample_to_location(self, sample: np.ndarray) -> Location: sample_dict = {variable: value for variable, value in zip(self.model.variables, sample)} target_x, target_y, target_z = self.target.pose.position_as_list() pose = [target_x + sample_dict[self.relative_x], target_y + sample_dict[self.relative_y], 0] - orientation = [0, 0, 0, 1] + orientation = [sample_dict[self.qx], sample_dict[self.qy], sample_dict[self.qz], 1] torso_height = sample_dict[self.torso_height] result = Location(Pose(pose, orientation), sample_dict[self.arm], torso_height, sample_dict[self.grasp]) return result From 11adc21921f01d24e59f7e82d7d5f817dc5918f6 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Thu, 7 Mar 2024 15:22:04 +0100 Subject: [PATCH 109/195] [Costmap] Updated custom resolver tutorial text --- examples/custom_resolver.ipynb | 160 ++++++++++++++++----------------- 1 file changed, 77 insertions(+), 83 deletions(-) diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb index 966f2a2fe..570c05a47 100644 --- a/examples/custom_resolver.ipynb +++ b/examples/custom_resolver.ipynb @@ -6,9 +6,13 @@ "source": [ "# Creating a custom Location Costmap\n", "\n", - "In this tutorial we will walk through the creation of a costmap through machine learning.\n", - "First we need to gather a lot of data. For that we will write a randomized experiment for grasping a couple of objects.\n", - "In the experiment the robot will try to grasp a randomized object using random poses and torso heights." + "In this tutorial we will walk through the creation of a costmap through probabilistic machine learning.\n", + "\n", + "After this tutorial you will know:\n", + "- Why probabilities are a useful thing in robot planning\n", + "- How to craft probabilistic models for your plan\n", + "\n", + "Lets start by installing the important package." ] }, { @@ -22,8 +26,8 @@ "cell_type": "code", "metadata": { "ExecuteTime": { - "end_time": "2024-03-07T14:07:44.495616Z", - "start_time": "2024-03-07T14:07:43.418329Z" + "end_time": "2024-03-07T14:18:35.388769Z", + "start_time": "2024-03-07T14:18:34.325541Z" } }, "source": [ @@ -50,12 +54,22 @@ ], "execution_count": 1 }, + { + "cell_type": "markdown", + "source": [ + "Next, we need to gather a lot of data. For that we will write a randomized experiment for grasping a couple of objects.\n", + "In the experiment the robot will try to grasp a randomized object using random poses and torso heights." + ], + "metadata": { + "collapsed": false + } + }, { "cell_type": "code", "metadata": { "ExecuteTime": { - "end_time": "2024-03-07T14:07:45.728089Z", - "start_time": "2024-03-07T14:07:44.501390Z" + "end_time": "2024-03-07T14:18:36.577596Z", + "start_time": "2024-03-07T14:18:35.394399Z" } }, "source": [ @@ -223,7 +237,7 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1709820465.515996]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + "[WARN] [1709821116.366007]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], @@ -242,8 +256,8 @@ "metadata": { "scrolled": false, "ExecuteTime": { - "end_time": "2024-03-07T14:07:45.744134Z", - "start_time": "2024-03-07T14:07:45.728897Z" + "end_time": "2024-03-07T14:18:36.594199Z", + "start_time": "2024-03-07T14:18:36.578364Z" } }, "source": [ @@ -252,8 +266,7 @@ "pycram.orm.base.Base.metadata.create_all(bind=engine)\n", "session.commit()\n", "\n", - "explorer = GraspingExplorer(samples_per_scenario=30)\n", - "# explorer.perform(session)" + "explorer = GraspingExplorer(samples_per_scenario=30)" ], "outputs": [], "execution_count": 3 @@ -269,19 +282,40 @@ "cell_type": "code", "metadata": { "ExecuteTime": { - "end_time": "2024-03-07T14:07:45.746036Z", - "start_time": "2024-03-07T14:07:45.744742Z" + "end_time": "2024-03-07T14:20:14.842937Z", + "start_time": "2024-03-07T14:18:36.594881Z" } }, "source": [ - "# import os\n", - "# con = engine.raw_connection()\n", - "# \n", - "# with open(os.path.join(os.path. expanduser('~'), \"Documents\", \"costmap.dump\"), 'w') as f:\n", - "# for line in con.iterdump():\n", - "# f.write('%s\\n' % line)" + "import os\n", + "explorer.perform(session)\n", + "con = engine.raw_connection()\n", + "\n", + "with open(os.path.join(os.path. expanduser('~'), \"Documents\", \"costmap.dump\"), 'w') as f:\n", + " for line in con.iterdump():\n", + " f.write('%s\\n' % line)" + ], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + " 0%| | 0/960 [00:00 Date: Mon, 11 Mar 2024 11:00:57 +0100 Subject: [PATCH 110/195] [Costmap] Added gaussian costmap --- src/pycram/resolver/location/jpt_location.py | 134 ++++++++++--------- test/test_jpt_resolver.py | 11 +- 2 files changed, 79 insertions(+), 66 deletions(-) diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index e6db72347..250215127 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -13,6 +13,7 @@ import numpy as np import pybullet import tf.transformations +from random_events.variables import Continuous from sqlalchemy import select import pycram.designators.location_designator @@ -31,7 +32,66 @@ import pandas as pd -from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit +from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit, DecomposableProductUnit +from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution + + +class GaussianCostmapModel: + """ + Class that generates a Gaussian Costmap around the center of an object. The costmap cuts out a square in the middle + that has side lengths given by ``distance_to_center``. + """ + + distance_to_center: float + """ + The side length of the cut out square. + """ + + variance: float + """ + The variance of the distributions involved + """ + + relative_x = Continuous("relative_x") + relative_y = Continuous("relative_y") + + def __init__(self, distance_to_center: float = 0., variance: float = 0.5): + self.distance_to_center = distance_to_center + self.variance = variance + + def create_model_with_center(self) -> ProbabilisticCircuit: + """ + Create a fully factorized gaussian at the center of the map. + """ + centered_model = DecomposableProductUnit() + centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., 0.5)) + centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., 0.5)) + return centered_model.probabilistic_circuit + + def create_model(self) -> ProbabilisticCircuit: + """ + Create a gaussian model that assumes mass everywhere besides the center square. + + :return: The probabilistic circuit + """ + centered_model = self.create_model_with_center() + + model = DeterministicSumUnit() + + north_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), + self.relative_y: portion.closed(self.distance_to_center, float("inf"))}) + south_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), + self.relative_y: portion.closed(-float("inf"), -self.distance_to_center)}) + east_region = Event({self.relative_x: portion.closed(self.distance_to_center, float("inf")), + self.relative_y: portion.open(-float("inf"), float("inf"))}) + west_region = Event({self.relative_x: portion.closed(-float("inf"), -self.distance_to_center), + self.relative_y: portion.open(-float("inf"), float("inf"))}) + + for region in [north_region, south_region, east_region, west_region]: + conditional, probability = centered_model.conditional(region) + model.add_subcircuit(conditional.root, probability) + + return model.probabilistic_circuit class QueryBuilder(RequiresDatabase): @@ -50,7 +110,7 @@ class JPTCostmapLocation(AbstractCostmapLocation): """ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, - model: Optional[JPT] = None): + model: Optional[ProbabilisticCircuit] = None): """ Create a JPT Costmap @@ -70,7 +130,8 @@ def __init__(self, target: Object, reachable_for=None, reachable_arm=None, self.qz) = self.model.variables @classmethod - def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False) -> JPT: + def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False) -> ( + ProbabilisticCircuit): """ Fit a JPT to become a location designator using the data from the database that is reachable via the session. @@ -87,7 +148,7 @@ def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) model = JPT(variables, min_samples_leaf=0.1) model.fit(samples) - return model + return model.probabilistic_circuit def events_from_occupancy_costmap(self) -> List[Event]: """ @@ -118,7 +179,7 @@ def ground_model(self) -> DeterministicSumUnit: for location in locations: conditional, probability = self.model.conditional(location) if probability > 0: - model.add_subcircuit(conditional, probability) + model.add_subcircuit(conditional.root, probability) if len(model.subcircuits) == 0: raise PlanFailure("No possible locations found") @@ -142,72 +203,17 @@ def sample_to_location(self, sample: np.ndarray) -> Location: return result def __iter__(self): - model = self.ground_model() - - for _ in range(20): - sample = model.sample(1) - yield self.sample_to_location(sample[0]) + samples = model.sample(20) + for sample in samples: + yield self.sample_to_location(sample) def visualize(self): """ Plot the possible areas to stand in the BulletWorld. The opacity is the probability of success. """ - - evidence = self.create_evidence(use_success=False) - - conditional_model = self.model.conditional_jpt(evidence) - - for leaf in conditional_model.leaves.values(): - - success = leaf.distributions["status"].p({"SUCCEEDED"}) - - if success == 0: - continue - - x_intervals = leaf.distributions["x"].cdf.intervals - y_intervals = leaf.distributions["y"].cdf.intervals - - x_range = np.array([x_intervals[0].upper, x_intervals[-1].lower]) - y_range = np.array([y_intervals[0].upper, y_intervals[-1].lower]) - - center = np.array([sum(x_range) / 2, sum(y_range) / 2]) - - visual = pybullet.createVisualShape(pybullet.GEOM_BOX, - halfExtents=[(x_range[1] - x_range[0]) / 2, - (y_range[1] - y_range[0]) / 2, 0.001], - rgbaColor=[1, 0, 0, success], - visualFramePosition=[*center, 0]) - - self.visual_ids.append(visual) - - for id_list in np.array_split(np.array(self.visual_ids), np.ceil(len(self.visual_ids) / 127)): - # Dummy paramater since these are needed to spawn visual shapes as a multibody. - link_poses = [[0, 0, 0] for c in id_list] - link_orientations = [[0, 0, 0, 1] for c in id_list] - link_masses = [1.0 for c in id_list] - link_parent = [0 for c in id_list] - link_joints = [pybullet.JOINT_FIXED for c in id_list] - link_collision = [-1 for c in id_list] - link_joint_axis = [[1, 0, 0] for c in id_list] - - # The position at which the multibody will be spawned. Offset such that - # the origin referes to the centre of the costmap. - origin_pose = self.target.pose.to_list() - base_position = list(origin_pose[0]) - base_position[2] = 0 - - map_obj = pybullet.createMultiBody(baseVisualShapeIndex=-1, linkVisualShapeIndices=id_list, - basePosition=base_position, baseOrientation=origin_pose[1], - linkPositions=link_poses, - linkMasses=link_masses, linkOrientations=link_orientations, - linkInertialFramePositions=link_poses, - linkInertialFrameOrientations=link_orientations, - linkParentIndices=link_parent, - linkJointTypes=link_joints, linkJointAxis=link_joint_axis, - linkCollisionShapeIndices=link_collision) - self.visual_ids.append(map_obj) + raise NotImplementedError def close_visualization(self) -> None: """ diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 521dccc0d..65e3ff091 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -18,7 +18,7 @@ from pycram.designators.object_designator import ObjectDesignatorDescription from pycram.ros.viz_marker_publisher import VizMarkerPublisher - +import plotly.graph_objects as go import sqlalchemy import sqlalchemy.orm @@ -27,7 +27,7 @@ try: from probabilistic_model.learning.jpt.jpt import JPT from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe - from pycram.resolver.location.jpt_location import JPTCostmapLocation + from pycram.resolver.location.jpt_location import JPTCostmapLocation, GaussianCostmapModel except ImportError: jpt_installed = False @@ -141,5 +141,12 @@ def test_object_at_different_location(self): raise p +class TruncatedNormalTestCase(unittest.TestCase): + + def test_normal_costmap(self): + model = GaussianCostmapModel(0.1, 0.5).create_model() + go.Figure(model.root.plot()).show() + + if __name__ == '__main__': unittest.main() From 3777f6700e25bf904b388310d79cddb20c983e54 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 12 Mar 2024 17:17:23 +0100 Subject: [PATCH 111/195] [Costmap] New pickup is working, yeeehaaaw --- examples/improving_actions.ipynb | 84203 ++++++++++++++++ src/pycram/orm/action_designator.py | 5 + .../resolver/location/database_location.py | 25 +- src/pycram/resolver/location/jpt_location.py | 258 +- test/test_jpt_resolver.py | 114 +- 5 files changed, 84556 insertions(+), 49 deletions(-) create mode 100644 examples/improving_actions.ipynb diff --git a/examples/improving_actions.ipynb b/examples/improving_actions.ipynb new file mode 100644 index 000000000..c0770e462 --- /dev/null +++ b/examples/improving_actions.ipynb @@ -0,0 +1,84203 @@ +{ + "cells": [ + { + "cell_type": "code", + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "[WARN] [1710260140.694276]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + ] + } + ], + "source": [ + "import os\n", + "import time\n", + "\n", + "import pandas as pd\n", + "from probabilistic_model.learning.jpt.jpt import JPT\n", + "from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe\n", + "from random_events.events import Event\n", + "from random_events.variables import Continuous\n", + "\n", + "from pycram.costmaps import OccupancyCostmap\n", + "from pycram.plan_failures import PlanFailure\n", + "from pycram.designators.object_designator import ObjectDesignatorDescription\n", + "from pycram.bullet_world import BulletWorld, Object\n", + "from pycram.robot_descriptions import robot_description\n", + "from pycram.enums import ObjectType, Arms, Grasp\n", + "from pycram.pose import Pose\n", + "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", + "from pycram.process_module import ProcessModule\n", + "import sqlalchemy\n", + "\n", + "from pycram.resolver.location.jpt_location import FunkyPickUpAction\n", + "from pycram.process_module import simulated_robot\n", + "\n", + "import plotly.graph_objects as go" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:40.799381Z", + "start_time": "2024-03-12T16:15:39.157802Z" + } + }, + "id": "690c193e24875d2b", + "execution_count": 1 + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "initial_id", + "metadata": { + "collapsed": true, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:40.801902Z", + "start_time": "2024-03-12T16:15:40.800292Z" + } + }, + "outputs": [], + "source": [ + "pycrorm_uri = os.getenv('PYCRORM_URI')\n", + "pycrorm_uri = \"mysql+pymysql://\" + pycrorm_uri" + ] + }, + { + "cell_type": "code", + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", + "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", + "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n" + ] + } + ], + "source": [ + "world = BulletWorld(\"DIRECT\")\n", + "robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + \".urdf\")\n", + "milk = Object(\"milk\", ObjectType.MILK, \"milk.stl\", pose=Pose([1.3, 1, 0.9]))\n", + "viz_marker_publisher = VizMarkerPublisher()\n", + "ProcessModule.execution_delay = False\n", + "engine = sqlalchemy.create_engine(pycrorm_uri)" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:41.248083Z", + "start_time": "2024-03-12T16:15:40.802487Z" + } + }, + "id": "a66e49b86c6c92f1", + "execution_count": 3 + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "text/html": " \n " + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "application/vnd.plotly.v1+json": { + "data": [ + { + "hovertext": [ + "Likelihood: 0.20810481334043096", + "Likelihood: 0.130459048254307", + "Likelihood: 0.279361821243727", + "Likelihood: 0.2623758353286913", + "Likelihood: 0.26639415563453156", + "Likelihood: 0.28495280432356346", + "Likelihood: 0.2640227539063325", + "Likelihood: 0.25204334147819357", + "Likelihood: 0.12282389990213616", + "Likelihood: 0.1412369924757717", + "Likelihood: 0.27311250059631004", + "Likelihood: 0.2574673623204562", + "Likelihood: 0.14678264667554577", + "Likelihood: 0.28443951484756747", + "Likelihood: 0.17611613156396946", + "Likelihood: 0.2808829340458293", + "Likelihood: 0.2709430034595791", + "Likelihood: 0.2758923054645284", + "Likelihood: 0.21664567925778497", + "Likelihood: 0.2510897448022212", + "Likelihood: 0.2451698361444219", + "Likelihood: 0.20769643583975694", + "Likelihood: 0.18521308912117365", + "Likelihood: 0.18164854908196645", + "Likelihood: 0.26758456328607005", + "Likelihood: 0.23749247715727267", + "Likelihood: 0.24467822527683625", + "Likelihood: 0.28727624564980525", + "Likelihood: 0.25983940895072016", + "Likelihood: 0.2063369412462767", + "Likelihood: 0.1761402247680179", + "Likelihood: 0.19558151439320048", + "Likelihood: 0.22784184737606428", + "Likelihood: 0.1841115124384866", + "Likelihood: 0.21661095530258678", + "Likelihood: 0.1684560740903216", + "Likelihood: 0.2332292590388241", + "Likelihood: 0.2085859412403264", + "Likelihood: 0.27384261652292086", + "Likelihood: 0.19846966644260242", + "Likelihood: 0.2691291369003733", + "Likelihood: 0.1629735276548189", + "Likelihood: 0.26473038880836886", + "Likelihood: 0.2575193899915376", + "Likelihood: 0.2847746842919087", + "Likelihood: 0.22874794937380089", + "Likelihood: 0.20135273269243567", + "Likelihood: 0.2635197540450226", + "Likelihood: 0.23864830416668756", + "Likelihood: 0.23101983901802056", + "Likelihood: 0.22148217992352823", + "Likelihood: 0.2167006556982333", + "Likelihood: 0.2873771506018316", + "Likelihood: 0.22710982071500477", + "Likelihood: 0.2895065405059108", + "Likelihood: 0.2651868063310899", + "Likelihood: 0.1876199845113221", + "Likelihood: 0.23774241080150338", + "Likelihood: 0.2455185230319284", + "Likelihood: 0.2010377824053368", + "Likelihood: 0.19360379139984443", + "Likelihood: 0.23905603395933453", + "Likelihood: 0.20716092211227183", + "Likelihood: 0.2526327031830973", + "Likelihood: 0.2396702062300729", + "Likelihood: 0.23940351368649546", + "Likelihood: 0.05225829033130935", + "Likelihood: 0.17322502948749022", + "Likelihood: 0.25312091532341524", + "Likelihood: 0.1936120355744652", + "Likelihood: 0.22159703650748017", + "Likelihood: 0.06009606272856525", + "Likelihood: 0.19820200608020666", + "Likelihood: 0.2676667912765636", + "Likelihood: 0.17533320227622898", + "Likelihood: 0.10201635310192712", + "Likelihood: 0.2831389952840865", + "Likelihood: 0.12345358567176208", + "Likelihood: 0.21095131847818682", + "Likelihood: 0.27913619083183805", + "Likelihood: 0.19785179562724367", + "Likelihood: 0.23746511250219057", + "Likelihood: 0.2330658653034207", + "Likelihood: 0.28309885873705665", + "Likelihood: 0.15811040060806905", + "Likelihood: 0.2571473504063117", + "Likelihood: 0.25870697889313626", + "Likelihood: 0.2342594050742677", + "Likelihood: 0.11570038472682766", + "Likelihood: 0.21407429038720072", + "Likelihood: 0.24495478484082994", + "Likelihood: 0.23091936106739244", + "Likelihood: 0.2802616883332199", + "Likelihood: 0.2649510107058665", + "Likelihood: 0.22455987980429734", + "Likelihood: 0.1053460292047151", + "Likelihood: 0.10466363437280556", + "Likelihood: 0.2736416772856022", + "Likelihood: 0.22674413039128336", + "Likelihood: 0.26594147474506086", + "Likelihood: 0.1990339547501295", + "Likelihood: 0.24995571607608832", + "Likelihood: 0.1331290500509582", + "Likelihood: 0.1567148457400675", + "Likelihood: 0.1253090362140565", + "Likelihood: 0.23279318897320403", + "Likelihood: 0.2741937172690832", + "Likelihood: 0.2281997598357138", + "Likelihood: 0.19279854266666913", + "Likelihood: 0.2007320895719151", + "Likelihood: 0.25917025899659896", + "Likelihood: 0.2805847559280088", + "Likelihood: 0.25495451167590655", + "Likelihood: 0.13431518630428455", + "Likelihood: 0.2032625510894358", + "Likelihood: 0.25365827664715995", + "Likelihood: 0.24413774931975904", + "Likelihood: 0.21716846596737666", + "Likelihood: 0.23772703468855133", + "Likelihood: 0.24613895948109846", + "Likelihood: 0.1704671700015591", + "Likelihood: 0.22157942127271377", + "Likelihood: 0.2673574698092946", + "Likelihood: 0.2622440775271852", + "Likelihood: 0.21643038215078203", + "Likelihood: 0.2412436318619522", + "Likelihood: 0.20277503957196144", + "Likelihood: 0.28074280240900074", + "Likelihood: 0.11790915874162812", + "Likelihood: 0.21010437123848366", + "Likelihood: 0.15607322199943666", + "Likelihood: 0.14547516011332096", + "Likelihood: 0.2799666033489401", + "Likelihood: 0.21600723385831017", + "Likelihood: 0.19781966742966378", + "Likelihood: 0.20625605489117316", + "Likelihood: 0.25047101838845", + "Likelihood: 0.26593399722678585", + "Likelihood: 0.12415398708281428", + "Likelihood: 0.2028190691781094", + "Likelihood: 0.28018603038259143", + "Likelihood: 0.13067072729399767", + "Likelihood: 0.27439361622676417", + "Likelihood: 0.2107268388383748", + "Likelihood: 0.1913368213294102", + "Likelihood: 0.1950765070746037", + "Likelihood: 0.19694001984250256", + "Likelihood: 0.09012528603474247", + "Likelihood: 0.06536243928254311", + "Likelihood: 0.23089817917164362", + "Likelihood: 0.2833050756224298", + "Likelihood: 0.12635014672826214", + "Likelihood: 0.2684640288950437", + "Likelihood: 0.2518734908524205", + "Likelihood: 0.28008126711781217", + "Likelihood: 0.19598492367836642", + "Likelihood: 0.2627041290440935", + "Likelihood: 0.13508540317143083", + "Likelihood: 0.2770850219388568", + "Likelihood: 0.22830484265512244", + "Likelihood: 0.2711485892354035", + "Likelihood: 0.16101344028676687", + "Likelihood: 0.24132209138698404", + "Likelihood: 0.1885878923259109", + "Likelihood: 0.16528662635728283", + "Likelihood: 0.09513910798852222", + "Likelihood: 0.1650224801138397", + "Likelihood: 0.23217250850163068", + "Likelihood: 0.23376675432776325", + "Likelihood: 0.176063045946337", + "Likelihood: 0.27927032602423346", + "Likelihood: 0.16054202415010332", + "Likelihood: 0.15292734474387673", + "Likelihood: 0.2625534745284116", + "Likelihood: 0.24858823971030938", + "Likelihood: 0.2753019808219775", + "Likelihood: 0.2298699923318757", + "Likelihood: 0.24901111727980982", + "Likelihood: 0.19063791623377557", + "Likelihood: 0.2350456215557457", + "Likelihood: 0.1867460498127031", + "Likelihood: 0.27152459566376813", + "Likelihood: 0.2578471572049096", + "Likelihood: 0.24803038681964948", + "Likelihood: 0.13877926521301018", + "Likelihood: 0.18918104058860125", + "Likelihood: 0.11329395245297653", + "Likelihood: 0.20828885710585282", + "Likelihood: 0.2237033502516991", + "Likelihood: 0.2519132001416812", + "Likelihood: 0.07042507467775543", + "Likelihood: 0.26315473419811797", + "Likelihood: 0.27232907226450603", + "Likelihood: 0.2579193500132577", + "Likelihood: 0.12391381848645035", + "Likelihood: 0.2188421477479769", + "Likelihood: 0.24314444569696025", + "Likelihood: 0.15112156915465236", + "Likelihood: 0.2715752487176161", + "Likelihood: 0.22548499580881587", + "Likelihood: 0.23327308143827608", + "Likelihood: 0.19619337555381042", + "Likelihood: 0.25374711209805595", + "Likelihood: 0.25225497173228234", + "Likelihood: 0.2733514961144272", + "Likelihood: 0.2611599558002902", + "Likelihood: 0.2730562851508506", + "Likelihood: 0.20919482735223807", + "Likelihood: 0.28603121644023816", + "Likelihood: 0.21675019678040344", + "Likelihood: 0.20029117949109082", + "Likelihood: 0.20535692251245288", + "Likelihood: 0.11627150576820083", + "Likelihood: 0.26319896077541993", + "Likelihood: 0.23729349858217977", + "Likelihood: 0.260419899668343", + "Likelihood: 0.17380938280004626", + "Likelihood: 0.2782585989782065", + "Likelihood: 0.17212511026867552", + "Likelihood: 0.2056944096459763", + "Likelihood: 0.2636236170572003", + "Likelihood: 0.14083730078787252", + "Likelihood: 0.19657070347231384", + "Likelihood: 0.20191655159480235", + "Likelihood: 0.11310814472083662", + "Likelihood: 0.07358471991174526", + "Likelihood: 0.12275972032400331", + "Likelihood: 0.2548554998531059", + "Likelihood: 0.25550570250714805", + "Likelihood: 0.2523399409841471", + "Likelihood: 0.2685510653417639", + "Likelihood: 0.2794815919849155", + "Likelihood: 0.25703616111794747", + "Likelihood: 0.2759197606081695", + "Likelihood: 0.2263255599802551", + "Likelihood: 0.21540525382980588", + "Likelihood: 0.22507528680165287", + "Likelihood: 0.2260723611365006", + "Likelihood: 0.27364260569672055", + "Likelihood: 0.19225297545903824", + "Likelihood: 0.2593886717594725", + "Likelihood: 0.1119874913874884", + "Likelihood: 0.20648833332507005", + "Likelihood: 0.044438876143319844", + "Likelihood: 0.13890771894237428", + "Likelihood: 0.23889966270389124", + "Likelihood: 0.23317497142620333", + "Likelihood: 0.2102553667084734", + "Likelihood: 0.21616553180205048", + "Likelihood: 0.16853177686607343", + "Likelihood: 0.20641927318215364", + "Likelihood: 0.2711895497852776", + "Likelihood: 0.24387441056312892", + "Likelihood: 0.20947162915365583", + "Likelihood: 0.1822319175645133", + "Likelihood: 0.21198795261071066", + "Likelihood: 0.2649170051970247", + "Likelihood: 0.24931753820384964", + "Likelihood: 0.17050873003416372", + "Likelihood: 0.2663033873430515", + "Likelihood: 0.14442534042814276", + "Likelihood: 0.18789048517727247", + "Likelihood: 0.22332167158878735", + "Likelihood: 0.12642837462246329", + "Likelihood: 0.27675444986039505", + "Likelihood: 0.24191997065653287", + "Likelihood: 0.2600101992809959", + "Likelihood: 0.12210956092338898", + "Likelihood: 0.26825711134847385", + "Likelihood: 0.26423161338586876", + "Likelihood: 0.06258616691020089", + "Likelihood: 0.193024956079963", + "Likelihood: 0.1947463468135252", + "Likelihood: 0.24711938680446735", + "Likelihood: 0.282200704826556", + "Likelihood: 0.23061468822813788", + "Likelihood: 0.13488963559946143", + "Likelihood: 0.19943324220893746", + "Likelihood: 0.22801130613798484", + "Likelihood: 0.2678312250942803", + "Likelihood: 0.2585146832850092", + "Likelihood: 0.1725715662046506", + "Likelihood: 0.21775774339110093", + "Likelihood: 0.15937553937788917", + "Likelihood: 0.24961570475553205", + "Likelihood: 0.24962294617409655", + "Likelihood: 0.23229335825650374", + "Likelihood: 0.23387422510410708", + "Likelihood: 0.23864939956610756", + "Likelihood: 0.17832022261968292", + "Likelihood: 0.2410697496298089", + "Likelihood: 0.11514468237688068", + "Likelihood: 0.1318932322212576", + "Likelihood: 0.07652130117404858", + "Likelihood: 0.2739095047903807", + "Likelihood: 0.2759844431248325", + "Likelihood: 0.27965121236776624", + "Likelihood: 0.24442455767938745", + "Likelihood: 0.2833661966518392", + "Likelihood: 0.25713473995879627", + "Likelihood: 0.19445694861958235", + "Likelihood: 0.2211565687578668", + "Likelihood: 0.2576077700186185", + "Likelihood: 0.16957145126214138", + "Likelihood: 0.2662120346286997", + "Likelihood: 0.22112608935728206", + "Likelihood: 0.26852572042865", + "Likelihood: 0.25495703937252867", + "Likelihood: 0.22061133155618806", + "Likelihood: 0.22894625870218757", + "Likelihood: 0.24169921854494403", + "Likelihood: 0.28537076057434413", + "Likelihood: 0.2246900976929709", + "Likelihood: 0.2711817044382062", + "Likelihood: 0.22783157325190118", + "Likelihood: 0.10539313432517713", + "Likelihood: 0.2515355208225933", + "Likelihood: 0.25367990157019965", + "Likelihood: 0.197550450370515", + "Likelihood: 0.25266725120394135", + "Likelihood: 0.16821034785734681", + "Likelihood: 0.2382480093559903", + "Likelihood: 0.24123584807470336", + "Likelihood: 0.26609479274200043", + "Likelihood: 0.17522568066606237", + "Likelihood: 0.2749509913640437", + "Likelihood: 0.2843692115393823", + "Likelihood: 0.11533336277001245", + "Likelihood: 0.26391241747975946", + "Likelihood: 0.17315266020051345", + "Likelihood: 0.2033314219910699", + "Likelihood: 0.14438667244340114", + "Likelihood: 0.17094959547356597", + "Likelihood: 0.28266483520111446", + "Likelihood: 0.1628463162249221", + "Likelihood: 0.2460110558863935", + "Likelihood: 0.24792508691975207", + "Likelihood: 0.21267525716859317", + "Likelihood: 0.2547644802967714", + "Likelihood: 0.2700029229010067", + "Likelihood: 0.26076901366946353", + "Likelihood: 0.2710488463974468", + "Likelihood: 0.26132909955516576", + "Likelihood: 0.2135344785313413", + "Likelihood: 0.26776469635706307", + "Likelihood: 0.055836377822829686", + "Likelihood: 0.03237613807828661", + "Likelihood: 0.2035075821300367", + "Likelihood: 0.1692176820175629", + "Likelihood: 0.2713221888816793", + "Likelihood: 0.06783075999443784", + "Likelihood: 0.2739008454389829", + "Likelihood: 0.2375583755748652", + "Likelihood: 0.13957784551588465", + "Likelihood: 0.26585255255294443", + "Likelihood: 0.25355415668033104", + "Likelihood: 0.21497673327807318", + "Likelihood: 0.16847549379388413", + "Likelihood: 0.1901110623008926", + "Likelihood: 0.24042630082135963", + "Likelihood: 0.16786379920727715", + "Likelihood: 0.12652496865183238", + "Likelihood: 0.28846617060862306", + "Likelihood: 0.27831133460769114", + "Likelihood: 0.19355754516174822", + "Likelihood: 0.27161988913699575", + "Likelihood: 0.019061972211805896", + "Likelihood: 0.2510548808649413", + "Likelihood: 0.28873156175650755", + "Likelihood: 0.10268129159966051", + "Likelihood: 0.2184105959422838", + "Likelihood: 0.09334958603861752", + "Likelihood: 0.25680562525105755", + "Likelihood: 0.16872211818543567", + "Likelihood: 0.26251776216629186", + "Likelihood: 0.2902066447214772", + "Likelihood: 0.19497516319409913", + "Likelihood: 0.20707217341819908", + "Likelihood: 0.26458572303459343", + "Likelihood: 0.16332832457993188", + "Likelihood: 0.24528139945293156", + "Likelihood: 0.2625350137413594", + "Likelihood: 0.25415014746149556", + "Likelihood: 0.254759088030215", + "Likelihood: 0.20405505520136463", + "Likelihood: 0.19548324814301626", + "Likelihood: 0.1626282137935981", + "Likelihood: 0.2029651364250574", + "Likelihood: 0.26572884951624165", + "Likelihood: 0.1662519814393004", + "Likelihood: 0.16542586955600683", + "Likelihood: 0.1528526913320465", + "Likelihood: 0.27714338854347337", + "Likelihood: 0.13356959270900132", + "Likelihood: 0.2642518063514087", + "Likelihood: 0.27911494735665704", + "Likelihood: 0.27697797949729025", + "Likelihood: 0.2666711173452773", + "Likelihood: 0.07000118470176697", + "Likelihood: 0.2693589399940803", + "Likelihood: 0.2795544719030789", + "Likelihood: 0.2770063445906241", + "Likelihood: 0.24530157581744833", + "Likelihood: 0.1387686536843856", + "Likelihood: 0.24890583323181453", + "Likelihood: 0.15633165203212165", + "Likelihood: 0.2549215733923591", + "Likelihood: 0.19534502794548358", + "Likelihood: 0.25888852371422905", + "Likelihood: 0.181839614096996", + "Likelihood: 0.2688719856491198", + "Likelihood: 0.025930218949395747", + "Likelihood: 0.0899445711796484", + "Likelihood: 0.27422537530227165", + "Likelihood: 0.06372553610659976", + "Likelihood: 0.16083056325603126", + "Likelihood: 0.21856227339295395", + "Likelihood: 0.2526359366751649", + "Likelihood: 0.21330697471854065", + "Likelihood: 0.06962277867756453", + "Likelihood: 0.09689748724334288", + "Likelihood: 0.2714108391575776", + "Likelihood: 0.2204201024938798", + "Likelihood: 0.20243563197188985", + "Likelihood: 0.24609370071350994", + "Likelihood: 0.05644387406624454", + "Likelihood: 0.20535196209824325", + "Likelihood: 0.05057598976086957", + "Likelihood: 0.2354055300851878", + "Likelihood: 0.27870822565143966", + "Likelihood: 0.0530741546504451", + "Likelihood: 0.08352144757761408", + "Likelihood: 0.20327448490406005", + "Likelihood: 0.2655066303395635", + "Likelihood: 0.1223006675008096", + "Likelihood: 0.19869908251311838", + "Likelihood: 0.2719988264944895", + "Likelihood: 0.19611191438370085", + "Likelihood: 0.2839031270270296", + "Likelihood: 0.19098543221758388", + "Likelihood: 0.22531431211467662", + "Likelihood: 0.2346321070666016", + "Likelihood: 0.2587341587736319", + "Likelihood: 0.16563521768114528", + "Likelihood: 0.16277027023726093", + "Likelihood: 0.2531216018435291", + "Likelihood: 0.06984437477846402", + "Likelihood: 0.20674436072887128", + "Likelihood: 0.25686924399013333", + "Likelihood: 0.26981301162672616", + "Likelihood: 0.22234697481032803", + "Likelihood: 0.15514889500158427", + "Likelihood: 0.26554128364372126", + "Likelihood: 0.1352078442728502", + "Likelihood: 0.14271413324796628", + "Likelihood: 0.24718405198205476", + "Likelihood: 0.0868283669538029", + "Likelihood: 0.08712345350067387", + "Likelihood: 0.033239711556303425", + "Likelihood: 0.2879048429773455", + "Likelihood: 0.1520627183830359", + "Likelihood: 0.06358972410540065", + "Likelihood: 0.26373982962338277", + "Likelihood: 0.2554836498009723", + "Likelihood: 0.2661266491004923", + "Likelihood: 0.26050154359449385", + "Likelihood: 0.22025050482557731", + "Likelihood: 0.266480371740285", + "Likelihood: 0.23927120483271191", + "Likelihood: 0.25308722085893826", + "Likelihood: 0.2717108233178077", + "Likelihood: 0.25115562522306994", + "Likelihood: 0.2559716754326736", + "Likelihood: 0.14116791141247215", + "Likelihood: 0.2063163533966333", + "Likelihood: 0.27770992176863196", + "Likelihood: 0.27416455725877", + "Likelihood: 0.16551447687399357", + "Likelihood: 0.23837149401253313", + "Likelihood: 0.2702321363277116", + "Likelihood: 0.13558449457261643", + "Likelihood: 0.23172460525896738", + "Likelihood: 0.2754452338811167", + "Likelihood: 0.2538045937208622", + "Likelihood: 0.2674379819328193", + "Likelihood: 0.261470463401047", + "Likelihood: 0.08513355042271804", + "Likelihood: 0.22228890676695942", + "Likelihood: 0.28348702556707184", + "Likelihood: 0.1516349611792574", + "Likelihood: 0.26905043680844404", + "Likelihood: 0.2762296624868539", + "Likelihood: 0.16928769160877064", + "Likelihood: 0.09172722730776872", + "Likelihood: 0.13634197540477175", + "Likelihood: 0.0753568010828628", + "Likelihood: 0.1380739367367254", + "Likelihood: 0.11758743842276549", + "Likelihood: 0.2414762279204087", + "Likelihood: 0.28851045894513033", + "Likelihood: 0.10964011353018717", + "Likelihood: 0.19679424484508418", + "Likelihood: 0.27367183907924103", + "Likelihood: 0.26531022348772754", + "Likelihood: 0.26882465104144637", + "Likelihood: 0.23655536217979678", + "Likelihood: 0.23724578303892838", + "Likelihood: 0.24151996930429837", + "Likelihood: 0.10443036652578257", + "Likelihood: 0.28093724600777237", + "Likelihood: 0.2683798718760461", + "Likelihood: 0.17705608228513947", + "Likelihood: 0.28407066339344667", + "Likelihood: 0.27296024952285236", + "Likelihood: 0.26100088320428294", + "Likelihood: 0.12450058133460544", + "Likelihood: 0.27698711701379836", + "Likelihood: 0.18688950658527265", + "Likelihood: 0.22776256099506384", + "Likelihood: 0.23725342632378404", + "Likelihood: 0.18674240989817797", + "Likelihood: 0.21857806620958065", + "Likelihood: 0.23615088740351026", + "Likelihood: 0.25668980742793235", + "Likelihood: 0.261999263151587", + "Likelihood: 0.19375080656529597", + "Likelihood: 0.19371300112068904", + "Likelihood: 0.1759562496872788", + "Likelihood: 0.24514336987943824", + "Likelihood: 0.1928506215241697", + "Likelihood: 0.23988142200609294", + "Likelihood: 0.22976975529204366", + "Likelihood: 0.2608592783345866", + "Likelihood: 0.22751432484684192", + "Likelihood: 0.1443932794397867", + "Likelihood: 0.14323138775180091", + "Likelihood: 0.2698105565605345", + "Likelihood: 0.21451531746282318", + "Likelihood: 0.24621508407014112", + "Likelihood: 0.2772398839543373", + "Likelihood: 0.17856739240136937", + "Likelihood: 0.2877743829168945", + "Likelihood: 0.18029332501451517", + "Likelihood: 0.2709614465795565", + "Likelihood: 0.18475334921221462", + "Likelihood: 0.2718610904785636", + "Likelihood: 0.27501173961078756", + "Likelihood: 0.18788152016365792", + "Likelihood: 0.2110387414026119", + "Likelihood: 0.2491427001078299", + "Likelihood: 0.26803138655002906", + "Likelihood: 0.21529631901178375", + "Likelihood: 0.26145936679472914", + "Likelihood: 0.1897506357207073", + "Likelihood: 0.2826715758930944", + "Likelihood: 0.26570463734307265", + "Likelihood: 0.2865114358780555", + "Likelihood: 0.1707517085288731", + "Likelihood: 0.23588043594527827", + "Likelihood: 0.17712039069623173", + "Likelihood: 0.2598781259990335", + "Likelihood: 0.21363295044077257", + "Likelihood: 0.28048436640884106", + "Likelihood: 0.2592611393286654", + "Likelihood: 0.21006654292411422", + "Likelihood: 0.25235759194762836", + "Likelihood: 0.09476490322638445", + "Likelihood: 0.24366518978594953", + "Likelihood: 0.22602743555336738", + "Likelihood: 0.24093512414359133", + "Likelihood: 0.07604118376243918", + "Likelihood: 0.23096879933603645", + "Likelihood: 0.08078296427039174", + "Likelihood: 0.1833639197428365", + "Likelihood: 0.15245545732213917", + "Likelihood: 0.07726942615364625", + "Likelihood: 0.2829585200089288", + "Likelihood: 0.25892013811996617", + "Likelihood: 0.19456251532709043", + "Likelihood: 0.241408648203832", + "Likelihood: 0.24484279029572054", + "Likelihood: 0.18118547527837522", + "Likelihood: 0.148070386345693", + "Likelihood: 0.18009084137858103", + "Likelihood: 0.28685652403511064", + "Likelihood: 0.27832104940088825", + "Likelihood: 0.12096901990695705", + "Likelihood: 0.22864792976315376", + "Likelihood: 0.24395947993878261", + "Likelihood: 0.2593805946728099", + "Likelihood: 0.2706360991210647", + "Likelihood: 0.1690175351854081", + "Likelihood: 0.24006194436770711", + "Likelihood: 0.27197176091247743", + "Likelihood: 0.18275495684840767", + "Likelihood: 0.24215742166403295", + "Likelihood: 0.2704704932587337", + "Likelihood: 0.2606360280100902", + "Likelihood: 0.28015082333378216", + "Likelihood: 0.1716744259645657", + "Likelihood: 0.22018778960795035", + "Likelihood: 0.14058492596353972", + "Likelihood: 0.09686416073991891", + "Likelihood: 0.21805257785832524", + "Likelihood: 0.2597934148765847", + "Likelihood: 0.2737424493066494", + "Likelihood: 0.24956032881133006", + "Likelihood: 0.24680338173404165", + "Likelihood: 0.2785780745195794", + "Likelihood: 0.2494055467396993", + "Likelihood: 0.26365589299955705", + "Likelihood: 0.27864786684452447", + "Likelihood: 0.14136193805310546", + "Likelihood: 0.2660999274359205", + "Likelihood: 0.2361053183999635", + "Likelihood: 0.11100780837623055", + "Likelihood: 0.25944299669392024", + "Likelihood: 0.2636566293873125", + "Likelihood: 0.17121547547752514", + "Likelihood: 0.23625623034616847", + "Likelihood: 0.21837781700653563", + "Likelihood: 0.2750408898916524", + "Likelihood: 0.22997733784999033", + "Likelihood: 0.2564859946303927", + "Likelihood: 0.24225927045060044", + "Likelihood: 0.2802960004864162", + "Likelihood: 0.2223369260017043", + "Likelihood: 0.24901240852821538", + "Likelihood: 0.2481992117269396", + "Likelihood: 0.23871672228036162", + "Likelihood: 0.2630499008426831", + "Likelihood: 0.22865050560017366", + "Likelihood: 0.2305716206819521", + "Likelihood: 0.23752497892315197", + "Likelihood: 0.2609852383027948", + "Likelihood: 0.12361461580448596", + "Likelihood: 0.17561498965939704", + "Likelihood: 0.18895741364403754", + "Likelihood: 0.2503413462026434", + "Likelihood: 0.21066553178452582", + "Likelihood: 0.20665943980085433", + "Likelihood: 0.18431197509429628", + "Likelihood: 0.24787111181028254", + "Likelihood: 0.1522439432048269", + "Likelihood: 0.27857889562198196", + "Likelihood: 0.25299552914198814", + "Likelihood: 0.21645419928276863", + "Likelihood: 0.1516118355615346", + "Likelihood: 0.24469572132139988", + "Likelihood: 0.2698765886400724", + "Likelihood: 0.19061889032775728", + "Likelihood: 0.2723035140878141", + "Likelihood: 0.23548722401261", + "Likelihood: 0.21840026906887428", + "Likelihood: 0.16688687005927647", + "Likelihood: 0.19251690511215583", + "Likelihood: 0.22720538670358456", + "Likelihood: 0.22145815178399408", + "Likelihood: 0.1967526695209055", + "Likelihood: 0.19402028984496697", + "Likelihood: 0.03165197110165006", + "Likelihood: 0.2693586059896015", + "Likelihood: 0.26421101151897436", + "Likelihood: 0.23289185598032458", + "Likelihood: 0.22731116959184017", + "Likelihood: 0.18096990465703713", + "Likelihood: 0.24405307593282988", + "Likelihood: 0.24170382207487903", + "Likelihood: 0.17532285375419218", + "Likelihood: 0.2433736170723819", + "Likelihood: 0.2476933887577213", + "Likelihood: 0.26830847445785816", + "Likelihood: 0.2653010530648962", + "Likelihood: 0.1865533490724739", + "Likelihood: 0.14981210369735087", + "Likelihood: 0.21280537935927551", + "Likelihood: 0.17844227380048097", + "Likelihood: 0.17955416692716472", + "Likelihood: 0.11661239286403335", + "Likelihood: 0.26543430313607597", + "Likelihood: 0.21579359080342572", + "Likelihood: 0.24548241660857417", + "Likelihood: 0.20664970112106898", + "Likelihood: 0.23880762510788567", + "Likelihood: 0.24016411271446864", + "Likelihood: 0.22852229576899008", + "Likelihood: 0.2396466272456302", + "Likelihood: 0.18095376159663532", + "Likelihood: 0.2532846853727245", + "Likelihood: 0.2879650179621261", + "Likelihood: 0.2799254389195942", + "Likelihood: 0.24739175865105295", + "Likelihood: 0.14388758042922475", + "Likelihood: 0.21403009559275496", + "Likelihood: 0.09341831044849531", + "Likelihood: 0.06438924253553914", + "Likelihood: 0.20139771596521558", + "Likelihood: 0.12173501572333656", + "Likelihood: 0.23579664631167682", + "Likelihood: 0.26147221550893524", + "Likelihood: 0.21272478803759257", + "Likelihood: 0.14755295384375533", + "Likelihood: 0.2876062174913059", + "Likelihood: 0.2459008633087963", + "Likelihood: 0.20221658631491454", + "Likelihood: 0.2798455095820042", + "Likelihood: 0.2692645729908878", + "Likelihood: 0.2657761619224121", + "Likelihood: 0.1918147631436304", + "Likelihood: 0.25026381240982004", + "Likelihood: 0.17857455534914954", + "Likelihood: 0.22903344742293347", + "Likelihood: 0.26460680588349594", + "Likelihood: 0.2893757126774011", + "Likelihood: 0.059336405972595825", + "Likelihood: 0.2666826867594761", + "Likelihood: 0.18224460717034477", + "Likelihood: 0.1647414521975642", + "Likelihood: 0.27253265087065653", + "Likelihood: 0.2690723119828284", + "Likelihood: 0.22902975033251555", + "Likelihood: 0.2843788138551999", + "Likelihood: 0.21720243644846454", + "Likelihood: 0.26483334759493216", + "Likelihood: 0.17467039979664262", + "Likelihood: 0.1582219895918987", + "Likelihood: 0.2806508924561494", + "Likelihood: 0.2603894021306378", + "Likelihood: 0.27651265837765754", + "Likelihood: 0.2051098904870037", + "Likelihood: 0.27209611544250945", + "Likelihood: 0.27348916887765623", + "Likelihood: 0.25880921292613907", + "Likelihood: 0.07313614929002732", + "Likelihood: 0.21291616995764145", + "Likelihood: 0.2550344915566977", + "Likelihood: 0.26700806536678684", + "Likelihood: 0.22489589247991584", + "Likelihood: 0.20130808399942357", + "Likelihood: 0.2649143198110591", + "Likelihood: 0.24908058013725", + "Likelihood: 0.255287390831867", + "Likelihood: 0.24683059834631155", + "Likelihood: 0.20536559267904356", + "Likelihood: 0.22805144669664484", + "Likelihood: 0.09544954267299562", + "Likelihood: 0.26348179903300867", + "Likelihood: 0.24941593748600863", + "Likelihood: 0.2529660947702746", + "Likelihood: 0.26376450757711345", + "Likelihood: 0.27877077092902663", + "Likelihood: 0.2436092628800255", + "Likelihood: 0.2215566471081495", + "Likelihood: 0.18120190663119443", + "Likelihood: 0.19401968937678168", + "Likelihood: 0.1903254324031618", + "Likelihood: 0.290546489275831", + "Likelihood: 0.28464125328999107", + "Likelihood: 0.2781995016219609", + "Likelihood: 0.13723684117365245", + "Likelihood: 0.1682741815238012", + "Likelihood: 0.14592918272003713", + "Likelihood: 0.07437620880520295", + "Likelihood: 0.27086254345694605", + "Likelihood: 0.15995084142206278", + "Likelihood: 0.2514413567801101", + "Likelihood: 0.13111625936891777", + "Likelihood: 0.2783309425369331", + "Likelihood: 0.2385159887862645", + "Likelihood: 0.23752615616090778", + "Likelihood: 0.21862687435449946", + "Likelihood: 0.21628697068006417", + "Likelihood: 0.1684907527622904", + "Likelihood: 0.2650169564044689", + "Likelihood: 0.17027588745192193", + "Likelihood: 0.11950642545692385", + "Likelihood: 0.23001176304144508", + "Likelihood: 0.21198015490184857", + "Likelihood: 0.25712174454969666", + "Likelihood: 0.1854671253383412", + "Likelihood: 0.07699234094817188", + "Likelihood: 0.2592266890969317", + "Likelihood: 0.2727950916755872", + "Likelihood: 0.26109806184400147", + "Likelihood: 0.26355818285772253", + "Likelihood: 0.25312137818287656", + "Likelihood: 0.26373027014806183", + "Likelihood: 0.281073288500227", + "Likelihood: 0.181029287049187", + "Likelihood: 0.27531446902491513", + "Likelihood: 0.17553316529440727", + "Likelihood: 0.06227575640185585", + "Likelihood: 0.2694072224926155", + "Likelihood: 0.2756903577791477", + "Likelihood: 0.2366595179124883", + "Likelihood: 0.22021964993754353", + "Likelihood: 0.286484079233775", + "Likelihood: 0.04852015406994278", + "Likelihood: 0.07776453604427092", + "Likelihood: 0.23906733329139274", + "Likelihood: 0.22125636356307726", + "Likelihood: 0.25810427526547763", + "Likelihood: 0.25545486757806884", + "Likelihood: 0.2512764143868585", + "Likelihood: 0.2722767503166838", + "Likelihood: 0.03556468051814721", + "Likelihood: 0.2778865014168398", + "Likelihood: 0.20619418268196063", + "Likelihood: 0.2783984648687409", + "Likelihood: 0.06275526262939132", + "Likelihood: 0.22398257887764583", + "Likelihood: 0.19183440476364674", + "Likelihood: 0.26417791819607456", + "Likelihood: 0.2356981469234701", + "Likelihood: 0.11884478701022907", + "Likelihood: 0.22324972138317478", + "Likelihood: 0.27291899498456856", + "Likelihood: 0.1983862808936293", + "Likelihood: 0.23921581811163453", + "Likelihood: 0.2749298488108668", + "Likelihood: 0.23677285070636384", + "Likelihood: 0.26041500637593606", + "Likelihood: 0.1868756266878638", + "Likelihood: 0.14656386996310405", + "Likelihood: 0.2596263605640581", + "Likelihood: 0.2751590406241067", + "Likelihood: 0.18536686448246617", + "Likelihood: 0.2149764456606123", + "Likelihood: 0.21477658626070753", + "Likelihood: 0.22708659020500832", + "Likelihood: 0.27408707375512587", + "Likelihood: 0.09066321480172265", + "Likelihood: 0.25630562602936", + "Likelihood: 0.24347547528695676", + "Likelihood: 0.09308848804144675", + "Likelihood: 0.2521064576220632", + "Likelihood: 0.12497996924446621", + "Likelihood: 0.22578182190675217", + "Likelihood: 0.09727189301637908", + "Likelihood: 0.25486339648601586", + "Likelihood: 0.2729747364519274", + "Likelihood: 0.1481364847697132", + "Likelihood: 0.2779120202188293", + "Likelihood: 0.15653566022091953", + "Likelihood: 0.1974672665675038", + "Likelihood: 0.17707179348101798", + "Likelihood: 0.18539970180259352", + "Likelihood: 0.2479997042657566", + "Likelihood: 0.18640959134085766", + "Likelihood: 0.2763135311495187", + "Likelihood: 0.07981768531193446", + "Likelihood: 0.2862824744813071", + "Likelihood: 0.2086916115410227", + "Likelihood: 0.2745544598257201", + "Likelihood: 0.16163728241566652", + "Likelihood: 0.23434636265842576", + "Likelihood: 0.2677682991566488", + "Likelihood: 0.1261685883786039", + "Likelihood: 0.16961513591956257", + "Likelihood: 0.16064945785732362", + "Likelihood: 0.23048578036663936", + "Likelihood: 0.24452043972021412", + "Likelihood: 0.28706436069264973", + "Likelihood: 0.2590563719198895", + "Likelihood: 0.23624876457970692", + "Likelihood: 0.23604690914172022", + "Likelihood: 0.2486047185016833", + "Likelihood: 0.24435937591743584", + "Likelihood: 0.15883202563102314", + "Likelihood: 0.24781553946766297", + "Likelihood: 0.17770858290997363", + "Likelihood: 0.28208654147152257", + "Likelihood: 0.2868479889935742", + "Likelihood: 0.2753362547014846", + "Likelihood: 0.2532946233319956", + "Likelihood: 0.19724838409407053", + "Likelihood: 0.12678254699668037", + "Likelihood: 0.28561362179373606", + "Likelihood: 0.25690985717891596", + "Likelihood: 0.2758892762180845", + "Likelihood: 0.14867908847884537", + "Likelihood: 0.1288137160230199", + "Likelihood: 0.23486248966867704", + "Likelihood: 0.21117632533732522", + "Likelihood: 0.2374565474326426", + "Likelihood: 0.28102157182583165", + "Likelihood: 0.23965791078764428", + "Likelihood: 0.18450307724008425", + "Likelihood: 0.13176944535043555", + "Likelihood: 0.27081076889797595", + "Likelihood: 0.2256273214216212", + "Likelihood: 0.2803845545035477", + "Likelihood: 0.14396121425167832", + "Likelihood: 0.23410677784630748", + "Likelihood: 0.23453297463131437", + "Likelihood: 0.1524709852550037", + "Likelihood: 0.19679336299310954", + "Likelihood: 0.11775720639091036", + "Likelihood: 0.1553669713635173", + "Likelihood: 0.23625974994753499", + "Likelihood: 0.2686982320008977", + "Likelihood: 0.2567443905001633", + "Likelihood: 0.280967513559528", + "Likelihood: 0.2510229908610971", + "Likelihood: 0.23177417376070159", + "Likelihood: 0.24262138198372193", + "Likelihood: 0.1126537936900903", + "Likelihood: 0.2577233017679166", + "Likelihood: 0.27532648104155305", + "Likelihood: 0.25171453090696844", + "Likelihood: 0.27269750826611266", + "Likelihood: 0.2501456028118101", + "Likelihood: 0.1626465524686415", + "Likelihood: 0.23577450542862202", + "Likelihood: 0.2489130544957073", + "Likelihood: 0.06060132578885715", + "Likelihood: 0.19906705940144143", + "Likelihood: 0.2656445773489714", + "Likelihood: 0.27911144954399286", + "Likelihood: 0.21514828823352225", + "Likelihood: 0.20726978261463644", + "Likelihood: 0.2492052386310184", + "Likelihood: 0.2638922308689337", + "Likelihood: 0.06803195200357028", + "Likelihood: 0.25276659631159304", + "Likelihood: 0.2842998631775639", + "Likelihood: 0.25318698099699277", + "Likelihood: 0.22539802113947205", + "Likelihood: 0.26373083467690545", + "Likelihood: 0.26856595460715266", + "Likelihood: 0.23173016209519612", + "Likelihood: 0.22848816464982044", + "Likelihood: 0.26644168508519933", + "Likelihood: 0.2802266840431035", + "Likelihood: 0.21852264971131805", + "Likelihood: 0.19117171391934448", + "Likelihood: 0.23327911423944458", + "Likelihood: 0.20169046528393603", + "Likelihood: 0.24913126512509923", + "Likelihood: 0.2736162636556534", + "Likelihood: 0.1726879421571588", + "Likelihood: 0.24596365387532307", + "Likelihood: 0.22691266253035985", + "Likelihood: 0.22032635947538065", + "Likelihood: 0.2155401687093313", + "Likelihood: 0.26464785560820575", + "Likelihood: 0.2052339721008131", + "Likelihood: 0.18758890906256914", + "Likelihood: 0.10495834672807089", + "Likelihood: 0.1592077515738598", + "Likelihood: 0.24044405236470826", + "Likelihood: 0.25405460886948067", + "Likelihood: 0.2572776574965564", + "Likelihood: 0.2082309988024704", + "Likelihood: 0.2540494096780359", + "Likelihood: 0.27226710144055954", + "Likelihood: 0.2522762278947608", + "Likelihood: 0.1640321498888107", + "Likelihood: 0.21631469200380637", + "Likelihood: 0.26181740318738694", + "Likelihood: 0.2658096067251571", + "Likelihood: 0.1523624173620177", + "Likelihood: 0.14079930903858923", + "Likelihood: 0.045305269407689225", + "Likelihood: 0.15774281244632407", + "Likelihood: 0.12981984660130164", + "Likelihood: 0.26376195064009206", + "Likelihood: 0.25045968130059454", + "Likelihood: 0.18542141152318328", + "Likelihood: 0.1495351759124211", + "Likelihood: 0.18258952662671013", + "Likelihood: 0.18546212936397868", + "Likelihood: 0.21963818577163133", + "Likelihood: 0.2786176957605934", + "Likelihood: 0.2558996805568438", + "Likelihood: 0.1934628014026105", + "Likelihood: 0.2625177393356755", + "Likelihood: 0.16004080752964742", + "Likelihood: 0.24584022166678177", + "Likelihood: 0.19330066077873037", + "Likelihood: 0.22547306405081913", + "Likelihood: 0.12284790248524012", + "Likelihood: 0.2580776328521437", + "Likelihood: 0.22555261322784673", + "Likelihood: 0.27705562826344426", + "Likelihood: 0.2131184242369306", + "Likelihood: 0.2445505738224783", + "Likelihood: 0.17690439833871008", + "Likelihood: 0.2757992540482892", + "Likelihood: 0.1991730180982271", + "Likelihood: 0.21481316577719764", + "Likelihood: 0.2718839601742654", + "Likelihood: 0.24097993684288288", + "Likelihood: 0.2619574060600212", + "Likelihood: 0.26219165923648097", + "Likelihood: 0.2267801826057626", + "Likelihood: 0.26026592994744485", + "Likelihood: 0.2755732795123286", + "Likelihood: 0.2430407274491166", + "Likelihood: 0.2179681796500437", + "Likelihood: 0.1735159403943495", + "Likelihood: 0.2712877199448693", + "Likelihood: 0.2541551552887553", + "Likelihood: 0.1298146021682781", + "Likelihood: 0.2722255519968362", + "Likelihood: 0.22779161992658978", + "Likelihood: 0.2570292227719222", + "Likelihood: 0.16908284847867602", + "Likelihood: 0.2480242416610786", + "Likelihood: 0.12834927630802428", + "Likelihood: 0.26935598157679713", + "Likelihood: 0.2835800087725838", + "Likelihood: 0.27931813312170944", + "Likelihood: 0.22934654550280154", + "Likelihood: 0.28145969058790254", + "Likelihood: 0.08192457372550728", + "Likelihood: 0.26031661818026136", + "Likelihood: 0.19526749287183076", + "Likelihood: 0.16349671766971458", + "Likelihood: 0.25249073624213847", + "Likelihood: 0.07181003597004564", + "Likelihood: 0.2724750791329256", + "Likelihood: 0.2767689147509632", + "Likelihood: 0.1988262924434514", + "Likelihood: 0.19116803358224438", + "Likelihood: 0.25424260284608646", + "Likelihood: 0.27103889227549655", + "Likelihood: 0.1312747250504108", + "Likelihood: 0.27049149469461214", + "Likelihood: 0.2526796368474521", + "Likelihood: 0.2879707516541813", + "Likelihood: 0.2624381968824294", + "Likelihood: 0.11108918468008298", + "Likelihood: 0.24028219325843453", + "Likelihood: 0.1439197006160816", + "Likelihood: 0.27666293847785983", + "Likelihood: 0.18014511930714236", + "Likelihood: 0.25706196029027417", + "Likelihood: 0.25787204990455453", + "Likelihood: 0.03389053737267386", + "Likelihood: 0.2773612816294091", + "Likelihood: 0.2837512837974911", + "Likelihood: 0.18848682212586088", + "Likelihood: 0.07609351234935541", + "Likelihood: 0.28685806883646453", + "Likelihood: 0.2120409045835825", + "Likelihood: 0.13787187490983935", + "Likelihood: 0.2791370325079298", + "Likelihood: 0.2488843592355302", + "Likelihood: 0.2872771346726806", + "Likelihood: 0.2516967528797034", + "Likelihood: 0.186329583043438", + "Likelihood: 0.23862236526197297", + "Likelihood: 0.22147607275657263", + "Likelihood: 0.234809016833285", + "Likelihood: 0.24207991078910066", + "Likelihood: 0.15734546674338284", + "Likelihood: 0.2605741600872656", + "Likelihood: 0.08593251150033612", + "Likelihood: 0.1899561347888706", + "Likelihood: 0.2558589298785291", + "Likelihood: 0.24879341345171796", + "Likelihood: 0.1877998696159295", + "Likelihood: 0.26947874455993415", + "Likelihood: 0.12466225204418807", + "Likelihood: 0.160321990178704", + "Likelihood: 0.22780048733545666", + "Likelihood: 0.22052198523147387", + "Likelihood: 0.25261839410434833", + "Likelihood: 0.2691340015750629", + "Likelihood: 0.20192102780505503", + "Likelihood: 0.175289745342132", + "Likelihood: 0.25450896294447684", + "Likelihood: 0.24492459959689955", + "Likelihood: 0.18503482581650868", + "Likelihood: 0.27002717650412933", + "Likelihood: 0.17971566872918932", + "Likelihood: 0.25985189670273207", + "Likelihood: 0.2581833391363144", + "Likelihood: 0.15316963787730373", + "Likelihood: 0.28877304348639665", + "Likelihood: 0.21540695346729283", + "Likelihood: 0.20984041461473488", + "Likelihood: 0.2540460005865899", + "Likelihood: 0.2678951617233007", + "Likelihood: 0.2572554160278005", + "Likelihood: 0.2614963621498901", + "Likelihood: 0.22385528356420903", + "Likelihood: 0.1525764528749906", + "Likelihood: 0.2134070193865599", + "Likelihood: 0.2794864870074231", + "Likelihood: 0.16799771767819835", + "Likelihood: 0.20370657646483412", + "Likelihood: 0.2229057795246239", + "Likelihood: 0.1501162947687321", + "Likelihood: 0.2469064934066097", + "Likelihood: 0.17472244003149062", + "Likelihood: 0.23754028417972128", + "Likelihood: 0.036356393837930885", + "Likelihood: 0.12411826683437095", + "Likelihood: 0.27867367412270017", + "Likelihood: 0.26623557836524375", + "Likelihood: 0.1510113842098582", + "Likelihood: 0.21835700740267627", + "Likelihood: 0.1496643463839976", + "Likelihood: 0.18514017229976426", + "Likelihood: 0.20931674732137734", + "Likelihood: 0.2228448655031189", + "Likelihood: 0.17148794952326063", + "Likelihood: 0.1956449162397797", + "Likelihood: 0.2313399020680827", + "Likelihood: 0.22672648745997984", + "Likelihood: 0.13872590829947362", + "Likelihood: 0.24629764328650303", + "Likelihood: 0.11037021200141144", + "Likelihood: 0.2577335922464449", + "Likelihood: 0.24722420625251415", + "Likelihood: 0.25510541735987685", + "Likelihood: 0.24698036675127466", + "Likelihood: 0.21635099054806972", + "Likelihood: 0.21122832105666786", + "Likelihood: 0.24245965362299576", + "Likelihood: 0.08186786176948396", + "Likelihood: 0.17426708967931318", + "Likelihood: 0.26598131543870374", + "Likelihood: 0.17472563166079608", + "Likelihood: 0.1266458661895604", + "Likelihood: 0.2169618075761659", + "Likelihood: 0.23408665510057422", + "Likelihood: 0.25540175308368684", + "Likelihood: 0.28253092283730236", + "Likelihood: 0.25088571791350794", + "Likelihood: 0.20919442814392097", + "Likelihood: 0.24736134419059724", + "Likelihood: 0.18639799303592136", + "Likelihood: 0.24971439338832155", + "Likelihood: 0.05683338421596529", + "Likelihood: 0.15427387136325585", + "Likelihood: 0.2769425921655928", + "Likelihood: 0.28604695410162184", + "Likelihood: 0.2071648813272708", + "Likelihood: 0.2680527524819207", + "Likelihood: 0.2514725159974678", + "Likelihood: 0.24060087902333802", + "Likelihood: 0.0893465425259003", + "Likelihood: 0.260440813286459", + "Likelihood: 0.2602525054921459", + "Likelihood: 0.2847393583574644", + "Likelihood: 0.13220155521594665", + "Likelihood: 0.24253246229368292", + "Likelihood: 0.26597914189672733", + "Likelihood: 0.2573788613197233", + "Likelihood: 0.24995654847829246", + "Likelihood: 0.21427139159323783", + "Likelihood: 0.07049227068086866", + "Likelihood: 0.28171094832203625", + "Likelihood: 0.24056089712828743", + "Likelihood: 0.159045769240542", + "Likelihood: 0.10308517924099025", + "Likelihood: 0.133115863921503", + "Likelihood: 0.19483062087553396", + "Likelihood: 0.2749092541679737", + "Likelihood: 0.2200373700159994", + "Likelihood: 0.14606113078078856", + "Likelihood: 0.19891743467030895", + "Likelihood: 0.2858767162253152", + "Likelihood: 0.2827977470432688", + "Likelihood: 0.2733701917441527", + "Likelihood: 0.28364406015792126", + "Likelihood: 0.16598042334255123", + "Likelihood: 0.20489172372413908", + "Likelihood: 0.14841724556033953", + "Likelihood: 0.19457021423119866", + "Likelihood: 0.15816751853633793", + "Likelihood: 0.24590535061159338", + "Likelihood: 0.24222516956379433", + "Likelihood: 0.27147672506575143", + "Likelihood: 0.27118181209111614", + "Likelihood: 0.259823154845583", + "Likelihood: 0.17649587449036153", + "Likelihood: 0.19295058610748234", + "Likelihood: 0.16515056669269393", + "Likelihood: 0.28166381306553107", + "Likelihood: 0.09287806819608047", + "Likelihood: 0.22562637225328155", + "Likelihood: 0.18381090682458487", + "Likelihood: 0.20990213390751122", + "Likelihood: 0.22771475430711471", + "Likelihood: 0.2739414423942593", + "Likelihood: 0.09815850210407089", + "Likelihood: 0.22433961793068452", + "Likelihood: 0.24776626212869005", + "Likelihood: 0.28419980148844937", + "Likelihood: 0.2675701723083817", + "Likelihood: 0.28947599096683346", + "Likelihood: 0.2204625202501865", + "Likelihood: 0.279252845660254", + "Likelihood: 0.2616779080231534", + "Likelihood: 0.17076791828165386", + "Likelihood: 0.1730047318831096", + "Likelihood: 0.24069016025243464", + "Likelihood: 0.2715041407045909", + "Likelihood: 0.22119187473658852", + "Likelihood: 0.1292212049945807", + "Likelihood: 0.21600500769005263", + "Likelihood: 0.14526830099517668", + "Likelihood: 0.26494175172978296", + "Likelihood: 0.14544343504332408", + "Likelihood: 0.2351230254153244", + "Likelihood: 0.2735759606737838", + "Likelihood: 0.28768401708237756", + "Likelihood: 0.1771922374413764", + "Likelihood: 0.20062187207180665", + "Likelihood: 0.06968399946900615", + "Likelihood: 0.2122215529951959", + "Likelihood: 0.22227802705563415", + "Likelihood: 0.20502548929017783", + "Likelihood: 0.2868674465616365", + "Likelihood: 0.26217088880854866", + "Likelihood: 0.13534788486586924", + "Likelihood: 0.14890602526180213", + "Likelihood: 0.25378854203315393", + "Likelihood: 0.14627486492481456", + "Likelihood: 0.19798350387046512", + "Likelihood: 0.24118923249814386", + "Likelihood: 0.26584658124011723", + "Likelihood: 0.18103566009985214", + "Likelihood: 0.10262500019570718", + "Likelihood: 0.21515075056819966", + "Likelihood: 0.10639030895364186", + "Likelihood: 0.12232091444954674", + "Likelihood: 0.21710181868983922", + "Likelihood: 0.20961560622357736", + "Likelihood: 0.10097416731760726", + "Likelihood: 0.2031252667841361", + "Likelihood: 0.07724258361004786", + "Likelihood: 0.1241615597530055", + "Likelihood: 0.26040767403677895", + "Likelihood: 0.18136357009191703", + "Likelihood: 0.1839344270413075", + "Likelihood: 0.22160796690644086", + "Likelihood: 0.23383426651318756", + "Likelihood: 0.07631093562432001", + "Likelihood: 0.1544876631365256", + "Likelihood: 0.17770172851594332", + "Likelihood: 0.0551964619817569", + "Likelihood: 0.15716583039009646", + "Likelihood: 0.08809283437423787", + "Likelihood: 0.2682538954202703", + "Likelihood: 0.21688443627064305", + "Likelihood: 0.0692284190589275", + "Likelihood: 0.17647897620140376", + "Likelihood: 0.08825523044389975", + "Likelihood: 0.20644804896560717", + "Likelihood: 0.240830237255483", + "Likelihood: 0.19147796230323114", + "Likelihood: 0.04229945620644664", + "Likelihood: 0.2128338374557287", + "Likelihood: 0.20294691477675036", + "Likelihood: 0.2344981792327447", + "Likelihood: 0.039262772005959234", + "Likelihood: 0.08317106512578483", + "Likelihood: 0.09180809930643442", + "Likelihood: 0.24377810303082526", + "Likelihood: 0.2863174145432201", + "Likelihood: 0.14472628928768747", + "Likelihood: 0.1433361288467958", + "Likelihood: 0.04617666299361631", + "Likelihood: 0.2249024945896988", + "Likelihood: 0.09288706164221261", + "Likelihood: 0.12985326569537728", + "Likelihood: 0.10453672014133789", + "Likelihood: 0.21809910482812417", + "Likelihood: 0.20789388243483597", + "Likelihood: 0.2321729753812562", + "Likelihood: 0.21707284836220117", + "Likelihood: 0.2301023113902955", + "Likelihood: 0.20902501394334716", + "Likelihood: 0.18284122129194655", + "Likelihood: 0.17224823762459018", + "Likelihood: 0.19838489775093657", + "Likelihood: 0.2677446139387228", + "Likelihood: 0.1571215855619267", + "Likelihood: 0.05971219179495876", + "Likelihood: 0.09293632257122714", + "Likelihood: 0.059964022001104504", + "Likelihood: 0.1499724469944722", + "Likelihood: 0.28548590127171086", + "Likelihood: 0.20585136081543026", + "Likelihood: 0.24779828937513457", + "Likelihood: 0.26033372828377715", + "Likelihood: 0.16771894552439898", + "Likelihood: 0.13428610741318647", + "Likelihood: 0.21184783329229323", + "Likelihood: 0.1364877357927606", + "Likelihood: 0.21271584316866612", + "Likelihood: 0.18245917964678407", + "Likelihood: 0.2345219621361327", + "Likelihood: 0.26661341794276805", + "Likelihood: 0.15080301962298423", + "Likelihood: 0.2846243800862095", + "Likelihood: 0.27688411744259245", + "Likelihood: 0.09317264833592231", + "Likelihood: 0.20447737633006915", + "Likelihood: 0.22607791151817938", + "Likelihood: 0.24389741550988725", + "Likelihood: 0.12984622184689998", + "Likelihood: 0.2503829788054369", + "Likelihood: 0.19639534380405813", + "Likelihood: 0.04835024535072436", + "Likelihood: 0.14924471118340085", + "Likelihood: 0.11326910595639525", + "Likelihood: 0.2080758112448512", + "Likelihood: 0.17882902985801966", + "Likelihood: 0.22351563660775833", + "Likelihood: 0.04148959111782978", + "Likelihood: 0.14027132672418638", + "Likelihood: 0.2051128482135276", + "Likelihood: 0.2436229158283561", + "Likelihood: 0.10126875426678544", + "Likelihood: 0.25888549483956713", + "Likelihood: 0.19473337375921834", + "Likelihood: 0.25756398874152375", + "Likelihood: 0.17653154651432856", + "Likelihood: 0.24416774229928703", + "Likelihood: 0.1738379890544695", + "Likelihood: 0.2145020438803428", + "Likelihood: 0.17125095058824488", + "Likelihood: 0.14544502951547347", + "Likelihood: 0.26747789595029", + "Likelihood: 0.02711197911444816", + "Likelihood: 0.21299838429857884", + "Likelihood: 0.11844998734038364", + "Likelihood: 0.2635919768642971", + "Likelihood: 0.2676343449270705", + "Likelihood: 0.18017684040030518", + "Likelihood: 0.27361048052942727", + "Likelihood: 0.1171932281239063", + "Likelihood: 0.13971306424934038", + "Likelihood: 0.07369961824929588", + "Likelihood: 0.24914014917745797", + "Likelihood: 0.15204218345533602", + "Likelihood: 0.16253470064279313", + "Likelihood: 0.25946670021404045", + "Likelihood: 0.2005841059817093", + "Likelihood: 0.21478239060582746", + "Likelihood: 0.25809240791128363", + "Likelihood: 0.2508329716295816", + "Likelihood: 0.24279202888884024", + "Likelihood: 0.19394487566146756", + "Likelihood: 0.19778391552934818", + "Likelihood: 0.19829249818386493", + "Likelihood: 0.16346326708751835", + "Likelihood: 0.26637845149810485", + "Likelihood: 0.19872165544199547", + "Likelihood: 0.11865973573668462", + "Likelihood: 0.22984606648513592", + "Likelihood: 0.0863495512105819", + "Likelihood: 0.15977514357893208", + "Likelihood: 0.11425630464721077", + "Likelihood: 0.24350848397913907", + "Likelihood: 0.20295779895146396", + "Likelihood: 0.22918390555834273", + "Likelihood: 0.18434151720357345", + "Likelihood: 0.1103723977631552", + "Likelihood: 0.17059432747435133", + "Likelihood: 0.05791654219071694", + "Likelihood: 0.028439567012417295", + "Likelihood: 0.2707548742987902", + "Likelihood: 0.12873586004359763", + "Likelihood: 0.14689840676015525", + "Likelihood: 0.2388560180469484", + "Likelihood: 0.058646664822871716", + "Likelihood: 0.1028048231717061", + "Likelihood: 0.2624468426116323", + "Likelihood: 0.23417799129985695", + "Likelihood: 0.08963438698811173", + "Likelihood: 0.1443506765604378", + "Likelihood: 0.28954317270399144", + "Likelihood: 0.1549307087368068", + "Likelihood: 0.244871959529343", + "Likelihood: 0.2418007707051667", + "Likelihood: 0.13051281833909256", + "Likelihood: 0.21482542398472282", + "Likelihood: 0.1929357206883528", + "Likelihood: 0.026560011358735675", + "Likelihood: 0.1988247111588973", + "Likelihood: 0.04416007279245558", + "Likelihood: 0.06051350081100071", + "Likelihood: 0.14155589992774514", + "Likelihood: 0.09531950257821634", + "Likelihood: 0.17292894519864338", + "Likelihood: 0.16529820407324256", + "Likelihood: 0.23307030726791714", + "Likelihood: 0.10023119431323806", + "Likelihood: 0.23182833968836683", + "Likelihood: 0.16821140612231558", + "Likelihood: 0.17407983685546594", + "Likelihood: 0.22737933151108985", + "Likelihood: 0.21982638581170535", + "Likelihood: 0.15541979191110689", + "Likelihood: 0.2676096141542056", + "Likelihood: 0.26901082764496614", + "Likelihood: 0.11163667865196386", + "Likelihood: 0.14527284826016543", + "Likelihood: 0.1238971216458578", + "Likelihood: 0.22848131609752526", + "Likelihood: 0.14188769515209707", + "Likelihood: 0.2361649939220183", + "Likelihood: 0.14576351039469257", + "Likelihood: 0.1280523699874008", + "Likelihood: 0.21261002046728822", + "Likelihood: 0.12057889684626531", + "Likelihood: 0.09381813102483688", + "Likelihood: 0.22476414749652143", + "Likelihood: 0.2833495520801082", + "Likelihood: 0.15382905368967714", + "Likelihood: 0.16854115970144595", + "Likelihood: 0.13189387243997266", + "Likelihood: 0.2304171617742575", + "Likelihood: 0.20157350945824243", + "Likelihood: 0.2056969587079807", + "Likelihood: 0.16324506512825013", + "Likelihood: 0.04259824393554179", + "Likelihood: 0.11639000162313337", + "Likelihood: 0.1941715468488561", + "Likelihood: 0.2606768651743186", + "Likelihood: 0.2718297333384577", + "Likelihood: 0.08926196075120357", + "Likelihood: 0.0957129146515823", + "Likelihood: 0.26316697665513555", + "Likelihood: 0.24389986411925454", + "Likelihood: 0.18534975147723665", + "Likelihood: 0.042909893294534256", + "Likelihood: 0.23367673016634755", + "Likelihood: 0.2555870112334192", + "Likelihood: 0.2729604532923857", + "Likelihood: 0.144319273596758", + "Likelihood: 0.20524824085618054", + "Likelihood: 0.10122192344268606", + "Likelihood: 0.24301613224349095", + "Likelihood: 0.17935690332465484", + "Likelihood: 0.18705226299595357", + "Likelihood: 0.26377573728165377", + "Likelihood: 0.23971283544376634", + "Likelihood: 0.07039448560524705", + "Likelihood: 0.2546297526019145", + "Likelihood: 0.06928558229217398", + "Likelihood: 0.13096591409927624", + "Likelihood: 0.2359358680513758", + "Likelihood: 0.18526932591667816", + "Likelihood: 0.2749778893207592", + "Likelihood: 0.14128016561292014", + "Likelihood: 0.23162854344127545", + "Likelihood: 0.266871506357275", + "Likelihood: 0.14221388185206366", + "Likelihood: 0.14736425820645346", + "Likelihood: 0.12031551578549189", + "Likelihood: 0.14985307336691014", + "Likelihood: 0.2608320952051009", + "Likelihood: 0.2817714926785862", + "Likelihood: 0.19523049199055098", + "Likelihood: 0.20071973488766764", + "Likelihood: 0.23229730329701415", + "Likelihood: 0.11431285717813283", + "Likelihood: 0.28086533196981045", + "Likelihood: 0.19801146707616402", + "Likelihood: 0.13218250324848713", + "Likelihood: 0.2047646593875008", + "Likelihood: 0.2613500584324332", + "Likelihood: 0.19009228170859627", + "Likelihood: 0.030785125553876812", + "Likelihood: 0.2367469224453345", + "Likelihood: 0.2075290619652275", + "Likelihood: 0.2058206785124014", + "Likelihood: 0.265404915900253", + "Likelihood: 0.136219008055952", + "Likelihood: 0.25135165945577137", + "Likelihood: 0.20184430981724058", + "Likelihood: 0.1903821304420371", + "Likelihood: 0.2183098861326631", + "Likelihood: 0.2501308314563087", + "Likelihood: 0.13158725899606669", + "Likelihood: 0.26566188920889466", + "Likelihood: 0.15242257397372524", + "Likelihood: 0.2094928697625468", + "Likelihood: 0.2041235876418902", + "Likelihood: 0.25719686108326667", + "Likelihood: 0.1202584609923521", + "Likelihood: 0.19587502604737164", + "Likelihood: 0.11768192844128479", + "Likelihood: 0.06498667825898807", + "Likelihood: 0.13613077947438673", + "Likelihood: 0.1815525375059637", + "Likelihood: 0.10883450877806723", + "Likelihood: 0.23235670092938118", + "Likelihood: 0.15835329529220324", + "Likelihood: 0.28196857864231745", + "Likelihood: 0.24011220762059285", + "Likelihood: 0.2534602722214404", + "Likelihood: 0.16898710341807674", + "Likelihood: 0.14848090055191304", + "Likelihood: 0.17560680614517513", + "Likelihood: 0.15321964393236293", + "Likelihood: 0.20129615967641476", + "Likelihood: 0.1772207150811561", + "Likelihood: 0.15836910816379246", + "Likelihood: 0.12928466444135187", + "Likelihood: 0.2021539522645047", + "Likelihood: 0.2676224379993714", + "Likelihood: 0.289426623599089", + "Likelihood: 0.2573841106174896", + "Likelihood: 0.04909944270718949", + "Likelihood: 0.25892226925796064", + "Likelihood: 0.14812298530841056", + "Likelihood: 0.17505852822560136", + "Likelihood: 0.21648667445548098", + "Likelihood: 0.17675777172127724", + "Likelihood: 0.11295528973743453", + "Likelihood: 0.2406632329487745", + "Likelihood: 0.18964886901295555", + "Likelihood: 0.25302774414106116", + "Likelihood: 0.20411398960295887", + "Likelihood: 0.18105258926632883", + "Likelihood: 0.1530628142697841", + "Likelihood: 0.2093451754883044", + "Likelihood: 0.12662782995822527", + "Likelihood: 0.24612113578055358", + "Likelihood: 0.15560737112712755", + "Likelihood: 0.22967194070375938", + "Likelihood: 0.2461806393384184", + "Likelihood: 0.030745299414614787", + "Likelihood: 0.2225816545938214", + "Likelihood: 0.12336749863573855", + "Likelihood: 0.11132957752178628", + "Likelihood: 0.21858030826237812", + "Likelihood: 0.09455944623032203", + "Likelihood: 0.18129099244062474", + "Likelihood: 0.1847385350113696", + "Likelihood: 0.19241803057025678", + "Likelihood: 0.25140958369004623", + "Likelihood: 0.23653748610494008", + "Likelihood: 0.22365573905392871", + "Likelihood: 0.14920112388023163", + "Likelihood: 0.26057979896054806", + "Likelihood: 0.13015400666560084", + "Likelihood: 0.04623316786908865", + "Likelihood: 0.04058319436136979", + "Likelihood: 0.16285370353277026", + "Likelihood: 0.2106461453763092", + "Likelihood: 0.07990965618424609", + "Likelihood: 0.03058196650013465", + "Likelihood: 0.19583570332434166", + "Likelihood: 0.13337348933980261", + "Likelihood: 0.1766237532793417", + "Likelihood: 0.04765625726693236", + "Likelihood: 0.21096183159908105", + "Likelihood: 0.17387096169688568", + "Likelihood: 0.22255341282002736", + "Likelihood: 0.24328778757928177", + "Likelihood: 0.2622352679432388", + "Likelihood: 0.24836113875923213", + "Likelihood: 0.19919124857171863", + "Likelihood: 0.11445988973510697", + "Likelihood: 0.17844958875139", + "Likelihood: 0.2434861401228003", + "Likelihood: 0.260349292002124", + "Likelihood: 0.17419010366920448", + "Likelihood: 0.10360655592853638", + "Likelihood: 0.08312486284006712", + "Likelihood: 0.12573898217433144", + "Likelihood: 0.21508216221362528", + "Likelihood: 0.23268318396917148", + "Likelihood: 0.11586835974136762", + "Likelihood: 0.11440335668402525", + "Likelihood: 0.2534584249114448", + "Likelihood: 0.28622345218334805", + "Likelihood: 0.214392194578067", + "Likelihood: 0.25677813460905413", + "Likelihood: 0.17426097444292624", + "Likelihood: 0.10855624674131427", + "Likelihood: 0.26813627220744435", + "Likelihood: 0.2199297613648956", + "Likelihood: 0.20165369195127403", + "Likelihood: 0.23776693646892538", + "Likelihood: 0.28053470726208996", + "Likelihood: 0.2804456832363384", + "Likelihood: 0.08573983438103142", + "Likelihood: 0.17481141694669217", + "Likelihood: 0.14582320752858888", + "Likelihood: 0.19940077725013558", + "Likelihood: 0.12291270842639361", + "Likelihood: 0.2612430657411288", + "Likelihood: 0.0985157741456799", + "Likelihood: 0.07076176221946888", + "Likelihood: 0.19145309681173886", + "Likelihood: 0.25171742949443876", + "Likelihood: 0.28207842375294484", + "Likelihood: 0.27882808970988915", + "Likelihood: 0.07047460562906496", + "Likelihood: 0.24887134674953204", + "Likelihood: 0.20764759595759805", + "Likelihood: 0.1338735707427028", + "Likelihood: 0.047173202126125975", + "Likelihood: 0.2578985922046003", + "Likelihood: 0.23917943088780888", + "Likelihood: 0.246311485152825", + "Likelihood: 0.21257684306035582", + "Likelihood: 0.20259290844967262", + "Likelihood: 0.26410275379301756", + "Likelihood: 0.2187059936923489", + "Likelihood: 0.21756125574525093", + "Likelihood: 0.23549401203229203", + "Likelihood: 0.2226346299625143", + "Likelihood: 0.033643774535904815", + "Likelihood: 0.2211617379313504", + "Likelihood: 0.15984065320018823", + "Likelihood: 0.2811160098458375", + "Likelihood: 0.1707357455811625", + "Likelihood: 0.27554243741756373", + "Likelihood: 0.18751778378191208", + "Likelihood: 0.2585838492679017", + "Likelihood: 0.15973365994441022", + "Likelihood: 0.1326913271078117", + "Likelihood: 0.13930090965267997", + "Likelihood: 0.14704680094527967", + "Likelihood: 0.12267028615066851", + "Likelihood: 0.23917324352657474", + "Likelihood: 0.23072993805943218", + "Likelihood: 0.2527203926312571", + "Likelihood: 0.06891615072197746", + "Likelihood: 0.15161710500801973", + "Likelihood: 0.21768968374733036", + "Likelihood: 0.09303835614258427", + "Likelihood: 0.28794790187977704", + "Likelihood: 0.18829362185388637", + "Likelihood: 0.18684277217233866", + "Likelihood: 0.11061501124524195", + "Likelihood: 0.2600254077341044", + "Likelihood: 0.23682281589446458", + "Likelihood: 0.07057967021485426", + "Likelihood: 0.25907951561241266", + "Likelihood: 0.16189976124072095", + "Likelihood: 0.19786135648103026", + "Likelihood: 0.06592123209999878", + "Likelihood: 0.17205112947143053", + "Likelihood: 0.12249218875274016", + "Likelihood: 0.2065640922059286", + "Likelihood: 0.13945085162937307", + "Likelihood: 0.012270626827779406", + "Likelihood: 0.08781425896022542", + "Likelihood: 0.1945670720608544", + "Likelihood: 0.16860589239327334", + "Likelihood: 0.08145156421510999", + "Likelihood: 0.19161140993195358", + "Likelihood: 0.07792078435971311", + "Likelihood: 0.23614177562250785", + "Likelihood: 0.22197008863579015", + "Likelihood: 0.26653887601399895", + "Likelihood: 0.2661336106129942", + "Likelihood: 0.13073414102970524", + "Likelihood: 0.24898379914339833", + "Likelihood: 0.07612171032231405", + "Likelihood: 0.1272538752808306", + "Likelihood: 0.2164918439713343", + "Likelihood: 0.26977378035973404", + "Likelihood: 0.25318365491562045", + "Likelihood: 0.19689787776830073", + "Likelihood: 0.1983423862031187", + "Likelihood: 0.04813499905398605", + "Likelihood: 0.14775341870823974", + "Likelihood: 0.25198519319057283", + "Likelihood: 0.24479391806286704", + "Likelihood: 0.17934442137364215", + "Likelihood: 0.17789835530682477", + "Likelihood: 0.2302126044794862", + "Likelihood: 0.13794605716237082", + "Likelihood: 0.14098099005240625", + "Likelihood: 0.24866218042933438", + "Likelihood: 0.20755485769751209", + "Likelihood: 0.10104267764174944", + "Likelihood: 0.22043332593378398", + "Likelihood: 0.08695644511014695", + "Likelihood: 0.1453242714452553", + "Likelihood: 0.24415409861158413", + "Likelihood: 0.06222380839529767", + "Likelihood: 0.2758616490793457", + "Likelihood: 0.16952539000805233", + "Likelihood: 0.09729423319395736", + "Likelihood: 0.20977150196232522", + "Likelihood: 0.1426670250613599", + "Likelihood: 0.19410589621039562", + "Likelihood: 0.1611994381725433", + "Likelihood: 0.04237213926673334", + "Likelihood: 0.22808364421367192", + "Likelihood: 0.1957495848197651", + "Likelihood: 0.27318669049121164", + "Likelihood: 0.15387292937843278", + "Likelihood: 0.24119269703349486", + "Likelihood: 0.1597726680025723", + "Likelihood: 0.13967027276535732", + "Likelihood: 0.20062598557520153", + "Likelihood: 0.23118837064434986", + "Likelihood: 0.10612820087868466", + "Likelihood: 0.2576366444843", + "Likelihood: 0.14039554317620861", + "Likelihood: 0.23344166911251432", + "Likelihood: 0.16613748055505864", + "Likelihood: 0.09207498904573348", + "Likelihood: 0.24479534878627446", + "Likelihood: 0.09217864710247838", + "Likelihood: 0.13831419389743363", + "Likelihood: 0.2276565888116025", + "Likelihood: 0.18654414744576112", + "Likelihood: 0.09698824124593812", + "Likelihood: 0.20651942016364436", + "Likelihood: 0.28627685061670716", + "Likelihood: 0.18253118223162898", + "Likelihood: 0.1430630027263925", + "Likelihood: 0.2264006773744767", + "Likelihood: 0.26540897305457817", + "Likelihood: 0.2179404167504423", + "Likelihood: 0.2287498997604672", + "Likelihood: 0.15416237862048593", + "Likelihood: 0.06737241178223709", + "Likelihood: 0.08411247905167434", + "Likelihood: 0.15705322293607193", + "Likelihood: 0.2826979834594651", + "Likelihood: 0.10745023675110464", + "Likelihood: 0.1308967988200497", + "Likelihood: 0.17599689296741206", + "Likelihood: 0.1941303949631091", + "Likelihood: 0.26839478283359386", + "Likelihood: 0.08786182426142308", + "Likelihood: 0.18237750415671192", + "Likelihood: 0.2210841924551775", + "Likelihood: 0.09235126238827696", + "Likelihood: 0.25866415735014436", + "Likelihood: 0.28854592928592804", + "Likelihood: 0.2423888716059655", + "Likelihood: 0.27626322311817064", + "Likelihood: 0.139256035275102", + "Likelihood: 0.06749752212905767", + "Likelihood: 0.2114329617046887", + "Likelihood: 0.17842013186278077", + "Likelihood: 0.15020593624416337", + "Likelihood: 0.12809460036186193", + "Likelihood: 0.2096434304603408", + "Likelihood: 0.22785351577628873", + "Likelihood: 0.2697742456765819", + "Likelihood: 0.1940933992435547", + "Likelihood: 0.25537331554393045", + "Likelihood: 0.2442753877189558", + "Likelihood: 0.2093938853570889", + "Likelihood: 0.2395800839379614", + "Likelihood: 0.17943091846885817", + "Likelihood: 0.16589919413216417", + "Likelihood: 0.2762152736935443", + "Likelihood: 0.16333055852482467", + "Likelihood: 0.1654754834667832", + "Likelihood: 0.12291899203333542", + "Likelihood: 0.25035177405547776", + "Likelihood: 0.07679795273244724", + "Likelihood: 0.26657340042186495", + "Likelihood: 0.24725306543349693", + "Likelihood: 0.2021967440780308", + "Likelihood: 0.23480991343211804", + "Likelihood: 0.11528415722051279", + "Likelihood: 0.23519688734140481", + "Likelihood: 0.0375656900082059", + "Likelihood: 0.252479763964231", + "Likelihood: 0.21705024226148362", + "Likelihood: 0.15168608947219195", + "Likelihood: 0.27861778808250554", + "Likelihood: 0.1920949835910784", + "Likelihood: 0.14797893829824266", + "Likelihood: 0.1277777961882036", + "Likelihood: 0.21508261858011396", + "Likelihood: 0.1808135029554435", + "Likelihood: 0.2807347127029819", + "Likelihood: 0.0621280004450454", + "Likelihood: 0.2798583357974967", + "Likelihood: 0.08381054342440435", + "Likelihood: 0.28475205563828027", + "Likelihood: 0.20746192988923864", + "Likelihood: 0.2620860710341987", + "Likelihood: 0.20087661057107248", + "Likelihood: 0.2770847163101976", + "Likelihood: 0.1750677186362352", + "Likelihood: 0.2246786635927177", + "Likelihood: 0.27279885675003274", + "Likelihood: 0.14040157271405326", + "Likelihood: 0.21567458173554563", + "Likelihood: 0.23896784467234672", + "Likelihood: 0.1546435032417671", + "Likelihood: 0.25742534632702047", + "Likelihood: 0.1316210151017962", + "Likelihood: 0.16351489296022895", + "Likelihood: 0.10701019632465722", + "Likelihood: 0.15316402786464767", + "Likelihood: 0.18268921672714408", + "Likelihood: 0.10441962035625062", + "Likelihood: 0.20531331603649453", + "Likelihood: 0.14588940670161216", + "Likelihood: 0.247213823883763", + "Likelihood: 0.25229310142121825", + "Likelihood: 0.09600737467391032", + "Likelihood: 0.12158727269564742", + "Likelihood: 0.19182073576740563", + "Likelihood: 0.12529045663833432", + "Likelihood: 0.03024920551395619", + "Likelihood: 0.10283276490637698", + "Likelihood: 0.208925525850516", + "Likelihood: 0.16069289253296334", + "Likelihood: 0.11508284650453525", + "Likelihood: 0.2688506253310587", + "Likelihood: 0.1257860396652202", + "Likelihood: 0.26012947470503994", + "Likelihood: 0.1193088322527172", + "Likelihood: 0.11821392168757376", + "Likelihood: 0.2524648481570442", + "Likelihood: 0.19199515212733193", + "Likelihood: 0.15662379133423487", + "Likelihood: 0.2521210806463315", + "Likelihood: 0.19691173743660018", + "Likelihood: 0.13775604889986387", + "Likelihood: 0.1708908403780286", + "Likelihood: 0.2069122868762995", + "Likelihood: 0.1836368082833266", + "Likelihood: 0.23257775693719593", + "Likelihood: 0.2819272885875473", + "Likelihood: 0.1227453723231736", + "Likelihood: 0.09408503728016182", + "Likelihood: 0.2837898992728114", + "Likelihood: 0.1132760446215896", + "Likelihood: 0.2036273208195514", + "Likelihood: 0.1245927851032294", + "Likelihood: 0.170645802613902", + "Likelihood: 0.14385332380529384", + "Likelihood: 0.19190748055985102", + "Likelihood: 0.19275070003318753", + "Likelihood: 0.2072323743589119", + "Likelihood: 0.15603788030182988", + "Likelihood: 0.24310512791148584", + "Likelihood: 0.2153937962202863", + "Likelihood: 0.21729430719194828", + "Likelihood: 0.1416604758526873", + "Likelihood: 0.1730997539675717", + "Likelihood: 0.24331709946745883", + "Likelihood: 0.17385556342329786", + "Likelihood: 0.15269928072171188", + "Likelihood: 0.22203837833850862", + "Likelihood: 0.19891347551157507", + "Likelihood: 0.2086556879025255", + "Likelihood: 0.09088967052251984", + "Likelihood: 0.16040686799525758", + "Likelihood: 0.1090653385267299", + "Likelihood: 0.141256637231975", + "Likelihood: 0.21197275620608966", + "Likelihood: 0.18984696615884944", + "Likelihood: 0.25786065642420475", + "Likelihood: 0.23168427531085148", + "Likelihood: 0.12883298105039426", + "Likelihood: 0.2744791270479169", + "Likelihood: 0.2578024097930092", + "Likelihood: 0.19614549903553444", + "Likelihood: 0.2858542663678962", + "Likelihood: 0.2656492558015909", + "Likelihood: 0.0776264476064738", + "Likelihood: 0.105624353149062", + "Likelihood: 0.26893623340232553", + "Likelihood: 0.16588964361653888", + "Likelihood: 0.1355980546153005", + "Likelihood: 0.2480290972862495", + "Likelihood: 0.19165979622073728", + "Likelihood: 0.2241955780319615", + "Likelihood: 0.033850014998731845", + "Likelihood: 0.165068648161465", + "Likelihood: 0.15767304971381754", + "Likelihood: 0.19182723910183805", + "Likelihood: 0.18984869556989517", + "Likelihood: 0.17276720527245013", + "Likelihood: 0.21194632107558634", + "Likelihood: 0.0872176448924518", + "Likelihood: 0.27599902582261493", + "Likelihood: 0.15443851306869402", + "Likelihood: 0.20367502610950228", + "Likelihood: 0.14184360996873147", + "Likelihood: 0.18850483281375274", + "Likelihood: 0.21549831881628434", + "Likelihood: 0.1982751759791204", + "Likelihood: 0.23232044186948902", + "Likelihood: 0.12265809164401838", + "Likelihood: 0.15041909581180612", + "Likelihood: 0.1807972710235749", + "Likelihood: 0.2334383933483611", + "Likelihood: 0.25731469238743543", + "Likelihood: 0.25311745597610197", + "Likelihood: 0.09916246052046698", + "Likelihood: 0.2594052774986187", + "Likelihood: 0.17667451988956678", + "Likelihood: 0.1084320443858997", + "Likelihood: 0.06539499582408863", + "Likelihood: 0.13138385605850864", + "Likelihood: 0.20837509250586078", + "Likelihood: 0.15053920991176153", + "Likelihood: 0.175015544354918", + "Likelihood: 0.08050361034902569", + "Likelihood: 0.25558943368066805", + "Likelihood: 0.16334508911904017", + "Likelihood: 0.269678067517947", + "Likelihood: 0.2263244448827851", + "Likelihood: 0.26071508473684113", + "Likelihood: 0.23006843128348778", + "Likelihood: 0.17243811438777107", + "Likelihood: 0.20592681592622827", + "Likelihood: 0.2141043630530816", + "Likelihood: 0.1706348693244519", + "Likelihood: 0.15301364765313946", + "Likelihood: 0.14177944536283144", + "Likelihood: 0.1543882768249335", + "Likelihood: 0.17460776923291835", + "Likelihood: 0.18987833913501934", + "Likelihood: 0.10099899079605659", + "Likelihood: 0.1551923181408733", + "Likelihood: 0.029101450053915262", + "Likelihood: 0.21639730267427204", + "Likelihood: 0.09694379020784091", + "Likelihood: 0.19151785063209964", + "Likelihood: 0.2701816405780056", + "Likelihood: 0.15636569604664996", + "Likelihood: 0.03660474726921501", + "Likelihood: 0.27827564555036144", + "Likelihood: 0.10264769226753977", + "Likelihood: 0.1523111243969546", + "Likelihood: 0.14860929483215649", + "Likelihood: 0.15587475950427107", + "Likelihood: 0.05234819899797457", + "Likelihood: 0.25690476109960503", + "Likelihood: 0.08371109772804991", + "Likelihood: 0.2608313750829812", + "Likelihood: 0.2574940542962401", + "Likelihood: 0.06172693074290413", + "Likelihood: 0.08364499294034385", + "Likelihood: 0.1110479901878924", + "Likelihood: 0.26242371302763173", + "Likelihood: 0.158626100551709", + "Likelihood: 0.26313242284536276", + "Likelihood: 0.1852197363395226", + "Likelihood: 0.1982734390153032", + "Likelihood: 0.2886475947512067", + "Likelihood: 0.21059942549469587", + "Likelihood: 0.08018535906671541", + "Likelihood: 0.14792028319585968", + "Likelihood: 0.25979854034463495", + "Likelihood: 0.08710955928727382", + "Likelihood: 0.24748841927081633", + "Likelihood: 0.07330065812065258", + "Likelihood: 0.24196486647947976", + "Likelihood: 0.20778155882138596", + "Likelihood: 0.21311215296876637", + "Likelihood: 0.2403884102026312", + "Likelihood: 0.1330302003521689", + "Likelihood: 0.09187408359346724", + "Likelihood: 0.24733771903439047", + "Likelihood: 0.19724370025008559", + "Likelihood: 0.28597144334944347", + "Likelihood: 0.25063561543096174", + "Likelihood: 0.21953864352891145", + "Likelihood: 0.1635090883489984", + "Likelihood: 0.1833969262161917", + "Likelihood: 0.27666602840480375", + "Likelihood: 0.2771728746758523", + "Likelihood: 0.051466784493377424", + "Likelihood: 0.05677811148944689", + "Likelihood: 0.11399034867676054", + "Likelihood: 0.0953530908622952", + "Likelihood: 0.25654391928386616", + "Likelihood: 0.20291694206196653", + "Likelihood: 0.11554499204227446", + "Likelihood: 0.18063927187865877", + "Likelihood: 0.2537500888791862", + "Likelihood: 0.19676483256715904", + "Likelihood: 0.2466273730411907", + "Likelihood: 0.1417005528607608", + "Likelihood: 0.2000419758290969", + "Likelihood: 0.2738316693395545", + "Likelihood: 0.09709782910922778", + "Likelihood: 0.17931024884725094", + "Likelihood: 0.179709943207864", + "Likelihood: 0.22427744234958427", + "Likelihood: 0.188505033699171", + "Likelihood: 0.2111123577456583", + "Likelihood: 0.18883949519493434", + "Likelihood: 0.22316963405769677", + "Likelihood: 0.1954090260129116", + "Likelihood: 0.23395215869635877", + "Likelihood: 0.28498917945669994", + "Likelihood: 0.21728512598224453", + "Likelihood: 0.11183559115425482", + "Likelihood: 0.2585430856850834", + "Likelihood: 0.19951195317140077", + "Likelihood: 0.2525730170237296", + "Likelihood: 0.11338618203406148", + "Likelihood: 0.22811432104407817", + "Likelihood: 0.2891941751830169", + "Likelihood: 0.03471749113098697", + "Likelihood: 0.1464924677754743", + "Likelihood: 0.09971543319014378", + "Likelihood: 0.17317207357330222", + "Likelihood: 0.17351489552150953", + "Likelihood: 0.2349055801078571", + "Likelihood: 0.11635705440883842", + "Likelihood: 0.22778245859950835", + "Likelihood: 0.043639433185540796", + "Likelihood: 0.23832817634010142", + "Likelihood: 0.14793800591120415", + "Likelihood: 0.2731981938593026", + "Likelihood: 0.09695757533737179", + "Likelihood: 0.12556831357302795", + "Likelihood: 0.18201097456385024", + "Likelihood: 0.011632088391526664", + "Likelihood: 0.20047414151719808", + "Likelihood: 0.14864974261664243", + "Likelihood: 0.18735749656158243", + "Likelihood: 0.09701827765647197", + "Likelihood: 0.28010826018993384", + "Likelihood: 0.07561978875596259", + "Likelihood: 0.20769961512694385", + "Likelihood: 0.16436639215263288", + "Likelihood: 0.11095847075349814", + "Likelihood: 0.1779160140658837", + "Likelihood: 0.2358549803910504", + "Likelihood: 0.13488923393716606", + "Likelihood: 0.27946283257898447", + "Likelihood: 0.13769143691001468", + "Likelihood: 0.1942134315220407", + "Likelihood: 0.10631018314930203", + "Likelihood: 0.2754834383808306", + "Likelihood: 0.24988381089979173", + "Likelihood: 0.23480074785494207", + "Likelihood: 0.2452160280247035", + "Likelihood: 0.22510844035863403", + "Likelihood: 0.09092752817093103", + "Likelihood: 0.268165037708702", + "Likelihood: 0.03906318767409115", + "Likelihood: 0.18170790983838117", + "Likelihood: 0.25132336991733545", + "Likelihood: 0.23282561122789866", + "Likelihood: 0.19458879773575943", + "Likelihood: 0.2695542641320645", + "Likelihood: 0.1696750277504574", + "Likelihood: 0.19192850287311866", + "Likelihood: 0.1510535500845508", + "Likelihood: 0.11725025901939735", + "Likelihood: 0.12838645260063375", + "Likelihood: 0.11169360500013296", + "Likelihood: 0.11869405441423508", + "Likelihood: 0.16191609911539886", + "Likelihood: 0.04376955943918977", + "Likelihood: 0.1999868198470099", + "Likelihood: 0.21237456719968056", + "Likelihood: 0.22267988970786554", + "Likelihood: 0.2303051824679936", + "Likelihood: 0.2542879530987271", + "Likelihood: 0.141998273955245", + "Likelihood: 0.062239716968171946", + "Likelihood: 0.197766543979011", + "Likelihood: 0.1346296299473567", + "Likelihood: 0.16577872238880306", + "Likelihood: 0.26414734640632864", + "Likelihood: 0.2629768907125166", + "Likelihood: 0.19641418546334471", + "Likelihood: 0.2599056258571008", + "Likelihood: 0.12849039771762166", + "Likelihood: 0.0582865161606589", + "Likelihood: 0.07602599389379368", + "Likelihood: 0.1676512730824043", + "Likelihood: 0.12605281499461332", + "Likelihood: 0.13701493261573736", + "Likelihood: 0.1732988436362183", + "Likelihood: 0.21138716241759822", + "Likelihood: 0.06823739929183552", + "Likelihood: 0.06703652712074798", + "Likelihood: 0.2657630997589362", + "Likelihood: 0.1254674782398654", + "Likelihood: 0.16148367674718425", + "Likelihood: 0.10918611618445022", + "Likelihood: 0.20219690137029625", + "Likelihood: 0.2400065752464977", + "Likelihood: 0.17925497510344984", + "Likelihood: 0.07830953289534001", + "Likelihood: 0.14143147766768588", + "Likelihood: 0.2392477885489649", + "Likelihood: 0.20433136719466635", + "Likelihood: 0.20563365484461732", + "Likelihood: 0.2824973233045272", + "Likelihood: 0.2723855285257391", + "Likelihood: 0.22930634278456738", + "Likelihood: 0.15897917021203808", + "Likelihood: 0.2861893069457066", + "Likelihood: 0.2636737455794576", + "Likelihood: 0.24450929482630726", + "Likelihood: 0.10271747954200527", + "Likelihood: 0.15988648730671748", + "Likelihood: 0.22921520310531993", + "Likelihood: 0.24090173274098936", + "Likelihood: 0.24705401723135936", + "Likelihood: 0.16762952522599775", + "Likelihood: 0.14102665215435098", + "Likelihood: 0.15559078887060482", + "Likelihood: 0.0939737763886684", + "Likelihood: 0.10399114575475242", + "Likelihood: 0.15769978336689758", + "Likelihood: 0.2607187802856008", + "Likelihood: 0.18692480322052482", + "Likelihood: 0.24892296464604205", + "Likelihood: 0.17093055758122566", + "Likelihood: 0.27946700620323667", + "Likelihood: 0.25408062649944274", + "Likelihood: 0.2636210344661899", + "Likelihood: 0.12037986917089719", + "Likelihood: 0.13354509902910822", + "Likelihood: 0.1568801835650685", + "Likelihood: 0.11830576964262525", + "Likelihood: 0.2630888699703665", + "Likelihood: 0.26564951613682114", + "Likelihood: 0.25214160919449374", + "Likelihood: 0.1929350671600347", + "Likelihood: 0.2182599340556476", + "Likelihood: 0.16370475101029186", + "Likelihood: 0.1992863371991725", + "Likelihood: 0.17159956275204444", + "Likelihood: 0.2445117748464269", + "Likelihood: 0.2431048722374709", + "Likelihood: 0.212519270346447", + "Likelihood: 0.21427158039336575", + "Likelihood: 0.26934980063867164", + "Likelihood: 0.21638870571732252", + "Likelihood: 0.15910609563142164", + "Likelihood: 0.1401523494055488", + "Likelihood: 0.26736606895084974", + "Likelihood: 0.12887054112047638", + "Likelihood: 0.28950850437743825", + "Likelihood: 0.2782204488678203", + "Likelihood: 0.2272735707894255", + "Likelihood: 0.19158155843746258", + "Likelihood: 0.2410927040582266", + "Likelihood: 0.27345478894068465", + "Likelihood: 0.12283709921837145", + "Likelihood: 0.1993258999116287", + "Likelihood: 0.08076771036699043", + "Likelihood: 0.11708245842276428", + "Likelihood: 0.07770203057205514", + "Likelihood: 0.13993127705683833", + "Likelihood: 0.2826176672407659", + "Likelihood: 0.2383664450873173", + "Likelihood: 0.2768796028748017", + "Likelihood: 0.06094254150419864", + "Likelihood: 0.2846379145777949", + "Likelihood: 0.14958515060585523", + "Likelihood: 0.10694761864884914", + "Likelihood: 0.1416970618601137", + "Likelihood: 0.059818402720707", + "Likelihood: 0.21865587715113163", + "Likelihood: 0.12104579782803734", + "Likelihood: 0.20517143485057088", + "Likelihood: 0.2461553478711322", + "Likelihood: 0.2061793203821505", + "Likelihood: 0.25234140685901246", + "Likelihood: 0.2600298214770484", + "Likelihood: 0.24763916744740688", + "Likelihood: 0.2075247479703903", + "Likelihood: 0.0929239333721719", + "Likelihood: 0.28642325712961025", + "Likelihood: 0.16529615400988903", + "Likelihood: 0.25089351026434836", + "Likelihood: 0.24593596100575113", + "Likelihood: 0.10301431869919027", + "Likelihood: 0.15191822893392726", + "Likelihood: 0.14864104746886467", + "Likelihood: 0.15707969782613745", + "Likelihood: 0.09475543496299942", + "Likelihood: 0.18801686550028315", + "Likelihood: 0.15073276074463307", + "Likelihood: 0.18632724050436145", + "Likelihood: 0.1205634687277288", + "Likelihood: 0.2526858699840442", + "Likelihood: 0.19882703351804967", + "Likelihood: 0.2354966357202248", + "Likelihood: 0.23597095599672863", + "Likelihood: 0.2403124977172766", + "Likelihood: 0.18463848881086772", + "Likelihood: 0.02217855115392386", + "Likelihood: 0.11343263487818461", + "Likelihood: 0.2059083441293325", + "Likelihood: 0.24941617675755803", + "Likelihood: 0.08724454740261992", + "Likelihood: 0.18291213838762427", + "Likelihood: 0.2182543128384094", + "Likelihood: 0.2566627042200325", + "Likelihood: 0.05373810596229329", + "Likelihood: 0.20689530145291393", + "Likelihood: 0.09014471862805955", + "Likelihood: 0.14883536778585388", + "Likelihood: 0.24525176294677056", + "Likelihood: 0.15619888989664293", + "Likelihood: 0.11804668887978326", + "Likelihood: 0.26189718103106", + "Likelihood: 0.04054158534574264", + "Likelihood: 0.1923375122595892", + "Likelihood: 0.2265099376520235", + "Likelihood: 0.13969297778207257", + "Likelihood: 0.2185401205333522", + "Likelihood: 0.23428056471356898", + "Likelihood: 0.22246127302478783", + "Likelihood: 0.18887818258052141", + "Likelihood: 0.23973524863750859", + "Likelihood: 0.1388523044637558", + "Likelihood: 0.268708578326544", + "Likelihood: 0.17434616819490276", + "Likelihood: 0.2725523538449824", + "Likelihood: 0.2753247189904028", + "Likelihood: 0.20329910823215208", + "Likelihood: 0.28937814864522987", + "Likelihood: 0.10850781254519838", + "Likelihood: 0.2208581054413282", + "Likelihood: 0.19282850464834173", + "Likelihood: 0.17575684479807818", + "Likelihood: 0.1990420326305716", + "Likelihood: 0.28163997983778305", + "Likelihood: 0.13486012779213774", + "Likelihood: 0.14458359161351597", + "Likelihood: 0.23466641614018843", + "Likelihood: 0.06290883820611347", + "Likelihood: 0.27596698405666803", + "Likelihood: 0.13893938872873085", + "Likelihood: 0.1610110587627423", + "Likelihood: 0.09733157075381993", + "Likelihood: 0.2025585654249374", + "Likelihood: 0.1185017210551913", + "Likelihood: 0.23092998500720938", + "Likelihood: 0.21175082959802127", + "Likelihood: 0.17559459429471302", + "Likelihood: 0.11053665008593389", + "Likelihood: 0.08561950952246578", + "Likelihood: 0.22569476347038422", + "Likelihood: 0.19600195169627177", + "Likelihood: 0.04635732682685011", + "Likelihood: 0.06911759229418932", + "Likelihood: 0.24065561606833527", + "Likelihood: 0.28458209489532493", + "Likelihood: 0.23159187138751952", + "Likelihood: 0.24310620180423426", + "Likelihood: 0.04456369978698915", + "Likelihood: 0.14508502608885837", + "Likelihood: 0.12577828308627045", + "Likelihood: 0.2716781564882761", + "Likelihood: 0.1262058593365751", + "Likelihood: 0.25994121162962575", + "Likelihood: 0.19670969285938883", + "Likelihood: 0.20199631872939403", + "Likelihood: 0.24943933556737935", + "Likelihood: 0.14856664437785352", + "Likelihood: 0.19135650712513408", + "Likelihood: 0.1396906056211332", + "Likelihood: 0.1324394267170767", + "Likelihood: 0.1806107263660591", + "Likelihood: 0.2746554213904888", + "Likelihood: 0.15228780075011206", + "Likelihood: 0.06030760487905215", + "Likelihood: 0.15199477722969057", + "Likelihood: 0.24900805178864033", + "Likelihood: 0.19065841984070625", + "Likelihood: 0.147666977906874", + "Likelihood: 0.18005425421210022", + "Likelihood: 0.06752236765333357", + "Likelihood: 0.1413545531221729", + "Likelihood: 0.08261891141846689", + "Likelihood: 0.19424160275762914", + "Likelihood: 0.17846265771776026", + "Likelihood: 0.27345494853173524", + "Likelihood: 0.17908028428711426", + "Likelihood: 0.12193220211153928", + "Likelihood: 0.11182495057238527", + "Likelihood: 0.27168983280172304", + "Likelihood: 0.19044238954011503", + "Likelihood: 0.09092173133790131", + "Likelihood: 0.020424119258540815", + "Likelihood: 0.1691984642156462", + "Likelihood: 0.23918673782153355", + "Likelihood: 0.23388127333539135", + "Likelihood: 0.24448162901795456", + "Likelihood: 0.19692911407428756", + "Likelihood: 0.1387014228077532", + "Likelihood: 0.12060099040055873", + "Likelihood: 0.13159960135581786", + "Likelihood: 0.2877151269919149", + "Likelihood: 0.29087775923362114", + "Likelihood: 0.2680410109353732", + "Likelihood: 0.27256462484521066", + "Likelihood: 0.12236819028704102", + "Likelihood: 0.24124216380539312", + "Likelihood: 0.169236142647081", + "Likelihood: 0.11542757925868867", + "Likelihood: 0.12416655538832443", + "Likelihood: 0.19235169792609197", + "Likelihood: 0.2153688860178787", + "Likelihood: 0.04487536325730397", + "Likelihood: 0.21715724733789066", + "Likelihood: 0.17109341341565334", + "Likelihood: 0.20269909308394646", + "Likelihood: 0.2180826808762483", + "Likelihood: 0.09067603335338557", + "Likelihood: 0.26465182272837345", + "Likelihood: 0.0058671612233197196", + "Likelihood: 0.04172074996116439", + "Likelihood: 0.08888839755698216", + "Likelihood: 0.24327935636558465", + "Likelihood: 0.05026885078866334", + "Likelihood: 0.22000938748298748", + "Likelihood: 0.1090954493055032", + "Likelihood: 0.26712438807431865", + "Likelihood: 0.2007246119600219", + "Likelihood: 0.2570605466458923", + "Likelihood: 0.24047989971289102", + "Likelihood: 0.2421100232247362", + "Likelihood: 0.2902778096154945", + "Likelihood: 0.15776318350478274", + "Likelihood: 0.21330276851382185", + "Likelihood: 0.11704897630642898", + "Likelihood: 0.2385135702920149", + "Likelihood: 0.08647746057758379", + "Likelihood: 0.26255064857153304", + "Likelihood: 0.23581847667929598", + "Likelihood: 0.23758521086385254", + "Likelihood: 0.180712172870437", + "Likelihood: 0.18807284450997866", + "Likelihood: 0.18545495242836202", + "Likelihood: 0.16203992711677898", + "Likelihood: 0.11410753841599613", + "Likelihood: 0.1608526787827645", + "Likelihood: 0.11839101286412264", + "Likelihood: 0.163331314188879", + "Likelihood: 0.05657197086540291", + "Likelihood: 0.06953916639673564", + "Likelihood: 0.19062598265773523", + "Likelihood: 0.23421605428470738", + "Likelihood: 0.25739885998135886", + "Likelihood: 0.07772703293848618", + "Likelihood: 0.13651313649468938", + "Likelihood: 0.1837737988824325", + "Likelihood: 0.27094643016899056", + "Likelihood: 0.25295750428168867", + "Likelihood: 0.22672033891405535", + "Likelihood: 0.17948677408432942", + "Likelihood: 0.203355982562457", + "Likelihood: 0.11409033120298932", + "Likelihood: 0.08411268621729814", + "Likelihood: 0.024319864958075522", + "Likelihood: 0.20654673847387006", + "Likelihood: 0.27814372164513673", + "Likelihood: 0.12789439002316763", + "Likelihood: 0.24140813649519083", + "Likelihood: 0.2666002698008852", + "Likelihood: 0.06012823237667371", + "Likelihood: 0.16349666157492473", + "Likelihood: 0.15778208491858342", + "Likelihood: 0.20239553704429242", + "Likelihood: 0.24927603763518177", + "Likelihood: 0.10780610208151081", + "Likelihood: 0.22887475987509606", + "Likelihood: 0.18006174804355352", + "Likelihood: 0.1186274897999771", + "Likelihood: 0.1360887053585363", + "Likelihood: 0.06278824447804462", + "Likelihood: 0.1743039498914448", + "Likelihood: 0.2813629877065194", + "Likelihood: 0.04619981473823426", + "Likelihood: 0.2488105964206593", + "Likelihood: 0.24564958966371808", + "Likelihood: 0.15815657339480138", + "Likelihood: 0.22769251144831898", + "Likelihood: 0.056250379769217776", + "Likelihood: 0.13532363697838845", + "Likelihood: 0.27753784103101026", + "Likelihood: 0.04525125484813817", + "Likelihood: 0.1785064083962465", + "Likelihood: 0.1788742327193124", + "Likelihood: 0.1146401934960285", + "Likelihood: 0.21567588871090096", + "Likelihood: 0.09287534256698171", + "Likelihood: 0.20759846677509436", + "Likelihood: 0.22442755774738626", + "Likelihood: 0.03963665205565956", + "Likelihood: 0.21285850857141606", + "Likelihood: 0.20347486671680323", + "Likelihood: 0.14974974448732026", + "Likelihood: 0.13266319045191777", + "Likelihood: 0.0891996171158043", + "Likelihood: 0.0983404142118975", + "Likelihood: 0.17339952830347574", + "Likelihood: 0.2697260605360561", + "Likelihood: 0.1837946716895355", + "Likelihood: 0.24964133200491279", + "Likelihood: 0.14740836477776026", + "Likelihood: 0.16809720194960698", + "Likelihood: 0.2631212058416629", + "Likelihood: 0.17328821910704034", + "Likelihood: 0.25854681170971233", + "Likelihood: 0.13707166930976591", + "Likelihood: 0.11301128479514316", + "Likelihood: 0.1430803758701711", + "Likelihood: 0.09824672010822348", + "Likelihood: 0.27225261221397945", + "Likelihood: 0.20046252529261332", + "Likelihood: 0.23717265574475682", + "Likelihood: 0.16360328365980292", + "Likelihood: 0.16089807321971106", + "Likelihood: 0.2553875050589144", + "Likelihood: 0.15965678420587126", + "Likelihood: 0.1619361678152101", + "Likelihood: 0.24737218135392114", + "Likelihood: 0.16437869137348413", + "Likelihood: 0.17862011042476575", + "Likelihood: 0.206023237967503", + "Likelihood: 0.055682681909969146", + "Likelihood: 0.20004087142815338", + "Likelihood: 0.0427061558274348", + "Likelihood: 0.09751486204630405", + "Likelihood: 0.1609138138159152", + "Likelihood: 0.21608594870081815", + "Likelihood: 0.1288654979199855", + "Likelihood: 0.16653698339074643", + "Likelihood: 0.048816543607479466", + "Likelihood: 0.2077544814151611", + "Likelihood: 0.14240763664596928", + "Likelihood: 0.01634545532188688", + "Likelihood: 0.281473924488448", + "Likelihood: 0.04735350245343979", + "Likelihood: 0.26476474042392933", + "Likelihood: 0.17374111799895692", + "Likelihood: 0.2146946993993338", + "Likelihood: 0.15319725561351852", + "Likelihood: 0.2739126128541199", + "Likelihood: 0.12978372417537062", + "Likelihood: 0.14504491361765168", + "Likelihood: 0.24229739032331485", + "Likelihood: 0.16846223701687235", + "Likelihood: 0.2688733659914104", + "Likelihood: 0.259540267766537", + "Likelihood: 0.2427200135340016", + "Likelihood: 0.18019613052947334", + "Likelihood: 0.21329140672251054", + "Likelihood: 0.07165157259045002", + "Likelihood: 0.06433593817665653", + "Likelihood: 0.2338459854275045", + "Likelihood: 0.1711227663067419", + "Likelihood: 0.2736104403020991", + "Likelihood: 0.22732140323480923", + "Likelihood: 0.16384398582946744", + "Likelihood: 0.07664543469576982", + "Likelihood: 0.23410099432863207", + "Likelihood: 0.1124884355110475", + "Likelihood: 0.23996943845739446", + "Likelihood: 0.17215641551529998", + "Likelihood: 0.11737407517866397", + "Likelihood: 0.17204167423416195", + "Likelihood: 0.21005847198753047", + "Likelihood: 0.2163795661242579", + "Likelihood: 0.07059723348018208", + "Likelihood: 0.20423108978641835", + "Likelihood: 0.09696615748752817", + "Likelihood: 0.0929310445246747", + "Likelihood: 0.1804945644313111", + "Likelihood: 0.2608108396975335", + "Likelihood: 0.09491961920615463", + "Likelihood: 0.24930518828451717", + "Likelihood: 0.16996071077657127", + "Likelihood: 0.21629769184891423", + "Likelihood: 0.19625024345517553", + "Likelihood: 0.08277336455632059", + "Likelihood: 0.2105948473334796", + "Likelihood: 0.20176809935990805", + "Likelihood: 0.10825361641185018", + "Likelihood: 0.05642857656513266", + "Likelihood: 0.11607228394812873", + "Likelihood: 0.16596031773660877", + "Likelihood: 0.016374620795713887", + "Likelihood: 0.15260878862608662", + "Likelihood: 0.14956268000447767", + "Likelihood: 0.21271286379768248", + "Likelihood: 0.04017005949267143", + "Likelihood: 0.08782578451837132", + "Likelihood: 0.16895031258206897", + "Likelihood: 0.23594459551336508", + "Likelihood: 0.17664202811878732", + "Likelihood: 0.2284521526181536", + "Likelihood: 0.13327860924856977", + "Likelihood: 0.2115167546693984", + "Likelihood: 0.20933832935276803", + "Likelihood: 0.16065258821130723", + "Likelihood: 0.24162559192552546", + "Likelihood: 0.07160667842873496", + "Likelihood: 0.24038718769456507", + "Likelihood: 0.131051593034899", + "Likelihood: 0.07831992434304112", + "Likelihood: 0.1818311136073989", + "Likelihood: 0.16521628453352963", + "Likelihood: 0.1413213955419574", + "Likelihood: 0.20107238738606834", + "Likelihood: 0.08576570792429655", + "Likelihood: 0.1931330189075556", + "Likelihood: 0.1559258867269575", + "Likelihood: 0.25361644485497037", + "Likelihood: 0.20013677290406412", + "Likelihood: 0.26380403980544287", + "Likelihood: 0.13857710448796795", + "Likelihood: 0.09485805871331195", + "Likelihood: 0.1871098746037949", + "Likelihood: 0.19664779323551743", + "Likelihood: 0.1589115536419999", + "Likelihood: 0.10036195644920455", + "Likelihood: 0.13032934782778685", + "Likelihood: 0.1513200254738299", + "Likelihood: 0.07513333624178471", + "Likelihood: 0.048386413457373566", + "Likelihood: 0.15067859310368034", + "Likelihood: 0.273852089666201", + "Likelihood: 0.24627815065328612", + "Likelihood: 0.19758118545084355", + "Likelihood: 0.21054531408265004", + "Likelihood: 0.10105115273561072", + "Likelihood: 0.18407461815078333", + "Likelihood: 0.26467587570888484", + "Likelihood: 0.13340365739042853", + "Likelihood: 0.173364113646045", + "Likelihood: 0.25213108589601113", + "Likelihood: 0.14549483822296094", + "Likelihood: 0.03621206617531403", + "Likelihood: 0.17327384703389825", + "Likelihood: 0.24267657639947915", + "Likelihood: 0.1686224030219138", + "Likelihood: 0.14252039558254598", + "Likelihood: 0.12626797376723978", + "Likelihood: 0.19360052886796064", + "Likelihood: 0.2116900649991725", + "Likelihood: 0.14479638042250076", + "Likelihood: 0.10614621663629216", + "Likelihood: 0.23558442342470617", + "Likelihood: 0.24208938989131215", + "Likelihood: 0.2267295596443124", + "Likelihood: 0.06284381399284492", + "Likelihood: 0.1808473239623343", + "Likelihood: 0.16575475389523103", + "Likelihood: 0.20984507424301882", + "Likelihood: 0.1493629074013103", + "Likelihood: 0.2458862406830813", + "Likelihood: 0.1873773189749172", + "Likelihood: 0.21847189503601766", + "Likelihood: 0.08847414333262095", + "Likelihood: 0.19758863478607824", + "Likelihood: 0.14933476821859432", + "Likelihood: 0.25543532412310627", + "Likelihood: 0.07367123145934845", + "Likelihood: 0.09047277072117908", + "Likelihood: 0.07289332317747109", + "Likelihood: 0.09297303531277318", + "Likelihood: 0.19247225208345306", + "Likelihood: 0.14093131884272944", + "Likelihood: 0.08744114967852494", + "Likelihood: 0.15668281784562296", + "Likelihood: 0.1250486557413418", + "Likelihood: 0.2687243299054113", + "Likelihood: 0.1869178496667146", + "Likelihood: 0.25008284556586136", + "Likelihood: 0.27646971982589863", + "Likelihood: 0.10569333943779034", + "Likelihood: 0.09711558078998862", + "Likelihood: 0.21969931694451109", + "Likelihood: 0.12400100196697958", + "Likelihood: 0.24133833034343938", + "Likelihood: 0.20427470885241908", + "Likelihood: 0.1708166302294297", + "Likelihood: 0.14439508909133386", + "Likelihood: 0.22088193279240564", + "Likelihood: 0.1375238454235334", + "Likelihood: 0.18437586474909654", + "Likelihood: 0.07345238199542205", + "Likelihood: 0.13359769747248124", + "Likelihood: 0.1525962872972788", + "Likelihood: 0.24838085288142547", + "Likelihood: 0.16858969841609436", + "Likelihood: 0.26749521236234053", + "Likelihood: 0.19873910456351726", + "Likelihood: 0.21801575771837808", + "Likelihood: 0.24485376882789342", + "Likelihood: 0.050625376436473316", + "Likelihood: 0.11688621861914", + "Likelihood: 0.171515716396771", + "Likelihood: 0.22423250810961706", + "Likelihood: 0.22750318845329612", + "Likelihood: 0.16642466263288785", + "Likelihood: 0.019242093220166484", + "Likelihood: 0.2398827529168181", + "Likelihood: 0.24281194079657403", + "Likelihood: 0.12980718498224272", + "Likelihood: 0.26732116819633617", + "Likelihood: 0.15259938043028531", + "Likelihood: 0.11440146997515012", + "Likelihood: 0.10146042705359637", + "Likelihood: 0.2328197454810622", + "Likelihood: 0.22813134385306136", + "Likelihood: 0.24342108004796742", + "Likelihood: 0.23666421539612972", + "Likelihood: 0.1794383089670677", + "Likelihood: 0.03782389655089879", + "Likelihood: 0.026458350761404615", + "Likelihood: 0.18067888982000807", + "Likelihood: 0.14853392000248603", + "Likelihood: 0.1910788914331031", + "Likelihood: 0.12342617893268844", + "Likelihood: 0.27986830300395255", + "Likelihood: 0.14141563671549304", + "Likelihood: 0.18518208395107075", + "Likelihood: 0.17393651886315933", + "Likelihood: 0.19174916865429972", + "Likelihood: 0.056882327755607164", + "Likelihood: 0.19008509433842852", + "Likelihood: 0.11610020171539902", + "Likelihood: 0.22152672048728347", + "Likelihood: 0.09240815746628245", + "Likelihood: 0.13250386271965545", + "Likelihood: 0.22953660735493558", + "Likelihood: 0.21575694080987762", + "Likelihood: 0.15654803621876523", + "Likelihood: 0.2604092300360847", + "Likelihood: 0.2904860416663066", + "Likelihood: 0.25607172236525677", + "Likelihood: 0.16801936069498097", + "Likelihood: 0.1619865343153777", + "Likelihood: 0.25436664727526603", + "Likelihood: 0.2851935878379861", + "Likelihood: 0.2372677382665155", + "Likelihood: 0.13894848071998847", + "Likelihood: 0.23213958946176697", + "Likelihood: 0.25091017503794366", + "Likelihood: 0.13874575492799904", + "Likelihood: 0.0746029871984201", + "Likelihood: 0.23677834955906793", + "Likelihood: 0.05221780900735466", + "Likelihood: 0.10747382666290482", + "Likelihood: 0.23109791170459149", + "Likelihood: 0.16688852263297757", + "Likelihood: 0.06310722306290198", + "Likelihood: 0.2592931411872891", + "Likelihood: 0.12310580759404384", + "Likelihood: 0.25850110564513357", + "Likelihood: 0.21957138091912548", + "Likelihood: 0.25693100111468486", + "Likelihood: 0.25938510180568947", + "Likelihood: 0.01897484645738172", + "Likelihood: 0.23192138739427628", + "Likelihood: 0.24643964138962554", + "Likelihood: 0.14485319878077696", + "Likelihood: 0.1912561118018028", + "Likelihood: 0.2555707904958018", + "Likelihood: 0.23934373063283873", + "Likelihood: 0.2517765252242687", + "Likelihood: 0.21513576787079836", + "Likelihood: 0.05545778527672275", + "Likelihood: 0.08235173325527824", + "Likelihood: 0.08779529797681922", + "Likelihood: 0.25882717601571986", + "Likelihood: 0.04023408059417382", + "Likelihood: 0.1723687839695026", + "Likelihood: 0.20153592395555364", + "Likelihood: 0.0693393256280751", + "Likelihood: 0.2589125127915354", + "Likelihood: 0.20258643876400131", + "Likelihood: 0.24514994037546475", + "Likelihood: 0.19346632072835393", + "Likelihood: 0.2703365923910326", + "Likelihood: 0.12334393801238466", + "Likelihood: 0.18991200569634203", + "Likelihood: 0.10598644825184884", + "Likelihood: 0.12214812781531939", + "Likelihood: 0.2278710238209529", + "Likelihood: 0.12476711452568605", + "Likelihood: 0.1251233268928531", + "Likelihood: 0.24679741988566034", + "Likelihood: 0.2356811419821229", + "Likelihood: 0.1927123492840143", + "Likelihood: 0.1613401542122227", + "Likelihood: 0.21261428479537992", + "Likelihood: 0.09818719237499463", + "Likelihood: 0.1720752795453218", + "Likelihood: 0.03283370805961862", + "Likelihood: 0.13192497721176294", + "Likelihood: 0.28075852428990217", + "Likelihood: 0.0988123898283362", + "Likelihood: 0.0762021384804548", + "Likelihood: 0.21012016578710369", + "Likelihood: 0.2316347280161581", + "Likelihood: 0.2692155653483172", + "Likelihood: 0.19614707230436043", + "Likelihood: 0.22689593391204474", + "Likelihood: 0.052675283889384666", + "Likelihood: 0.27401699368580634", + "Likelihood: 0.10732064021495691", + "Likelihood: 0.14217800311194895", + "Likelihood: 0.15700347834949993", + "Likelihood: 0.18192406485720997", + "Likelihood: 0.12443537167808055", + "Likelihood: 0.19735129732859183", + "Likelihood: 0.20119299531085771", + "Likelihood: 0.03768298637363166", + "Likelihood: 0.1718747467398713", + "Likelihood: 0.2658778393027599", + "Likelihood: 0.2119889291950858", + "Likelihood: 0.15931792882301374", + "Likelihood: 0.09180481025180605", + "Likelihood: 0.09953422196544205", + "Likelihood: 0.2548653791438873", + "Likelihood: 0.1309897646848051", + "Likelihood: 0.12704731042137235", + "Likelihood: 0.18315001533696657", + "Likelihood: 0.02538730450039948", + "Likelihood: 0.2758764298723586", + "Likelihood: 0.04102001035112055", + "Likelihood: 0.13091704250479713", + "Likelihood: 0.15772073346922022", + "Likelihood: 0.17265160669971635", + "Likelihood: 0.27312524267267313", + "Likelihood: 0.23842811286338655", + "Likelihood: 0.26375338159286127", + "Likelihood: 0.14767505532421893", + "Likelihood: 0.04620499231406952", + "Likelihood: 0.057443309043700465", + "Likelihood: 0.20365088580955676", + "Likelihood: 0.20102213879674558", + "Likelihood: 0.1372305368631217", + "Likelihood: 0.18839432990631477", + "Likelihood: 0.12408637437952331", + "Likelihood: 0.2831072138182253", + "Likelihood: 0.22945275591935355", + "Likelihood: 0.22677847269291257", + "Likelihood: 0.16350494785036648", + "Likelihood: 0.2721569320133675", + "Likelihood: 0.22095314158565105", + "Likelihood: 0.11566457259901558", + "Likelihood: 0.21659669190235586", + "Likelihood: 0.13539648438688015", + "Likelihood: 0.2765201599342607", + "Likelihood: 0.13894260267005143", + "Likelihood: 0.2149434348280845", + "Likelihood: 0.07911288608776999", + "Likelihood: 0.25256826203099103", + "Likelihood: 0.203530181044417", + "Likelihood: 0.2686740710565942", + "Likelihood: 0.20594818181623736", + "Likelihood: 0.23694314607650616", + "Likelihood: 0.17624142477584925", + "Likelihood: 0.2862256671915395", + "Likelihood: 0.12532403909657383", + "Likelihood: 0.15063126930194473", + "Likelihood: 0.12360306958390707", + "Likelihood: 0.12791583933504833", + "Likelihood: 0.20077420509529648", + "Likelihood: 0.24231437981658338", + "Likelihood: 0.2689888409237564", + "Likelihood: 0.21382106345379442", + "Likelihood: 0.2662945065654123", + "Likelihood: 0.2320928532862972", + "Likelihood: 0.23035311019662194", + "Likelihood: 0.14693644881775073", + "Likelihood: 0.24237100053987853", + "Likelihood: 0.22350151921264053", + "Likelihood: 0.07561150412889601", + "Likelihood: 0.22811930283988763", + "Likelihood: 0.274552744457703", + "Likelihood: 0.23102062726782407", + "Likelihood: 0.09319736380030585", + "Likelihood: 0.13440848051069934", + "Likelihood: 0.14911930917762578", + "Likelihood: 0.23382550153871698", + "Likelihood: 0.14503648084539897", + "Likelihood: 0.16301099824510307", + "Likelihood: 0.07515921818224519", + "Likelihood: 0.12254761791766498", + "Likelihood: 0.20641691222729516", + "Likelihood: 0.11108257320549453", + "Likelihood: 0.22537525997503516", + "Likelihood: 0.20334538736824467", + "Likelihood: 0.24150776476805613", + "Likelihood: 0.0490162364274884", + "Likelihood: 0.08608907843948485", + "Likelihood: 0.21422421719257043", + "Likelihood: 0.19054638485274392", + "Likelihood: 0.27267570830773696", + "Likelihood: 0.08768154003664119", + "Likelihood: 0.2381241919087955", + "Likelihood: 0.08130026408628842", + "Likelihood: 0.23366249288210422", + "Likelihood: 0.1413365833612797", + "Likelihood: 0.2605062257242758", + "Likelihood: 0.23614067044732084", + "Likelihood: 0.232560545014748", + "Likelihood: 0.1338607685914663", + "Likelihood: 0.28489053849476814", + "Likelihood: 0.0723815682654695", + "Likelihood: 0.230011511645343", + "Likelihood: 0.2890644214805805", + "Likelihood: 0.1121202355547099", + "Likelihood: 0.1778563317900454", + "Likelihood: 0.07549468406122045", + "Likelihood: 0.1256618801948419", + "Likelihood: 0.24986962680314617", + "Likelihood: 0.06501637631972641", + "Likelihood: 0.26624630288328066", + "Likelihood: 0.1919171507805826", + "Likelihood: 0.11862745845803835", + "Likelihood: 0.10029395438811838", + "Likelihood: 0.10532600441546104", + "Likelihood: 0.14680593788614718", + "Likelihood: 0.27516899990620053", + "Likelihood: 0.2029924789713634", + "Likelihood: 0.14994615940450248", + "Likelihood: 0.15953145610501496", + "Likelihood: 0.16629212299395482", + "Likelihood: 0.20637931736107407", + "Likelihood: 0.2616600696169328", + "Likelihood: 0.2812714188068577", + "Likelihood: 0.2699351189773426", + "Likelihood: 0.09788061351042154", + "Likelihood: 0.23204518726262585", + "Likelihood: 0.2089812579696612", + "Likelihood: 0.07690806301810138", + "Likelihood: 0.22866104638862475", + "Likelihood: 0.18020930327020251", + "Likelihood: 0.2316739250710516", + "Likelihood: 0.27992422484621565", + "Likelihood: 0.08840609947259861", + "Likelihood: 0.07988547718173994", + "Likelihood: 0.20987085151248314", + "Likelihood: 0.06509821489866886", + "Likelihood: 0.1773712581634337", + "Likelihood: 0.2188963349879703", + "Likelihood: 0.25002712273502065", + "Likelihood: 0.1394725078419654", + "Likelihood: 0.16107196797676826", + "Likelihood: 0.2233686347605881", + "Likelihood: 0.1210162329380484", + "Likelihood: 0.27624894318592025", + "Likelihood: 0.2569049311323376", + "Likelihood: 0.09542857184911546", + "Likelihood: 0.09622061038157564", + "Likelihood: 0.16314144377606973", + "Likelihood: 0.2118663211301128", + "Likelihood: 0.17398484124940125", + "Likelihood: 0.13909571649014524", + "Likelihood: 0.26493728207562506", + "Likelihood: 0.01154812118598273", + "Likelihood: 0.21658861822616024", + "Likelihood: 0.21095140657999048", + "Likelihood: 0.1937256185187361", + "Likelihood: 0.035906173099581426", + "Likelihood: 0.18761147576330633", + "Likelihood: 0.12021739673050734", + "Likelihood: 0.23716690655304495", + "Likelihood: 0.21999318439745885", + "Likelihood: 0.2598564844141253", + "Likelihood: 0.2606259644455135", + "Likelihood: 0.2021602637747857", + "Likelihood: 0.2457513978085065", + "Likelihood: 0.0995421566228758", + "Likelihood: 0.20370613019432104", + "Likelihood: 0.1883429542631558", + "Likelihood: 0.25738831902943377", + "Likelihood: 0.028601114473738014", + "Likelihood: 0.2788181187474038", + "Likelihood: 0.21405129736867937", + "Likelihood: 0.0586802874279074", + "Likelihood: 0.23187211504740982", + "Likelihood: 0.2279342558741967", + "Likelihood: 0.2225197422134491", + "Likelihood: 0.2164403763354759", + "Likelihood: 0.0970470257446943", + "Likelihood: 0.2182830626934984", + "Likelihood: 0.2265389579615588", + "Likelihood: 0.15359406640600404", + "Likelihood: 0.22044473683524773", + "Likelihood: 0.18274360922781058", + "Likelihood: 0.1105057521018886", + "Likelihood: 0.20243850615449707", + "Likelihood: 0.1563491732968464", + "Likelihood: 0.18736330364579815", + "Likelihood: 0.15320775153409366", + "Likelihood: 0.20892619666786882", + "Likelihood: 0.14663643964560788", + "Likelihood: 0.2662397729697243", + "Likelihood: 0.10325923005617806", + "Likelihood: 0.1665148628244975", + "Likelihood: 0.16331303149966672", + "Likelihood: 0.16508392928399923", + "Likelihood: 0.17963953656201076", + "Likelihood: 0.09653438548057731", + "Likelihood: 0.1348601674199905", + "Likelihood: 0.07105286179958158", + "Likelihood: 0.25769043146577536", + "Likelihood: 0.16240377685713472", + "Likelihood: 0.212585236623824", + "Likelihood: 0.2569574730542831", + "Likelihood: 0.24312767687028122", + "Likelihood: 0.13627445839461838", + "Likelihood: 0.24853276555173096", + "Likelihood: 0.2507574244700928", + "Likelihood: 0.2807926656924541", + "Likelihood: 0.27558485413156025", + "Likelihood: 0.12327773219270433", + "Likelihood: 0.09793877326948826", + "Likelihood: 0.1705601434657933", + "Likelihood: 0.1969544813711935", + "Likelihood: 0.16373985204497735", + "Likelihood: 0.23369130154401554", + "Likelihood: 0.19823136742213585", + "Likelihood: 0.24175433982339123", + "Likelihood: 0.20818937606624013", + "Likelihood: 0.1256506211360334", + "Likelihood: 0.234504632769493", + "Likelihood: 0.1530113345408747", + "Likelihood: 0.14581477173302607", + "Likelihood: 0.09060412519613267", + "Likelihood: 0.18538137121711823", + "Likelihood: 0.127278249432305", + "Likelihood: 0.17684641767747983", + "Likelihood: 0.15131543415288368", + "Likelihood: 0.17105806027332118", + "Likelihood: 0.13934195597405863", + "Likelihood: 0.2262788236344248", + "Likelihood: 0.16427342554071375", + "Likelihood: 0.2795768977319763", + "Likelihood: 0.28101714036156156", + "Likelihood: 0.24998530268336994", + "Likelihood: 0.16851067692177954", + "Likelihood: 0.029147703627498526", + "Likelihood: 0.22099769358238103", + "Likelihood: 0.18266050600164416", + "Likelihood: 0.06986710096436824", + "Likelihood: 0.12372291082212823", + "Likelihood: 0.28716765422326945", + "Likelihood: 0.22197964344908594", + "Likelihood: 0.1451513355899905", + "Likelihood: 0.23960789909358413", + "Likelihood: 0.04853851178465086", + "Likelihood: 0.18180986682328346", + "Likelihood: 0.044626725143958684", + "Likelihood: 0.23897361431535855", + "Likelihood: 0.09925109271857076", + "Likelihood: 0.10632067067763894", + "Likelihood: 0.18883057257131086", + "Likelihood: 0.09303054916876648", + "Likelihood: 0.040182865884303746", + "Likelihood: 0.1786230227252238", + "Likelihood: 0.2562281630826205", + "Likelihood: 0.07944639321801841", + "Likelihood: 0.18508014694102198", + "Likelihood: 0.06327644401237989", + "Likelihood: 0.12851644789557276", + "Likelihood: 0.23471103196374662", + "Likelihood: 0.19615471824859854", + "Likelihood: 0.22187095820652344", + "Likelihood: 0.23777927493376083", + "Likelihood: 0.14097952199651612", + "Likelihood: 0.23580789736217192", + "Likelihood: 0.19002778115909935", + "Likelihood: 0.12199811515058442", + "Likelihood: 0.2138585323782146", + "Likelihood: 0.1593821180794489", + "Likelihood: 0.06369329757151757", + "Likelihood: 0.282960279464533", + "Likelihood: 0.22310349714086367", + "Likelihood: 0.22598427148635655", + "Likelihood: 0.17458206951366906", + "Likelihood: 0.01544948197120005", + "Likelihood: 0.07345160007601702", + "Likelihood: 0.24913480001457883", + "Likelihood: 0.27895478443741195", + "Likelihood: 0.28942160484732204", + "Likelihood: 0.0235316014835756", + "Likelihood: 0.24219339722585123", + "Likelihood: 0.248004042140558", + "Likelihood: 0.1330304998594727", + "Likelihood: 0.05872227537603726", + "Likelihood: 0.17155558477850194", + "Likelihood: 0.1831030886377047", + "Likelihood: 0.1278297339084782", + "Likelihood: 0.281608973859768", + "Likelihood: 0.08765743643632334", + "Likelihood: 0.04018080614541682", + "Likelihood: 0.16963875568736725", + "Likelihood: 0.24404052540412702", + "Likelihood: 0.11030400026291971", + "Likelihood: 0.15649866134856594", + "Likelihood: 0.0745169721675499", + "Likelihood: 0.15982095775550328", + "Likelihood: 0.2874145502548209", + "Likelihood: 0.21674773798677346", + "Likelihood: 0.23155069010671941", + "Likelihood: 0.1639473208616979", + "Likelihood: 0.12790347777902836", + "Likelihood: 0.1484531078125883", + "Likelihood: 0.23779576136535463", + "Likelihood: 0.24403129662737488", + "Likelihood: 0.25251714432486166", + "Likelihood: 0.13331397503125791", + "Likelihood: 0.2331879194768175", + "Likelihood: 0.23107903276764982", + "Likelihood: 0.19661276726448831", + "Likelihood: 0.10283219893855827", + "Likelihood: 0.2325118408834194", + "Likelihood: 0.2370584400367794", + "Likelihood: 0.02342886461318712", + "Likelihood: 0.2878817440336684", + "Likelihood: 0.22868874081064716", + "Likelihood: 0.009573082086751629", + "Likelihood: 0.1462510857256414", + "Likelihood: 0.23965680513687843", + "Likelihood: 0.16401150863096997", + "Likelihood: 0.19344387798117385", + "Likelihood: 0.060292401797728934", + "Likelihood: 0.2548317438563696", + "Likelihood: 0.2430690378459724", + "Likelihood: 0.12543485214507877", + "Likelihood: 0.2011109643688415", + "Likelihood: 0.24441814712255047", + "Likelihood: 0.1531260520567447", + "Likelihood: 0.10518708436889378", + "Likelihood: 0.14918347973436524", + "Likelihood: 0.14629087651316183", + "Likelihood: 0.27149955081317134", + "Likelihood: 0.17483552300459645", + "Likelihood: 0.19683586418344126", + "Likelihood: 0.1778627700455352", + "Likelihood: 0.24535133345876875", + "Likelihood: 0.16353062114451591", + "Likelihood: 0.19687849491913054", + "Likelihood: 0.18603503552418607", + "Likelihood: 0.2200890827111848", + "Likelihood: 0.25398942983093986", + "Likelihood: 0.2389006478835384", + "Likelihood: 0.22784637408652814", + "Likelihood: 0.1917328088497621", + "Likelihood: 0.21254386578873705", + "Likelihood: 0.2052727339291574", + "Likelihood: 0.08236071525581101", + "Likelihood: 0.20958487596833172", + "Likelihood: 0.1964425823805395", + "Likelihood: 0.10987170975179385", + "Likelihood: 0.1718611419869608", + "Likelihood: 0.25483519875265226", + "Likelihood: 0.08253214809933325", + "Likelihood: 0.2214304288239464", + "Likelihood: 0.17518065254420506", + "Likelihood: 0.16712104586040377", + "Likelihood: 0.19744432676371995", + "Likelihood: 0.19498895669761343", + "Likelihood: 0.25796461873360277", + "Likelihood: 0.23459910456109495", + "Likelihood: 0.11321562735107565", + "Likelihood: 0.13132655747420965", + "Likelihood: 0.14724661208862538", + "Likelihood: 0.13086658112254457", + "Likelihood: 0.24916878399096157", + "Likelihood: 0.25684121135582055", + "Likelihood: 0.18928628895517452", + "Likelihood: 0.17008731554334952", + "Likelihood: 0.17076558455762145", + "Likelihood: 0.14498744230175678", + "Likelihood: 0.1274125202236822", + "Likelihood: 0.06992363866938031", + "Likelihood: 0.26918600832970235", + "Likelihood: 0.22060613017904204", + "Likelihood: 0.12956932423291237", + "Likelihood: 0.1288747675778598", + "Likelihood: 0.13443093776972923", + "Likelihood: 0.2308359415781864", + "Likelihood: 0.14171515528175893", + "Likelihood: 0.2055669360805273", + "Likelihood: 0.2503509981571358", + "Likelihood: 0.23860281068725692", + "Likelihood: 0.25179263263515106", + "Likelihood: 0.20252788185879286", + "Likelihood: 0.21682302996403358", + "Likelihood: 0.12644913940046182", + "Likelihood: 0.16515564871987995", + "Likelihood: 0.24592949795557706", + "Likelihood: 0.21024838383722025", + "Likelihood: 0.14301653077807044", + "Likelihood: 0.15539245828773357", + "Likelihood: 0.13940294971170467", + "Likelihood: 0.1108657486160763", + "Likelihood: 0.23775796036775396", + "Likelihood: 0.16409624445436316", + "Likelihood: 0.22389954210388227", + "Likelihood: 0.04195436306557465", + "Likelihood: 0.12788808136507707", + "Likelihood: 0.22346754704895583", + "Likelihood: 0.2255734431006948", + "Likelihood: 0.2051889569643317", + "Likelihood: 0.1305354770793356", + "Likelihood: 0.10165245478332985", + "Likelihood: 0.21954873296406657", + "Likelihood: 0.24654483070653072", + "Likelihood: 0.07092373815093599", + "Likelihood: 0.2510127823531089", + "Likelihood: 0.10921547255099762", + "Likelihood: 0.11862068336976613", + "Likelihood: 0.09977431706395891", + "Likelihood: 0.22620202189553051", + "Likelihood: 0.13686171472557726", + "Likelihood: 0.28478007831519764", + "Likelihood: 0.2028268895391845", + "Likelihood: 0.09795236111765943", + "Likelihood: 0.23180979480743016", + "Likelihood: 0.0617395890163214", + "Likelihood: 0.21292984582631763", + "Likelihood: 0.06473696588898999", + "Likelihood: 0.13387114935792893", + "Likelihood: 0.16331707279781071", + "Likelihood: 0.18157299519513445", + "Likelihood: 0.24528818406092462", + "Likelihood: 0.20006234728645153", + "Likelihood: 0.18992011292917846", + "Likelihood: 0.18304276113848938", + "Likelihood: 0.25480151793004335", + "Likelihood: 0.07066067949172182", + "Likelihood: 0.23524024642484154", + "Likelihood: 0.2805099355739309", + "Likelihood: 0.2751856071801444", + "Likelihood: 0.2709587109331679", + "Likelihood: 0.15786158290788357", + "Likelihood: 0.09638626204042111", + "Likelihood: 0.08942562175735917", + "Likelihood: 0.1582706404993759", + "Likelihood: 0.1043898230947901", + "Likelihood: 0.20254766893488346", + "Likelihood: 0.25462590735645413", + "Likelihood: 0.19370711383184275", + "Likelihood: 0.10253642309808675", + "Likelihood: 0.1277301429288482", + "Likelihood: 0.16085133121857748", + "Likelihood: 0.18722305506427125", + "Likelihood: 0.14520902619561846", + "Likelihood: 0.15522481345689162", + "Likelihood: 0.1311993204710856", + "Likelihood: 0.20546317638183503", + "Likelihood: 0.20851708014564826", + "Likelihood: 0.10748753858756933", + "Likelihood: 0.1381003687853452", + "Likelihood: 0.175523627538617", + "Likelihood: 0.1801314374548453", + "Likelihood: 0.28580825002712046", + "Likelihood: 0.27002705065468446", + "Likelihood: 0.11658790495556375", + "Likelihood: 0.26308116913180984", + "Likelihood: 0.18518595820182518", + "Likelihood: 0.18046610593466947", + "Likelihood: 0.24806402044450665", + "Likelihood: 0.12859504860160195", + "Likelihood: 0.12299283477196224", + "Likelihood: 0.16563961602599525", + "Likelihood: 0.2538759178450788", + "Likelihood: 0.13751289184322393", + "Likelihood: 0.15181369203866782", + "Likelihood: 0.10936624661053616", + "Likelihood: 0.2030132874301688", + "Likelihood: 0.13950860107387855", + "Likelihood: 0.09265127498011078", + "Likelihood: 0.26174290781356596", + "Likelihood: 0.2349099973815564", + "Likelihood: 0.24942261207242142", + "Likelihood: 0.1418943454204948", + "Likelihood: 0.06305847252277604", + "Likelihood: 0.1152760789225843", + "Likelihood: 0.1765312341722523", + "Likelihood: 0.1729424943004417", + "Likelihood: 0.15024576992696959", + "Likelihood: 0.06346237649279099", + "Likelihood: 0.21220211700597533", + "Likelihood: 0.13726375657960355", + "Likelihood: 0.18742452420354866", + "Likelihood: 0.1041561321188323", + "Likelihood: 0.2750719417940779", + "Likelihood: 0.1266129671338532", + "Likelihood: 0.24446722720849032", + "Likelihood: 0.09269652159893495", + "Likelihood: 0.2435879158674603", + "Likelihood: 0.24691083245936354", + "Likelihood: 0.10514369562560409", + "Likelihood: 0.21502826472268927", + "Likelihood: 0.26913543118997274", + "Likelihood: 0.14759706038823964", + "Likelihood: 0.18545457661328166", + "Likelihood: 0.15548675746781715", + "Likelihood: 0.21934452064716686", + "Likelihood: 0.27149611045083843", + "Likelihood: 0.27910863551649934", + "Likelihood: 0.23123459059813847", + "Likelihood: 0.19377295103606715", + "Likelihood: 0.018385275834710793", + "Likelihood: 0.28054706353727343", + "Likelihood: 0.18005039472671705", + "Likelihood: 0.2093219217285687", + "Likelihood: 0.24268773141944097", + "Likelihood: 0.15822727443559925", + "Likelihood: 0.15112058261840666", + "Likelihood: 0.03828191371671185", + "Likelihood: 0.2577597075622527", + "Likelihood: 0.18994308086705733", + "Likelihood: 0.26933718307391247", + "Likelihood: 0.24769266431568795", + "Likelihood: 0.24200850664779228", + "Likelihood: 0.18187882965643334", + "Likelihood: 0.09410061172744419", + "Likelihood: 0.10941847496976861", + "Likelihood: 0.05985884626357189", + "Likelihood: 0.2099488960048446", + "Likelihood: 0.2618703051681542", + "Likelihood: 0.21089066621668293", + "Likelihood: 0.08410647308056186", + "Likelihood: 0.17753492437611404", + "Likelihood: 0.23264708145242732", + "Likelihood: 0.14223007445465463", + "Likelihood: 0.23918046593401196", + "Likelihood: 0.2308053297091397", + "Likelihood: 0.2791888961278851", + "Likelihood: 0.13517097206386627", + "Likelihood: 0.14425923809889635", + "Likelihood: 0.10305927816414642", + "Likelihood: 0.27777993628522357", + "Likelihood: 0.19676213505832832", + "Likelihood: 0.2732701748973665", + "Likelihood: 0.08205400022567842", + "Likelihood: 0.14599796110694785", + "Likelihood: 0.2628875125786282", + "Likelihood: 0.23414713478503937", + "Likelihood: 0.16107700129796043", + "Likelihood: 0.2498467395818682", + "Likelihood: 0.17155598986052203", + "Likelihood: 0.08841295925012352", + "Likelihood: 0.08996823941611011", + "Likelihood: 0.22322609669826843", + "Likelihood: 0.25495665648267246", + "Likelihood: 0.2782446561528808", + "Likelihood: 0.18422308595823084", + "Likelihood: 0.156730408071402", + "Likelihood: 0.09439876408514396", + "Likelihood: 0.1849908317938209", + "Likelihood: 0.09999183091874238", + "Likelihood: 0.28436217092984095", + "Likelihood: 0.24688127358675727", + "Likelihood: 0.2608144915652566", + "Likelihood: 0.2321004202475302", + "Likelihood: 0.14319324197511088", + "Likelihood: 0.03124408168586998", + "Likelihood: 0.20235027625995075", + "Likelihood: 0.24072726011382464", + "Likelihood: 0.060841976935954", + "Likelihood: 0.024361210230679272", + "Likelihood: 0.1783704290479809", + "Likelihood: 0.13844159037607306", + "Likelihood: 0.22896430303502593", + "Likelihood: 0.16391808731627452", + "Likelihood: 0.22050339227844504", + "Likelihood: 0.2068012184311085", + "Likelihood: 0.26997283741811295", + "Likelihood: 0.12162321678697731", + "Likelihood: 0.17909015268239736", + "Likelihood: 0.08880143959862741", + "Likelihood: 0.22549110318404425", + "Likelihood: 0.2355672188499326", + "Likelihood: 0.17464816739802777", + "Likelihood: 0.17354646182724126", + "Likelihood: 0.12106594476625503", + "Likelihood: 0.2083241267694092", + "Likelihood: 0.150346783186659", + "Likelihood: 0.2155396232779018", + "Likelihood: 0.2552788099488428", + "Likelihood: 0.17800858426996005", + "Likelihood: 0.15533034637280324", + "Likelihood: 0.24323029731646376", + "Likelihood: 0.22835617015059345", + "Likelihood: 0.21757423994079633", + "Likelihood: 0.24551262546654795", + "Likelihood: 0.10872949493624463", + "Likelihood: 0.27194238814496935", + "Likelihood: 0.2439506638012433", + "Likelihood: 0.18651154984218252", + "Likelihood: 0.24031230326175193", + "Likelihood: 0.21366660797934509", + "Likelihood: 0.1440564969059288", + "Likelihood: 0.07921823591572658", + "Likelihood: 0.15545773362165793", + "Likelihood: 0.200642430792782", + "Likelihood: 0.19470706988493572", + "Likelihood: 0.11757265428751072", + "Likelihood: 0.1860631202145594", + "Likelihood: 0.22230533595335855", + "Likelihood: 0.06757172674082984", + "Likelihood: 0.13555081930809876", + "Likelihood: 0.20176753193074454", + "Likelihood: 0.23106180883101896", + "Likelihood: 0.21568132473065943", + "Likelihood: 0.2575868370408447", + "Likelihood: 0.2318500468462608", + "Likelihood: 0.24841903400424323", + "Likelihood: 0.01893344587517215", + "Likelihood: 0.14090291908001276", + "Likelihood: 0.16143481605991145", + "Likelihood: 0.23306102128329895", + "Likelihood: 0.1779509104055416", + "Likelihood: 0.059713653552576705", + "Likelihood: 0.2053582006516953", + "Likelihood: 0.18553198711178184", + "Likelihood: 0.10939369036878549", + "Likelihood: 0.2112533876150553", + "Likelihood: 0.09167145634840063", + "Likelihood: 0.10363283545359091", + "Likelihood: 0.23270854972075322", + "Likelihood: 0.16026585310631997", + "Likelihood: 0.19269392992971646", + "Likelihood: 0.24282968002946437", + "Likelihood: 0.2091444686360388", + "Likelihood: 0.16178896405800344", + "Likelihood: 0.18117074839180014", + "Likelihood: 0.24978295398382966", + "Likelihood: 0.25425561166045724", + "Likelihood: 0.18452562415857435", + "Likelihood: 0.15008427615091288", + "Likelihood: 0.17230659086739356", + "Likelihood: 0.15308347881154113", + "Likelihood: 0.1376674815573975", + "Likelihood: 0.24985043077102387", + "Likelihood: 0.2647927702534455", + "Likelihood: 0.23413904459725818", + "Likelihood: 0.22459058639382862", + "Likelihood: 0.22208920727557974", + "Likelihood: 0.2302023310195361", + "Likelihood: 0.19623916927166085", + "Likelihood: 0.2135555724124201", + "Likelihood: 0.23208973797566268", + "Likelihood: 0.2813654208159488", + "Likelihood: 0.12290424907592111", + "Likelihood: 0.1138084776550276", + "Likelihood: 0.2519812098720567", + "Likelihood: 0.26878088559916236", + "Likelihood: 0.22844821013613903", + "Likelihood: 0.0422247261085978", + "Likelihood: 0.19433313145399894", + "Likelihood: 0.12100199534496235", + "Likelihood: 0.1166580237182887", + "Likelihood: 0.2553455811315587", + "Likelihood: 0.030662930467084144", + "Likelihood: 0.269970692672027", + "Likelihood: 0.19254801426457113", + "Likelihood: 0.21794178293657065", + "Likelihood: 0.20008001723647312", + "Likelihood: 0.18620038559583119", + "Likelihood: 0.11277916663081636", + "Likelihood: 0.05783991595493631", + "Likelihood: 0.15631280996242533", + "Likelihood: 0.16582576841513225", + "Likelihood: 0.24062496162163619", + "Likelihood: 0.17607391637094347", + "Likelihood: 0.21381759283427726", + "Likelihood: 0.09779966503830712", + "Likelihood: 0.14549141534340362", + "Likelihood: 0.2730190809392558", + "Likelihood: 0.20768791050006594", + "Likelihood: 0.2259328885526515", + "Likelihood: 0.28221537919916095", + "Likelihood: 0.1051128363293702", + "Likelihood: 0.18706842969180754", + "Likelihood: 0.15907232985442146", + "Likelihood: 0.16049922272696276", + "Likelihood: 0.21183311548930422", + "Likelihood: 0.12994478876072516", + "Likelihood: 0.22794898552585008", + "Likelihood: 0.1728612728869246", + "Likelihood: 0.15217593708244953", + "Likelihood: 0.18518416409964358", + "Likelihood: 0.22116629053918344", + "Likelihood: 0.0773556669092797", + "Likelihood: 0.27981086984199555", + "Likelihood: 0.2634744120878306", + "Likelihood: 0.06668652845141623", + "Likelihood: 0.2330610441538682", + "Likelihood: 0.2503260138420162", + "Likelihood: 0.25070793542858966", + "Likelihood: 0.11364743558123541", + "Likelihood: 0.08708906907387795", + "Likelihood: 0.07452318192966889", + "Likelihood: 0.1351743075446977", + "Likelihood: 0.21089425040051332", + "Likelihood: 0.0448080390126848", + "Likelihood: 0.03687238277479624", + "Likelihood: 0.1962923167624862", + "Likelihood: 0.2376157172401921", + "Likelihood: 0.04261490582520124", + "Likelihood: 0.07850004354251709", + "Likelihood: 0.1808455610986939", + "Likelihood: 0.2670212667194116", + "Likelihood: 0.19941787312107392", + "Likelihood: 0.15225058173878614", + "Likelihood: 0.1843070441308571", + "Likelihood: 0.2680957573217019", + "Likelihood: 0.21512252926682252", + "Likelihood: 0.13819373944080485", + "Likelihood: 0.15852081883816851", + "Likelihood: 0.2231078925288702", + "Likelihood: 0.12759277413999154", + "Likelihood: 0.22447816883803867", + "Likelihood: 0.15421403547725498", + "Likelihood: 0.1835182820864251", + "Likelihood: 0.09774187610486956", + "Likelihood: 0.0913241406261354", + "Likelihood: 0.14559033032975202", + "Likelihood: 0.17807552661338172", + "Likelihood: 0.17224970728301126", + "Likelihood: 0.2541615686592652", + "Likelihood: 0.1751933529590565", + "Likelihood: 0.2825876404961108", + "Likelihood: 0.1806854659556176", + "Likelihood: 0.18375123339410007", + "Likelihood: 0.06147670605099388", + "Likelihood: 0.14796008777005867", + "Likelihood: 0.12549227630898843", + "Likelihood: 0.12227723948838336", + "Likelihood: 0.2351667696911679", + "Likelihood: 0.25543766893790976", + "Likelihood: 0.20303751221083077", + "Likelihood: 0.21022988528851544", + "Likelihood: 0.2813268224343496", + "Likelihood: 0.08228792264861169", + "Likelihood: 0.09698589114564794", + "Likelihood: 0.10651566891853506", + "Likelihood: 0.27698817955622873", + "Likelihood: 0.2445595283193129", + "Likelihood: 0.02444168275780006", + "Likelihood: 0.19542258466287293", + "Likelihood: 0.26078512401890996", + "Likelihood: 0.09570929529317082", + "Likelihood: 0.17409368882235748", + "Likelihood: 0.06731720054865684", + "Likelihood: 0.25256373317567665", + "Likelihood: 0.28528125454485787", + "Likelihood: 0.11747870519835232", + "Likelihood: 0.2343367746526207", + "Likelihood: 0.1833625370608855", + "Likelihood: 0.22591399544790736", + "Likelihood: 0.10691194285032399", + "Likelihood: 0.2364396055406148", + "Likelihood: 0.22429962025444095", + "Likelihood: 0.154464376737813", + "Likelihood: 0.1823427335443161", + "Likelihood: 0.07935848725462788", + "Likelihood: 0.14451933301656691", + "Likelihood: 0.1313917444320599", + "Likelihood: 0.19363062696882447", + "Likelihood: 0.21193208375240927", + "Likelihood: 0.15636266842155006", + "Likelihood: 0.09898234460854514", + "Likelihood: 0.1184290402704772", + "Likelihood: 0.22476677708683956", + "Likelihood: 0.11143356978288119", + "Likelihood: 0.18180413224094322", + "Likelihood: 0.20652696384926753", + "Likelihood: 0.1267447551018557", + "Likelihood: 0.2372592465960273", + "Likelihood: 0.059362396288206436", + "Likelihood: 0.19872625168539282", + "Likelihood: 0.2293267337780825", + "Likelihood: 0.2610115352237983", + "Likelihood: 0.21521960623364375", + "Likelihood: 0.22909404173920897", + "Likelihood: 0.24683176176880733", + "Likelihood: 0.24360326230031926", + "Likelihood: 0.2749280807855159", + "Likelihood: 0.24111057833078098", + "Likelihood: 0.12016605779275924", + "Likelihood: 0.259601963387217", + "Likelihood: 0.2753218886997463", + "Likelihood: 0.09099216723817201", + "Likelihood: 0.12191624222775939", + "Likelihood: 0.18732744663409637", + "Likelihood: 0.19163139522312783", + "Likelihood: 0.10032170976040039", + "Likelihood: 0.030943995116914806", + "Likelihood: 0.12710690270850347", + "Likelihood: 0.16017954887255526", + "Likelihood: 0.1557027848871559", + "Likelihood: 0.24798800502273552", + "Likelihood: 0.09184734808775438", + "Likelihood: 0.21331386438854355", + "Likelihood: 0.0980581596744191", + "Likelihood: 0.1289483798045744", + "Likelihood: 0.047194765110113744", + "Likelihood: 0.2343578866250666", + "Likelihood: 0.19705696871822148", + "Likelihood: 0.23574593873207322", + "Likelihood: 0.19849589965172248", + "Likelihood: 0.17766382731535263", + "Likelihood: 0.18474899028345385", + "Likelihood: 0.26606513252654473", + "Likelihood: 0.13136856884971498", + "Likelihood: 0.23561322560733336", + "Likelihood: 0.1553053446477593", + "Likelihood: 0.1495453116750624", + "Likelihood: 0.21334446535220947", + "Likelihood: 0.180323972486796", + "Likelihood: 0.2611439337001824", + "Likelihood: 0.1963991524079432", + "Likelihood: 0.08616513769032849", + "Likelihood: 0.08827131787169108", + "Likelihood: 0.16046664598340815", + "Likelihood: 0.2527342392851324", + "Likelihood: 0.2837056923201313", + "Likelihood: 0.14504482264029772", + "Likelihood: 0.18767256499153692", + "Likelihood: 0.18478170326260424", + "Likelihood: 0.20997087885990487", + "Likelihood: 0.11753187384353125", + "Likelihood: 0.09491724069132812", + "Likelihood: 0.047648758129321206", + "Likelihood: 0.23069177944886862", + "Likelihood: 0.13039773870654217", + "Likelihood: 0.2814787626817173", + "Likelihood: 0.21513774999558585", + "Likelihood: 0.13700880540905244", + "Likelihood: 0.09486392655602763", + "Likelihood: 0.2549662416561284", + "Likelihood: 0.17380922545233124", + "Likelihood: 0.09228170294641225", + "Likelihood: 0.19123569910282512", + "Likelihood: 0.21545112871407837", + "Likelihood: 0.21038318379008925", + "Likelihood: 0.06677429137028082", + "Likelihood: 0.1507792257506956", + "Likelihood: 0.17479096014673923", + "Likelihood: 0.11870012007647555", + "Likelihood: 0.11189167918018503", + "Likelihood: 0.20433407051244332", + "Likelihood: 0.1138510886675404", + "Likelihood: 0.1328046960970819", + "Likelihood: 0.21112166125063503", + "Likelihood: 0.2729013431139196", + "Likelihood: 0.17315201094991078", + "Likelihood: 0.28091856357377776", + "Likelihood: 0.24578260859264806", + "Likelihood: 0.20589797194381304", + "Likelihood: 0.19825142872547816", + "Likelihood: 0.1040081214908735", + "Likelihood: 0.21623123035924147", + "Likelihood: 0.10150362358799343", + "Likelihood: 0.19677120312312202", + "Likelihood: 0.17638291259486258", + "Likelihood: 0.12021989575974242", + "Likelihood: 0.18152662945177137", + "Likelihood: 0.09085751954982613", + "Likelihood: 0.1887081518617763", + "Likelihood: 0.20633276721982294", + "Likelihood: 0.08291867177372707", + "Likelihood: 0.2459636180489415", + "Likelihood: 0.25665723626819437", + "Likelihood: 0.28651092062149447", + "Likelihood: 0.16181883341789524", + "Likelihood: 0.09089819559163205", + "Likelihood: 0.27130370921232094", + "Likelihood: 0.16100505815061653", + "Likelihood: 0.20187625751707294", + "Likelihood: 0.25430480230969343", + "Likelihood: 0.27011073919215883", + "Likelihood: 0.12316870526093468", + "Likelihood: 0.18499278266666772", + "Likelihood: 0.12481269298589935", + "Likelihood: 0.20683525039093306", + "Likelihood: 0.22704823991035758", + "Likelihood: 0.16508896394123102", + "Likelihood: 0.20691996203906018", + "Likelihood: 0.16863985593629738", + "Likelihood: 0.07697846066159666", + "Likelihood: 0.08111278498238665", + "Likelihood: 0.07349501786532625", + "Likelihood: 0.22049560845418603", + "Likelihood: 0.2784650230036371", + "Likelihood: 0.1478103237222155", + "Likelihood: 0.1340871839442319", + "Likelihood: 0.17073165909601565", + "Likelihood: 0.2849994864280817", + "Likelihood: 0.07819019382986052", + "Likelihood: 0.225492205113468", + "Likelihood: 0.22343897473946583", + "Likelihood: 0.15076782216822232", + "Likelihood: 0.22258177627263723", + "Likelihood: 0.17450418214690733", + "Likelihood: 0.04851969406273496", + "Likelihood: 0.25917991706059273", + "Likelihood: 0.1751464247287525", + "Likelihood: 0.1902285527737025", + "Likelihood: 0.1377100995653421", + "Likelihood: 0.197212661103159", + "Likelihood: 0.014356765620392833", + "Likelihood: 0.09843704429460669", + "Likelihood: 0.15657890485246015", + "Likelihood: 0.2702986974927474", + "Likelihood: 0.2203321916822206", + "Likelihood: 0.1858366471852901", + "Likelihood: 0.24027590545285948", + "Likelihood: 0.28116750809435936", + "Likelihood: 0.1683051466812305", + "Likelihood: 0.12509219275121633", + "Likelihood: 0.10148952993591866", + "Likelihood: 0.21640909659551882", + "Likelihood: 0.1396812380570916", + "Likelihood: 0.14058773013216408", + "Likelihood: 0.17404798441163624", + "Likelihood: 0.14896734763620503", + "Likelihood: 0.05027998068075436", + "Likelihood: 0.2032271112469403", + "Likelihood: 0.18551066733225074", + "Likelihood: 0.1317077053123156", + "Likelihood: 0.23133386979856602", + "Likelihood: 0.20504409872673965", + "Likelihood: 0.16296307846346025", + "Likelihood: 0.19290686827033504", + "Likelihood: 0.15669453698773633", + "Likelihood: 0.11586931895494099", + "Likelihood: 0.21580765494954313", + "Likelihood: 0.2639394962498403", + "Likelihood: 0.14843864884310884", + "Likelihood: 0.09288169942163917", + "Likelihood: 0.0890938692023224", + "Likelihood: 0.2801498336663532", + "Likelihood: 0.0345645327163383", + "Likelihood: 0.27455692817893856", + "Likelihood: 0.11090097890904674", + "Likelihood: 0.14459819904092053", + "Likelihood: 0.2711457883482673", + "Likelihood: 0.05865575506012201", + "Likelihood: 0.1360774289071205", + "Likelihood: 0.23916475397765405", + "Likelihood: 0.25501087175693876", + "Likelihood: 0.08637261971109268", + "Likelihood: 0.0801792926609707", + "Likelihood: 0.21756463102280038", + "Likelihood: 0.26140433689859405", + "Likelihood: 0.01576109483477311", + "Likelihood: 0.2701392484872838", + "Likelihood: 0.20818160526318666", + "Likelihood: 0.1901790290162918", + "Likelihood: 0.19960256019897435", + "Likelihood: 0.19617656837589215", + "Likelihood: 0.26656866055977824", + "Likelihood: 0.27022980767296306", + "Likelihood: 0.26352714361813395", + "Likelihood: 0.2576558570224565", + "Likelihood: 0.11308347537594635", + "Likelihood: 0.1431794121544741", + "Likelihood: 0.19945140086545257", + "Likelihood: 0.09496642172175018", + "Likelihood: 0.2637109423247643", + "Likelihood: 0.2201576482043911", + "Likelihood: 0.11244889756413635", + "Likelihood: 0.22968653259514896", + "Likelihood: 0.1631790709064954", + "Likelihood: 0.2273080741973008", + "Likelihood: 0.2144797588833549", + "Likelihood: 0.21702776544302702", + "Likelihood: 0.0745684303279305", + "Likelihood: 0.23057721925305547", + "Likelihood: 0.18939727210302074", + "Likelihood: 0.27661747789193075", + "Likelihood: 0.12635340386490512", + "Likelihood: 0.03031856430036962", + "Likelihood: 0.22361584511970226", + "Likelihood: 0.2856625304500877", + "Likelihood: 0.04603550607606845", + "Likelihood: 0.23122253738016607", + "Likelihood: 0.26351695070196574", + "Likelihood: 0.059809139895290395", + "Likelihood: 0.24062687326847343", + "Likelihood: 0.09807575708389353", + "Likelihood: 0.2807684606649259", + "Likelihood: 0.1953830023574005", + "Likelihood: 0.2218219265742466", + "Likelihood: 0.10050290630424816", + "Likelihood: 0.1591533581195706", + "Likelihood: 0.2046937952194248", + "Likelihood: 0.2341160904535092", + "Likelihood: 0.13276307237010265", + "Likelihood: 0.28500785626999364", + "Likelihood: 0.2901398075184446", + "Likelihood: 0.1835164484286003", + "Likelihood: 0.00970057163077782", + "Likelihood: 0.23916749191328301", + "Likelihood: 0.2872737951490986", + "Likelihood: 0.16469602884833073", + "Likelihood: 0.10775661931222137", + "Likelihood: 0.2132059723763217", + "Likelihood: 0.17584366829693612", + "Likelihood: 0.26658818468619866", + "Likelihood: 0.26112226380482023", + "Likelihood: 0.2717138690711273", + "Likelihood: 0.19886766617208185", + "Likelihood: 0.2116543345959662", + "Likelihood: 0.13900430389243107", + "Likelihood: 0.25278467586541437", + "Likelihood: 0.20229353457932564", + "Likelihood: 0.07178310517451093", + "Likelihood: 0.017280667029619515", + "Likelihood: 0.15723519474860526", + "Likelihood: 0.15816047354258106", + "Likelihood: 0.13077338241475903", + "Likelihood: 0.24744621110780846", + "Likelihood: 0.19004595870880653", + "Likelihood: 0.22979779655650787", + "Likelihood: 0.13335638225808788", + "Likelihood: 0.09462285987339014", + "Likelihood: 0.21827732113661572", + "Likelihood: 0.20707271213090464", + "Likelihood: 0.23747230706532912", + "Likelihood: 0.05244646863509738", + "Likelihood: 0.2883656179476465", + "Likelihood: 0.25094370919367076", + "Likelihood: 0.13600053127709635", + "Likelihood: 0.2205321031628623", + "Likelihood: 0.20772064876630122", + "Likelihood: 0.07443499909713408", + "Likelihood: 0.04732721801343189", + "Likelihood: 0.14403306680570285", + "Likelihood: 0.16487743288187762", + "Likelihood: 0.11124495396288304", + "Likelihood: 0.19083781428346433", + "Likelihood: 0.09453382267966097", + "Likelihood: 0.2542202625348542", + "Likelihood: 0.1252974025068017", + "Likelihood: 0.2558446468234114", + "Likelihood: 0.22693639741250904", + "Likelihood: 0.2590156501307513", + "Likelihood: 0.15675627021159821", + "Likelihood: 0.2439965372745814", + "Likelihood: 0.14678109947393517", + "Likelihood: 0.19142847918567038", + "Likelihood: 0.11818467457283817", + "Likelihood: 0.10319192022154614", + "Likelihood: 0.14582262927945303", + "Likelihood: 0.13662379388390922", + "Likelihood: 0.16002773248726368", + "Likelihood: 0.23973116909416292", + "Likelihood: 0.09134046037712006", + "Likelihood: 0.19030201051986415", + "Likelihood: 0.2265942059569411", + "Likelihood: 0.1750936141040744", + "Likelihood: 0.11142640018997525", + "Likelihood: 0.09071591849845811", + "Likelihood: 0.1848018203966993", + "Likelihood: 0.19223619971315853", + "Likelihood: 0.2389870123270074", + "Likelihood: 0.16309327197656115", + "Likelihood: 0.22750273324894843", + "Likelihood: 0.09227226651081652", + "Likelihood: 0.24479267126822155", + "Likelihood: 0.07969454377899317", + "Likelihood: 0.14731184838811537", + "Likelihood: 0.22685938235447967", + "Likelihood: 0.09917279381394614", + "Likelihood: 0.1377603871075548", + "Likelihood: 0.20119043476511242", + "Likelihood: 0.21058610646867035", + "Likelihood: 0.15036712571981187", + "Likelihood: 0.28180595300266514", + "Likelihood: 0.2544117478228359", + "Likelihood: 0.1783772223160883", + "Likelihood: 0.03169827024121578", + "Likelihood: 0.272159251166642", + "Likelihood: 0.0609716719718059", + "Likelihood: 0.20265690965815128", + "Likelihood: 0.21297148893035012", + "Likelihood: 0.1738774007493026", + "Likelihood: 0.14587091472331257", + "Likelihood: 0.26255667993076276", + "Likelihood: 0.0501720785459636", + "Likelihood: 0.08970064490011007", + "Likelihood: 0.07162419925634717", + "Likelihood: 0.09474521583198812", + "Likelihood: 0.25420085886450694", + "Likelihood: 0.26543653605182815", + "Likelihood: 0.2563092802889412", + "Likelihood: 0.25049248539014646", + "Likelihood: 0.21851278123686782", + "Likelihood: 0.19822689344053157", + "Likelihood: 0.21506621912481697", + "Likelihood: 0.15591985240113643", + "Likelihood: 0.0929427189136034", + "Likelihood: 0.17696121332124268", + "Likelihood: 0.2724373520678437", + "Likelihood: 0.22651664656760045", + "Likelihood: 0.1690225172955796", + "Likelihood: 0.17287507498622964", + "Likelihood: 0.14184573542155904", + "Likelihood: 0.26037090541240876", + "Likelihood: 0.08128157308659201", + "Likelihood: 0.24414187943355778", + "Likelihood: 0.2171330107885756", + "Likelihood: 0.1483146203833132", + "Likelihood: 0.21497141861454314", + "Likelihood: 0.2265297825184703", + "Likelihood: 0.2765307651952019", + "Likelihood: 0.2363126502746818", + "Likelihood: 0.2437271132625978", + "Likelihood: 0.274472698115061", + "Likelihood: 0.1695731549572051", + "Likelihood: 0.08760261630112144", + "Likelihood: 0.13453766946742582", + "Likelihood: 0.02844219197524083", + "Likelihood: 0.04353284591549257", + "Likelihood: 0.042729313917989994", + "Likelihood: 0.1499872600016861", + "Likelihood: 0.0540942629733465", + "Likelihood: 0.1387091358277007", + "Likelihood: 0.2685530430863949", + "Likelihood: 0.14161264334028084", + "Likelihood: 0.23674754254808372", + "Likelihood: 0.17365291851734876", + "Likelihood: 0.1038724357166547", + "Likelihood: 0.148884238144895", + "Likelihood: 0.11947675516389623", + "Likelihood: 0.22549703789683828", + "Likelihood: 0.17414732298936889", + "Likelihood: 0.20005108992520002", + "Likelihood: 0.05128585584522426", + "Likelihood: 0.22406198501069857", + "Likelihood: 0.23201799516515967", + "Likelihood: 0.15273336254708295", + "Likelihood: 0.1891387773185248", + "Likelihood: 0.13417394840962926", + "Likelihood: 0.12398661376214527", + "Likelihood: 0.21559188457470832", + "Likelihood: 0.25080135560735806", + "Likelihood: 0.029536281406107256", + "Likelihood: 0.26375376769903347", + "Likelihood: 0.21589497555735532", + "Likelihood: 0.2160574417649704", + "Likelihood: 0.06185165655975309", + "Likelihood: 0.10872084943476941", + "Likelihood: 0.21228239885955127", + "Likelihood: 0.01944954009107855", + "Likelihood: 0.111081651890694", + "Likelihood: 0.23163309413915995", + "Likelihood: 0.20716062862614684", + "Likelihood: 0.04616120733654128", + "Likelihood: 0.23452400979016422", + "Likelihood: 0.12305245020723257", + "Likelihood: 0.16430786246600698", + "Likelihood: 0.16635114497310816", + "Likelihood: 0.17994150425217925", + "Likelihood: 0.11488599836856822", + "Likelihood: 0.19213903946075303", + "Likelihood: 0.16202813756176915", + "Likelihood: 0.18398070067126376", + "Likelihood: 0.1815688096889441", + "Likelihood: 0.09474192712533044", + "Likelihood: 0.23090309114877716", + "Likelihood: 0.19138209538701917", + "Likelihood: 0.20501656420642092", + "Likelihood: 0.0902819482325894", + "Likelihood: 0.15685855502227608", + "Likelihood: 0.18316048756930245", + "Likelihood: 0.07938010497249132", + "Likelihood: 0.23950634990514844", + "Likelihood: 0.20929190277529577", + "Likelihood: 0.07022621451499542", + "Likelihood: 0.1641258467834545", + "Likelihood: 0.1629656441206332", + "Likelihood: 0.21648258207546134", + "Likelihood: 0.21925277492911172", + "Likelihood: 0.12134154065939044", + "Likelihood: 0.05362765296434231", + "Likelihood: 0.13318197502057388", + "Likelihood: 0.23448706273240483", + "Likelihood: 0.06151755092528526", + "Likelihood: 0.2657696017577946", + "Likelihood: 0.02651738316891696", + "Likelihood: 0.15873100653938377", + "Likelihood: 0.035713063210498254", + "Likelihood: 0.26761384787654174", + "Likelihood: 0.09064025504452718", + "Likelihood: 0.15848833654975675", + "Likelihood: 0.22952885675406942", + "Likelihood: 0.1421185473952486", + "Likelihood: 0.12750970307527404", + "Likelihood: 0.10005685207519187", + "Likelihood: 0.2739501388717101", + "Likelihood: 0.2656144664469721", + "Likelihood: 0.19466377935980306", + "Likelihood: 0.17991694226185073", + "Likelihood: 0.11535155449819211", + "Likelihood: 0.19019253142744996", + "Likelihood: 0.16506003097702834", + "Likelihood: 0.23496433081684215", + "Likelihood: 0.20222275014261337", + "Likelihood: 0.2600755180430181", + "Likelihood: 0.18068803141834563", + "Likelihood: 0.12048030532553872", + "Likelihood: 0.2764831818260263", + "Likelihood: 0.19223678976331457", + "Likelihood: 0.22046024337803607", + "Likelihood: 0.05972575307574936", + "Likelihood: 0.2251030540849542", + "Likelihood: 0.18626701240764662", + "Likelihood: 0.08371685874114783", + "Likelihood: 0.20046940404735814", + "Likelihood: 0.26501974988040444", + "Likelihood: 0.17498554644752903", + "Likelihood: 0.09161934136462721", + "Likelihood: 0.13987066120290512", + "Likelihood: 0.23821700014345956", + "Likelihood: 0.11105664348657805", + "Likelihood: 0.1922297373968139", + "Likelihood: 0.2194525957642039", + "Likelihood: 0.14386601657266535", + "Likelihood: 0.16616243641034362", + "Likelihood: 0.163821973353351", + "Likelihood: 0.18409094147546445", + "Likelihood: 0.04560870274342289", + "Likelihood: 0.25825757633530255", + "Likelihood: 0.14277329450522985", + "Likelihood: 0.039907473337732986", + "Likelihood: 0.28157256597992886", + "Likelihood: 0.27308134247052657", + "Likelihood: 0.26876877224951595", + "Likelihood: 0.2377828367680646", + "Likelihood: 0.07266979985574099", + "Likelihood: 0.14460030060335685", + "Likelihood: 0.17960955972236436", + "Likelihood: 0.22294959486426502", + "Likelihood: 0.11136253629125391", + "Likelihood: 0.0882350934113113", + "Likelihood: 0.1487023684414704", + "Likelihood: 0.20411222606368995", + "Likelihood: 0.12942656395686175", + "Likelihood: 0.26381230518021853", + "Likelihood: 0.27464905830931746", + "Likelihood: 0.1829339421602223", + "Likelihood: 0.16365755903175025", + "Likelihood: 0.18819234091826567", + "Likelihood: 0.20739875636894048", + "Likelihood: 0.2066077701313965", + "Likelihood: 0.27943263469093843", + "Likelihood: 0.21976921935831484", + "Likelihood: 0.2829277181133609", + "Likelihood: 0.06810704806793978", + "Likelihood: 0.21109993613912423", + "Likelihood: 0.2667438227114919", + "Likelihood: 0.13354382469684506", + "Likelihood: 0.2192168177385231", + "Likelihood: 0.11964688909324113", + "Likelihood: 0.26422540339370554", + "Likelihood: 0.14891823118494135", + "Likelihood: 0.28767798284289203", + "Likelihood: 0.19880184445534183", + "Likelihood: 0.235996653423135", + "Likelihood: 0.20374485684615024", + "Likelihood: 0.22419903083384", + "Likelihood: 0.19071762956413854", + "Likelihood: 0.06333351688313936", + "Likelihood: 0.19595786947691626", + "Likelihood: 0.20967975020202712", + "Likelihood: 0.28836867380313297", + "Likelihood: 0.060194500165129464", + "Likelihood: 0.06550390865612132", + "Likelihood: 0.08615352457530252", + "Likelihood: 0.2487184901625701", + "Likelihood: 0.12910214646127788", + "Likelihood: 0.10642938389287109", + "Likelihood: 0.1985525640378336", + "Likelihood: 0.16687265977129218", + "Likelihood: 0.16500220793940723", + "Likelihood: 0.04014363649698663", + "Likelihood: 0.20295743614241554", + "Likelihood: 0.23135818208755324", + "Likelihood: 0.09462747407680779", + "Likelihood: 0.276394741268018", + "Likelihood: 0.11626802525017266", + "Likelihood: 0.25632630903481823", + "Likelihood: 0.16350370842396542", + "Likelihood: 0.2407246560516707", + "Likelihood: 0.13807248246892", + "Likelihood: 0.030300436145937193", + "Likelihood: 0.21445851013822376", + "Likelihood: 0.09956973887952254", + "Likelihood: 0.17857714102166203", + "Likelihood: 0.17755592128434097", + "Likelihood: 0.2712918007692392", + "Likelihood: 0.21370323754165707", + "Likelihood: 0.24324070445054696", + "Likelihood: 0.1568269120830866", + "Likelihood: 0.20978783032682616", + "Likelihood: 0.15880687137175623", + "Likelihood: 0.2804227792356542", + "Likelihood: 0.18088489163712104", + "Likelihood: 0.2696789104118985", + "Likelihood: 0.20862250545818897", + "Likelihood: 0.11158953291261828", + "Likelihood: 0.2288880120890885", + "Likelihood: 0.2528472829595088", + "Likelihood: 0.08706542110527714", + "Likelihood: 0.15121448607999216", + "Likelihood: 0.11990285493293362", + "Likelihood: 0.21726908383347765", + "Likelihood: 0.19407336237356643", + "Likelihood: 0.11202831350519608", + "Likelihood: 0.14025310444740502", + "Likelihood: 0.14423749432733873", + "Likelihood: 0.23422632874844554", + "Likelihood: 0.16642998708630816", + "Likelihood: 0.07391375205697562", + "Likelihood: 0.06329839871790527", + "Likelihood: 0.11389315307347898", + "Likelihood: 0.19237816091103505", + "Likelihood: 0.2237934897378224", + "Likelihood: 0.18891349884299274", + "Likelihood: 0.13741821533146978", + "Likelihood: 0.1464006767197084", + "Likelihood: 0.2751519164238694", + "Likelihood: 0.05042799173097106", + "Likelihood: 0.07655933325113043", + "Likelihood: 0.26757470678693934", + "Likelihood: 0.23094008441238853", + "Likelihood: 0.11888409557545111", + "Likelihood: 0.22816782787313286", + "Likelihood: 0.24038842672342942", + "Likelihood: 0.0995915740477861", + "Likelihood: 0.19809181277907495", + "Likelihood: 0.22413768664040323", + "Likelihood: 0.20725544244174224", + "Likelihood: 0.25648291856036143", + "Likelihood: 0.2525074864991396", + "Likelihood: 0.263957266409505", + "Likelihood: 0.2207037670937461", + "Likelihood: 0.18873375598897382", + "Likelihood: 0.25114587000125443", + "Likelihood: 0.23292613948583782", + "Likelihood: 0.18381227129386452", + "Likelihood: 0.1822391265534296", + "Likelihood: 0.22741828497330085", + "Likelihood: 0.2425090008504716", + "Likelihood: 0.10922895950358556", + "Likelihood: 0.26157279348674967", + "Likelihood: 0.2348838818305145", + "Likelihood: 0.11407124008899222", + "Likelihood: 0.0380733254036387", + "Likelihood: 0.18583497873885668", + "Likelihood: 0.18498911647494132", + "Likelihood: 0.2014187616664264", + "Likelihood: 0.19013674963199803", + "Likelihood: 0.224433845065413", + "Likelihood: 0.03266008905508327", + "Likelihood: 0.18756047006883736", + "Likelihood: 0.15299711994599346", + "Likelihood: 0.17755174793117828", + "Likelihood: 0.24534469463038466", + "Likelihood: 0.08364569285106076", + "Likelihood: 0.146444997867839", + "Likelihood: 0.1182485579170543", + "Likelihood: 0.206533589281752", + "Likelihood: 0.19973222671873525", + "Likelihood: 0.19993320014104832", + "Likelihood: 0.20322325627936455", + "Likelihood: 0.2127807591533208", + "Likelihood: 0.2545734133245548", + "Likelihood: 0.2699084391897154", + "Likelihood: 0.23017378742513717", + "Likelihood: 0.20492158525372375", + "Likelihood: 0.2346117052293675", + "Likelihood: 0.10386395730271923", + "Likelihood: 0.135586897030973", + "Likelihood: 0.125399694857219", + "Likelihood: 0.21432676716258978", + "Likelihood: 0.1369747487598308", + "Likelihood: 0.2775207454539363", + "Likelihood: 0.1865451905001158", + "Likelihood: 0.24531026400164105", + "Likelihood: 0.19330911042942064", + "Likelihood: 0.10390216677444422", + "Likelihood: 0.2544493779372618", + "Likelihood: 0.18952982611453006", + "Likelihood: 0.20259813944093355", + "Likelihood: 0.26632041910867577", + "Likelihood: 0.20313081622788398", + "Likelihood: 0.23206748630692975", + "Likelihood: 0.19649911496391664", + "Likelihood: 0.07090682854059491", + "Likelihood: 0.28280935243227173", + "Likelihood: 0.2543757973840437", + "Likelihood: 0.12323787044255975", + "Likelihood: 0.17043585712277118", + "Likelihood: 0.15352968167850428", + "Likelihood: 0.17246557962717643", + "Likelihood: 0.1792355742841171", + "Likelihood: 0.10257346356141975", + "Likelihood: 0.21568657877646172", + "Likelihood: 0.280175795191773", + "Likelihood: 0.27752724347897095", + "Likelihood: 0.28424039856786304", + "Likelihood: 0.1900176634598063", + "Likelihood: 0.038535913413772216", + "Likelihood: 0.05222268294273132", + "Likelihood: 0.2632902162396743", + "Likelihood: 0.21366424267616366", + "Likelihood: 0.27888750661418726", + "Likelihood: 0.0823546193516431", + "Likelihood: 0.14036714811822745", + "Likelihood: 0.09352535935578245", + "Likelihood: 0.1865681010013904", + "Likelihood: 0.19867120658166113", + "Likelihood: 0.2834662474888149", + "Likelihood: 0.19690890568787012", + "Likelihood: 0.08661939996730209", + "Likelihood: 0.18975360380470954", + "Likelihood: 0.10728931359928565", + "Likelihood: 0.01143598800080781", + "Likelihood: 0.08434178014660461", + "Likelihood: 0.16261729878587602", + "Likelihood: 0.18906683273964012", + "Likelihood: 0.22498346827210228", + "Likelihood: 0.05808554639563979", + "Likelihood: 0.1686468071268644", + "Likelihood: 0.2230512115675496", + "Likelihood: 0.16170160544785497", + "Likelihood: 0.1987842320212684", + "Likelihood: 0.12244971958566367", + "Likelihood: 0.16885361335069804", + "Likelihood: 0.21689930553158518", + "Likelihood: 0.16404739452528666", + "Likelihood: 0.2611530368868096", + "Likelihood: 0.21334727381197555", + "Likelihood: 0.26878352725265353", + "Likelihood: 0.2869533651628008", + "Likelihood: 0.28026107344827694", + "Likelihood: 0.014246925678309466", + "Likelihood: 0.2265508698994347", + "Likelihood: 0.2169087502322392", + "Likelihood: 0.2114752424798395", + "Likelihood: 0.12270862762423244", + "Likelihood: 0.17386570705431179", + "Likelihood: 0.13013704191379982", + "Likelihood: 0.0342233949101799", + "Likelihood: 0.17746591011926643", + "Likelihood: 0.2173145279250944", + "Likelihood: 0.1783336906694226", + "Likelihood: 0.12788123438092094", + "Likelihood: 0.21048245133528942", + "Likelihood: 0.23605261843174147", + "Likelihood: 0.1972214563344147", + "Likelihood: 0.24372923881869873", + "Likelihood: 0.15397240533021941", + "Likelihood: 0.28445831830782087", + "Likelihood: 0.21186912639220165", + "Likelihood: 0.139603706762292", + "Likelihood: 0.18519184451468365", + "Likelihood: 0.17691995969359692", + "Likelihood: 0.029677663812376343", + "Likelihood: 0.1760631308650212", + "Likelihood: 0.1768959948629047", + "Likelihood: 0.14182835941626995", + "Likelihood: 0.18726993339018927", + "Likelihood: 0.2502446607169403", + "Likelihood: 0.017853624762735144", + "Likelihood: 0.27593285661908606", + "Likelihood: 0.2777280028738239", + "Likelihood: 0.2389271036154957", + "Likelihood: 0.22575031492601644", + "Likelihood: 0.17659294559967884", + "Likelihood: 0.12785358266158361", + "Likelihood: 0.2767628687327118", + "Likelihood: 0.2816674439907576", + "Likelihood: 0.2395079468771755", + "Likelihood: 0.07135197689713817", + "Likelihood: 0.20669027580714996", + "Likelihood: 0.17317255182484684", + "Likelihood: 0.15509467148012854", + "Likelihood: 0.19188252773523853", + "Likelihood: 0.2238110264201735", + "Likelihood: 0.18390107102808836", + "Likelihood: 0.09242300303408381", + "Likelihood: 0.23221762223918366", + "Likelihood: 0.0911494637630681", + "Likelihood: 0.22874012821719147", + "Likelihood: 0.02082763890184723", + "Likelihood: 0.17992045499927442", + "Likelihood: 0.10741106009576895", + "Likelihood: 0.25229039121755203", + "Likelihood: 0.09363571004609765", + "Likelihood: 0.20494265016457772", + "Likelihood: 0.1765259625367124", + "Likelihood: 0.23467424335574438", + "Likelihood: 0.2674479265103851", + "Likelihood: 0.21298706165639533", + "Likelihood: 0.1828837629820079", + "Likelihood: 0.10748267005122641", + "Likelihood: 0.22294180432774985", + "Likelihood: 0.24757009780996608", + "Likelihood: 0.28926880399543337", + "Likelihood: 0.21805528945795188", + "Likelihood: 0.11039879738379853", + "Likelihood: 0.2775006440196405", + "Likelihood: 0.26240491464609833", + "Likelihood: 0.21037345085071402", + "Likelihood: 0.22385297251106595", + "Likelihood: 0.22621277114899707", + "Likelihood: 0.19849314416966238", + "Likelihood: 0.1005764067397968", + "Likelihood: 0.11383661888795406", + "Likelihood: 0.18231733458855937", + "Likelihood: 0.2298422711225041", + "Likelihood: 0.11692146753081181", + "Likelihood: 0.11653074277128875", + "Likelihood: 0.22785114637162232", + "Likelihood: 0.1775047008945258", + "Likelihood: 0.2620872060012288", + "Likelihood: 0.2433998429531589", + "Likelihood: 0.26859420671463263", + "Likelihood: 0.08154345110237114", + "Likelihood: 0.21600677282865322", + "Likelihood: 0.23019928359967629", + "Likelihood: 0.12378657094617039", + "Likelihood: 0.0978789908726701", + "Likelihood: 0.1516391442151675", + "Likelihood: 0.277919195101613", + "Likelihood: 0.26261950680873797", + "Likelihood: 0.25941252416741445", + "Likelihood: 0.17586973404046147", + "Likelihood: 0.02843636285868444", + "Likelihood: 0.21972502772123803", + "Likelihood: 0.06263513519728846", + "Likelihood: 0.07665125796198931", + "Likelihood: 0.1578266386696471", + "Likelihood: 0.11937768389726233", + "Likelihood: 0.10029367810397134", + "Likelihood: 0.24476182730473237", + "Likelihood: 0.17649103313523867", + "Likelihood: 0.16739971611114082", + "Likelihood: 0.2734684521171595", + "Likelihood: 0.24695372595635307", + "Likelihood: 0.012724000330107278", + "Likelihood: 0.2588114043672984", + "Likelihood: 0.20873008430120732", + "Likelihood: 0.2798522627892641", + "Likelihood: 0.1666863326877503", + "Likelihood: 0.2140055895232708", + "Likelihood: 0.1164161966856171", + "Likelihood: 0.25598398451303717", + "Likelihood: 0.21161744682275493", + "Likelihood: 0.1437270714475828", + "Likelihood: 0.010526226026960343", + "Likelihood: 0.15572359194926783", + "Likelihood: 0.20820840525167905", + "Likelihood: 0.15220599945174196", + "Likelihood: 0.19390147600832247", + "Likelihood: 0.23110689096709464", + "Likelihood: 0.061378306870886176", + "Likelihood: 0.19850381962564284", + "Likelihood: 0.12082228562591636", + "Likelihood: 0.04459549854010178", + "Likelihood: 0.2787363856102138", + "Likelihood: 0.2617595665806236", + "Likelihood: 0.24011213306331758", + "Likelihood: 0.2499934537366623", + "Likelihood: 0.23874176374529552", + "Likelihood: 0.2226981096195345", + "Likelihood: 0.15174997538715018", + "Likelihood: 0.23232307358397775", + "Likelihood: 0.14180729184871146", + "Likelihood: 0.23160427231315975", + "Likelihood: 0.2031810132758636", + "Likelihood: 0.22955146049519", + "Likelihood: 0.055966715371478674", + "Likelihood: 0.1997097603710583", + "Likelihood: 0.19306323569772224", + "Likelihood: 0.19258185288006327", + "Likelihood: 0.28061446367447535", + "Likelihood: 0.12131521456680908", + "Likelihood: 0.2535119498968596", + "Likelihood: 0.24443024093077537", + "Likelihood: 0.16803542990906226", + "Likelihood: 0.26316054709533915", + "Likelihood: 0.2325894297870387", + "Likelihood: 0.279275392757937", + "Likelihood: 0.23775500896238466", + "Likelihood: 0.2863475661539364", + "Likelihood: 0.08652421506615987", + "Likelihood: 0.2327882344961813", + "Likelihood: 0.22078244076292525", + "Likelihood: 0.009099683651942605", + "Likelihood: 0.1185142836325544", + "Likelihood: 0.1743842578922476", + "Likelihood: 0.26383826178670716", + "Likelihood: 0.10326223836016604", + "Likelihood: 0.23402600838040896", + "Likelihood: 0.2059247140795454", + "Likelihood: 0.15151836565718294", + "Likelihood: 0.11057992953544493", + "Likelihood: 0.2122644416811156", + "Likelihood: 0.2063581036147184", + "Likelihood: 0.13101341939232924", + "Likelihood: 0.1945132962842551", + "Likelihood: 0.24003488676950635", + "Likelihood: 0.09302691202804778", + "Likelihood: 0.16672215153197778", + "Likelihood: 0.17029783736172144", + "Likelihood: 0.27321407681807885", + "Likelihood: 0.21650271953076153", + "Likelihood: 0.2389372350845983", + "Likelihood: 0.2758205593724607", + "Likelihood: 0.1502229495385174", + "Likelihood: 0.1578266045080728", + "Likelihood: 0.09372961384474816", + "Likelihood: 0.13868710195171735", + "Likelihood: 0.18239248942732852", + "Likelihood: 0.18028333566358834", + "Likelihood: 0.2728838301393029", + "Likelihood: 0.08516345683514782", + "Likelihood: 0.03928017222466698", + "Likelihood: 0.2796293915474823", + "Likelihood: 0.24904874924937426", + "Likelihood: 0.25808478315388605", + "Likelihood: 0.12767232926336575", + "Likelihood: 0.07671934493200255", + "Likelihood: 0.1592853607165589", + "Likelihood: 0.2595765530395761", + "Likelihood: 0.2170911434450657", + "Likelihood: 0.23251968246645965", + "Likelihood: 0.2585116526474263", + "Likelihood: 0.18108541538548514", + "Likelihood: 0.23691365925040112", + "Likelihood: 0.09220184447037351", + "Likelihood: 0.05635178290633606", + "Likelihood: 0.16924597376390452", + "Likelihood: 0.09252865450079839", + "Likelihood: 0.22646999636618398", + "Likelihood: 0.22426974343823985", + "Likelihood: 0.25484982431482517", + "Likelihood: 0.20379158286672916", + "Likelihood: 0.09482812060240808", + "Likelihood: 0.2687778166207337", + "Likelihood: 0.11694061413633162", + "Likelihood: 0.17047444343967444", + "Likelihood: 0.28919208513852057", + "Likelihood: 0.17334773422294575", + "Likelihood: 0.21777734858442652", + "Likelihood: 0.2657266354543486", + "Likelihood: 0.21431127097867333", + "Likelihood: 0.13494707182983673", + "Likelihood: 0.09324878467424097", + "Likelihood: 0.1976678351288563", + "Likelihood: 0.1684486216788311", + "Likelihood: 0.1348811081214203", + "Likelihood: 0.11452827500012693", + "Likelihood: 0.16100327560946326", + "Likelihood: 0.11979623333350281", + "Likelihood: 0.274535682812855", + "Likelihood: 0.20875689418130494", + "Likelihood: 0.115959523690649", + "Likelihood: 0.27214541604883896", + "Likelihood: 0.1248934813425728", + "Likelihood: 0.031180515130985346", + "Likelihood: 0.21317962398548798", + "Likelihood: 0.20977079602541945", + "Likelihood: 0.15442850517688636", + "Likelihood: 0.2661328221704736", + "Likelihood: 0.24550386205525374", + "Likelihood: 0.19107266132187653", + "Likelihood: 0.2662946499177628", + "Likelihood: 0.18650265826913812", + "Likelihood: 0.20204014373107884", + "Likelihood: 0.029489596992762192", + "Likelihood: 0.26589746562798655", + "Likelihood: 0.27150149120897754", + "Likelihood: 0.19637696047282374", + "Likelihood: 0.205348280696398", + "Likelihood: 0.10176913019855502", + "Likelihood: 0.22974470987069107", + "Likelihood: 0.1545355045125501", + "Likelihood: 0.1323492765189992", + "Likelihood: 0.17601207330676286", + "Likelihood: 0.23951455689911522", + "Likelihood: 0.05143452391999559", + "Likelihood: 0.1887187193669743", + "Likelihood: 0.18025497095568596", + "Likelihood: 0.09688176008808126", + "Likelihood: 0.05201044412757983", + "Likelihood: 0.2366325539408753", + "Likelihood: 0.22485445503603954", + "Likelihood: 0.13498101593975106", + "Likelihood: 0.2762488572715116", + "Likelihood: 0.21450695366886924", + "Likelihood: 0.19106521740531537", + "Likelihood: 0.22222561896379883", + "Likelihood: 0.23035999815548935", + "Likelihood: 0.15129795127935855", + "Likelihood: 0.12101384479627346", + "Likelihood: 0.2590123815859898", + "Likelihood: 0.17128219522888186", + "Likelihood: 0.0506307998722573", + "Likelihood: 0.2452405491943193", + "Likelihood: 0.11317737496221603", + "Likelihood: 0.20555704400268124", + "Likelihood: 0.15002769497968768", + "Likelihood: 0.21914830166258267", + "Likelihood: 0.23048087953993474", + "Likelihood: 0.18298205864441444", + "Likelihood: 0.27742082181029226", + "Likelihood: 0.1775572095678699", + "Likelihood: 0.2765985255397203", + "Likelihood: 0.2590067947008017", + "Likelihood: 0.1516747317101526", + "Likelihood: 0.06733297331246815", + "Likelihood: 0.13693426839754297", + "Likelihood: 0.07395484773712498", + "Likelihood: 0.2161440870447583", + "Likelihood: 0.20789569473553682", + "Likelihood: 0.03713849802791059", + "Likelihood: 0.22726234460477532", + "Likelihood: 0.09400525467087446", + "Likelihood: 0.07765858569908306", + "Likelihood: 0.05909173671429007", + "Likelihood: 0.22886794041941794", + "Likelihood: 0.28929274560164503", + "Likelihood: 0.21897532774607437", + "Likelihood: 0.17348431569490108", + "Likelihood: 0.23415887153989173", + "Likelihood: 0.029115766409395713", + "Likelihood: 0.18681036526266412", + "Likelihood: 0.22175523336874092", + "Likelihood: 0.12412354745134985", + "Likelihood: 0.2062101736252434", + "Likelihood: 0.1364331621896498", + "Likelihood: 0.1870032019664114", + "Likelihood: 0.09749356767599442", + "Likelihood: 0.15170101171018513", + "Likelihood: 0.13425073340674637", + "Likelihood: 0.05879367966677618", + "Likelihood: 0.02194101781116257", + "Likelihood: 0.14978043007428024", + "Likelihood: 0.07413531548598778", + "Likelihood: 0.28417901242965843", + "Likelihood: 0.243869497752256", + "Likelihood: 0.16906910071711978", + "Likelihood: 0.1897168385091218", + "Likelihood: 0.2836636161894404", + "Likelihood: 0.1678467009416015", + "Likelihood: 0.23789104362465086", + "Likelihood: 0.14731369589274984", + "Likelihood: 0.058199748948363085", + "Likelihood: 0.206170790070612", + "Likelihood: 0.18326701244253987", + "Likelihood: 0.11402831686281317", + "Likelihood: 0.2740394059664022", + "Likelihood: 0.15748848920083963", + "Likelihood: 0.17965782550323156", + "Likelihood: 0.2404615231686066", + "Likelihood: 0.056342163321165706", + "Likelihood: 0.24626530913472547", + "Likelihood: 0.21514471482281416", + "Likelihood: 0.16001000565367945", + "Likelihood: 0.059476354039446774", + "Likelihood: 0.27850512821278073", + "Likelihood: 0.22758949980459578", + "Likelihood: 0.1312229150535346", + "Likelihood: 0.18777749284243428", + "Likelihood: 0.2391142520226597", + "Likelihood: 0.04748577624690274", + "Likelihood: 0.11750206731385358", + "Likelihood: 0.16515236099026928", + "Likelihood: 0.1577365132800141", + "Likelihood: 0.17592115785859855", + "Likelihood: 0.09692463490955784", + "Likelihood: 0.12071414692801488", + "Likelihood: 0.15422683927501327", + "Likelihood: 0.06872197079559991", + "Likelihood: 0.27597582615850663", + "Likelihood: 0.18220758654427419", + "Likelihood: 0.1518675261806705", + "Likelihood: 0.24364001623768652", + "Likelihood: 0.27355006332084125", + "Likelihood: 0.23028724051812471", + "Likelihood: 0.24645108935011284", + "Likelihood: 0.027995581801057046", + "Likelihood: 0.19179317402050974", + "Likelihood: 0.2640925181791417", + "Likelihood: 0.2438620080334452", + "Likelihood: 0.0849897418649541", + "Likelihood: 0.05035494518910662", + "Likelihood: 0.2800470845681965", + "Likelihood: 0.09918423080404246", + "Likelihood: 0.18010193159156165", + "Likelihood: 0.2162560216047614", + "Likelihood: 0.2178340401138276", + "Likelihood: 0.12641375377971806", + "Likelihood: 0.15270504748321603", + "Likelihood: 0.09310620603718342", + "Likelihood: 0.16254863063517783", + "Likelihood: 0.19735763015215413", + "Likelihood: 0.2580634914587296", + "Likelihood: 0.2810887638478791", + "Likelihood: 0.2825977573399516", + "Likelihood: 0.21785034095944694", + "Likelihood: 0.21846780651242728", + "Likelihood: 0.011380368573709426", + "Likelihood: 0.06682526638869198", + "Likelihood: 0.23475974791201185", + "Likelihood: 0.22685565486660703", + "Likelihood: 0.06495639829177985", + "Likelihood: 0.20774043427066008", + "Likelihood: 0.15030939472888416", + "Likelihood: 0.15156488107239172", + "Likelihood: 0.2811196537028435", + "Likelihood: 0.15991731113467875", + "Likelihood: 0.12144926075826447", + "Likelihood: 0.23063734450097387", + "Likelihood: 0.15811578180373023", + "Likelihood: 0.25025311718935456", + "Likelihood: 0.20687710747294294", + "Likelihood: 0.16928424195598532", + "Likelihood: 0.2609877776040435", + "Likelihood: 0.062535773956851", + "Likelihood: 0.1661183004199035", + "Likelihood: 0.10947273301685352", + "Likelihood: 0.2172499465294787", + "Likelihood: 0.18738230745413148", + "Likelihood: 0.18707823819919944", + "Likelihood: 0.02403218298746428", + "Likelihood: 0.189419546261557", + "Likelihood: 0.2294856376383044", + "Likelihood: 0.24425448501644062", + "Likelihood: 0.12120093249544128", + "Likelihood: 0.20385437309948654", + "Likelihood: 0.09966605652866102", + "Likelihood: 0.1880682731090598", + "Likelihood: 0.2704376290886085", + "Likelihood: 0.15540712943227036", + "Likelihood: 0.20187050221559993", + "Likelihood: 0.2140419925646083", + "Likelihood: 0.277153101108303", + "Likelihood: 0.26532478000584125", + "Likelihood: 0.16980295541477647", + "Likelihood: 0.2681042194063786", + "Likelihood: 0.1788004919482549", + "Likelihood: 0.13269321542893103", + "Likelihood: 0.1654686736678191", + "Likelihood: 0.1945479469454434", + "Likelihood: 0.17775249209535784", + "Likelihood: 0.12487892476874753", + "Likelihood: 0.15068418103029832", + "Likelihood: 0.2618709384077892", + "Likelihood: 0.27580827743132585", + "Likelihood: 0.09400746616341903", + "Likelihood: 0.20446927360368053", + "Likelihood: 0.23413898112036433", + "Likelihood: 0.1796725182921532", + "Likelihood: 0.23442651446343987", + "Likelihood: 0.1144267721583956", + "Likelihood: 0.05189290490518817", + "Likelihood: 0.23526285583498216", + "Likelihood: 0.1787769252746086", + "Likelihood: 0.2344965134550689", + "Likelihood: 0.2280651283351392", + "Likelihood: 0.09373130551337484", + "Likelihood: 0.1355973201536299", + "Likelihood: 0.272784091714228", + "Likelihood: 0.25236615952369673", + "Likelihood: 0.20699893874313144", + "Likelihood: 0.15185795946657385", + "Likelihood: 0.14333948549449307", + "Likelihood: 0.18018236762022496", + "Likelihood: 0.15459409183137562", + "Likelihood: 0.2595501399531416", + "Likelihood: 0.20524921896000226", + "Likelihood: 0.1846891608681612", + "Likelihood: 0.1935610788013063", + "Likelihood: 0.28422949021161364", + "Likelihood: 0.09891983636885526", + "Likelihood: 0.22835273632612774", + "Likelihood: 0.21454239242605558", + "Likelihood: 0.20468737255283412", + "Likelihood: 0.2269464159761762", + "Likelihood: 0.21999278470030026", + "Likelihood: 0.2397431692792463", + "Likelihood: 0.23770446268475492", + "Likelihood: 0.1334580602648444", + "Likelihood: 0.16102707188155096", + "Likelihood: 0.1938051920478279", + "Likelihood: 0.14127241731330822", + "Likelihood: 0.07265902485059149", + "Likelihood: 0.2515287977189626", + "Likelihood: 0.20780954528886428", + "Likelihood: 0.05149308887688985", + "Likelihood: 0.24662597614252826", + "Likelihood: 0.23503458382670486", + "Likelihood: 0.162352276724768", + "Likelihood: 0.14479050528157703", + "Likelihood: 0.15508131490533636", + "Likelihood: 0.2591719951179701", + "Likelihood: 0.2804423107006447", + "Likelihood: 0.1810597328282424", + "Likelihood: 0.13527262520178057", + "Likelihood: 0.1978238434410223", + "Likelihood: 0.28704082369550027", + "Likelihood: 0.08146388630744011", + "Likelihood: 0.28173548435572215", + "Likelihood: 0.21268622905540344", + "Likelihood: 0.2886037652710781", + "Likelihood: 0.08424566327544378", + "Likelihood: 0.27121958041276256", + "Likelihood: 0.13394769779748736", + "Likelihood: 0.06614839552871833", + "Likelihood: 0.2110356461790751", + "Likelihood: 0.21893214076992334", + "Likelihood: 0.07924656495952231", + "Likelihood: 0.08689295106443909", + "Likelihood: 0.22469725471536386", + "Likelihood: 0.21896257401943856", + "Likelihood: 0.2593761322289698", + "Likelihood: 0.09104085328101202", + "Likelihood: 0.08820769427471822", + "Likelihood: 0.2807791324582594", + "Likelihood: 0.2232710935057777", + "Likelihood: 0.2388143299598718", + "Likelihood: 0.14208829528866518", + "Likelihood: 0.2021434724713678", + "Likelihood: 0.2684071978682509", + "Likelihood: 0.2396093224535497", + "Likelihood: 0.26975882758628517", + "Likelihood: 0.1443833336771563", + "Likelihood: 0.1990230489478879", + "Likelihood: 0.08438830264007693", + "Likelihood: 0.03653591034684818", + "Likelihood: 0.15388546460731142", + "Likelihood: 0.2682700077599595", + "Likelihood: 0.05124461408566397", + "Likelihood: 0.12425988012538328", + "Likelihood: 0.28302607311175465", + "Likelihood: 0.14150070915827279", + "Likelihood: 0.19101383445578307", + "Likelihood: 0.23719748641043242", + "Likelihood: 0.15022156871874606", + "Likelihood: 0.2672650142806676", + "Likelihood: 0.19692869071055485", + "Likelihood: 0.23383399894691206", + "Likelihood: 0.16569340931645765", + "Likelihood: 0.22231448315927343", + "Likelihood: 0.01584574428433615", + "Likelihood: 0.2238821052273318", + "Likelihood: 0.18214679472795592", + "Likelihood: 0.10075094193361964", + "Likelihood: 0.18061198236172835", + "Likelihood: 0.2827197256267674", + "Likelihood: 0.27580581979134194", + "Likelihood: 0.09930770731454573", + "Likelihood: 0.25916862231120513", + "Likelihood: 0.28098711366526513", + "Likelihood: 0.1714801632330398", + "Likelihood: 0.21896110528562798", + "Likelihood: 0.19476819428735456", + "Likelihood: 0.24859556107907965", + "Likelihood: 0.16732858711938428", + "Likelihood: 0.2810649078705633", + "Likelihood: 0.19326489010515135", + "Likelihood: 0.057163521332239633", + "Likelihood: 0.18845683773739866", + "Likelihood: 0.218443088145563", + "Likelihood: 0.2731983538109391", + "Likelihood: 0.22166966097984256", + "Likelihood: 0.2663968325129949", + "Likelihood: 0.14175681182899008", + "Likelihood: 0.2672162125739677", + "Likelihood: 0.13420084918689448", + "Likelihood: 0.14893684623428058", + "Likelihood: 0.15866299864767922", + "Likelihood: 0.08563537323011944", + "Likelihood: 0.22280539088482162", + "Likelihood: 0.14344760027171316", + "Likelihood: 0.041731360910018174", + "Likelihood: 0.25914496504827395", + "Likelihood: 0.21392200375141485", + "Likelihood: 0.1825973502777", + "Likelihood: 0.15732536561760088", + "Likelihood: 0.24574047301261773", + "Likelihood: 0.22579349759188339", + "Likelihood: 0.17722155339839302", + "Likelihood: 0.06276538430008603", + "Likelihood: 0.2673206383722046", + "Likelihood: 0.26355550559529506", + "Likelihood: 0.21311399490080518", + "Likelihood: 0.0895448357033654", + "Likelihood: 0.20976859939486525", + "Likelihood: 0.25684546805649583", + "Likelihood: 0.1948410066504755", + "Likelihood: 0.2358667365213015", + "Likelihood: 0.08579044950865929", + "Likelihood: 0.15813762720742378", + "Likelihood: 0.1212410947871281", + "Likelihood: 0.14091789182685138", + "Likelihood: 0.025790447123878412", + "Likelihood: 0.1856309265850252", + "Likelihood: 0.2063794521487963", + "Likelihood: 0.24122034553590063", + "Likelihood: 0.23151661774886317", + "Likelihood: 0.07974404040431442", + "Likelihood: 0.20770768655680769", + "Likelihood: 0.07744725424181502", + "Likelihood: 0.10063069443486188", + "Likelihood: 0.22481914297250521", + "Likelihood: 0.06661239830212728", + "Likelihood: 0.23441878656668788", + "Likelihood: 0.21030314784302948", + "Likelihood: 0.05680920753944354", + "Likelihood: 0.13132757185716315", + "Likelihood: 0.17413553517769007", + "Likelihood: 0.1527375991718045", + "Likelihood: 0.011550766344343707", + "Likelihood: 0.24168167415760372", + "Likelihood: 0.2761278744356048", + "Likelihood: 0.22805932230629591", + "Likelihood: 0.176956983850943", + "Likelihood: 0.2797270078787621", + "Likelihood: 0.16550671950967538", + "Likelihood: 0.07478730195777836", + "Likelihood: 0.14168527607441883", + "Likelihood: 0.19781521112404588", + "Likelihood: 0.24057734512507079", + "Likelihood: 0.24210225524315768", + "Likelihood: 0.26204860930874474", + "Likelihood: 0.2789634833203219", + "Likelihood: 0.05287292658723826", + "Likelihood: 0.21716369935252178", + "Likelihood: 0.26437008623651104", + "Likelihood: 0.22950979620626438", + "Likelihood: 0.11960295533968451", + "Likelihood: 0.2578756494268529", + "Likelihood: 0.15004230563346585", + "Likelihood: 0.20746867753642598", + "Likelihood: 0.21705519113852872", + "Likelihood: 0.17003993021288952", + "Likelihood: 0.2213831915693447", + "Likelihood: 0.07141476607123319", + "Likelihood: 0.25536013539417485", + "Likelihood: 0.15590736474065864", + "Likelihood: 0.12352221182171821", + "Likelihood: 0.14260226173187565", + "Likelihood: 0.21998557979940622", + "Likelihood: 0.19878583895081023", + "Likelihood: 0.2512958039319278", + "Likelihood: 0.03552583253239364", + "Likelihood: 0.03258284458201401", + "Likelihood: 0.2514617285577082", + "Likelihood: 0.11628662570092552", + "Likelihood: 0.17391896253273184", + "Likelihood: 0.2795168575041745", + "Likelihood: 0.0985455590203309", + "Likelihood: 0.1984202328746561", + "Likelihood: 0.15440471740795203", + "Likelihood: 0.163034448006597", + "Likelihood: 0.2664183949286903", + "Likelihood: 0.08084326774067387", + "Likelihood: 0.22848028556323918", + "Likelihood: 0.2638907604421195", + "Likelihood: 0.155561910733963", + "Likelihood: 0.27169826178221035", + "Likelihood: 0.19143468223980498", + "Likelihood: 0.21526682501339003", + "Likelihood: 0.13041888120308587", + "Likelihood: 0.18742977168835992", + "Likelihood: 0.239236211395895", + "Likelihood: 0.18194711105963035", + "Likelihood: 0.24219306808065638", + "Likelihood: 0.13361197646462405", + "Likelihood: 0.18110339479346874", + "Likelihood: 0.1296402528980772", + "Likelihood: 0.1651123612862162", + "Likelihood: 0.05755121489298626", + "Likelihood: 0.2011154418928068", + "Likelihood: 0.26108240153247025", + "Likelihood: 0.17998344243706457", + "Likelihood: 0.23151279009293083", + "Likelihood: 0.100373816786746", + "Likelihood: 0.2657877435798972", + "Likelihood: 0.17395910421403565", + "Likelihood: 0.14951304447198502", + "Likelihood: 0.10177530565703731", + "Likelihood: 0.10021243606893085", + "Likelihood: 0.19305523647192033", + "Likelihood: 0.187995051644596", + "Likelihood: 0.2244525808722255", + "Likelihood: 0.08550304872786062", + "Likelihood: 0.2663225770083532", + "Likelihood: 0.22645765050941333", + "Likelihood: 0.11961472289352951", + "Likelihood: 0.27614752431407585", + "Likelihood: 0.2691308542447152", + "Likelihood: 0.2759955635133959", + "Likelihood: 0.2259549080602816", + "Likelihood: 0.19615461064098388", + "Likelihood: 0.1890464677146549", + "Likelihood: 0.20871612513042145", + "Likelihood: 0.12219556307538611", + "Likelihood: 0.08487201617854828", + "Likelihood: 0.12213000489585078", + "Likelihood: 0.1361557512349929", + "Likelihood: 0.2543743103879533", + "Likelihood: 0.258768051223715", + "Likelihood: 0.16318702016900732", + "Likelihood: 0.10997542268083788", + "Likelihood: 0.1955731783984643", + "Likelihood: 0.23102958593277112", + "Likelihood: 0.15661795152495483", + "Likelihood: 0.18442603689398357", + "Likelihood: 0.13252127593850352", + "Likelihood: 0.2538655461516623", + "Likelihood: 0.09261060857219913", + "Likelihood: 0.1918693952715367", + "Likelihood: 0.15868103250995877", + "Likelihood: 0.15891935889378417", + "Likelihood: 0.1319302999539979", + "Likelihood: 0.11218037970982768", + "Likelihood: 0.13685075550420617", + "Likelihood: 0.24135552543353464", + "Likelihood: 0.09726071212478139", + "Likelihood: 0.06811907702341727", + "Likelihood: 0.1933198226526675", + "Likelihood: 0.1625441106500723", + "Likelihood: 0.1472030269060981", + "Likelihood: 0.06378127719216238", + "Likelihood: 0.20415924032360946", + "Likelihood: 0.16747952711859848", + "Likelihood: 0.21865708238911566", + "Likelihood: 0.13782221667687608", + "Likelihood: 0.22250333742054168", + "Likelihood: 0.18612774242896712", + "Likelihood: 0.23529544511913955", + "Likelihood: 0.06856957585125056", + "Likelihood: 0.26961001208893454", + "Likelihood: 0.1178584935874544", + "Likelihood: 0.18404593796590618", + "Likelihood: 0.20771831351649667", + "Likelihood: 0.10195603302111199", + "Likelihood: 0.06126476162096061", + "Likelihood: 0.14718080363774014", + "Likelihood: 0.2807489655439646", + "Likelihood: 0.2334950697408501", + "Likelihood: 0.10808242751563324", + "Likelihood: 0.18127156821509305", + "Likelihood: 0.26279323743307614", + "Likelihood: 0.04566204270127868", + "Likelihood: 0.2596779872971632", + "Likelihood: 0.2460916174488517", + "Likelihood: 0.11980133687955909", + "Likelihood: 0.09646664134609872", + "Likelihood: 0.18004061505353336", + "Likelihood: 0.270570844875757", + "Likelihood: 0.1671368796640103", + "Likelihood: 0.19092669432442463", + "Likelihood: 0.22213094758949845", + "Likelihood: 0.214555915306704", + "Likelihood: 0.09031001479364907", + "Likelihood: 0.19786508319955579", + "Likelihood: 0.25017463209588264", + "Likelihood: 0.1559076738214522", + "Likelihood: 0.18960903429685025", + "Likelihood: 0.09060644950487612", + "Likelihood: 0.23330453595842596", + "Likelihood: 0.20669275690296832", + "Likelihood: 0.2744383384885781", + "Likelihood: 0.25170497222465255", + "Likelihood: 0.26487032822140766", + "Likelihood: 0.1738799111030557", + "Likelihood: 0.07111476676975181", + "Likelihood: 0.1999196998065858", + "Likelihood: 0.11835533056005113", + "Likelihood: 0.21599139256723088", + "Likelihood: 0.1325419859699359", + "Likelihood: 0.12380568117126646", + "Likelihood: 0.19989985756325815", + "Likelihood: 0.25636604396853646", + "Likelihood: 0.029826452587543857", + "Likelihood: 0.25956081485972343", + "Likelihood: 0.2729822124777515", + "Likelihood: 0.24722999215816407", + "Likelihood: 0.036671379094603926", + "Likelihood: 0.20958944340493543", + "Likelihood: 0.06754921899182088", + "Likelihood: 0.06859624435403426", + "Likelihood: 0.09936787351079918", + "Likelihood: 0.051638343624265254", + "Likelihood: 0.2511312749755615", + "Likelihood: 0.21893307941110196", + "Likelihood: 0.07476088428473006", + "Likelihood: 0.06938671748074801", + "Likelihood: 0.1776482478644269", + "Likelihood: 0.2789917971310168", + "Likelihood: 0.19688206030207764", + "Likelihood: 0.14367885355732687", + "Likelihood: 0.07196687838312278", + "Likelihood: 0.23965226081743682", + "Likelihood: 0.20388632582422536", + "Likelihood: 0.13490762482418128", + "Likelihood: 0.11877439297434968", + "Likelihood: 0.22811801099159695", + "Likelihood: 0.09973565762743483", + "Likelihood: 0.2621061120668067", + "Likelihood: 0.24946197213643492", + "Likelihood: 0.13318381284391104", + "Likelihood: 0.020757877097614712", + "Likelihood: 0.18195985067229573", + "Likelihood: 0.1826025769344938", + "Likelihood: 0.07871132598283377", + "Likelihood: 0.24746069806739615", + "Likelihood: 0.1773045402131875", + "Likelihood: 0.04618152828700166", + "Likelihood: 0.06851839681677757", + "Likelihood: 0.03417827575568901", + "Likelihood: 0.24653355505614805", + "Likelihood: 0.20873736434363105", + "Likelihood: 0.13845846850822835", + "Likelihood: 0.04662940825244758", + "Likelihood: 0.14177481456134228", + "Likelihood: 0.14728505597329486", + "Likelihood: 0.15207105807954538", + "Likelihood: 0.0992973068172536", + "Likelihood: 0.21127206186606814", + "Likelihood: 0.21722036995710037", + "Likelihood: 0.2727094845410803", + "Likelihood: 0.11578148462713975", + "Likelihood: 0.19944362142606864", + "Likelihood: 0.16395781182868713", + "Likelihood: 0.26777136001874646", + "Likelihood: 0.03596323763170796", + "Likelihood: 0.204427365896868", + "Likelihood: 0.2521046584921667", + "Likelihood: 0.2803574737244649", + "Likelihood: 0.24259842127163012", + "Likelihood: 0.25783198208800306", + "Likelihood: 0.09269031163912946", + "Likelihood: 0.2586943228931857", + "Likelihood: 0.13377630914119143", + "Likelihood: 0.08215997166738176", + "Likelihood: 0.20727460821618512", + "Likelihood: 0.2340557595827285", + "Likelihood: 0.20343768862735165", + "Likelihood: 0.27773579664674825", + "Likelihood: 0.20009283403632458", + "Likelihood: 0.17333440680840348", + "Likelihood: 0.25564681024619484", + "Likelihood: 0.08452882858182544", + "Likelihood: 0.08699769897833157", + "Likelihood: 0.08300416439133423", + "Likelihood: 0.1813226337106974", + "Likelihood: 0.2014078320623688", + "Likelihood: 0.0775204976329323", + "Likelihood: 0.22643751049794378", + "Likelihood: 0.2144149867041298", + "Likelihood: 0.15955727201755096", + "Likelihood: 0.1857482629656314", + "Likelihood: 0.26222861720174434", + "Likelihood: 0.13465247456686225", + "Likelihood: 0.10335166295871452", + "Likelihood: 0.0775668834954069", + "Likelihood: 0.042057581850934854", + "Likelihood: 0.2068228008147008", + "Likelihood: 0.22088441249632776", + "Likelihood: 0.2641158837608712", + "Likelihood: 0.10735438250065249", + "Likelihood: 0.2899144760705634", + "Likelihood: 0.17951198998301646", + "Likelihood: 0.15668633968161422", + "Likelihood: 0.20305332724561748", + "Likelihood: 0.16333384772864284", + "Likelihood: 0.1547767128624694", + "Likelihood: 0.2747750624884991", + "Likelihood: 0.25368313808379134", + "Likelihood: 0.052255671752824126", + "Likelihood: 0.1883218201459819", + "Likelihood: 0.22650864093026918", + "Likelihood: 0.23616831400449861", + "Likelihood: 0.05978587627746159", + "Likelihood: 0.174780055765628", + "Likelihood: 0.2606174647966849", + "Likelihood: 0.220631248611805" + ], + "marker": { + "color": [ + 0.20810481334043096, + 0.130459048254307, + 0.279361821243727, + 0.2623758353286913, + 0.26639415563453156, + 0.28495280432356346, + 0.2640227539063325, + 0.25204334147819357, + 0.12282389990213616, + 0.1412369924757717, + 0.27311250059631004, + 0.2574673623204562, + 0.14678264667554577, + 0.28443951484756747, + 0.17611613156396946, + 0.2808829340458293, + 0.2709430034595791, + 0.2758923054645284, + 0.21664567925778497, + 0.2510897448022212, + 0.2451698361444219, + 0.20769643583975694, + 0.18521308912117365, + 0.18164854908196645, + 0.26758456328607005, + 0.23749247715727267, + 0.24467822527683625, + 0.28727624564980525, + 0.25983940895072016, + 0.2063369412462767, + 0.1761402247680179, + 0.19558151439320048, + 0.22784184737606428, + 0.1841115124384866, + 0.21661095530258678, + 0.1684560740903216, + 0.2332292590388241, + 0.2085859412403264, + 0.27384261652292086, + 0.19846966644260242, + 0.2691291369003733, + 0.1629735276548189, + 0.26473038880836886, + 0.2575193899915376, + 0.2847746842919087, + 0.22874794937380089, + 0.20135273269243567, + 0.2635197540450226, + 0.23864830416668756, + 0.23101983901802056, + 0.22148217992352823, + 0.2167006556982333, + 0.2873771506018316, + 0.22710982071500477, + 0.2895065405059108, + 0.2651868063310899, + 0.1876199845113221, + 0.23774241080150338, + 0.2455185230319284, + 0.2010377824053368, + 0.19360379139984443, + 0.23905603395933453, + 0.20716092211227183, + 0.2526327031830973, + 0.2396702062300729, + 0.23940351368649546, + 0.05225829033130935, + 0.17322502948749022, + 0.25312091532341524, + 0.1936120355744652, + 0.22159703650748017, + 0.06009606272856525, + 0.19820200608020666, + 0.2676667912765636, + 0.17533320227622898, + 0.10201635310192712, + 0.2831389952840865, + 0.12345358567176208, + 0.21095131847818682, + 0.27913619083183805, + 0.19785179562724367, + 0.23746511250219057, + 0.2330658653034207, + 0.28309885873705665, + 0.15811040060806905, + 0.2571473504063117, + 0.25870697889313626, + 0.2342594050742677, + 0.11570038472682766, + 0.21407429038720072, + 0.24495478484082994, + 0.23091936106739244, + 0.2802616883332199, + 0.2649510107058665, + 0.22455987980429734, + 0.1053460292047151, + 0.10466363437280556, + 0.2736416772856022, + 0.22674413039128336, + 0.26594147474506086, + 0.1990339547501295, + 0.24995571607608832, + 0.1331290500509582, + 0.1567148457400675, + 0.1253090362140565, + 0.23279318897320403, + 0.2741937172690832, + 0.2281997598357138, + 0.19279854266666913, + 0.2007320895719151, + 0.25917025899659896, + 0.2805847559280088, + 0.25495451167590655, + 0.13431518630428455, + 0.2032625510894358, + 0.25365827664715995, + 0.24413774931975904, + 0.21716846596737666, + 0.23772703468855133, + 0.24613895948109846, + 0.1704671700015591, + 0.22157942127271377, + 0.2673574698092946, + 0.2622440775271852, + 0.21643038215078203, + 0.2412436318619522, + 0.20277503957196144, + 0.28074280240900074, + 0.11790915874162812, + 0.21010437123848366, + 0.15607322199943666, + 0.14547516011332096, + 0.2799666033489401, + 0.21600723385831017, + 0.19781966742966378, + 0.20625605489117316, + 0.25047101838845, + 0.26593399722678585, + 0.12415398708281428, + 0.2028190691781094, + 0.28018603038259143, + 0.13067072729399767, + 0.27439361622676417, + 0.2107268388383748, + 0.1913368213294102, + 0.1950765070746037, + 0.19694001984250256, + 0.09012528603474247, + 0.06536243928254311, + 0.23089817917164362, + 0.2833050756224298, + 0.12635014672826214, + 0.2684640288950437, + 0.2518734908524205, + 0.28008126711781217, + 0.19598492367836642, + 0.2627041290440935, + 0.13508540317143083, + 0.2770850219388568, + 0.22830484265512244, + 0.2711485892354035, + 0.16101344028676687, + 0.24132209138698404, + 0.1885878923259109, + 0.16528662635728283, + 0.09513910798852222, + 0.1650224801138397, + 0.23217250850163068, + 0.23376675432776325, + 0.176063045946337, + 0.27927032602423346, + 0.16054202415010332, + 0.15292734474387673, + 0.2625534745284116, + 0.24858823971030938, + 0.2753019808219775, + 0.2298699923318757, + 0.24901111727980982, + 0.19063791623377557, + 0.2350456215557457, + 0.1867460498127031, + 0.27152459566376813, + 0.2578471572049096, + 0.24803038681964948, + 0.13877926521301018, + 0.18918104058860125, + 0.11329395245297653, + 0.20828885710585282, + 0.2237033502516991, + 0.2519132001416812, + 0.07042507467775543, + 0.26315473419811797, + 0.27232907226450603, + 0.2579193500132577, + 0.12391381848645035, + 0.2188421477479769, + 0.24314444569696025, + 0.15112156915465236, + 0.2715752487176161, + 0.22548499580881587, + 0.23327308143827608, + 0.19619337555381042, + 0.25374711209805595, + 0.25225497173228234, + 0.2733514961144272, + 0.2611599558002902, + 0.2730562851508506, + 0.20919482735223807, + 0.28603121644023816, + 0.21675019678040344, + 0.20029117949109082, + 0.20535692251245288, + 0.11627150576820083, + 0.26319896077541993, + 0.23729349858217977, + 0.260419899668343, + 0.17380938280004626, + 0.2782585989782065, + 0.17212511026867552, + 0.2056944096459763, + 0.2636236170572003, + 0.14083730078787252, + 0.19657070347231384, + 0.20191655159480235, + 0.11310814472083662, + 0.07358471991174526, + 0.12275972032400331, + 0.2548554998531059, + 0.25550570250714805, + 0.2523399409841471, + 0.2685510653417639, + 0.2794815919849155, + 0.25703616111794747, + 0.2759197606081695, + 0.2263255599802551, + 0.21540525382980588, + 0.22507528680165287, + 0.2260723611365006, + 0.27364260569672055, + 0.19225297545903824, + 0.2593886717594725, + 0.1119874913874884, + 0.20648833332507005, + 0.044438876143319844, + 0.13890771894237428, + 0.23889966270389124, + 0.23317497142620333, + 0.2102553667084734, + 0.21616553180205048, + 0.16853177686607343, + 0.20641927318215364, + 0.2711895497852776, + 0.24387441056312892, + 0.20947162915365583, + 0.1822319175645133, + 0.21198795261071066, + 0.2649170051970247, + 0.24931753820384964, + 0.17050873003416372, + 0.2663033873430515, + 0.14442534042814276, + 0.18789048517727247, + 0.22332167158878735, + 0.12642837462246329, + 0.27675444986039505, + 0.24191997065653287, + 0.2600101992809959, + 0.12210956092338898, + 0.26825711134847385, + 0.26423161338586876, + 0.06258616691020089, + 0.193024956079963, + 0.1947463468135252, + 0.24711938680446735, + 0.282200704826556, + 0.23061468822813788, + 0.13488963559946143, + 0.19943324220893746, + 0.22801130613798484, + 0.2678312250942803, + 0.2585146832850092, + 0.1725715662046506, + 0.21775774339110093, + 0.15937553937788917, + 0.24961570475553205, + 0.24962294617409655, + 0.23229335825650374, + 0.23387422510410708, + 0.23864939956610756, + 0.17832022261968292, + 0.2410697496298089, + 0.11514468237688068, + 0.1318932322212576, + 0.07652130117404858, + 0.2739095047903807, + 0.2759844431248325, + 0.27965121236776624, + 0.24442455767938745, + 0.2833661966518392, + 0.25713473995879627, + 0.19445694861958235, + 0.2211565687578668, + 0.2576077700186185, + 0.16957145126214138, + 0.2662120346286997, + 0.22112608935728206, + 0.26852572042865, + 0.25495703937252867, + 0.22061133155618806, + 0.22894625870218757, + 0.24169921854494403, + 0.28537076057434413, + 0.2246900976929709, + 0.2711817044382062, + 0.22783157325190118, + 0.10539313432517713, + 0.2515355208225933, + 0.25367990157019965, + 0.197550450370515, + 0.25266725120394135, + 0.16821034785734681, + 0.2382480093559903, + 0.24123584807470336, + 0.26609479274200043, + 0.17522568066606237, + 0.2749509913640437, + 0.2843692115393823, + 0.11533336277001245, + 0.26391241747975946, + 0.17315266020051345, + 0.2033314219910699, + 0.14438667244340114, + 0.17094959547356597, + 0.28266483520111446, + 0.1628463162249221, + 0.2460110558863935, + 0.24792508691975207, + 0.21267525716859317, + 0.2547644802967714, + 0.2700029229010067, + 0.26076901366946353, + 0.2710488463974468, + 0.26132909955516576, + 0.2135344785313413, + 0.26776469635706307, + 0.055836377822829686, + 0.03237613807828661, + 0.2035075821300367, + 0.1692176820175629, + 0.2713221888816793, + 0.06783075999443784, + 0.2739008454389829, + 0.2375583755748652, + 0.13957784551588465, + 0.26585255255294443, + 0.25355415668033104, + 0.21497673327807318, + 0.16847549379388413, + 0.1901110623008926, + 0.24042630082135963, + 0.16786379920727715, + 0.12652496865183238, + 0.28846617060862306, + 0.27831133460769114, + 0.19355754516174822, + 0.27161988913699575, + 0.019061972211805896, + 0.2510548808649413, + 0.28873156175650755, + 0.10268129159966051, + 0.2184105959422838, + 0.09334958603861752, + 0.25680562525105755, + 0.16872211818543567, + 0.26251776216629186, + 0.2902066447214772, + 0.19497516319409913, + 0.20707217341819908, + 0.26458572303459343, + 0.16332832457993188, + 0.24528139945293156, + 0.2625350137413594, + 0.25415014746149556, + 0.254759088030215, + 0.20405505520136463, + 0.19548324814301626, + 0.1626282137935981, + 0.2029651364250574, + 0.26572884951624165, + 0.1662519814393004, + 0.16542586955600683, + 0.1528526913320465, + 0.27714338854347337, + 0.13356959270900132, + 0.2642518063514087, + 0.27911494735665704, + 0.27697797949729025, + 0.2666711173452773, + 0.07000118470176697, + 0.2693589399940803, + 0.2795544719030789, + 0.2770063445906241, + 0.24530157581744833, + 0.1387686536843856, + 0.24890583323181453, + 0.15633165203212165, + 0.2549215733923591, + 0.19534502794548358, + 0.25888852371422905, + 0.181839614096996, + 0.2688719856491198, + 0.025930218949395747, + 0.0899445711796484, + 0.27422537530227165, + 0.06372553610659976, + 0.16083056325603126, + 0.21856227339295395, + 0.2526359366751649, + 0.21330697471854065, + 0.06962277867756453, + 0.09689748724334288, + 0.2714108391575776, + 0.2204201024938798, + 0.20243563197188985, + 0.24609370071350994, + 0.05644387406624454, + 0.20535196209824325, + 0.05057598976086957, + 0.2354055300851878, + 0.27870822565143966, + 0.0530741546504451, + 0.08352144757761408, + 0.20327448490406005, + 0.2655066303395635, + 0.1223006675008096, + 0.19869908251311838, + 0.2719988264944895, + 0.19611191438370085, + 0.2839031270270296, + 0.19098543221758388, + 0.22531431211467662, + 0.2346321070666016, + 0.2587341587736319, + 0.16563521768114528, + 0.16277027023726093, + 0.2531216018435291, + 0.06984437477846402, + 0.20674436072887128, + 0.25686924399013333, + 0.26981301162672616, + 0.22234697481032803, + 0.15514889500158427, + 0.26554128364372126, + 0.1352078442728502, + 0.14271413324796628, + 0.24718405198205476, + 0.0868283669538029, + 0.08712345350067387, + 0.033239711556303425, + 0.2879048429773455, + 0.1520627183830359, + 0.06358972410540065, + 0.26373982962338277, + 0.2554836498009723, + 0.2661266491004923, + 0.26050154359449385, + 0.22025050482557731, + 0.266480371740285, + 0.23927120483271191, + 0.25308722085893826, + 0.2717108233178077, + 0.25115562522306994, + 0.2559716754326736, + 0.14116791141247215, + 0.2063163533966333, + 0.27770992176863196, + 0.27416455725877, + 0.16551447687399357, + 0.23837149401253313, + 0.2702321363277116, + 0.13558449457261643, + 0.23172460525896738, + 0.2754452338811167, + 0.2538045937208622, + 0.2674379819328193, + 0.261470463401047, + 0.08513355042271804, + 0.22228890676695942, + 0.28348702556707184, + 0.1516349611792574, + 0.26905043680844404, + 0.2762296624868539, + 0.16928769160877064, + 0.09172722730776872, + 0.13634197540477175, + 0.0753568010828628, + 0.1380739367367254, + 0.11758743842276549, + 0.2414762279204087, + 0.28851045894513033, + 0.10964011353018717, + 0.19679424484508418, + 0.27367183907924103, + 0.26531022348772754, + 0.26882465104144637, + 0.23655536217979678, + 0.23724578303892838, + 0.24151996930429837, + 0.10443036652578257, + 0.28093724600777237, + 0.2683798718760461, + 0.17705608228513947, + 0.28407066339344667, + 0.27296024952285236, + 0.26100088320428294, + 0.12450058133460544, + 0.27698711701379836, + 0.18688950658527265, + 0.22776256099506384, + 0.23725342632378404, + 0.18674240989817797, + 0.21857806620958065, + 0.23615088740351026, + 0.25668980742793235, + 0.261999263151587, + 0.19375080656529597, + 0.19371300112068904, + 0.1759562496872788, + 0.24514336987943824, + 0.1928506215241697, + 0.23988142200609294, + 0.22976975529204366, + 0.2608592783345866, + 0.22751432484684192, + 0.1443932794397867, + 0.14323138775180091, + 0.2698105565605345, + 0.21451531746282318, + 0.24621508407014112, + 0.2772398839543373, + 0.17856739240136937, + 0.2877743829168945, + 0.18029332501451517, + 0.2709614465795565, + 0.18475334921221462, + 0.2718610904785636, + 0.27501173961078756, + 0.18788152016365792, + 0.2110387414026119, + 0.2491427001078299, + 0.26803138655002906, + 0.21529631901178375, + 0.26145936679472914, + 0.1897506357207073, + 0.2826715758930944, + 0.26570463734307265, + 0.2865114358780555, + 0.1707517085288731, + 0.23588043594527827, + 0.17712039069623173, + 0.2598781259990335, + 0.21363295044077257, + 0.28048436640884106, + 0.2592611393286654, + 0.21006654292411422, + 0.25235759194762836, + 0.09476490322638445, + 0.24366518978594953, + 0.22602743555336738, + 0.24093512414359133, + 0.07604118376243918, + 0.23096879933603645, + 0.08078296427039174, + 0.1833639197428365, + 0.15245545732213917, + 0.07726942615364625, + 0.2829585200089288, + 0.25892013811996617, + 0.19456251532709043, + 0.241408648203832, + 0.24484279029572054, + 0.18118547527837522, + 0.148070386345693, + 0.18009084137858103, + 0.28685652403511064, + 0.27832104940088825, + 0.12096901990695705, + 0.22864792976315376, + 0.24395947993878261, + 0.2593805946728099, + 0.2706360991210647, + 0.1690175351854081, + 0.24006194436770711, + 0.27197176091247743, + 0.18275495684840767, + 0.24215742166403295, + 0.2704704932587337, + 0.2606360280100902, + 0.28015082333378216, + 0.1716744259645657, + 0.22018778960795035, + 0.14058492596353972, + 0.09686416073991891, + 0.21805257785832524, + 0.2597934148765847, + 0.2737424493066494, + 0.24956032881133006, + 0.24680338173404165, + 0.2785780745195794, + 0.2494055467396993, + 0.26365589299955705, + 0.27864786684452447, + 0.14136193805310546, + 0.2660999274359205, + 0.2361053183999635, + 0.11100780837623055, + 0.25944299669392024, + 0.2636566293873125, + 0.17121547547752514, + 0.23625623034616847, + 0.21837781700653563, + 0.2750408898916524, + 0.22997733784999033, + 0.2564859946303927, + 0.24225927045060044, + 0.2802960004864162, + 0.2223369260017043, + 0.24901240852821538, + 0.2481992117269396, + 0.23871672228036162, + 0.2630499008426831, + 0.22865050560017366, + 0.2305716206819521, + 0.23752497892315197, + 0.2609852383027948, + 0.12361461580448596, + 0.17561498965939704, + 0.18895741364403754, + 0.2503413462026434, + 0.21066553178452582, + 0.20665943980085433, + 0.18431197509429628, + 0.24787111181028254, + 0.1522439432048269, + 0.27857889562198196, + 0.25299552914198814, + 0.21645419928276863, + 0.1516118355615346, + 0.24469572132139988, + 0.2698765886400724, + 0.19061889032775728, + 0.2723035140878141, + 0.23548722401261, + 0.21840026906887428, + 0.16688687005927647, + 0.19251690511215583, + 0.22720538670358456, + 0.22145815178399408, + 0.1967526695209055, + 0.19402028984496697, + 0.03165197110165006, + 0.2693586059896015, + 0.26421101151897436, + 0.23289185598032458, + 0.22731116959184017, + 0.18096990465703713, + 0.24405307593282988, + 0.24170382207487903, + 0.17532285375419218, + 0.2433736170723819, + 0.2476933887577213, + 0.26830847445785816, + 0.2653010530648962, + 0.1865533490724739, + 0.14981210369735087, + 0.21280537935927551, + 0.17844227380048097, + 0.17955416692716472, + 0.11661239286403335, + 0.26543430313607597, + 0.21579359080342572, + 0.24548241660857417, + 0.20664970112106898, + 0.23880762510788567, + 0.24016411271446864, + 0.22852229576899008, + 0.2396466272456302, + 0.18095376159663532, + 0.2532846853727245, + 0.2879650179621261, + 0.2799254389195942, + 0.24739175865105295, + 0.14388758042922475, + 0.21403009559275496, + 0.09341831044849531, + 0.06438924253553914, + 0.20139771596521558, + 0.12173501572333656, + 0.23579664631167682, + 0.26147221550893524, + 0.21272478803759257, + 0.14755295384375533, + 0.2876062174913059, + 0.2459008633087963, + 0.20221658631491454, + 0.2798455095820042, + 0.2692645729908878, + 0.2657761619224121, + 0.1918147631436304, + 0.25026381240982004, + 0.17857455534914954, + 0.22903344742293347, + 0.26460680588349594, + 0.2893757126774011, + 0.059336405972595825, + 0.2666826867594761, + 0.18224460717034477, + 0.1647414521975642, + 0.27253265087065653, + 0.2690723119828284, + 0.22902975033251555, + 0.2843788138551999, + 0.21720243644846454, + 0.26483334759493216, + 0.17467039979664262, + 0.1582219895918987, + 0.2806508924561494, + 0.2603894021306378, + 0.27651265837765754, + 0.2051098904870037, + 0.27209611544250945, + 0.27348916887765623, + 0.25880921292613907, + 0.07313614929002732, + 0.21291616995764145, + 0.2550344915566977, + 0.26700806536678684, + 0.22489589247991584, + 0.20130808399942357, + 0.2649143198110591, + 0.24908058013725, + 0.255287390831867, + 0.24683059834631155, + 0.20536559267904356, + 0.22805144669664484, + 0.09544954267299562, + 0.26348179903300867, + 0.24941593748600863, + 0.2529660947702746, + 0.26376450757711345, + 0.27877077092902663, + 0.2436092628800255, + 0.2215566471081495, + 0.18120190663119443, + 0.19401968937678168, + 0.1903254324031618, + 0.290546489275831, + 0.28464125328999107, + 0.2781995016219609, + 0.13723684117365245, + 0.1682741815238012, + 0.14592918272003713, + 0.07437620880520295, + 0.27086254345694605, + 0.15995084142206278, + 0.2514413567801101, + 0.13111625936891777, + 0.2783309425369331, + 0.2385159887862645, + 0.23752615616090778, + 0.21862687435449946, + 0.21628697068006417, + 0.1684907527622904, + 0.2650169564044689, + 0.17027588745192193, + 0.11950642545692385, + 0.23001176304144508, + 0.21198015490184857, + 0.25712174454969666, + 0.1854671253383412, + 0.07699234094817188, + 0.2592266890969317, + 0.2727950916755872, + 0.26109806184400147, + 0.26355818285772253, + 0.25312137818287656, + 0.26373027014806183, + 0.281073288500227, + 0.181029287049187, + 0.27531446902491513, + 0.17553316529440727, + 0.06227575640185585, + 0.2694072224926155, + 0.2756903577791477, + 0.2366595179124883, + 0.22021964993754353, + 0.286484079233775, + 0.04852015406994278, + 0.07776453604427092, + 0.23906733329139274, + 0.22125636356307726, + 0.25810427526547763, + 0.25545486757806884, + 0.2512764143868585, + 0.2722767503166838, + 0.03556468051814721, + 0.2778865014168398, + 0.20619418268196063, + 0.2783984648687409, + 0.06275526262939132, + 0.22398257887764583, + 0.19183440476364674, + 0.26417791819607456, + 0.2356981469234701, + 0.11884478701022907, + 0.22324972138317478, + 0.27291899498456856, + 0.1983862808936293, + 0.23921581811163453, + 0.2749298488108668, + 0.23677285070636384, + 0.26041500637593606, + 0.1868756266878638, + 0.14656386996310405, + 0.2596263605640581, + 0.2751590406241067, + 0.18536686448246617, + 0.2149764456606123, + 0.21477658626070753, + 0.22708659020500832, + 0.27408707375512587, + 0.09066321480172265, + 0.25630562602936, + 0.24347547528695676, + 0.09308848804144675, + 0.2521064576220632, + 0.12497996924446621, + 0.22578182190675217, + 0.09727189301637908, + 0.25486339648601586, + 0.2729747364519274, + 0.1481364847697132, + 0.2779120202188293, + 0.15653566022091953, + 0.1974672665675038, + 0.17707179348101798, + 0.18539970180259352, + 0.2479997042657566, + 0.18640959134085766, + 0.2763135311495187, + 0.07981768531193446, + 0.2862824744813071, + 0.2086916115410227, + 0.2745544598257201, + 0.16163728241566652, + 0.23434636265842576, + 0.2677682991566488, + 0.1261685883786039, + 0.16961513591956257, + 0.16064945785732362, + 0.23048578036663936, + 0.24452043972021412, + 0.28706436069264973, + 0.2590563719198895, + 0.23624876457970692, + 0.23604690914172022, + 0.2486047185016833, + 0.24435937591743584, + 0.15883202563102314, + 0.24781553946766297, + 0.17770858290997363, + 0.28208654147152257, + 0.2868479889935742, + 0.2753362547014846, + 0.2532946233319956, + 0.19724838409407053, + 0.12678254699668037, + 0.28561362179373606, + 0.25690985717891596, + 0.2758892762180845, + 0.14867908847884537, + 0.1288137160230199, + 0.23486248966867704, + 0.21117632533732522, + 0.2374565474326426, + 0.28102157182583165, + 0.23965791078764428, + 0.18450307724008425, + 0.13176944535043555, + 0.27081076889797595, + 0.2256273214216212, + 0.2803845545035477, + 0.14396121425167832, + 0.23410677784630748, + 0.23453297463131437, + 0.1524709852550037, + 0.19679336299310954, + 0.11775720639091036, + 0.1553669713635173, + 0.23625974994753499, + 0.2686982320008977, + 0.2567443905001633, + 0.280967513559528, + 0.2510229908610971, + 0.23177417376070159, + 0.24262138198372193, + 0.1126537936900903, + 0.2577233017679166, + 0.27532648104155305, + 0.25171453090696844, + 0.27269750826611266, + 0.2501456028118101, + 0.1626465524686415, + 0.23577450542862202, + 0.2489130544957073, + 0.06060132578885715, + 0.19906705940144143, + 0.2656445773489714, + 0.27911144954399286, + 0.21514828823352225, + 0.20726978261463644, + 0.2492052386310184, + 0.2638922308689337, + 0.06803195200357028, + 0.25276659631159304, + 0.2842998631775639, + 0.25318698099699277, + 0.22539802113947205, + 0.26373083467690545, + 0.26856595460715266, + 0.23173016209519612, + 0.22848816464982044, + 0.26644168508519933, + 0.2802266840431035, + 0.21852264971131805, + 0.19117171391934448, + 0.23327911423944458, + 0.20169046528393603, + 0.24913126512509923, + 0.2736162636556534, + 0.1726879421571588, + 0.24596365387532307, + 0.22691266253035985, + 0.22032635947538065, + 0.2155401687093313, + 0.26464785560820575, + 0.2052339721008131, + 0.18758890906256914, + 0.10495834672807089, + 0.1592077515738598, + 0.24044405236470826, + 0.25405460886948067, + 0.2572776574965564, + 0.2082309988024704, + 0.2540494096780359, + 0.27226710144055954, + 0.2522762278947608, + 0.1640321498888107, + 0.21631469200380637, + 0.26181740318738694, + 0.2658096067251571, + 0.1523624173620177, + 0.14079930903858923, + 0.045305269407689225, + 0.15774281244632407, + 0.12981984660130164, + 0.26376195064009206, + 0.25045968130059454, + 0.18542141152318328, + 0.1495351759124211, + 0.18258952662671013, + 0.18546212936397868, + 0.21963818577163133, + 0.2786176957605934, + 0.2558996805568438, + 0.1934628014026105, + 0.2625177393356755, + 0.16004080752964742, + 0.24584022166678177, + 0.19330066077873037, + 0.22547306405081913, + 0.12284790248524012, + 0.2580776328521437, + 0.22555261322784673, + 0.27705562826344426, + 0.2131184242369306, + 0.2445505738224783, + 0.17690439833871008, + 0.2757992540482892, + 0.1991730180982271, + 0.21481316577719764, + 0.2718839601742654, + 0.24097993684288288, + 0.2619574060600212, + 0.26219165923648097, + 0.2267801826057626, + 0.26026592994744485, + 0.2755732795123286, + 0.2430407274491166, + 0.2179681796500437, + 0.1735159403943495, + 0.2712877199448693, + 0.2541551552887553, + 0.1298146021682781, + 0.2722255519968362, + 0.22779161992658978, + 0.2570292227719222, + 0.16908284847867602, + 0.2480242416610786, + 0.12834927630802428, + 0.26935598157679713, + 0.2835800087725838, + 0.27931813312170944, + 0.22934654550280154, + 0.28145969058790254, + 0.08192457372550728, + 0.26031661818026136, + 0.19526749287183076, + 0.16349671766971458, + 0.25249073624213847, + 0.07181003597004564, + 0.2724750791329256, + 0.2767689147509632, + 0.1988262924434514, + 0.19116803358224438, + 0.25424260284608646, + 0.27103889227549655, + 0.1312747250504108, + 0.27049149469461214, + 0.2526796368474521, + 0.2879707516541813, + 0.2624381968824294, + 0.11108918468008298, + 0.24028219325843453, + 0.1439197006160816, + 0.27666293847785983, + 0.18014511930714236, + 0.25706196029027417, + 0.25787204990455453, + 0.03389053737267386, + 0.2773612816294091, + 0.2837512837974911, + 0.18848682212586088, + 0.07609351234935541, + 0.28685806883646453, + 0.2120409045835825, + 0.13787187490983935, + 0.2791370325079298, + 0.2488843592355302, + 0.2872771346726806, + 0.2516967528797034, + 0.186329583043438, + 0.23862236526197297, + 0.22147607275657263, + 0.234809016833285, + 0.24207991078910066, + 0.15734546674338284, + 0.2605741600872656, + 0.08593251150033612, + 0.1899561347888706, + 0.2558589298785291, + 0.24879341345171796, + 0.1877998696159295, + 0.26947874455993415, + 0.12466225204418807, + 0.160321990178704, + 0.22780048733545666, + 0.22052198523147387, + 0.25261839410434833, + 0.2691340015750629, + 0.20192102780505503, + 0.175289745342132, + 0.25450896294447684, + 0.24492459959689955, + 0.18503482581650868, + 0.27002717650412933, + 0.17971566872918932, + 0.25985189670273207, + 0.2581833391363144, + 0.15316963787730373, + 0.28877304348639665, + 0.21540695346729283, + 0.20984041461473488, + 0.2540460005865899, + 0.2678951617233007, + 0.2572554160278005, + 0.2614963621498901, + 0.22385528356420903, + 0.1525764528749906, + 0.2134070193865599, + 0.2794864870074231, + 0.16799771767819835, + 0.20370657646483412, + 0.2229057795246239, + 0.1501162947687321, + 0.2469064934066097, + 0.17472244003149062, + 0.23754028417972128, + 0.036356393837930885, + 0.12411826683437095, + 0.27867367412270017, + 0.26623557836524375, + 0.1510113842098582, + 0.21835700740267627, + 0.1496643463839976, + 0.18514017229976426, + 0.20931674732137734, + 0.2228448655031189, + 0.17148794952326063, + 0.1956449162397797, + 0.2313399020680827, + 0.22672648745997984, + 0.13872590829947362, + 0.24629764328650303, + 0.11037021200141144, + 0.2577335922464449, + 0.24722420625251415, + 0.25510541735987685, + 0.24698036675127466, + 0.21635099054806972, + 0.21122832105666786, + 0.24245965362299576, + 0.08186786176948396, + 0.17426708967931318, + 0.26598131543870374, + 0.17472563166079608, + 0.1266458661895604, + 0.2169618075761659, + 0.23408665510057422, + 0.25540175308368684, + 0.28253092283730236, + 0.25088571791350794, + 0.20919442814392097, + 0.24736134419059724, + 0.18639799303592136, + 0.24971439338832155, + 0.05683338421596529, + 0.15427387136325585, + 0.2769425921655928, + 0.28604695410162184, + 0.2071648813272708, + 0.2680527524819207, + 0.2514725159974678, + 0.24060087902333802, + 0.0893465425259003, + 0.260440813286459, + 0.2602525054921459, + 0.2847393583574644, + 0.13220155521594665, + 0.24253246229368292, + 0.26597914189672733, + 0.2573788613197233, + 0.24995654847829246, + 0.21427139159323783, + 0.07049227068086866, + 0.28171094832203625, + 0.24056089712828743, + 0.159045769240542, + 0.10308517924099025, + 0.133115863921503, + 0.19483062087553396, + 0.2749092541679737, + 0.2200373700159994, + 0.14606113078078856, + 0.19891743467030895, + 0.2858767162253152, + 0.2827977470432688, + 0.2733701917441527, + 0.28364406015792126, + 0.16598042334255123, + 0.20489172372413908, + 0.14841724556033953, + 0.19457021423119866, + 0.15816751853633793, + 0.24590535061159338, + 0.24222516956379433, + 0.27147672506575143, + 0.27118181209111614, + 0.259823154845583, + 0.17649587449036153, + 0.19295058610748234, + 0.16515056669269393, + 0.28166381306553107, + 0.09287806819608047, + 0.22562637225328155, + 0.18381090682458487, + 0.20990213390751122, + 0.22771475430711471, + 0.2739414423942593, + 0.09815850210407089, + 0.22433961793068452, + 0.24776626212869005, + 0.28419980148844937, + 0.2675701723083817, + 0.28947599096683346, + 0.2204625202501865, + 0.279252845660254, + 0.2616779080231534, + 0.17076791828165386, + 0.1730047318831096, + 0.24069016025243464, + 0.2715041407045909, + 0.22119187473658852, + 0.1292212049945807, + 0.21600500769005263, + 0.14526830099517668, + 0.26494175172978296, + 0.14544343504332408, + 0.2351230254153244, + 0.2735759606737838, + 0.28768401708237756, + 0.1771922374413764, + 0.20062187207180665, + 0.06968399946900615, + 0.2122215529951959, + 0.22227802705563415, + 0.20502548929017783, + 0.2868674465616365, + 0.26217088880854866, + 0.13534788486586924, + 0.14890602526180213, + 0.25378854203315393, + 0.14627486492481456, + 0.19798350387046512, + 0.24118923249814386, + 0.26584658124011723, + 0.18103566009985214, + 0.10262500019570718, + 0.21515075056819966, + 0.10639030895364186, + 0.12232091444954674, + 0.21710181868983922, + 0.20961560622357736, + 0.10097416731760726, + 0.2031252667841361, + 0.07724258361004786, + 0.1241615597530055, + 0.26040767403677895, + 0.18136357009191703, + 0.1839344270413075, + 0.22160796690644086, + 0.23383426651318756, + 0.07631093562432001, + 0.1544876631365256, + 0.17770172851594332, + 0.0551964619817569, + 0.15716583039009646, + 0.08809283437423787, + 0.2682538954202703, + 0.21688443627064305, + 0.0692284190589275, + 0.17647897620140376, + 0.08825523044389975, + 0.20644804896560717, + 0.240830237255483, + 0.19147796230323114, + 0.04229945620644664, + 0.2128338374557287, + 0.20294691477675036, + 0.2344981792327447, + 0.039262772005959234, + 0.08317106512578483, + 0.09180809930643442, + 0.24377810303082526, + 0.2863174145432201, + 0.14472628928768747, + 0.1433361288467958, + 0.04617666299361631, + 0.2249024945896988, + 0.09288706164221261, + 0.12985326569537728, + 0.10453672014133789, + 0.21809910482812417, + 0.20789388243483597, + 0.2321729753812562, + 0.21707284836220117, + 0.2301023113902955, + 0.20902501394334716, + 0.18284122129194655, + 0.17224823762459018, + 0.19838489775093657, + 0.2677446139387228, + 0.1571215855619267, + 0.05971219179495876, + 0.09293632257122714, + 0.059964022001104504, + 0.1499724469944722, + 0.28548590127171086, + 0.20585136081543026, + 0.24779828937513457, + 0.26033372828377715, + 0.16771894552439898, + 0.13428610741318647, + 0.21184783329229323, + 0.1364877357927606, + 0.21271584316866612, + 0.18245917964678407, + 0.2345219621361327, + 0.26661341794276805, + 0.15080301962298423, + 0.2846243800862095, + 0.27688411744259245, + 0.09317264833592231, + 0.20447737633006915, + 0.22607791151817938, + 0.24389741550988725, + 0.12984622184689998, + 0.2503829788054369, + 0.19639534380405813, + 0.04835024535072436, + 0.14924471118340085, + 0.11326910595639525, + 0.2080758112448512, + 0.17882902985801966, + 0.22351563660775833, + 0.04148959111782978, + 0.14027132672418638, + 0.2051128482135276, + 0.2436229158283561, + 0.10126875426678544, + 0.25888549483956713, + 0.19473337375921834, + 0.25756398874152375, + 0.17653154651432856, + 0.24416774229928703, + 0.1738379890544695, + 0.2145020438803428, + 0.17125095058824488, + 0.14544502951547347, + 0.26747789595029, + 0.02711197911444816, + 0.21299838429857884, + 0.11844998734038364, + 0.2635919768642971, + 0.2676343449270705, + 0.18017684040030518, + 0.27361048052942727, + 0.1171932281239063, + 0.13971306424934038, + 0.07369961824929588, + 0.24914014917745797, + 0.15204218345533602, + 0.16253470064279313, + 0.25946670021404045, + 0.2005841059817093, + 0.21478239060582746, + 0.25809240791128363, + 0.2508329716295816, + 0.24279202888884024, + 0.19394487566146756, + 0.19778391552934818, + 0.19829249818386493, + 0.16346326708751835, + 0.26637845149810485, + 0.19872165544199547, + 0.11865973573668462, + 0.22984606648513592, + 0.0863495512105819, + 0.15977514357893208, + 0.11425630464721077, + 0.24350848397913907, + 0.20295779895146396, + 0.22918390555834273, + 0.18434151720357345, + 0.1103723977631552, + 0.17059432747435133, + 0.05791654219071694, + 0.028439567012417295, + 0.2707548742987902, + 0.12873586004359763, + 0.14689840676015525, + 0.2388560180469484, + 0.058646664822871716, + 0.1028048231717061, + 0.2624468426116323, + 0.23417799129985695, + 0.08963438698811173, + 0.1443506765604378, + 0.28954317270399144, + 0.1549307087368068, + 0.244871959529343, + 0.2418007707051667, + 0.13051281833909256, + 0.21482542398472282, + 0.1929357206883528, + 0.026560011358735675, + 0.1988247111588973, + 0.04416007279245558, + 0.06051350081100071, + 0.14155589992774514, + 0.09531950257821634, + 0.17292894519864338, + 0.16529820407324256, + 0.23307030726791714, + 0.10023119431323806, + 0.23182833968836683, + 0.16821140612231558, + 0.17407983685546594, + 0.22737933151108985, + 0.21982638581170535, + 0.15541979191110689, + 0.2676096141542056, + 0.26901082764496614, + 0.11163667865196386, + 0.14527284826016543, + 0.1238971216458578, + 0.22848131609752526, + 0.14188769515209707, + 0.2361649939220183, + 0.14576351039469257, + 0.1280523699874008, + 0.21261002046728822, + 0.12057889684626531, + 0.09381813102483688, + 0.22476414749652143, + 0.2833495520801082, + 0.15382905368967714, + 0.16854115970144595, + 0.13189387243997266, + 0.2304171617742575, + 0.20157350945824243, + 0.2056969587079807, + 0.16324506512825013, + 0.04259824393554179, + 0.11639000162313337, + 0.1941715468488561, + 0.2606768651743186, + 0.2718297333384577, + 0.08926196075120357, + 0.0957129146515823, + 0.26316697665513555, + 0.24389986411925454, + 0.18534975147723665, + 0.042909893294534256, + 0.23367673016634755, + 0.2555870112334192, + 0.2729604532923857, + 0.144319273596758, + 0.20524824085618054, + 0.10122192344268606, + 0.24301613224349095, + 0.17935690332465484, + 0.18705226299595357, + 0.26377573728165377, + 0.23971283544376634, + 0.07039448560524705, + 0.2546297526019145, + 0.06928558229217398, + 0.13096591409927624, + 0.2359358680513758, + 0.18526932591667816, + 0.2749778893207592, + 0.14128016561292014, + 0.23162854344127545, + 0.266871506357275, + 0.14221388185206366, + 0.14736425820645346, + 0.12031551578549189, + 0.14985307336691014, + 0.2608320952051009, + 0.2817714926785862, + 0.19523049199055098, + 0.20071973488766764, + 0.23229730329701415, + 0.11431285717813283, + 0.28086533196981045, + 0.19801146707616402, + 0.13218250324848713, + 0.2047646593875008, + 0.2613500584324332, + 0.19009228170859627, + 0.030785125553876812, + 0.2367469224453345, + 0.2075290619652275, + 0.2058206785124014, + 0.265404915900253, + 0.136219008055952, + 0.25135165945577137, + 0.20184430981724058, + 0.1903821304420371, + 0.2183098861326631, + 0.2501308314563087, + 0.13158725899606669, + 0.26566188920889466, + 0.15242257397372524, + 0.2094928697625468, + 0.2041235876418902, + 0.25719686108326667, + 0.1202584609923521, + 0.19587502604737164, + 0.11768192844128479, + 0.06498667825898807, + 0.13613077947438673, + 0.1815525375059637, + 0.10883450877806723, + 0.23235670092938118, + 0.15835329529220324, + 0.28196857864231745, + 0.24011220762059285, + 0.2534602722214404, + 0.16898710341807674, + 0.14848090055191304, + 0.17560680614517513, + 0.15321964393236293, + 0.20129615967641476, + 0.1772207150811561, + 0.15836910816379246, + 0.12928466444135187, + 0.2021539522645047, + 0.2676224379993714, + 0.289426623599089, + 0.2573841106174896, + 0.04909944270718949, + 0.25892226925796064, + 0.14812298530841056, + 0.17505852822560136, + 0.21648667445548098, + 0.17675777172127724, + 0.11295528973743453, + 0.2406632329487745, + 0.18964886901295555, + 0.25302774414106116, + 0.20411398960295887, + 0.18105258926632883, + 0.1530628142697841, + 0.2093451754883044, + 0.12662782995822527, + 0.24612113578055358, + 0.15560737112712755, + 0.22967194070375938, + 0.2461806393384184, + 0.030745299414614787, + 0.2225816545938214, + 0.12336749863573855, + 0.11132957752178628, + 0.21858030826237812, + 0.09455944623032203, + 0.18129099244062474, + 0.1847385350113696, + 0.19241803057025678, + 0.25140958369004623, + 0.23653748610494008, + 0.22365573905392871, + 0.14920112388023163, + 0.26057979896054806, + 0.13015400666560084, + 0.04623316786908865, + 0.04058319436136979, + 0.16285370353277026, + 0.2106461453763092, + 0.07990965618424609, + 0.03058196650013465, + 0.19583570332434166, + 0.13337348933980261, + 0.1766237532793417, + 0.04765625726693236, + 0.21096183159908105, + 0.17387096169688568, + 0.22255341282002736, + 0.24328778757928177, + 0.2622352679432388, + 0.24836113875923213, + 0.19919124857171863, + 0.11445988973510697, + 0.17844958875139, + 0.2434861401228003, + 0.260349292002124, + 0.17419010366920448, + 0.10360655592853638, + 0.08312486284006712, + 0.12573898217433144, + 0.21508216221362528, + 0.23268318396917148, + 0.11586835974136762, + 0.11440335668402525, + 0.2534584249114448, + 0.28622345218334805, + 0.214392194578067, + 0.25677813460905413, + 0.17426097444292624, + 0.10855624674131427, + 0.26813627220744435, + 0.2199297613648956, + 0.20165369195127403, + 0.23776693646892538, + 0.28053470726208996, + 0.2804456832363384, + 0.08573983438103142, + 0.17481141694669217, + 0.14582320752858888, + 0.19940077725013558, + 0.12291270842639361, + 0.2612430657411288, + 0.0985157741456799, + 0.07076176221946888, + 0.19145309681173886, + 0.25171742949443876, + 0.28207842375294484, + 0.27882808970988915, + 0.07047460562906496, + 0.24887134674953204, + 0.20764759595759805, + 0.1338735707427028, + 0.047173202126125975, + 0.2578985922046003, + 0.23917943088780888, + 0.246311485152825, + 0.21257684306035582, + 0.20259290844967262, + 0.26410275379301756, + 0.2187059936923489, + 0.21756125574525093, + 0.23549401203229203, + 0.2226346299625143, + 0.033643774535904815, + 0.2211617379313504, + 0.15984065320018823, + 0.2811160098458375, + 0.1707357455811625, + 0.27554243741756373, + 0.18751778378191208, + 0.2585838492679017, + 0.15973365994441022, + 0.1326913271078117, + 0.13930090965267997, + 0.14704680094527967, + 0.12267028615066851, + 0.23917324352657474, + 0.23072993805943218, + 0.2527203926312571, + 0.06891615072197746, + 0.15161710500801973, + 0.21768968374733036, + 0.09303835614258427, + 0.28794790187977704, + 0.18829362185388637, + 0.18684277217233866, + 0.11061501124524195, + 0.2600254077341044, + 0.23682281589446458, + 0.07057967021485426, + 0.25907951561241266, + 0.16189976124072095, + 0.19786135648103026, + 0.06592123209999878, + 0.17205112947143053, + 0.12249218875274016, + 0.2065640922059286, + 0.13945085162937307, + 0.012270626827779406, + 0.08781425896022542, + 0.1945670720608544, + 0.16860589239327334, + 0.08145156421510999, + 0.19161140993195358, + 0.07792078435971311, + 0.23614177562250785, + 0.22197008863579015, + 0.26653887601399895, + 0.2661336106129942, + 0.13073414102970524, + 0.24898379914339833, + 0.07612171032231405, + 0.1272538752808306, + 0.2164918439713343, + 0.26977378035973404, + 0.25318365491562045, + 0.19689787776830073, + 0.1983423862031187, + 0.04813499905398605, + 0.14775341870823974, + 0.25198519319057283, + 0.24479391806286704, + 0.17934442137364215, + 0.17789835530682477, + 0.2302126044794862, + 0.13794605716237082, + 0.14098099005240625, + 0.24866218042933438, + 0.20755485769751209, + 0.10104267764174944, + 0.22043332593378398, + 0.08695644511014695, + 0.1453242714452553, + 0.24415409861158413, + 0.06222380839529767, + 0.2758616490793457, + 0.16952539000805233, + 0.09729423319395736, + 0.20977150196232522, + 0.1426670250613599, + 0.19410589621039562, + 0.1611994381725433, + 0.04237213926673334, + 0.22808364421367192, + 0.1957495848197651, + 0.27318669049121164, + 0.15387292937843278, + 0.24119269703349486, + 0.1597726680025723, + 0.13967027276535732, + 0.20062598557520153, + 0.23118837064434986, + 0.10612820087868466, + 0.2576366444843, + 0.14039554317620861, + 0.23344166911251432, + 0.16613748055505864, + 0.09207498904573348, + 0.24479534878627446, + 0.09217864710247838, + 0.13831419389743363, + 0.2276565888116025, + 0.18654414744576112, + 0.09698824124593812, + 0.20651942016364436, + 0.28627685061670716, + 0.18253118223162898, + 0.1430630027263925, + 0.2264006773744767, + 0.26540897305457817, + 0.2179404167504423, + 0.2287498997604672, + 0.15416237862048593, + 0.06737241178223709, + 0.08411247905167434, + 0.15705322293607193, + 0.2826979834594651, + 0.10745023675110464, + 0.1308967988200497, + 0.17599689296741206, + 0.1941303949631091, + 0.26839478283359386, + 0.08786182426142308, + 0.18237750415671192, + 0.2210841924551775, + 0.09235126238827696, + 0.25866415735014436, + 0.28854592928592804, + 0.2423888716059655, + 0.27626322311817064, + 0.139256035275102, + 0.06749752212905767, + 0.2114329617046887, + 0.17842013186278077, + 0.15020593624416337, + 0.12809460036186193, + 0.2096434304603408, + 0.22785351577628873, + 0.2697742456765819, + 0.1940933992435547, + 0.25537331554393045, + 0.2442753877189558, + 0.2093938853570889, + 0.2395800839379614, + 0.17943091846885817, + 0.16589919413216417, + 0.2762152736935443, + 0.16333055852482467, + 0.1654754834667832, + 0.12291899203333542, + 0.25035177405547776, + 0.07679795273244724, + 0.26657340042186495, + 0.24725306543349693, + 0.2021967440780308, + 0.23480991343211804, + 0.11528415722051279, + 0.23519688734140481, + 0.0375656900082059, + 0.252479763964231, + 0.21705024226148362, + 0.15168608947219195, + 0.27861778808250554, + 0.1920949835910784, + 0.14797893829824266, + 0.1277777961882036, + 0.21508261858011396, + 0.1808135029554435, + 0.2807347127029819, + 0.0621280004450454, + 0.2798583357974967, + 0.08381054342440435, + 0.28475205563828027, + 0.20746192988923864, + 0.2620860710341987, + 0.20087661057107248, + 0.2770847163101976, + 0.1750677186362352, + 0.2246786635927177, + 0.27279885675003274, + 0.14040157271405326, + 0.21567458173554563, + 0.23896784467234672, + 0.1546435032417671, + 0.25742534632702047, + 0.1316210151017962, + 0.16351489296022895, + 0.10701019632465722, + 0.15316402786464767, + 0.18268921672714408, + 0.10441962035625062, + 0.20531331603649453, + 0.14588940670161216, + 0.247213823883763, + 0.25229310142121825, + 0.09600737467391032, + 0.12158727269564742, + 0.19182073576740563, + 0.12529045663833432, + 0.03024920551395619, + 0.10283276490637698, + 0.208925525850516, + 0.16069289253296334, + 0.11508284650453525, + 0.2688506253310587, + 0.1257860396652202, + 0.26012947470503994, + 0.1193088322527172, + 0.11821392168757376, + 0.2524648481570442, + 0.19199515212733193, + 0.15662379133423487, + 0.2521210806463315, + 0.19691173743660018, + 0.13775604889986387, + 0.1708908403780286, + 0.2069122868762995, + 0.1836368082833266, + 0.23257775693719593, + 0.2819272885875473, + 0.1227453723231736, + 0.09408503728016182, + 0.2837898992728114, + 0.1132760446215896, + 0.2036273208195514, + 0.1245927851032294, + 0.170645802613902, + 0.14385332380529384, + 0.19190748055985102, + 0.19275070003318753, + 0.2072323743589119, + 0.15603788030182988, + 0.24310512791148584, + 0.2153937962202863, + 0.21729430719194828, + 0.1416604758526873, + 0.1730997539675717, + 0.24331709946745883, + 0.17385556342329786, + 0.15269928072171188, + 0.22203837833850862, + 0.19891347551157507, + 0.2086556879025255, + 0.09088967052251984, + 0.16040686799525758, + 0.1090653385267299, + 0.141256637231975, + 0.21197275620608966, + 0.18984696615884944, + 0.25786065642420475, + 0.23168427531085148, + 0.12883298105039426, + 0.2744791270479169, + 0.2578024097930092, + 0.19614549903553444, + 0.2858542663678962, + 0.2656492558015909, + 0.0776264476064738, + 0.105624353149062, + 0.26893623340232553, + 0.16588964361653888, + 0.1355980546153005, + 0.2480290972862495, + 0.19165979622073728, + 0.2241955780319615, + 0.033850014998731845, + 0.165068648161465, + 0.15767304971381754, + 0.19182723910183805, + 0.18984869556989517, + 0.17276720527245013, + 0.21194632107558634, + 0.0872176448924518, + 0.27599902582261493, + 0.15443851306869402, + 0.20367502610950228, + 0.14184360996873147, + 0.18850483281375274, + 0.21549831881628434, + 0.1982751759791204, + 0.23232044186948902, + 0.12265809164401838, + 0.15041909581180612, + 0.1807972710235749, + 0.2334383933483611, + 0.25731469238743543, + 0.25311745597610197, + 0.09916246052046698, + 0.2594052774986187, + 0.17667451988956678, + 0.1084320443858997, + 0.06539499582408863, + 0.13138385605850864, + 0.20837509250586078, + 0.15053920991176153, + 0.175015544354918, + 0.08050361034902569, + 0.25558943368066805, + 0.16334508911904017, + 0.269678067517947, + 0.2263244448827851, + 0.26071508473684113, + 0.23006843128348778, + 0.17243811438777107, + 0.20592681592622827, + 0.2141043630530816, + 0.1706348693244519, + 0.15301364765313946, + 0.14177944536283144, + 0.1543882768249335, + 0.17460776923291835, + 0.18987833913501934, + 0.10099899079605659, + 0.1551923181408733, + 0.029101450053915262, + 0.21639730267427204, + 0.09694379020784091, + 0.19151785063209964, + 0.2701816405780056, + 0.15636569604664996, + 0.03660474726921501, + 0.27827564555036144, + 0.10264769226753977, + 0.1523111243969546, + 0.14860929483215649, + 0.15587475950427107, + 0.05234819899797457, + 0.25690476109960503, + 0.08371109772804991, + 0.2608313750829812, + 0.2574940542962401, + 0.06172693074290413, + 0.08364499294034385, + 0.1110479901878924, + 0.26242371302763173, + 0.158626100551709, + 0.26313242284536276, + 0.1852197363395226, + 0.1982734390153032, + 0.2886475947512067, + 0.21059942549469587, + 0.08018535906671541, + 0.14792028319585968, + 0.25979854034463495, + 0.08710955928727382, + 0.24748841927081633, + 0.07330065812065258, + 0.24196486647947976, + 0.20778155882138596, + 0.21311215296876637, + 0.2403884102026312, + 0.1330302003521689, + 0.09187408359346724, + 0.24733771903439047, + 0.19724370025008559, + 0.28597144334944347, + 0.25063561543096174, + 0.21953864352891145, + 0.1635090883489984, + 0.1833969262161917, + 0.27666602840480375, + 0.2771728746758523, + 0.051466784493377424, + 0.05677811148944689, + 0.11399034867676054, + 0.0953530908622952, + 0.25654391928386616, + 0.20291694206196653, + 0.11554499204227446, + 0.18063927187865877, + 0.2537500888791862, + 0.19676483256715904, + 0.2466273730411907, + 0.1417005528607608, + 0.2000419758290969, + 0.2738316693395545, + 0.09709782910922778, + 0.17931024884725094, + 0.179709943207864, + 0.22427744234958427, + 0.188505033699171, + 0.2111123577456583, + 0.18883949519493434, + 0.22316963405769677, + 0.1954090260129116, + 0.23395215869635877, + 0.28498917945669994, + 0.21728512598224453, + 0.11183559115425482, + 0.2585430856850834, + 0.19951195317140077, + 0.2525730170237296, + 0.11338618203406148, + 0.22811432104407817, + 0.2891941751830169, + 0.03471749113098697, + 0.1464924677754743, + 0.09971543319014378, + 0.17317207357330222, + 0.17351489552150953, + 0.2349055801078571, + 0.11635705440883842, + 0.22778245859950835, + 0.043639433185540796, + 0.23832817634010142, + 0.14793800591120415, + 0.2731981938593026, + 0.09695757533737179, + 0.12556831357302795, + 0.18201097456385024, + 0.011632088391526664, + 0.20047414151719808, + 0.14864974261664243, + 0.18735749656158243, + 0.09701827765647197, + 0.28010826018993384, + 0.07561978875596259, + 0.20769961512694385, + 0.16436639215263288, + 0.11095847075349814, + 0.1779160140658837, + 0.2358549803910504, + 0.13488923393716606, + 0.27946283257898447, + 0.13769143691001468, + 0.1942134315220407, + 0.10631018314930203, + 0.2754834383808306, + 0.24988381089979173, + 0.23480074785494207, + 0.2452160280247035, + 0.22510844035863403, + 0.09092752817093103, + 0.268165037708702, + 0.03906318767409115, + 0.18170790983838117, + 0.25132336991733545, + 0.23282561122789866, + 0.19458879773575943, + 0.2695542641320645, + 0.1696750277504574, + 0.19192850287311866, + 0.1510535500845508, + 0.11725025901939735, + 0.12838645260063375, + 0.11169360500013296, + 0.11869405441423508, + 0.16191609911539886, + 0.04376955943918977, + 0.1999868198470099, + 0.21237456719968056, + 0.22267988970786554, + 0.2303051824679936, + 0.2542879530987271, + 0.141998273955245, + 0.062239716968171946, + 0.197766543979011, + 0.1346296299473567, + 0.16577872238880306, + 0.26414734640632864, + 0.2629768907125166, + 0.19641418546334471, + 0.2599056258571008, + 0.12849039771762166, + 0.0582865161606589, + 0.07602599389379368, + 0.1676512730824043, + 0.12605281499461332, + 0.13701493261573736, + 0.1732988436362183, + 0.21138716241759822, + 0.06823739929183552, + 0.06703652712074798, + 0.2657630997589362, + 0.1254674782398654, + 0.16148367674718425, + 0.10918611618445022, + 0.20219690137029625, + 0.2400065752464977, + 0.17925497510344984, + 0.07830953289534001, + 0.14143147766768588, + 0.2392477885489649, + 0.20433136719466635, + 0.20563365484461732, + 0.2824973233045272, + 0.2723855285257391, + 0.22930634278456738, + 0.15897917021203808, + 0.2861893069457066, + 0.2636737455794576, + 0.24450929482630726, + 0.10271747954200527, + 0.15988648730671748, + 0.22921520310531993, + 0.24090173274098936, + 0.24705401723135936, + 0.16762952522599775, + 0.14102665215435098, + 0.15559078887060482, + 0.0939737763886684, + 0.10399114575475242, + 0.15769978336689758, + 0.2607187802856008, + 0.18692480322052482, + 0.24892296464604205, + 0.17093055758122566, + 0.27946700620323667, + 0.25408062649944274, + 0.2636210344661899, + 0.12037986917089719, + 0.13354509902910822, + 0.1568801835650685, + 0.11830576964262525, + 0.2630888699703665, + 0.26564951613682114, + 0.25214160919449374, + 0.1929350671600347, + 0.2182599340556476, + 0.16370475101029186, + 0.1992863371991725, + 0.17159956275204444, + 0.2445117748464269, + 0.2431048722374709, + 0.212519270346447, + 0.21427158039336575, + 0.26934980063867164, + 0.21638870571732252, + 0.15910609563142164, + 0.1401523494055488, + 0.26736606895084974, + 0.12887054112047638, + 0.28950850437743825, + 0.2782204488678203, + 0.2272735707894255, + 0.19158155843746258, + 0.2410927040582266, + 0.27345478894068465, + 0.12283709921837145, + 0.1993258999116287, + 0.08076771036699043, + 0.11708245842276428, + 0.07770203057205514, + 0.13993127705683833, + 0.2826176672407659, + 0.2383664450873173, + 0.2768796028748017, + 0.06094254150419864, + 0.2846379145777949, + 0.14958515060585523, + 0.10694761864884914, + 0.1416970618601137, + 0.059818402720707, + 0.21865587715113163, + 0.12104579782803734, + 0.20517143485057088, + 0.2461553478711322, + 0.2061793203821505, + 0.25234140685901246, + 0.2600298214770484, + 0.24763916744740688, + 0.2075247479703903, + 0.0929239333721719, + 0.28642325712961025, + 0.16529615400988903, + 0.25089351026434836, + 0.24593596100575113, + 0.10301431869919027, + 0.15191822893392726, + 0.14864104746886467, + 0.15707969782613745, + 0.09475543496299942, + 0.18801686550028315, + 0.15073276074463307, + 0.18632724050436145, + 0.1205634687277288, + 0.2526858699840442, + 0.19882703351804967, + 0.2354966357202248, + 0.23597095599672863, + 0.2403124977172766, + 0.18463848881086772, + 0.02217855115392386, + 0.11343263487818461, + 0.2059083441293325, + 0.24941617675755803, + 0.08724454740261992, + 0.18291213838762427, + 0.2182543128384094, + 0.2566627042200325, + 0.05373810596229329, + 0.20689530145291393, + 0.09014471862805955, + 0.14883536778585388, + 0.24525176294677056, + 0.15619888989664293, + 0.11804668887978326, + 0.26189718103106, + 0.04054158534574264, + 0.1923375122595892, + 0.2265099376520235, + 0.13969297778207257, + 0.2185401205333522, + 0.23428056471356898, + 0.22246127302478783, + 0.18887818258052141, + 0.23973524863750859, + 0.1388523044637558, + 0.268708578326544, + 0.17434616819490276, + 0.2725523538449824, + 0.2753247189904028, + 0.20329910823215208, + 0.28937814864522987, + 0.10850781254519838, + 0.2208581054413282, + 0.19282850464834173, + 0.17575684479807818, + 0.1990420326305716, + 0.28163997983778305, + 0.13486012779213774, + 0.14458359161351597, + 0.23466641614018843, + 0.06290883820611347, + 0.27596698405666803, + 0.13893938872873085, + 0.1610110587627423, + 0.09733157075381993, + 0.2025585654249374, + 0.1185017210551913, + 0.23092998500720938, + 0.21175082959802127, + 0.17559459429471302, + 0.11053665008593389, + 0.08561950952246578, + 0.22569476347038422, + 0.19600195169627177, + 0.04635732682685011, + 0.06911759229418932, + 0.24065561606833527, + 0.28458209489532493, + 0.23159187138751952, + 0.24310620180423426, + 0.04456369978698915, + 0.14508502608885837, + 0.12577828308627045, + 0.2716781564882761, + 0.1262058593365751, + 0.25994121162962575, + 0.19670969285938883, + 0.20199631872939403, + 0.24943933556737935, + 0.14856664437785352, + 0.19135650712513408, + 0.1396906056211332, + 0.1324394267170767, + 0.1806107263660591, + 0.2746554213904888, + 0.15228780075011206, + 0.06030760487905215, + 0.15199477722969057, + 0.24900805178864033, + 0.19065841984070625, + 0.147666977906874, + 0.18005425421210022, + 0.06752236765333357, + 0.1413545531221729, + 0.08261891141846689, + 0.19424160275762914, + 0.17846265771776026, + 0.27345494853173524, + 0.17908028428711426, + 0.12193220211153928, + 0.11182495057238527, + 0.27168983280172304, + 0.19044238954011503, + 0.09092173133790131, + 0.020424119258540815, + 0.1691984642156462, + 0.23918673782153355, + 0.23388127333539135, + 0.24448162901795456, + 0.19692911407428756, + 0.1387014228077532, + 0.12060099040055873, + 0.13159960135581786, + 0.2877151269919149, + 0.29087775923362114, + 0.2680410109353732, + 0.27256462484521066, + 0.12236819028704102, + 0.24124216380539312, + 0.169236142647081, + 0.11542757925868867, + 0.12416655538832443, + 0.19235169792609197, + 0.2153688860178787, + 0.04487536325730397, + 0.21715724733789066, + 0.17109341341565334, + 0.20269909308394646, + 0.2180826808762483, + 0.09067603335338557, + 0.26465182272837345, + 0.0058671612233197196, + 0.04172074996116439, + 0.08888839755698216, + 0.24327935636558465, + 0.05026885078866334, + 0.22000938748298748, + 0.1090954493055032, + 0.26712438807431865, + 0.2007246119600219, + 0.2570605466458923, + 0.24047989971289102, + 0.2421100232247362, + 0.2902778096154945, + 0.15776318350478274, + 0.21330276851382185, + 0.11704897630642898, + 0.2385135702920149, + 0.08647746057758379, + 0.26255064857153304, + 0.23581847667929598, + 0.23758521086385254, + 0.180712172870437, + 0.18807284450997866, + 0.18545495242836202, + 0.16203992711677898, + 0.11410753841599613, + 0.1608526787827645, + 0.11839101286412264, + 0.163331314188879, + 0.05657197086540291, + 0.06953916639673564, + 0.19062598265773523, + 0.23421605428470738, + 0.25739885998135886, + 0.07772703293848618, + 0.13651313649468938, + 0.1837737988824325, + 0.27094643016899056, + 0.25295750428168867, + 0.22672033891405535, + 0.17948677408432942, + 0.203355982562457, + 0.11409033120298932, + 0.08411268621729814, + 0.024319864958075522, + 0.20654673847387006, + 0.27814372164513673, + 0.12789439002316763, + 0.24140813649519083, + 0.2666002698008852, + 0.06012823237667371, + 0.16349666157492473, + 0.15778208491858342, + 0.20239553704429242, + 0.24927603763518177, + 0.10780610208151081, + 0.22887475987509606, + 0.18006174804355352, + 0.1186274897999771, + 0.1360887053585363, + 0.06278824447804462, + 0.1743039498914448, + 0.2813629877065194, + 0.04619981473823426, + 0.2488105964206593, + 0.24564958966371808, + 0.15815657339480138, + 0.22769251144831898, + 0.056250379769217776, + 0.13532363697838845, + 0.27753784103101026, + 0.04525125484813817, + 0.1785064083962465, + 0.1788742327193124, + 0.1146401934960285, + 0.21567588871090096, + 0.09287534256698171, + 0.20759846677509436, + 0.22442755774738626, + 0.03963665205565956, + 0.21285850857141606, + 0.20347486671680323, + 0.14974974448732026, + 0.13266319045191777, + 0.0891996171158043, + 0.0983404142118975, + 0.17339952830347574, + 0.2697260605360561, + 0.1837946716895355, + 0.24964133200491279, + 0.14740836477776026, + 0.16809720194960698, + 0.2631212058416629, + 0.17328821910704034, + 0.25854681170971233, + 0.13707166930976591, + 0.11301128479514316, + 0.1430803758701711, + 0.09824672010822348, + 0.27225261221397945, + 0.20046252529261332, + 0.23717265574475682, + 0.16360328365980292, + 0.16089807321971106, + 0.2553875050589144, + 0.15965678420587126, + 0.1619361678152101, + 0.24737218135392114, + 0.16437869137348413, + 0.17862011042476575, + 0.206023237967503, + 0.055682681909969146, + 0.20004087142815338, + 0.0427061558274348, + 0.09751486204630405, + 0.1609138138159152, + 0.21608594870081815, + 0.1288654979199855, + 0.16653698339074643, + 0.048816543607479466, + 0.2077544814151611, + 0.14240763664596928, + 0.01634545532188688, + 0.281473924488448, + 0.04735350245343979, + 0.26476474042392933, + 0.17374111799895692, + 0.2146946993993338, + 0.15319725561351852, + 0.2739126128541199, + 0.12978372417537062, + 0.14504491361765168, + 0.24229739032331485, + 0.16846223701687235, + 0.2688733659914104, + 0.259540267766537, + 0.2427200135340016, + 0.18019613052947334, + 0.21329140672251054, + 0.07165157259045002, + 0.06433593817665653, + 0.2338459854275045, + 0.1711227663067419, + 0.2736104403020991, + 0.22732140323480923, + 0.16384398582946744, + 0.07664543469576982, + 0.23410099432863207, + 0.1124884355110475, + 0.23996943845739446, + 0.17215641551529998, + 0.11737407517866397, + 0.17204167423416195, + 0.21005847198753047, + 0.2163795661242579, + 0.07059723348018208, + 0.20423108978641835, + 0.09696615748752817, + 0.0929310445246747, + 0.1804945644313111, + 0.2608108396975335, + 0.09491961920615463, + 0.24930518828451717, + 0.16996071077657127, + 0.21629769184891423, + 0.19625024345517553, + 0.08277336455632059, + 0.2105948473334796, + 0.20176809935990805, + 0.10825361641185018, + 0.05642857656513266, + 0.11607228394812873, + 0.16596031773660877, + 0.016374620795713887, + 0.15260878862608662, + 0.14956268000447767, + 0.21271286379768248, + 0.04017005949267143, + 0.08782578451837132, + 0.16895031258206897, + 0.23594459551336508, + 0.17664202811878732, + 0.2284521526181536, + 0.13327860924856977, + 0.2115167546693984, + 0.20933832935276803, + 0.16065258821130723, + 0.24162559192552546, + 0.07160667842873496, + 0.24038718769456507, + 0.131051593034899, + 0.07831992434304112, + 0.1818311136073989, + 0.16521628453352963, + 0.1413213955419574, + 0.20107238738606834, + 0.08576570792429655, + 0.1931330189075556, + 0.1559258867269575, + 0.25361644485497037, + 0.20013677290406412, + 0.26380403980544287, + 0.13857710448796795, + 0.09485805871331195, + 0.1871098746037949, + 0.19664779323551743, + 0.1589115536419999, + 0.10036195644920455, + 0.13032934782778685, + 0.1513200254738299, + 0.07513333624178471, + 0.048386413457373566, + 0.15067859310368034, + 0.273852089666201, + 0.24627815065328612, + 0.19758118545084355, + 0.21054531408265004, + 0.10105115273561072, + 0.18407461815078333, + 0.26467587570888484, + 0.13340365739042853, + 0.173364113646045, + 0.25213108589601113, + 0.14549483822296094, + 0.03621206617531403, + 0.17327384703389825, + 0.24267657639947915, + 0.1686224030219138, + 0.14252039558254598, + 0.12626797376723978, + 0.19360052886796064, + 0.2116900649991725, + 0.14479638042250076, + 0.10614621663629216, + 0.23558442342470617, + 0.24208938989131215, + 0.2267295596443124, + 0.06284381399284492, + 0.1808473239623343, + 0.16575475389523103, + 0.20984507424301882, + 0.1493629074013103, + 0.2458862406830813, + 0.1873773189749172, + 0.21847189503601766, + 0.08847414333262095, + 0.19758863478607824, + 0.14933476821859432, + 0.25543532412310627, + 0.07367123145934845, + 0.09047277072117908, + 0.07289332317747109, + 0.09297303531277318, + 0.19247225208345306, + 0.14093131884272944, + 0.08744114967852494, + 0.15668281784562296, + 0.1250486557413418, + 0.2687243299054113, + 0.1869178496667146, + 0.25008284556586136, + 0.27646971982589863, + 0.10569333943779034, + 0.09711558078998862, + 0.21969931694451109, + 0.12400100196697958, + 0.24133833034343938, + 0.20427470885241908, + 0.1708166302294297, + 0.14439508909133386, + 0.22088193279240564, + 0.1375238454235334, + 0.18437586474909654, + 0.07345238199542205, + 0.13359769747248124, + 0.1525962872972788, + 0.24838085288142547, + 0.16858969841609436, + 0.26749521236234053, + 0.19873910456351726, + 0.21801575771837808, + 0.24485376882789342, + 0.050625376436473316, + 0.11688621861914, + 0.171515716396771, + 0.22423250810961706, + 0.22750318845329612, + 0.16642466263288785, + 0.019242093220166484, + 0.2398827529168181, + 0.24281194079657403, + 0.12980718498224272, + 0.26732116819633617, + 0.15259938043028531, + 0.11440146997515012, + 0.10146042705359637, + 0.2328197454810622, + 0.22813134385306136, + 0.24342108004796742, + 0.23666421539612972, + 0.1794383089670677, + 0.03782389655089879, + 0.026458350761404615, + 0.18067888982000807, + 0.14853392000248603, + 0.1910788914331031, + 0.12342617893268844, + 0.27986830300395255, + 0.14141563671549304, + 0.18518208395107075, + 0.17393651886315933, + 0.19174916865429972, + 0.056882327755607164, + 0.19008509433842852, + 0.11610020171539902, + 0.22152672048728347, + 0.09240815746628245, + 0.13250386271965545, + 0.22953660735493558, + 0.21575694080987762, + 0.15654803621876523, + 0.2604092300360847, + 0.2904860416663066, + 0.25607172236525677, + 0.16801936069498097, + 0.1619865343153777, + 0.25436664727526603, + 0.2851935878379861, + 0.2372677382665155, + 0.13894848071998847, + 0.23213958946176697, + 0.25091017503794366, + 0.13874575492799904, + 0.0746029871984201, + 0.23677834955906793, + 0.05221780900735466, + 0.10747382666290482, + 0.23109791170459149, + 0.16688852263297757, + 0.06310722306290198, + 0.2592931411872891, + 0.12310580759404384, + 0.25850110564513357, + 0.21957138091912548, + 0.25693100111468486, + 0.25938510180568947, + 0.01897484645738172, + 0.23192138739427628, + 0.24643964138962554, + 0.14485319878077696, + 0.1912561118018028, + 0.2555707904958018, + 0.23934373063283873, + 0.2517765252242687, + 0.21513576787079836, + 0.05545778527672275, + 0.08235173325527824, + 0.08779529797681922, + 0.25882717601571986, + 0.04023408059417382, + 0.1723687839695026, + 0.20153592395555364, + 0.0693393256280751, + 0.2589125127915354, + 0.20258643876400131, + 0.24514994037546475, + 0.19346632072835393, + 0.2703365923910326, + 0.12334393801238466, + 0.18991200569634203, + 0.10598644825184884, + 0.12214812781531939, + 0.2278710238209529, + 0.12476711452568605, + 0.1251233268928531, + 0.24679741988566034, + 0.2356811419821229, + 0.1927123492840143, + 0.1613401542122227, + 0.21261428479537992, + 0.09818719237499463, + 0.1720752795453218, + 0.03283370805961862, + 0.13192497721176294, + 0.28075852428990217, + 0.0988123898283362, + 0.0762021384804548, + 0.21012016578710369, + 0.2316347280161581, + 0.2692155653483172, + 0.19614707230436043, + 0.22689593391204474, + 0.052675283889384666, + 0.27401699368580634, + 0.10732064021495691, + 0.14217800311194895, + 0.15700347834949993, + 0.18192406485720997, + 0.12443537167808055, + 0.19735129732859183, + 0.20119299531085771, + 0.03768298637363166, + 0.1718747467398713, + 0.2658778393027599, + 0.2119889291950858, + 0.15931792882301374, + 0.09180481025180605, + 0.09953422196544205, + 0.2548653791438873, + 0.1309897646848051, + 0.12704731042137235, + 0.18315001533696657, + 0.02538730450039948, + 0.2758764298723586, + 0.04102001035112055, + 0.13091704250479713, + 0.15772073346922022, + 0.17265160669971635, + 0.27312524267267313, + 0.23842811286338655, + 0.26375338159286127, + 0.14767505532421893, + 0.04620499231406952, + 0.057443309043700465, + 0.20365088580955676, + 0.20102213879674558, + 0.1372305368631217, + 0.18839432990631477, + 0.12408637437952331, + 0.2831072138182253, + 0.22945275591935355, + 0.22677847269291257, + 0.16350494785036648, + 0.2721569320133675, + 0.22095314158565105, + 0.11566457259901558, + 0.21659669190235586, + 0.13539648438688015, + 0.2765201599342607, + 0.13894260267005143, + 0.2149434348280845, + 0.07911288608776999, + 0.25256826203099103, + 0.203530181044417, + 0.2686740710565942, + 0.20594818181623736, + 0.23694314607650616, + 0.17624142477584925, + 0.2862256671915395, + 0.12532403909657383, + 0.15063126930194473, + 0.12360306958390707, + 0.12791583933504833, + 0.20077420509529648, + 0.24231437981658338, + 0.2689888409237564, + 0.21382106345379442, + 0.2662945065654123, + 0.2320928532862972, + 0.23035311019662194, + 0.14693644881775073, + 0.24237100053987853, + 0.22350151921264053, + 0.07561150412889601, + 0.22811930283988763, + 0.274552744457703, + 0.23102062726782407, + 0.09319736380030585, + 0.13440848051069934, + 0.14911930917762578, + 0.23382550153871698, + 0.14503648084539897, + 0.16301099824510307, + 0.07515921818224519, + 0.12254761791766498, + 0.20641691222729516, + 0.11108257320549453, + 0.22537525997503516, + 0.20334538736824467, + 0.24150776476805613, + 0.0490162364274884, + 0.08608907843948485, + 0.21422421719257043, + 0.19054638485274392, + 0.27267570830773696, + 0.08768154003664119, + 0.2381241919087955, + 0.08130026408628842, + 0.23366249288210422, + 0.1413365833612797, + 0.2605062257242758, + 0.23614067044732084, + 0.232560545014748, + 0.1338607685914663, + 0.28489053849476814, + 0.0723815682654695, + 0.230011511645343, + 0.2890644214805805, + 0.1121202355547099, + 0.1778563317900454, + 0.07549468406122045, + 0.1256618801948419, + 0.24986962680314617, + 0.06501637631972641, + 0.26624630288328066, + 0.1919171507805826, + 0.11862745845803835, + 0.10029395438811838, + 0.10532600441546104, + 0.14680593788614718, + 0.27516899990620053, + 0.2029924789713634, + 0.14994615940450248, + 0.15953145610501496, + 0.16629212299395482, + 0.20637931736107407, + 0.2616600696169328, + 0.2812714188068577, + 0.2699351189773426, + 0.09788061351042154, + 0.23204518726262585, + 0.2089812579696612, + 0.07690806301810138, + 0.22866104638862475, + 0.18020930327020251, + 0.2316739250710516, + 0.27992422484621565, + 0.08840609947259861, + 0.07988547718173994, + 0.20987085151248314, + 0.06509821489866886, + 0.1773712581634337, + 0.2188963349879703, + 0.25002712273502065, + 0.1394725078419654, + 0.16107196797676826, + 0.2233686347605881, + 0.1210162329380484, + 0.27624894318592025, + 0.2569049311323376, + 0.09542857184911546, + 0.09622061038157564, + 0.16314144377606973, + 0.2118663211301128, + 0.17398484124940125, + 0.13909571649014524, + 0.26493728207562506, + 0.01154812118598273, + 0.21658861822616024, + 0.21095140657999048, + 0.1937256185187361, + 0.035906173099581426, + 0.18761147576330633, + 0.12021739673050734, + 0.23716690655304495, + 0.21999318439745885, + 0.2598564844141253, + 0.2606259644455135, + 0.2021602637747857, + 0.2457513978085065, + 0.0995421566228758, + 0.20370613019432104, + 0.1883429542631558, + 0.25738831902943377, + 0.028601114473738014, + 0.2788181187474038, + 0.21405129736867937, + 0.0586802874279074, + 0.23187211504740982, + 0.2279342558741967, + 0.2225197422134491, + 0.2164403763354759, + 0.0970470257446943, + 0.2182830626934984, + 0.2265389579615588, + 0.15359406640600404, + 0.22044473683524773, + 0.18274360922781058, + 0.1105057521018886, + 0.20243850615449707, + 0.1563491732968464, + 0.18736330364579815, + 0.15320775153409366, + 0.20892619666786882, + 0.14663643964560788, + 0.2662397729697243, + 0.10325923005617806, + 0.1665148628244975, + 0.16331303149966672, + 0.16508392928399923, + 0.17963953656201076, + 0.09653438548057731, + 0.1348601674199905, + 0.07105286179958158, + 0.25769043146577536, + 0.16240377685713472, + 0.212585236623824, + 0.2569574730542831, + 0.24312767687028122, + 0.13627445839461838, + 0.24853276555173096, + 0.2507574244700928, + 0.2807926656924541, + 0.27558485413156025, + 0.12327773219270433, + 0.09793877326948826, + 0.1705601434657933, + 0.1969544813711935, + 0.16373985204497735, + 0.23369130154401554, + 0.19823136742213585, + 0.24175433982339123, + 0.20818937606624013, + 0.1256506211360334, + 0.234504632769493, + 0.1530113345408747, + 0.14581477173302607, + 0.09060412519613267, + 0.18538137121711823, + 0.127278249432305, + 0.17684641767747983, + 0.15131543415288368, + 0.17105806027332118, + 0.13934195597405863, + 0.2262788236344248, + 0.16427342554071375, + 0.2795768977319763, + 0.28101714036156156, + 0.24998530268336994, + 0.16851067692177954, + 0.029147703627498526, + 0.22099769358238103, + 0.18266050600164416, + 0.06986710096436824, + 0.12372291082212823, + 0.28716765422326945, + 0.22197964344908594, + 0.1451513355899905, + 0.23960789909358413, + 0.04853851178465086, + 0.18180986682328346, + 0.044626725143958684, + 0.23897361431535855, + 0.09925109271857076, + 0.10632067067763894, + 0.18883057257131086, + 0.09303054916876648, + 0.040182865884303746, + 0.1786230227252238, + 0.2562281630826205, + 0.07944639321801841, + 0.18508014694102198, + 0.06327644401237989, + 0.12851644789557276, + 0.23471103196374662, + 0.19615471824859854, + 0.22187095820652344, + 0.23777927493376083, + 0.14097952199651612, + 0.23580789736217192, + 0.19002778115909935, + 0.12199811515058442, + 0.2138585323782146, + 0.1593821180794489, + 0.06369329757151757, + 0.282960279464533, + 0.22310349714086367, + 0.22598427148635655, + 0.17458206951366906, + 0.01544948197120005, + 0.07345160007601702, + 0.24913480001457883, + 0.27895478443741195, + 0.28942160484732204, + 0.0235316014835756, + 0.24219339722585123, + 0.248004042140558, + 0.1330304998594727, + 0.05872227537603726, + 0.17155558477850194, + 0.1831030886377047, + 0.1278297339084782, + 0.281608973859768, + 0.08765743643632334, + 0.04018080614541682, + 0.16963875568736725, + 0.24404052540412702, + 0.11030400026291971, + 0.15649866134856594, + 0.0745169721675499, + 0.15982095775550328, + 0.2874145502548209, + 0.21674773798677346, + 0.23155069010671941, + 0.1639473208616979, + 0.12790347777902836, + 0.1484531078125883, + 0.23779576136535463, + 0.24403129662737488, + 0.25251714432486166, + 0.13331397503125791, + 0.2331879194768175, + 0.23107903276764982, + 0.19661276726448831, + 0.10283219893855827, + 0.2325118408834194, + 0.2370584400367794, + 0.02342886461318712, + 0.2878817440336684, + 0.22868874081064716, + 0.009573082086751629, + 0.1462510857256414, + 0.23965680513687843, + 0.16401150863096997, + 0.19344387798117385, + 0.060292401797728934, + 0.2548317438563696, + 0.2430690378459724, + 0.12543485214507877, + 0.2011109643688415, + 0.24441814712255047, + 0.1531260520567447, + 0.10518708436889378, + 0.14918347973436524, + 0.14629087651316183, + 0.27149955081317134, + 0.17483552300459645, + 0.19683586418344126, + 0.1778627700455352, + 0.24535133345876875, + 0.16353062114451591, + 0.19687849491913054, + 0.18603503552418607, + 0.2200890827111848, + 0.25398942983093986, + 0.2389006478835384, + 0.22784637408652814, + 0.1917328088497621, + 0.21254386578873705, + 0.2052727339291574, + 0.08236071525581101, + 0.20958487596833172, + 0.1964425823805395, + 0.10987170975179385, + 0.1718611419869608, + 0.25483519875265226, + 0.08253214809933325, + 0.2214304288239464, + 0.17518065254420506, + 0.16712104586040377, + 0.19744432676371995, + 0.19498895669761343, + 0.25796461873360277, + 0.23459910456109495, + 0.11321562735107565, + 0.13132655747420965, + 0.14724661208862538, + 0.13086658112254457, + 0.24916878399096157, + 0.25684121135582055, + 0.18928628895517452, + 0.17008731554334952, + 0.17076558455762145, + 0.14498744230175678, + 0.1274125202236822, + 0.06992363866938031, + 0.26918600832970235, + 0.22060613017904204, + 0.12956932423291237, + 0.1288747675778598, + 0.13443093776972923, + 0.2308359415781864, + 0.14171515528175893, + 0.2055669360805273, + 0.2503509981571358, + 0.23860281068725692, + 0.25179263263515106, + 0.20252788185879286, + 0.21682302996403358, + 0.12644913940046182, + 0.16515564871987995, + 0.24592949795557706, + 0.21024838383722025, + 0.14301653077807044, + 0.15539245828773357, + 0.13940294971170467, + 0.1108657486160763, + 0.23775796036775396, + 0.16409624445436316, + 0.22389954210388227, + 0.04195436306557465, + 0.12788808136507707, + 0.22346754704895583, + 0.2255734431006948, + 0.2051889569643317, + 0.1305354770793356, + 0.10165245478332985, + 0.21954873296406657, + 0.24654483070653072, + 0.07092373815093599, + 0.2510127823531089, + 0.10921547255099762, + 0.11862068336976613, + 0.09977431706395891, + 0.22620202189553051, + 0.13686171472557726, + 0.28478007831519764, + 0.2028268895391845, + 0.09795236111765943, + 0.23180979480743016, + 0.0617395890163214, + 0.21292984582631763, + 0.06473696588898999, + 0.13387114935792893, + 0.16331707279781071, + 0.18157299519513445, + 0.24528818406092462, + 0.20006234728645153, + 0.18992011292917846, + 0.18304276113848938, + 0.25480151793004335, + 0.07066067949172182, + 0.23524024642484154, + 0.2805099355739309, + 0.2751856071801444, + 0.2709587109331679, + 0.15786158290788357, + 0.09638626204042111, + 0.08942562175735917, + 0.1582706404993759, + 0.1043898230947901, + 0.20254766893488346, + 0.25462590735645413, + 0.19370711383184275, + 0.10253642309808675, + 0.1277301429288482, + 0.16085133121857748, + 0.18722305506427125, + 0.14520902619561846, + 0.15522481345689162, + 0.1311993204710856, + 0.20546317638183503, + 0.20851708014564826, + 0.10748753858756933, + 0.1381003687853452, + 0.175523627538617, + 0.1801314374548453, + 0.28580825002712046, + 0.27002705065468446, + 0.11658790495556375, + 0.26308116913180984, + 0.18518595820182518, + 0.18046610593466947, + 0.24806402044450665, + 0.12859504860160195, + 0.12299283477196224, + 0.16563961602599525, + 0.2538759178450788, + 0.13751289184322393, + 0.15181369203866782, + 0.10936624661053616, + 0.2030132874301688, + 0.13950860107387855, + 0.09265127498011078, + 0.26174290781356596, + 0.2349099973815564, + 0.24942261207242142, + 0.1418943454204948, + 0.06305847252277604, + 0.1152760789225843, + 0.1765312341722523, + 0.1729424943004417, + 0.15024576992696959, + 0.06346237649279099, + 0.21220211700597533, + 0.13726375657960355, + 0.18742452420354866, + 0.1041561321188323, + 0.2750719417940779, + 0.1266129671338532, + 0.24446722720849032, + 0.09269652159893495, + 0.2435879158674603, + 0.24691083245936354, + 0.10514369562560409, + 0.21502826472268927, + 0.26913543118997274, + 0.14759706038823964, + 0.18545457661328166, + 0.15548675746781715, + 0.21934452064716686, + 0.27149611045083843, + 0.27910863551649934, + 0.23123459059813847, + 0.19377295103606715, + 0.018385275834710793, + 0.28054706353727343, + 0.18005039472671705, + 0.2093219217285687, + 0.24268773141944097, + 0.15822727443559925, + 0.15112058261840666, + 0.03828191371671185, + 0.2577597075622527, + 0.18994308086705733, + 0.26933718307391247, + 0.24769266431568795, + 0.24200850664779228, + 0.18187882965643334, + 0.09410061172744419, + 0.10941847496976861, + 0.05985884626357189, + 0.2099488960048446, + 0.2618703051681542, + 0.21089066621668293, + 0.08410647308056186, + 0.17753492437611404, + 0.23264708145242732, + 0.14223007445465463, + 0.23918046593401196, + 0.2308053297091397, + 0.2791888961278851, + 0.13517097206386627, + 0.14425923809889635, + 0.10305927816414642, + 0.27777993628522357, + 0.19676213505832832, + 0.2732701748973665, + 0.08205400022567842, + 0.14599796110694785, + 0.2628875125786282, + 0.23414713478503937, + 0.16107700129796043, + 0.2498467395818682, + 0.17155598986052203, + 0.08841295925012352, + 0.08996823941611011, + 0.22322609669826843, + 0.25495665648267246, + 0.2782446561528808, + 0.18422308595823084, + 0.156730408071402, + 0.09439876408514396, + 0.1849908317938209, + 0.09999183091874238, + 0.28436217092984095, + 0.24688127358675727, + 0.2608144915652566, + 0.2321004202475302, + 0.14319324197511088, + 0.03124408168586998, + 0.20235027625995075, + 0.24072726011382464, + 0.060841976935954, + 0.024361210230679272, + 0.1783704290479809, + 0.13844159037607306, + 0.22896430303502593, + 0.16391808731627452, + 0.22050339227844504, + 0.2068012184311085, + 0.26997283741811295, + 0.12162321678697731, + 0.17909015268239736, + 0.08880143959862741, + 0.22549110318404425, + 0.2355672188499326, + 0.17464816739802777, + 0.17354646182724126, + 0.12106594476625503, + 0.2083241267694092, + 0.150346783186659, + 0.2155396232779018, + 0.2552788099488428, + 0.17800858426996005, + 0.15533034637280324, + 0.24323029731646376, + 0.22835617015059345, + 0.21757423994079633, + 0.24551262546654795, + 0.10872949493624463, + 0.27194238814496935, + 0.2439506638012433, + 0.18651154984218252, + 0.24031230326175193, + 0.21366660797934509, + 0.1440564969059288, + 0.07921823591572658, + 0.15545773362165793, + 0.200642430792782, + 0.19470706988493572, + 0.11757265428751072, + 0.1860631202145594, + 0.22230533595335855, + 0.06757172674082984, + 0.13555081930809876, + 0.20176753193074454, + 0.23106180883101896, + 0.21568132473065943, + 0.2575868370408447, + 0.2318500468462608, + 0.24841903400424323, + 0.01893344587517215, + 0.14090291908001276, + 0.16143481605991145, + 0.23306102128329895, + 0.1779509104055416, + 0.059713653552576705, + 0.2053582006516953, + 0.18553198711178184, + 0.10939369036878549, + 0.2112533876150553, + 0.09167145634840063, + 0.10363283545359091, + 0.23270854972075322, + 0.16026585310631997, + 0.19269392992971646, + 0.24282968002946437, + 0.2091444686360388, + 0.16178896405800344, + 0.18117074839180014, + 0.24978295398382966, + 0.25425561166045724, + 0.18452562415857435, + 0.15008427615091288, + 0.17230659086739356, + 0.15308347881154113, + 0.1376674815573975, + 0.24985043077102387, + 0.2647927702534455, + 0.23413904459725818, + 0.22459058639382862, + 0.22208920727557974, + 0.2302023310195361, + 0.19623916927166085, + 0.2135555724124201, + 0.23208973797566268, + 0.2813654208159488, + 0.12290424907592111, + 0.1138084776550276, + 0.2519812098720567, + 0.26878088559916236, + 0.22844821013613903, + 0.0422247261085978, + 0.19433313145399894, + 0.12100199534496235, + 0.1166580237182887, + 0.2553455811315587, + 0.030662930467084144, + 0.269970692672027, + 0.19254801426457113, + 0.21794178293657065, + 0.20008001723647312, + 0.18620038559583119, + 0.11277916663081636, + 0.05783991595493631, + 0.15631280996242533, + 0.16582576841513225, + 0.24062496162163619, + 0.17607391637094347, + 0.21381759283427726, + 0.09779966503830712, + 0.14549141534340362, + 0.2730190809392558, + 0.20768791050006594, + 0.2259328885526515, + 0.28221537919916095, + 0.1051128363293702, + 0.18706842969180754, + 0.15907232985442146, + 0.16049922272696276, + 0.21183311548930422, + 0.12994478876072516, + 0.22794898552585008, + 0.1728612728869246, + 0.15217593708244953, + 0.18518416409964358, + 0.22116629053918344, + 0.0773556669092797, + 0.27981086984199555, + 0.2634744120878306, + 0.06668652845141623, + 0.2330610441538682, + 0.2503260138420162, + 0.25070793542858966, + 0.11364743558123541, + 0.08708906907387795, + 0.07452318192966889, + 0.1351743075446977, + 0.21089425040051332, + 0.0448080390126848, + 0.03687238277479624, + 0.1962923167624862, + 0.2376157172401921, + 0.04261490582520124, + 0.07850004354251709, + 0.1808455610986939, + 0.2670212667194116, + 0.19941787312107392, + 0.15225058173878614, + 0.1843070441308571, + 0.2680957573217019, + 0.21512252926682252, + 0.13819373944080485, + 0.15852081883816851, + 0.2231078925288702, + 0.12759277413999154, + 0.22447816883803867, + 0.15421403547725498, + 0.1835182820864251, + 0.09774187610486956, + 0.0913241406261354, + 0.14559033032975202, + 0.17807552661338172, + 0.17224970728301126, + 0.2541615686592652, + 0.1751933529590565, + 0.2825876404961108, + 0.1806854659556176, + 0.18375123339410007, + 0.06147670605099388, + 0.14796008777005867, + 0.12549227630898843, + 0.12227723948838336, + 0.2351667696911679, + 0.25543766893790976, + 0.20303751221083077, + 0.21022988528851544, + 0.2813268224343496, + 0.08228792264861169, + 0.09698589114564794, + 0.10651566891853506, + 0.27698817955622873, + 0.2445595283193129, + 0.02444168275780006, + 0.19542258466287293, + 0.26078512401890996, + 0.09570929529317082, + 0.17409368882235748, + 0.06731720054865684, + 0.25256373317567665, + 0.28528125454485787, + 0.11747870519835232, + 0.2343367746526207, + 0.1833625370608855, + 0.22591399544790736, + 0.10691194285032399, + 0.2364396055406148, + 0.22429962025444095, + 0.154464376737813, + 0.1823427335443161, + 0.07935848725462788, + 0.14451933301656691, + 0.1313917444320599, + 0.19363062696882447, + 0.21193208375240927, + 0.15636266842155006, + 0.09898234460854514, + 0.1184290402704772, + 0.22476677708683956, + 0.11143356978288119, + 0.18180413224094322, + 0.20652696384926753, + 0.1267447551018557, + 0.2372592465960273, + 0.059362396288206436, + 0.19872625168539282, + 0.2293267337780825, + 0.2610115352237983, + 0.21521960623364375, + 0.22909404173920897, + 0.24683176176880733, + 0.24360326230031926, + 0.2749280807855159, + 0.24111057833078098, + 0.12016605779275924, + 0.259601963387217, + 0.2753218886997463, + 0.09099216723817201, + 0.12191624222775939, + 0.18732744663409637, + 0.19163139522312783, + 0.10032170976040039, + 0.030943995116914806, + 0.12710690270850347, + 0.16017954887255526, + 0.1557027848871559, + 0.24798800502273552, + 0.09184734808775438, + 0.21331386438854355, + 0.0980581596744191, + 0.1289483798045744, + 0.047194765110113744, + 0.2343578866250666, + 0.19705696871822148, + 0.23574593873207322, + 0.19849589965172248, + 0.17766382731535263, + 0.18474899028345385, + 0.26606513252654473, + 0.13136856884971498, + 0.23561322560733336, + 0.1553053446477593, + 0.1495453116750624, + 0.21334446535220947, + 0.180323972486796, + 0.2611439337001824, + 0.1963991524079432, + 0.08616513769032849, + 0.08827131787169108, + 0.16046664598340815, + 0.2527342392851324, + 0.2837056923201313, + 0.14504482264029772, + 0.18767256499153692, + 0.18478170326260424, + 0.20997087885990487, + 0.11753187384353125, + 0.09491724069132812, + 0.047648758129321206, + 0.23069177944886862, + 0.13039773870654217, + 0.2814787626817173, + 0.21513774999558585, + 0.13700880540905244, + 0.09486392655602763, + 0.2549662416561284, + 0.17380922545233124, + 0.09228170294641225, + 0.19123569910282512, + 0.21545112871407837, + 0.21038318379008925, + 0.06677429137028082, + 0.1507792257506956, + 0.17479096014673923, + 0.11870012007647555, + 0.11189167918018503, + 0.20433407051244332, + 0.1138510886675404, + 0.1328046960970819, + 0.21112166125063503, + 0.2729013431139196, + 0.17315201094991078, + 0.28091856357377776, + 0.24578260859264806, + 0.20589797194381304, + 0.19825142872547816, + 0.1040081214908735, + 0.21623123035924147, + 0.10150362358799343, + 0.19677120312312202, + 0.17638291259486258, + 0.12021989575974242, + 0.18152662945177137, + 0.09085751954982613, + 0.1887081518617763, + 0.20633276721982294, + 0.08291867177372707, + 0.2459636180489415, + 0.25665723626819437, + 0.28651092062149447, + 0.16181883341789524, + 0.09089819559163205, + 0.27130370921232094, + 0.16100505815061653, + 0.20187625751707294, + 0.25430480230969343, + 0.27011073919215883, + 0.12316870526093468, + 0.18499278266666772, + 0.12481269298589935, + 0.20683525039093306, + 0.22704823991035758, + 0.16508896394123102, + 0.20691996203906018, + 0.16863985593629738, + 0.07697846066159666, + 0.08111278498238665, + 0.07349501786532625, + 0.22049560845418603, + 0.2784650230036371, + 0.1478103237222155, + 0.1340871839442319, + 0.17073165909601565, + 0.2849994864280817, + 0.07819019382986052, + 0.225492205113468, + 0.22343897473946583, + 0.15076782216822232, + 0.22258177627263723, + 0.17450418214690733, + 0.04851969406273496, + 0.25917991706059273, + 0.1751464247287525, + 0.1902285527737025, + 0.1377100995653421, + 0.197212661103159, + 0.014356765620392833, + 0.09843704429460669, + 0.15657890485246015, + 0.2702986974927474, + 0.2203321916822206, + 0.1858366471852901, + 0.24027590545285948, + 0.28116750809435936, + 0.1683051466812305, + 0.12509219275121633, + 0.10148952993591866, + 0.21640909659551882, + 0.1396812380570916, + 0.14058773013216408, + 0.17404798441163624, + 0.14896734763620503, + 0.05027998068075436, + 0.2032271112469403, + 0.18551066733225074, + 0.1317077053123156, + 0.23133386979856602, + 0.20504409872673965, + 0.16296307846346025, + 0.19290686827033504, + 0.15669453698773633, + 0.11586931895494099, + 0.21580765494954313, + 0.2639394962498403, + 0.14843864884310884, + 0.09288169942163917, + 0.0890938692023224, + 0.2801498336663532, + 0.0345645327163383, + 0.27455692817893856, + 0.11090097890904674, + 0.14459819904092053, + 0.2711457883482673, + 0.05865575506012201, + 0.1360774289071205, + 0.23916475397765405, + 0.25501087175693876, + 0.08637261971109268, + 0.0801792926609707, + 0.21756463102280038, + 0.26140433689859405, + 0.01576109483477311, + 0.2701392484872838, + 0.20818160526318666, + 0.1901790290162918, + 0.19960256019897435, + 0.19617656837589215, + 0.26656866055977824, + 0.27022980767296306, + 0.26352714361813395, + 0.2576558570224565, + 0.11308347537594635, + 0.1431794121544741, + 0.19945140086545257, + 0.09496642172175018, + 0.2637109423247643, + 0.2201576482043911, + 0.11244889756413635, + 0.22968653259514896, + 0.1631790709064954, + 0.2273080741973008, + 0.2144797588833549, + 0.21702776544302702, + 0.0745684303279305, + 0.23057721925305547, + 0.18939727210302074, + 0.27661747789193075, + 0.12635340386490512, + 0.03031856430036962, + 0.22361584511970226, + 0.2856625304500877, + 0.04603550607606845, + 0.23122253738016607, + 0.26351695070196574, + 0.059809139895290395, + 0.24062687326847343, + 0.09807575708389353, + 0.2807684606649259, + 0.1953830023574005, + 0.2218219265742466, + 0.10050290630424816, + 0.1591533581195706, + 0.2046937952194248, + 0.2341160904535092, + 0.13276307237010265, + 0.28500785626999364, + 0.2901398075184446, + 0.1835164484286003, + 0.00970057163077782, + 0.23916749191328301, + 0.2872737951490986, + 0.16469602884833073, + 0.10775661931222137, + 0.2132059723763217, + 0.17584366829693612, + 0.26658818468619866, + 0.26112226380482023, + 0.2717138690711273, + 0.19886766617208185, + 0.2116543345959662, + 0.13900430389243107, + 0.25278467586541437, + 0.20229353457932564, + 0.07178310517451093, + 0.017280667029619515, + 0.15723519474860526, + 0.15816047354258106, + 0.13077338241475903, + 0.24744621110780846, + 0.19004595870880653, + 0.22979779655650787, + 0.13335638225808788, + 0.09462285987339014, + 0.21827732113661572, + 0.20707271213090464, + 0.23747230706532912, + 0.05244646863509738, + 0.2883656179476465, + 0.25094370919367076, + 0.13600053127709635, + 0.2205321031628623, + 0.20772064876630122, + 0.07443499909713408, + 0.04732721801343189, + 0.14403306680570285, + 0.16487743288187762, + 0.11124495396288304, + 0.19083781428346433, + 0.09453382267966097, + 0.2542202625348542, + 0.1252974025068017, + 0.2558446468234114, + 0.22693639741250904, + 0.2590156501307513, + 0.15675627021159821, + 0.2439965372745814, + 0.14678109947393517, + 0.19142847918567038, + 0.11818467457283817, + 0.10319192022154614, + 0.14582262927945303, + 0.13662379388390922, + 0.16002773248726368, + 0.23973116909416292, + 0.09134046037712006, + 0.19030201051986415, + 0.2265942059569411, + 0.1750936141040744, + 0.11142640018997525, + 0.09071591849845811, + 0.1848018203966993, + 0.19223619971315853, + 0.2389870123270074, + 0.16309327197656115, + 0.22750273324894843, + 0.09227226651081652, + 0.24479267126822155, + 0.07969454377899317, + 0.14731184838811537, + 0.22685938235447967, + 0.09917279381394614, + 0.1377603871075548, + 0.20119043476511242, + 0.21058610646867035, + 0.15036712571981187, + 0.28180595300266514, + 0.2544117478228359, + 0.1783772223160883, + 0.03169827024121578, + 0.272159251166642, + 0.0609716719718059, + 0.20265690965815128, + 0.21297148893035012, + 0.1738774007493026, + 0.14587091472331257, + 0.26255667993076276, + 0.0501720785459636, + 0.08970064490011007, + 0.07162419925634717, + 0.09474521583198812, + 0.25420085886450694, + 0.26543653605182815, + 0.2563092802889412, + 0.25049248539014646, + 0.21851278123686782, + 0.19822689344053157, + 0.21506621912481697, + 0.15591985240113643, + 0.0929427189136034, + 0.17696121332124268, + 0.2724373520678437, + 0.22651664656760045, + 0.1690225172955796, + 0.17287507498622964, + 0.14184573542155904, + 0.26037090541240876, + 0.08128157308659201, + 0.24414187943355778, + 0.2171330107885756, + 0.1483146203833132, + 0.21497141861454314, + 0.2265297825184703, + 0.2765307651952019, + 0.2363126502746818, + 0.2437271132625978, + 0.274472698115061, + 0.1695731549572051, + 0.08760261630112144, + 0.13453766946742582, + 0.02844219197524083, + 0.04353284591549257, + 0.042729313917989994, + 0.1499872600016861, + 0.0540942629733465, + 0.1387091358277007, + 0.2685530430863949, + 0.14161264334028084, + 0.23674754254808372, + 0.17365291851734876, + 0.1038724357166547, + 0.148884238144895, + 0.11947675516389623, + 0.22549703789683828, + 0.17414732298936889, + 0.20005108992520002, + 0.05128585584522426, + 0.22406198501069857, + 0.23201799516515967, + 0.15273336254708295, + 0.1891387773185248, + 0.13417394840962926, + 0.12398661376214527, + 0.21559188457470832, + 0.25080135560735806, + 0.029536281406107256, + 0.26375376769903347, + 0.21589497555735532, + 0.2160574417649704, + 0.06185165655975309, + 0.10872084943476941, + 0.21228239885955127, + 0.01944954009107855, + 0.111081651890694, + 0.23163309413915995, + 0.20716062862614684, + 0.04616120733654128, + 0.23452400979016422, + 0.12305245020723257, + 0.16430786246600698, + 0.16635114497310816, + 0.17994150425217925, + 0.11488599836856822, + 0.19213903946075303, + 0.16202813756176915, + 0.18398070067126376, + 0.1815688096889441, + 0.09474192712533044, + 0.23090309114877716, + 0.19138209538701917, + 0.20501656420642092, + 0.0902819482325894, + 0.15685855502227608, + 0.18316048756930245, + 0.07938010497249132, + 0.23950634990514844, + 0.20929190277529577, + 0.07022621451499542, + 0.1641258467834545, + 0.1629656441206332, + 0.21648258207546134, + 0.21925277492911172, + 0.12134154065939044, + 0.05362765296434231, + 0.13318197502057388, + 0.23448706273240483, + 0.06151755092528526, + 0.2657696017577946, + 0.02651738316891696, + 0.15873100653938377, + 0.035713063210498254, + 0.26761384787654174, + 0.09064025504452718, + 0.15848833654975675, + 0.22952885675406942, + 0.1421185473952486, + 0.12750970307527404, + 0.10005685207519187, + 0.2739501388717101, + 0.2656144664469721, + 0.19466377935980306, + 0.17991694226185073, + 0.11535155449819211, + 0.19019253142744996, + 0.16506003097702834, + 0.23496433081684215, + 0.20222275014261337, + 0.2600755180430181, + 0.18068803141834563, + 0.12048030532553872, + 0.2764831818260263, + 0.19223678976331457, + 0.22046024337803607, + 0.05972575307574936, + 0.2251030540849542, + 0.18626701240764662, + 0.08371685874114783, + 0.20046940404735814, + 0.26501974988040444, + 0.17498554644752903, + 0.09161934136462721, + 0.13987066120290512, + 0.23821700014345956, + 0.11105664348657805, + 0.1922297373968139, + 0.2194525957642039, + 0.14386601657266535, + 0.16616243641034362, + 0.163821973353351, + 0.18409094147546445, + 0.04560870274342289, + 0.25825757633530255, + 0.14277329450522985, + 0.039907473337732986, + 0.28157256597992886, + 0.27308134247052657, + 0.26876877224951595, + 0.2377828367680646, + 0.07266979985574099, + 0.14460030060335685, + 0.17960955972236436, + 0.22294959486426502, + 0.11136253629125391, + 0.0882350934113113, + 0.1487023684414704, + 0.20411222606368995, + 0.12942656395686175, + 0.26381230518021853, + 0.27464905830931746, + 0.1829339421602223, + 0.16365755903175025, + 0.18819234091826567, + 0.20739875636894048, + 0.2066077701313965, + 0.27943263469093843, + 0.21976921935831484, + 0.2829277181133609, + 0.06810704806793978, + 0.21109993613912423, + 0.2667438227114919, + 0.13354382469684506, + 0.2192168177385231, + 0.11964688909324113, + 0.26422540339370554, + 0.14891823118494135, + 0.28767798284289203, + 0.19880184445534183, + 0.235996653423135, + 0.20374485684615024, + 0.22419903083384, + 0.19071762956413854, + 0.06333351688313936, + 0.19595786947691626, + 0.20967975020202712, + 0.28836867380313297, + 0.060194500165129464, + 0.06550390865612132, + 0.08615352457530252, + 0.2487184901625701, + 0.12910214646127788, + 0.10642938389287109, + 0.1985525640378336, + 0.16687265977129218, + 0.16500220793940723, + 0.04014363649698663, + 0.20295743614241554, + 0.23135818208755324, + 0.09462747407680779, + 0.276394741268018, + 0.11626802525017266, + 0.25632630903481823, + 0.16350370842396542, + 0.2407246560516707, + 0.13807248246892, + 0.030300436145937193, + 0.21445851013822376, + 0.09956973887952254, + 0.17857714102166203, + 0.17755592128434097, + 0.2712918007692392, + 0.21370323754165707, + 0.24324070445054696, + 0.1568269120830866, + 0.20978783032682616, + 0.15880687137175623, + 0.2804227792356542, + 0.18088489163712104, + 0.2696789104118985, + 0.20862250545818897, + 0.11158953291261828, + 0.2288880120890885, + 0.2528472829595088, + 0.08706542110527714, + 0.15121448607999216, + 0.11990285493293362, + 0.21726908383347765, + 0.19407336237356643, + 0.11202831350519608, + 0.14025310444740502, + 0.14423749432733873, + 0.23422632874844554, + 0.16642998708630816, + 0.07391375205697562, + 0.06329839871790527, + 0.11389315307347898, + 0.19237816091103505, + 0.2237934897378224, + 0.18891349884299274, + 0.13741821533146978, + 0.1464006767197084, + 0.2751519164238694, + 0.05042799173097106, + 0.07655933325113043, + 0.26757470678693934, + 0.23094008441238853, + 0.11888409557545111, + 0.22816782787313286, + 0.24038842672342942, + 0.0995915740477861, + 0.19809181277907495, + 0.22413768664040323, + 0.20725544244174224, + 0.25648291856036143, + 0.2525074864991396, + 0.263957266409505, + 0.2207037670937461, + 0.18873375598897382, + 0.25114587000125443, + 0.23292613948583782, + 0.18381227129386452, + 0.1822391265534296, + 0.22741828497330085, + 0.2425090008504716, + 0.10922895950358556, + 0.26157279348674967, + 0.2348838818305145, + 0.11407124008899222, + 0.0380733254036387, + 0.18583497873885668, + 0.18498911647494132, + 0.2014187616664264, + 0.19013674963199803, + 0.224433845065413, + 0.03266008905508327, + 0.18756047006883736, + 0.15299711994599346, + 0.17755174793117828, + 0.24534469463038466, + 0.08364569285106076, + 0.146444997867839, + 0.1182485579170543, + 0.206533589281752, + 0.19973222671873525, + 0.19993320014104832, + 0.20322325627936455, + 0.2127807591533208, + 0.2545734133245548, + 0.2699084391897154, + 0.23017378742513717, + 0.20492158525372375, + 0.2346117052293675, + 0.10386395730271923, + 0.135586897030973, + 0.125399694857219, + 0.21432676716258978, + 0.1369747487598308, + 0.2775207454539363, + 0.1865451905001158, + 0.24531026400164105, + 0.19330911042942064, + 0.10390216677444422, + 0.2544493779372618, + 0.18952982611453006, + 0.20259813944093355, + 0.26632041910867577, + 0.20313081622788398, + 0.23206748630692975, + 0.19649911496391664, + 0.07090682854059491, + 0.28280935243227173, + 0.2543757973840437, + 0.12323787044255975, + 0.17043585712277118, + 0.15352968167850428, + 0.17246557962717643, + 0.1792355742841171, + 0.10257346356141975, + 0.21568657877646172, + 0.280175795191773, + 0.27752724347897095, + 0.28424039856786304, + 0.1900176634598063, + 0.038535913413772216, + 0.05222268294273132, + 0.2632902162396743, + 0.21366424267616366, + 0.27888750661418726, + 0.0823546193516431, + 0.14036714811822745, + 0.09352535935578245, + 0.1865681010013904, + 0.19867120658166113, + 0.2834662474888149, + 0.19690890568787012, + 0.08661939996730209, + 0.18975360380470954, + 0.10728931359928565, + 0.01143598800080781, + 0.08434178014660461, + 0.16261729878587602, + 0.18906683273964012, + 0.22498346827210228, + 0.05808554639563979, + 0.1686468071268644, + 0.2230512115675496, + 0.16170160544785497, + 0.1987842320212684, + 0.12244971958566367, + 0.16885361335069804, + 0.21689930553158518, + 0.16404739452528666, + 0.2611530368868096, + 0.21334727381197555, + 0.26878352725265353, + 0.2869533651628008, + 0.28026107344827694, + 0.014246925678309466, + 0.2265508698994347, + 0.2169087502322392, + 0.2114752424798395, + 0.12270862762423244, + 0.17386570705431179, + 0.13013704191379982, + 0.0342233949101799, + 0.17746591011926643, + 0.2173145279250944, + 0.1783336906694226, + 0.12788123438092094, + 0.21048245133528942, + 0.23605261843174147, + 0.1972214563344147, + 0.24372923881869873, + 0.15397240533021941, + 0.28445831830782087, + 0.21186912639220165, + 0.139603706762292, + 0.18519184451468365, + 0.17691995969359692, + 0.029677663812376343, + 0.1760631308650212, + 0.1768959948629047, + 0.14182835941626995, + 0.18726993339018927, + 0.2502446607169403, + 0.017853624762735144, + 0.27593285661908606, + 0.2777280028738239, + 0.2389271036154957, + 0.22575031492601644, + 0.17659294559967884, + 0.12785358266158361, + 0.2767628687327118, + 0.2816674439907576, + 0.2395079468771755, + 0.07135197689713817, + 0.20669027580714996, + 0.17317255182484684, + 0.15509467148012854, + 0.19188252773523853, + 0.2238110264201735, + 0.18390107102808836, + 0.09242300303408381, + 0.23221762223918366, + 0.0911494637630681, + 0.22874012821719147, + 0.02082763890184723, + 0.17992045499927442, + 0.10741106009576895, + 0.25229039121755203, + 0.09363571004609765, + 0.20494265016457772, + 0.1765259625367124, + 0.23467424335574438, + 0.2674479265103851, + 0.21298706165639533, + 0.1828837629820079, + 0.10748267005122641, + 0.22294180432774985, + 0.24757009780996608, + 0.28926880399543337, + 0.21805528945795188, + 0.11039879738379853, + 0.2775006440196405, + 0.26240491464609833, + 0.21037345085071402, + 0.22385297251106595, + 0.22621277114899707, + 0.19849314416966238, + 0.1005764067397968, + 0.11383661888795406, + 0.18231733458855937, + 0.2298422711225041, + 0.11692146753081181, + 0.11653074277128875, + 0.22785114637162232, + 0.1775047008945258, + 0.2620872060012288, + 0.2433998429531589, + 0.26859420671463263, + 0.08154345110237114, + 0.21600677282865322, + 0.23019928359967629, + 0.12378657094617039, + 0.0978789908726701, + 0.1516391442151675, + 0.277919195101613, + 0.26261950680873797, + 0.25941252416741445, + 0.17586973404046147, + 0.02843636285868444, + 0.21972502772123803, + 0.06263513519728846, + 0.07665125796198931, + 0.1578266386696471, + 0.11937768389726233, + 0.10029367810397134, + 0.24476182730473237, + 0.17649103313523867, + 0.16739971611114082, + 0.2734684521171595, + 0.24695372595635307, + 0.012724000330107278, + 0.2588114043672984, + 0.20873008430120732, + 0.2798522627892641, + 0.1666863326877503, + 0.2140055895232708, + 0.1164161966856171, + 0.25598398451303717, + 0.21161744682275493, + 0.1437270714475828, + 0.010526226026960343, + 0.15572359194926783, + 0.20820840525167905, + 0.15220599945174196, + 0.19390147600832247, + 0.23110689096709464, + 0.061378306870886176, + 0.19850381962564284, + 0.12082228562591636, + 0.04459549854010178, + 0.2787363856102138, + 0.2617595665806236, + 0.24011213306331758, + 0.2499934537366623, + 0.23874176374529552, + 0.2226981096195345, + 0.15174997538715018, + 0.23232307358397775, + 0.14180729184871146, + 0.23160427231315975, + 0.2031810132758636, + 0.22955146049519, + 0.055966715371478674, + 0.1997097603710583, + 0.19306323569772224, + 0.19258185288006327, + 0.28061446367447535, + 0.12131521456680908, + 0.2535119498968596, + 0.24443024093077537, + 0.16803542990906226, + 0.26316054709533915, + 0.2325894297870387, + 0.279275392757937, + 0.23775500896238466, + 0.2863475661539364, + 0.08652421506615987, + 0.2327882344961813, + 0.22078244076292525, + 0.009099683651942605, + 0.1185142836325544, + 0.1743842578922476, + 0.26383826178670716, + 0.10326223836016604, + 0.23402600838040896, + 0.2059247140795454, + 0.15151836565718294, + 0.11057992953544493, + 0.2122644416811156, + 0.2063581036147184, + 0.13101341939232924, + 0.1945132962842551, + 0.24003488676950635, + 0.09302691202804778, + 0.16672215153197778, + 0.17029783736172144, + 0.27321407681807885, + 0.21650271953076153, + 0.2389372350845983, + 0.2758205593724607, + 0.1502229495385174, + 0.1578266045080728, + 0.09372961384474816, + 0.13868710195171735, + 0.18239248942732852, + 0.18028333566358834, + 0.2728838301393029, + 0.08516345683514782, + 0.03928017222466698, + 0.2796293915474823, + 0.24904874924937426, + 0.25808478315388605, + 0.12767232926336575, + 0.07671934493200255, + 0.1592853607165589, + 0.2595765530395761, + 0.2170911434450657, + 0.23251968246645965, + 0.2585116526474263, + 0.18108541538548514, + 0.23691365925040112, + 0.09220184447037351, + 0.05635178290633606, + 0.16924597376390452, + 0.09252865450079839, + 0.22646999636618398, + 0.22426974343823985, + 0.25484982431482517, + 0.20379158286672916, + 0.09482812060240808, + 0.2687778166207337, + 0.11694061413633162, + 0.17047444343967444, + 0.28919208513852057, + 0.17334773422294575, + 0.21777734858442652, + 0.2657266354543486, + 0.21431127097867333, + 0.13494707182983673, + 0.09324878467424097, + 0.1976678351288563, + 0.1684486216788311, + 0.1348811081214203, + 0.11452827500012693, + 0.16100327560946326, + 0.11979623333350281, + 0.274535682812855, + 0.20875689418130494, + 0.115959523690649, + 0.27214541604883896, + 0.1248934813425728, + 0.031180515130985346, + 0.21317962398548798, + 0.20977079602541945, + 0.15442850517688636, + 0.2661328221704736, + 0.24550386205525374, + 0.19107266132187653, + 0.2662946499177628, + 0.18650265826913812, + 0.20204014373107884, + 0.029489596992762192, + 0.26589746562798655, + 0.27150149120897754, + 0.19637696047282374, + 0.205348280696398, + 0.10176913019855502, + 0.22974470987069107, + 0.1545355045125501, + 0.1323492765189992, + 0.17601207330676286, + 0.23951455689911522, + 0.05143452391999559, + 0.1887187193669743, + 0.18025497095568596, + 0.09688176008808126, + 0.05201044412757983, + 0.2366325539408753, + 0.22485445503603954, + 0.13498101593975106, + 0.2762488572715116, + 0.21450695366886924, + 0.19106521740531537, + 0.22222561896379883, + 0.23035999815548935, + 0.15129795127935855, + 0.12101384479627346, + 0.2590123815859898, + 0.17128219522888186, + 0.0506307998722573, + 0.2452405491943193, + 0.11317737496221603, + 0.20555704400268124, + 0.15002769497968768, + 0.21914830166258267, + 0.23048087953993474, + 0.18298205864441444, + 0.27742082181029226, + 0.1775572095678699, + 0.2765985255397203, + 0.2590067947008017, + 0.1516747317101526, + 0.06733297331246815, + 0.13693426839754297, + 0.07395484773712498, + 0.2161440870447583, + 0.20789569473553682, + 0.03713849802791059, + 0.22726234460477532, + 0.09400525467087446, + 0.07765858569908306, + 0.05909173671429007, + 0.22886794041941794, + 0.28929274560164503, + 0.21897532774607437, + 0.17348431569490108, + 0.23415887153989173, + 0.029115766409395713, + 0.18681036526266412, + 0.22175523336874092, + 0.12412354745134985, + 0.2062101736252434, + 0.1364331621896498, + 0.1870032019664114, + 0.09749356767599442, + 0.15170101171018513, + 0.13425073340674637, + 0.05879367966677618, + 0.02194101781116257, + 0.14978043007428024, + 0.07413531548598778, + 0.28417901242965843, + 0.243869497752256, + 0.16906910071711978, + 0.1897168385091218, + 0.2836636161894404, + 0.1678467009416015, + 0.23789104362465086, + 0.14731369589274984, + 0.058199748948363085, + 0.206170790070612, + 0.18326701244253987, + 0.11402831686281317, + 0.2740394059664022, + 0.15748848920083963, + 0.17965782550323156, + 0.2404615231686066, + 0.056342163321165706, + 0.24626530913472547, + 0.21514471482281416, + 0.16001000565367945, + 0.059476354039446774, + 0.27850512821278073, + 0.22758949980459578, + 0.1312229150535346, + 0.18777749284243428, + 0.2391142520226597, + 0.04748577624690274, + 0.11750206731385358, + 0.16515236099026928, + 0.1577365132800141, + 0.17592115785859855, + 0.09692463490955784, + 0.12071414692801488, + 0.15422683927501327, + 0.06872197079559991, + 0.27597582615850663, + 0.18220758654427419, + 0.1518675261806705, + 0.24364001623768652, + 0.27355006332084125, + 0.23028724051812471, + 0.24645108935011284, + 0.027995581801057046, + 0.19179317402050974, + 0.2640925181791417, + 0.2438620080334452, + 0.0849897418649541, + 0.05035494518910662, + 0.2800470845681965, + 0.09918423080404246, + 0.18010193159156165, + 0.2162560216047614, + 0.2178340401138276, + 0.12641375377971806, + 0.15270504748321603, + 0.09310620603718342, + 0.16254863063517783, + 0.19735763015215413, + 0.2580634914587296, + 0.2810887638478791, + 0.2825977573399516, + 0.21785034095944694, + 0.21846780651242728, + 0.011380368573709426, + 0.06682526638869198, + 0.23475974791201185, + 0.22685565486660703, + 0.06495639829177985, + 0.20774043427066008, + 0.15030939472888416, + 0.15156488107239172, + 0.2811196537028435, + 0.15991731113467875, + 0.12144926075826447, + 0.23063734450097387, + 0.15811578180373023, + 0.25025311718935456, + 0.20687710747294294, + 0.16928424195598532, + 0.2609877776040435, + 0.062535773956851, + 0.1661183004199035, + 0.10947273301685352, + 0.2172499465294787, + 0.18738230745413148, + 0.18707823819919944, + 0.02403218298746428, + 0.189419546261557, + 0.2294856376383044, + 0.24425448501644062, + 0.12120093249544128, + 0.20385437309948654, + 0.09966605652866102, + 0.1880682731090598, + 0.2704376290886085, + 0.15540712943227036, + 0.20187050221559993, + 0.2140419925646083, + 0.277153101108303, + 0.26532478000584125, + 0.16980295541477647, + 0.2681042194063786, + 0.1788004919482549, + 0.13269321542893103, + 0.1654686736678191, + 0.1945479469454434, + 0.17775249209535784, + 0.12487892476874753, + 0.15068418103029832, + 0.2618709384077892, + 0.27580827743132585, + 0.09400746616341903, + 0.20446927360368053, + 0.23413898112036433, + 0.1796725182921532, + 0.23442651446343987, + 0.1144267721583956, + 0.05189290490518817, + 0.23526285583498216, + 0.1787769252746086, + 0.2344965134550689, + 0.2280651283351392, + 0.09373130551337484, + 0.1355973201536299, + 0.272784091714228, + 0.25236615952369673, + 0.20699893874313144, + 0.15185795946657385, + 0.14333948549449307, + 0.18018236762022496, + 0.15459409183137562, + 0.2595501399531416, + 0.20524921896000226, + 0.1846891608681612, + 0.1935610788013063, + 0.28422949021161364, + 0.09891983636885526, + 0.22835273632612774, + 0.21454239242605558, + 0.20468737255283412, + 0.2269464159761762, + 0.21999278470030026, + 0.2397431692792463, + 0.23770446268475492, + 0.1334580602648444, + 0.16102707188155096, + 0.1938051920478279, + 0.14127241731330822, + 0.07265902485059149, + 0.2515287977189626, + 0.20780954528886428, + 0.05149308887688985, + 0.24662597614252826, + 0.23503458382670486, + 0.162352276724768, + 0.14479050528157703, + 0.15508131490533636, + 0.2591719951179701, + 0.2804423107006447, + 0.1810597328282424, + 0.13527262520178057, + 0.1978238434410223, + 0.28704082369550027, + 0.08146388630744011, + 0.28173548435572215, + 0.21268622905540344, + 0.2886037652710781, + 0.08424566327544378, + 0.27121958041276256, + 0.13394769779748736, + 0.06614839552871833, + 0.2110356461790751, + 0.21893214076992334, + 0.07924656495952231, + 0.08689295106443909, + 0.22469725471536386, + 0.21896257401943856, + 0.2593761322289698, + 0.09104085328101202, + 0.08820769427471822, + 0.2807791324582594, + 0.2232710935057777, + 0.2388143299598718, + 0.14208829528866518, + 0.2021434724713678, + 0.2684071978682509, + 0.2396093224535497, + 0.26975882758628517, + 0.1443833336771563, + 0.1990230489478879, + 0.08438830264007693, + 0.03653591034684818, + 0.15388546460731142, + 0.2682700077599595, + 0.05124461408566397, + 0.12425988012538328, + 0.28302607311175465, + 0.14150070915827279, + 0.19101383445578307, + 0.23719748641043242, + 0.15022156871874606, + 0.2672650142806676, + 0.19692869071055485, + 0.23383399894691206, + 0.16569340931645765, + 0.22231448315927343, + 0.01584574428433615, + 0.2238821052273318, + 0.18214679472795592, + 0.10075094193361964, + 0.18061198236172835, + 0.2827197256267674, + 0.27580581979134194, + 0.09930770731454573, + 0.25916862231120513, + 0.28098711366526513, + 0.1714801632330398, + 0.21896110528562798, + 0.19476819428735456, + 0.24859556107907965, + 0.16732858711938428, + 0.2810649078705633, + 0.19326489010515135, + 0.057163521332239633, + 0.18845683773739866, + 0.218443088145563, + 0.2731983538109391, + 0.22166966097984256, + 0.2663968325129949, + 0.14175681182899008, + 0.2672162125739677, + 0.13420084918689448, + 0.14893684623428058, + 0.15866299864767922, + 0.08563537323011944, + 0.22280539088482162, + 0.14344760027171316, + 0.041731360910018174, + 0.25914496504827395, + 0.21392200375141485, + 0.1825973502777, + 0.15732536561760088, + 0.24574047301261773, + 0.22579349759188339, + 0.17722155339839302, + 0.06276538430008603, + 0.2673206383722046, + 0.26355550559529506, + 0.21311399490080518, + 0.0895448357033654, + 0.20976859939486525, + 0.25684546805649583, + 0.1948410066504755, + 0.2358667365213015, + 0.08579044950865929, + 0.15813762720742378, + 0.1212410947871281, + 0.14091789182685138, + 0.025790447123878412, + 0.1856309265850252, + 0.2063794521487963, + 0.24122034553590063, + 0.23151661774886317, + 0.07974404040431442, + 0.20770768655680769, + 0.07744725424181502, + 0.10063069443486188, + 0.22481914297250521, + 0.06661239830212728, + 0.23441878656668788, + 0.21030314784302948, + 0.05680920753944354, + 0.13132757185716315, + 0.17413553517769007, + 0.1527375991718045, + 0.011550766344343707, + 0.24168167415760372, + 0.2761278744356048, + 0.22805932230629591, + 0.176956983850943, + 0.2797270078787621, + 0.16550671950967538, + 0.07478730195777836, + 0.14168527607441883, + 0.19781521112404588, + 0.24057734512507079, + 0.24210225524315768, + 0.26204860930874474, + 0.2789634833203219, + 0.05287292658723826, + 0.21716369935252178, + 0.26437008623651104, + 0.22950979620626438, + 0.11960295533968451, + 0.2578756494268529, + 0.15004230563346585, + 0.20746867753642598, + 0.21705519113852872, + 0.17003993021288952, + 0.2213831915693447, + 0.07141476607123319, + 0.25536013539417485, + 0.15590736474065864, + 0.12352221182171821, + 0.14260226173187565, + 0.21998557979940622, + 0.19878583895081023, + 0.2512958039319278, + 0.03552583253239364, + 0.03258284458201401, + 0.2514617285577082, + 0.11628662570092552, + 0.17391896253273184, + 0.2795168575041745, + 0.0985455590203309, + 0.1984202328746561, + 0.15440471740795203, + 0.163034448006597, + 0.2664183949286903, + 0.08084326774067387, + 0.22848028556323918, + 0.2638907604421195, + 0.155561910733963, + 0.27169826178221035, + 0.19143468223980498, + 0.21526682501339003, + 0.13041888120308587, + 0.18742977168835992, + 0.239236211395895, + 0.18194711105963035, + 0.24219306808065638, + 0.13361197646462405, + 0.18110339479346874, + 0.1296402528980772, + 0.1651123612862162, + 0.05755121489298626, + 0.2011154418928068, + 0.26108240153247025, + 0.17998344243706457, + 0.23151279009293083, + 0.100373816786746, + 0.2657877435798972, + 0.17395910421403565, + 0.14951304447198502, + 0.10177530565703731, + 0.10021243606893085, + 0.19305523647192033, + 0.187995051644596, + 0.2244525808722255, + 0.08550304872786062, + 0.2663225770083532, + 0.22645765050941333, + 0.11961472289352951, + 0.27614752431407585, + 0.2691308542447152, + 0.2759955635133959, + 0.2259549080602816, + 0.19615461064098388, + 0.1890464677146549, + 0.20871612513042145, + 0.12219556307538611, + 0.08487201617854828, + 0.12213000489585078, + 0.1361557512349929, + 0.2543743103879533, + 0.258768051223715, + 0.16318702016900732, + 0.10997542268083788, + 0.1955731783984643, + 0.23102958593277112, + 0.15661795152495483, + 0.18442603689398357, + 0.13252127593850352, + 0.2538655461516623, + 0.09261060857219913, + 0.1918693952715367, + 0.15868103250995877, + 0.15891935889378417, + 0.1319302999539979, + 0.11218037970982768, + 0.13685075550420617, + 0.24135552543353464, + 0.09726071212478139, + 0.06811907702341727, + 0.1933198226526675, + 0.1625441106500723, + 0.1472030269060981, + 0.06378127719216238, + 0.20415924032360946, + 0.16747952711859848, + 0.21865708238911566, + 0.13782221667687608, + 0.22250333742054168, + 0.18612774242896712, + 0.23529544511913955, + 0.06856957585125056, + 0.26961001208893454, + 0.1178584935874544, + 0.18404593796590618, + 0.20771831351649667, + 0.10195603302111199, + 0.06126476162096061, + 0.14718080363774014, + 0.2807489655439646, + 0.2334950697408501, + 0.10808242751563324, + 0.18127156821509305, + 0.26279323743307614, + 0.04566204270127868, + 0.2596779872971632, + 0.2460916174488517, + 0.11980133687955909, + 0.09646664134609872, + 0.18004061505353336, + 0.270570844875757, + 0.1671368796640103, + 0.19092669432442463, + 0.22213094758949845, + 0.214555915306704, + 0.09031001479364907, + 0.19786508319955579, + 0.25017463209588264, + 0.1559076738214522, + 0.18960903429685025, + 0.09060644950487612, + 0.23330453595842596, + 0.20669275690296832, + 0.2744383384885781, + 0.25170497222465255, + 0.26487032822140766, + 0.1738799111030557, + 0.07111476676975181, + 0.1999196998065858, + 0.11835533056005113, + 0.21599139256723088, + 0.1325419859699359, + 0.12380568117126646, + 0.19989985756325815, + 0.25636604396853646, + 0.029826452587543857, + 0.25956081485972343, + 0.2729822124777515, + 0.24722999215816407, + 0.036671379094603926, + 0.20958944340493543, + 0.06754921899182088, + 0.06859624435403426, + 0.09936787351079918, + 0.051638343624265254, + 0.2511312749755615, + 0.21893307941110196, + 0.07476088428473006, + 0.06938671748074801, + 0.1776482478644269, + 0.2789917971310168, + 0.19688206030207764, + 0.14367885355732687, + 0.07196687838312278, + 0.23965226081743682, + 0.20388632582422536, + 0.13490762482418128, + 0.11877439297434968, + 0.22811801099159695, + 0.09973565762743483, + 0.2621061120668067, + 0.24946197213643492, + 0.13318381284391104, + 0.020757877097614712, + 0.18195985067229573, + 0.1826025769344938, + 0.07871132598283377, + 0.24746069806739615, + 0.1773045402131875, + 0.04618152828700166, + 0.06851839681677757, + 0.03417827575568901, + 0.24653355505614805, + 0.20873736434363105, + 0.13845846850822835, + 0.04662940825244758, + 0.14177481456134228, + 0.14728505597329486, + 0.15207105807954538, + 0.0992973068172536, + 0.21127206186606814, + 0.21722036995710037, + 0.2727094845410803, + 0.11578148462713975, + 0.19944362142606864, + 0.16395781182868713, + 0.26777136001874646, + 0.03596323763170796, + 0.204427365896868, + 0.2521046584921667, + 0.2803574737244649, + 0.24259842127163012, + 0.25783198208800306, + 0.09269031163912946, + 0.2586943228931857, + 0.13377630914119143, + 0.08215997166738176, + 0.20727460821618512, + 0.2340557595827285, + 0.20343768862735165, + 0.27773579664674825, + 0.20009283403632458, + 0.17333440680840348, + 0.25564681024619484, + 0.08452882858182544, + 0.08699769897833157, + 0.08300416439133423, + 0.1813226337106974, + 0.2014078320623688, + 0.0775204976329323, + 0.22643751049794378, + 0.2144149867041298, + 0.15955727201755096, + 0.1857482629656314, + 0.26222861720174434, + 0.13465247456686225, + 0.10335166295871452, + 0.0775668834954069, + 0.042057581850934854, + 0.2068228008147008, + 0.22088441249632776, + 0.2641158837608712, + 0.10735438250065249, + 0.2899144760705634, + 0.17951198998301646, + 0.15668633968161422, + 0.20305332724561748, + 0.16333384772864284, + 0.1547767128624694, + 0.2747750624884991, + 0.25368313808379134, + 0.052255671752824126, + 0.1883218201459819, + 0.22650864093026918, + 0.23616831400449861, + 0.05978587627746159, + 0.174780055765628, + 0.2606174647966849, + 0.220631248611805 + ] + }, + "mode": "markers", + "name": "Samples", + "x": [ + 0.15922538196511846, + -0.10900632939266716, + 0.0671361065935423, + -0.08180018097217483, + 0.061578533789987094, + -0.10710366098657968, + -0.22995982283846586, + -0.01865850976860831, + 0.2829847892648814, + -0.08222804440191418, + 0.1177582974798366, + 0.21403505906730652, + 0.04792758358656712, + 0.07061753144140806, + 0.05227397165674028, + -0.009829305033055223, + 0.19718604957951166, + 0.21214605285722396, + -0.08497910921370218, + 0.2031659886881378, + 0.1610867848418781, + 0.24066029545401918, + 0.004875062188008638, + 0.1644554263815212, + -0.0033577537779625084, + 0.2898517706709398, + -0.2782851137377306, + 0.02158886465578794, + 0.06743287985559969, + 0.15127947478384987, + -0.2127979616468814, + 0.160617149919546, + 0.221878853323576, + -0.09046979040092788, + -0.036664141833864815, + 0.22572055716390865, + -0.16169428405594988, + -0.28723551765209626, + -0.050439918152217766, + 0.15307578767631316, + -0.1311611909909064, + 0.08428225840550436, + 0.16628402719240692, + 0.20715760660750657, + 0.01565634869863229, + -0.040449799531449324, + 0.1057200222516133, + 0.21382641209585768, + 0.07497979476756804, + 0.08766002904315567, + -0.08217531203141985, + -0.11037232084040324, + 0.03537535657726198, + 0.012460509341784514, + 0.04629409915803843, + -0.08689532835735075, + 0.2724379080176946, + 0.26187007459891004, + 0.26906398825919564, + 0.1222398757442418, + 0.29317796701389465, + 0.18536584463009853, + 0.15982879598323033, + -0.023722792999185158, + -0.22250923074243179, + 0.295502191409517, + 0.13482575466849267, + 0.26408965903869724, + -0.11849103991528129, + -0.018152368800660422, + 0.2490103953445099, + -0.2610622387565674, + -0.06417895539820855, + 0.06970426323834858, + 0.08565389517556714, + -0.21131097720289257, + -0.15716303216023655, + 0.2206749867945362, + -0.2625501595845603, + 0.10963830939061082, + 0.2960589697102607, + 0.29176382240079096, + 0.05755491734357688, + -0.06535209497329335, + -0.022050329028832007, + -0.2443273737755964, + 0.07902796769787501, + -0.2249325265245971, + 0.2525167044376563, + -0.2483658635991929, + -0.05369039612414739, + -0.08943833406062072, + 0.1382834874968196, + 0.1873757347074852, + 0.09253283721767497, + -0.2794087626853414, + 0.008653653245025131, + 0.019859828740914267, + -0.20113383263895793, + -0.15207187876898937, + 0.13634321747633768, + 0.0029850824755021546, + -0.007551110919426132, + 0.23358817130495108, + -0.039547071232296165, + 0.057042815654400884, + -0.1567333486440683, + -0.007376653752760635, + -0.20947627705966906, + 0.006169130893427065, + 0.14251582503061336, + 0.18509946915735603, + -0.20910188023489232, + -0.26679534317510417, + 0.2930805742201027, + 0.27624399363423086, + -0.2624437642393417, + 0.27664634723056586, + 0.0772053427113961, + 0.297562022807026, + 0.2639770992982363, + 0.27615654666071277, + 0.25027572892240463, + 0.17254401191685248, + 0.1475265785214961, + 0.1767991798947499, + 0.034280951754568266, + -0.12667314349176909, + -0.058899144546300866, + -0.1032792125003604, + -0.2733153964300344, + -0.011363522890988804, + 0.1765675548649226, + -0.0339123733318885, + -0.27054522176430457, + -0.1872853174558963, + -0.02111398184209988, + -0.06723074445013473, + 0.17154236291611816, + 0.022492343056204726, + 0.014166882810940808, + 0.19837032614858408, + -0.12807456935648906, + 0.1048530420940952, + -0.09708657525984288, + 0.11083362188411684, + -0.26390704499225526, + 0.04584207579272037, + 0.28878922546492697, + -0.016028372231859263, + 0.15733471813597555, + -0.22217962002163316, + -0.19312534512153012, + 0.15127514430609526, + -0.08109085196594473, + 0.10406083116038203, + -0.29116529017504367, + 0.2654500872336833, + -0.04760008236613555, + 0.25118600117294637, + 0.2581221584285026, + 0.2589922890436428, + 0.19483800382093197, + -0.1621611255181614, + 0.15603100258924463, + 0.29116261327318516, + 0.16532934721905831, + -0.1272507580217216, + 0.2854863563027727, + -0.14151387388514616, + -0.18334044400316535, + 0.26053274717138236, + -0.21712567268349925, + -0.27708392910663565, + -0.24165486861989838, + 0.006482137838351061, + -0.2873518181922631, + 0.10194790764246046, + -0.13993926909400556, + 0.1605980807978071, + 0.22255862832908682, + 0.03560373392696996, + -0.11798877787431966, + 0.058688071711300666, + -0.04894917653237209, + 0.07762304990841766, + 0.001034415536967533, + 0.07852259005656669, + -0.18936720845340066, + -0.18925493469620483, + 0.11062273531562981, + -0.0607479807801649, + -0.19489060907984107, + -0.18195083779581495, + -0.022975774558168394, + 0.19518159087257086, + -0.11266127624895411, + 0.1753390574974016, + 0.025396558945836256, + -0.04583379638602594, + 0.2528733960901226, + 0.28070953431962775, + 0.2626361105099272, + 0.2261853220685202, + 0.08192729007648368, + -0.26828404381916204, + 0.10939043207855152, + 0.1826817459306462, + 0.12636557729941356, + 0.18583506496055763, + -0.07961330638069498, + 0.24296193486133033, + 0.010648136697741306, + 0.19456274767954623, + -0.0638219611265556, + 0.004802899694580744, + 0.11740725715351731, + 0.08464522775339543, + -0.06949861813357254, + 0.2662699380256425, + -0.05259826407259735, + 0.03648734223863214, + -0.06318083524214539, + 0.004204231167902281, + 0.13025013310909284, + -0.185759549195025, + 0.16293351612258364, + -0.2549466231446974, + -0.27855454434537463, + 0.2940752082350832, + -0.06708830587064288, + -0.18234050445063676, + -0.28379994116329066, + -0.07350840936144128, + -0.22154783341666134, + -0.15575761898597412, + -0.003827000615576407, + 0.13020639942489995, + 0.12107139110462349, + -0.2740296877356427, + 0.2702283169782224, + 0.09330862970085661, + 0.07524615446361373, + 0.24235836020926024, + 0.09220400260732448, + 0.055480024443177574, + -0.15303685737151243, + 0.046742865052251385, + -0.16995845966774875, + -0.28418361243759366, + 0.2896318258922089, + 0.05356355500024789, + -0.1853071552039926, + 0.17637676297635368, + -0.13152811001108136, + 0.19385611675552972, + -0.1324903177540267, + -0.17055317318469476, + -0.23955631095821325, + -0.23479170090717388, + -0.1544148646421879, + 0.26939298146260493, + 0.25495193011511746, + -0.2935740925552608, + -0.20070028506713963, + 0.13742589591915857, + -0.29278864786032976, + -0.04140098471240295, + 0.08963449938695689, + 0.18514573440982451, + 0.09015480841748698, + -0.24202763483565862, + 0.15511108377164967, + 0.0849463865122343, + 0.15183660712951563, + 0.24888045724111052, + -0.11376105482085212, + -0.2044895169209617, + 0.1836078142262377, + -0.19435809203064197, + 0.1708216172983446, + 0.2992712180684638, + 0.09303328937628315, + 0.05716017427055961, + 0.19605736878450764, + -0.08476975661460807, + -0.25262087411184325, + 0.25512584920382814, + 0.278947639916905, + -0.2926852051276658, + 0.11362612034896102, + -0.10908826659992478, + 0.03777059648522317, + 0.11895686063379181, + -0.08020808430073559, + 0.03730612405313247, + 0.011820687660846095, + 0.09964546046712743, + -0.09983383786006249, + 0.23164866020543826, + 0.27109043132967187, + -0.20310657658439707, + 0.21663536322208118, + 0.05934675341194838, + 0.0808444950506623, + -0.16422210412630273, + 0.044176768388131046, + 0.2702451081939967, + 0.16756916365653646, + 0.15980186022354642, + 0.057984101472007235, + -0.11155652371850672, + 0.16972317332843845, + -0.2517087957249665, + 0.049399576030479155, + 0.016942524200965123, + -0.2982930462295885, + 0.2237503856990966, + 0.03637345494539802, + 0.10738829367715869, + 0.23326672916835023, + -0.1599265164952412, + 0.020009911758682268, + 0.02730521934255173, + 0.0876954498436078, + 0.2291169997249484, + -0.025049388079275665, + -0.04663628233394496, + 0.08518148021401774, + -0.20844174277006738, + -0.10017171770496193, + 0.22676100228620863, + -0.20849497517218182, + -0.07338914836765872, + -0.016610953631927883, + 0.2829338992085023, + -0.15695115650608218, + 0.2161525406683804, + 0.056629531072728785, + 0.11961688479589766, + -0.06860107632625437, + -0.01237200537032473, + 0.045442900490345405, + -0.26694526105468835, + -0.24435436913193403, + 0.09337916650012865, + 0.060562431320714864, + 0.292528880866488, + -0.16398573525479884, + -0.009170793962808727, + -0.059307325427851755, + 0.24096450625804353, + -0.16714774111243114, + 0.08830870212170168, + -0.07083637387345045, + 0.22625086695159333, + -0.15194903256535733, + 0.17591822515554925, + 0.19118596461833914, + -0.11424018225545698, + -0.2773106941933035, + -0.29549482032828833, + 0.08043617396333928, + -0.13534500534445315, + -0.09953093498110285, + 0.06211331506142245, + -0.03236194681394214, + 0.22458715126345605, + -0.07481257038889945, + -0.06787515809023466, + -0.15226003920619124, + 0.2768594160872698, + 0.17138592124601065, + 0.2328151998138139, + 0.14802229609259893, + -0.006423015770882544, + -0.2639778610905698, + -0.2885611401662585, + 0.29743535290255446, + 0.2466798149026552, + -0.03011407408186361, + -0.0030384101940072674, + -0.2962548664137789, + -0.16219420304945248, + 0.24176479384977684, + 0.07451528673142295, + -0.2663183410803702, + 0.006516260710793363, + -0.05546254109096842, + 0.1073678806206872, + -0.06351112560117965, + -0.05931433291073684, + 0.1352373819704667, + -0.17634199682854085, + 0.26031765173531507, + -0.11048766884470843, + 0.01554729634356836, + 0.10719889649417536, + 0.2644498841275547, + 0.10762740137226398, + -0.0829392434385598, + -0.2160058388762355, + 0.25652734606887806, + 0.025059173881566414, + 0.03919576736836879, + -0.12095259511006681, + -0.22099605593579363, + 0.15724169082188566, + -0.21112970478396637, + -0.019500415355618774, + 0.18779919481078194, + -0.0718593588901858, + 0.09059498661017626, + -0.20401960144260212, + 0.2190943722919673, + -0.21920695089984849, + -0.08598381634431664, + 0.25430682428406304, + 0.023254087828591726, + 0.10769905862181814, + 0.24049108739561692, + 0.14474308136573644, + 0.18224169940437301, + -0.21611390158484384, + -0.19238935234218985, + -0.14007877493046153, + 0.2033353936028325, + -0.007716908247911487, + -0.04783543825534772, + 0.09580504664389049, + 0.12341088727039856, + -0.12327683513105464, + 0.06112281368339711, + -0.15422672583643418, + 0.18806780760509992, + -0.25071866100788753, + 0.020231068859858887, + 0.23073604955492755, + -0.09575513873426786, + 0.07475540202418876, + 0.20124328273066994, + 0.21107464527702985, + -0.29920247570748776, + 0.21804945076198579, + -0.16418096906235646, + -0.15315698434935998, + 0.07139733377746126, + 0.2673467417160967, + 0.02378615529862173, + 0.02658962223108106, + 0.17376358039506154, + -0.08788418433063915, + 0.13800319181370507, + 0.0027610581815708337, + 0.09271679482389779, + -0.29435470287577353, + -0.16885562863496117, + 0.22800929622356053, + 0.17828176706368118, + -0.0387307834997224, + 0.2897599989015731, + 0.020373516762684955, + 0.13876737295972838, + 0.22946876942907163, + -0.20198801537474442, + 0.17276092888211295, + -0.19586561278121428, + -0.20063527869475659, + 0.17900589999622207, + 0.12239509791062583, + 0.25317020670367146, + -0.03934777665036646, + -0.17634270090265694, + -0.1708693313748781, + -0.24355769698789867, + -0.12022364442265468, + 0.1127238490669052, + 0.0267067662474895, + -0.07228620268361872, + 0.20757003473048338, + 0.1509086405168366, + -0.28530694935396805, + -0.19206492819347357, + -0.23261322282399122, + 0.07760208677191319, + -0.003495004526441464, + 0.2833091764882917, + -0.29206277930668423, + 0.07152967969466818, + 0.2819983907914988, + -0.0812746615558773, + -0.17644552159755836, + -0.2537922107676173, + 0.13062925615134266, + -0.049119350938817585, + -0.012116190963983647, + -0.21699274217283257, + 0.15192401132689673, + 0.14467755854484368, + 0.041587952784189204, + -0.2834336426381804, + 0.057840728546439325, + 0.19925332045332222, + 0.25380536088455297, + -0.05505956301012311, + -0.06562540605459305, + 0.25909276350723864, + -0.08696480637287904, + 0.19782896976637146, + -0.1558687240882059, + -0.11944863664110307, + 0.10309800972635885, + -0.11502520495136305, + -0.22819338787887583, + -0.035059582071881194, + -0.18555368644325018, + 0.07800465164986928, + -0.018196894321950183, + 0.22274996719674003, + -0.08612147919288536, + 0.27338341724136367, + 0.28660505682917237, + 0.12397118827218978, + -0.20444329759849597, + 0.24004037857872104, + -0.08155276229775975, + 0.04103741688228216, + -0.01178571606802319, + -0.24264537265319674, + -0.1059012960103217, + -0.03919978671111675, + -0.06295524626895743, + -0.2894039648758984, + 0.19692883362179486, + -0.1381597094471158, + 0.07091961441089967, + 0.024820484397231803, + 0.1648665811518924, + -0.09040938445353293, + 0.18221678041368491, + 0.045554714555968344, + -0.04717010312479808, + 0.03052345196120859, + 0.1310803593582522, + -0.04827105449361767, + -0.046043068201850806, + -0.20574184871736675, + -0.10279574022323873, + 0.09122767051357177, + -0.004749128783094745, + 0.19968980418223095, + -0.03868674582444769, + 0.04879377196502849, + -0.0335432025953111, + -0.04799256741979795, + -0.21746639833441292, + -0.08673178560454059, + -0.2006933489866243, + 0.0559481280217085, + 0.11734452795209005, + 0.2582893212102364, + -0.2428185781436054, + -0.12975840636623737, + 0.20058359576569232, + 0.11737779272617156, + 0.28211279194445466, + -0.1775397103244228, + -0.1698267635519582, + -0.038453730958611425, + 0.23475619830388766, + 0.1316274504116965, + -0.27274903802411465, + -0.11868782324218718, + -0.11771233867858669, + -0.26824370348310306, + -0.23666592041714302, + 0.015447245978521923, + -0.2663290253480373, + 0.016930145050442543, + -0.054224609876516124, + -0.17623783610018234, + 0.005112700949251482, + 0.14741626984510528, + -0.047023645558731564, + 0.03731589678191971, + -0.16240501079497835, + 0.1960075712144005, + -0.22162334239116815, + 0.26081891982833355, + -0.07739939022926143, + -0.06938686699422092, + 0.03934777888724514, + 0.011937955118116968, + -0.18473470905649733, + 0.16143913539874452, + -0.2813052542137018, + 0.1273126009289818, + -0.24475045298410256, + -0.033726886012660925, + 0.04312363151171892, + -0.05781880666094687, + 0.08002795643359344, + -0.17372306749215283, + -0.18315437928242015, + 0.13248405837161734, + 0.18258422636869956, + 0.256531586154641, + 0.22575782994238514, + -0.1630015539012322, + -0.1490164608090186, + -0.139975641570254, + 0.20039764141354904, + -0.29737027015825623, + -0.011196746861677973, + -0.27475781626140955, + -0.0889364367208435, + -0.22311175392941443, + -0.09853111880399865, + -0.006533146843983486, + -0.07353762548499548, + -0.21643030567642735, + 0.10488155942193085, + -0.25437885514834346, + -0.007037157295070733, + 0.23517513693762568, + -0.16687090942725827, + 0.2187090410828562, + 0.1756590816374262, + -0.02788663648378498, + -0.18891611784319995, + 0.13496661113147315, + -0.15831035929119808, + -0.2804922822389805, + -0.08685807996337286, + -0.02172152857934524, + 0.07288150757607373, + -0.06747144900246028, + -0.24035114210398154, + 0.027261973924337362, + 0.2619045574549215, + 0.1836341676682928, + -0.17779340156845472, + -0.004233618284031817, + -0.06573583541085373, + -0.20503132798419935, + 0.01403299627579829, + -0.24980937190808147, + -0.02836866959140438, + 0.14951268351749572, + -0.03895854454740389, + -0.08173079289147803, + 0.2010338696379272, + 0.007371960865726887, + -0.007496328211569074, + -0.17668002051777637, + 0.21804164166988507, + -0.17653088405677367, + 0.1214584773559999, + 0.07769229183550169, + -0.15125684435053233, + -0.21999596470165858, + -0.1351297424659423, + 0.17082318562369989, + -0.13945267902298494, + 0.11990887970019791, + 0.24582289471189173, + 0.2812765813246453, + -0.2933478271482537, + 0.07228334975213963, + 0.27747551954730704, + 0.09914373917947668, + -0.27138212364203906, + -0.08213396167716151, + -0.11761958428941438, + -0.16035926143507423, + -0.17776887619020745, + 0.03429528577867127, + 0.043925992093237755, + 0.17868662053981968, + -0.10625710735906704, + 0.28329181962511485, + 0.19460614443956045, + 0.1138034377829898, + 0.10466082094683733, + 0.2888344553937433, + -0.007092970240865934, + -0.2068945010185677, + 0.09187884618335382, + -0.06296321513868396, + 0.07764075392933424, + 0.1327678479359506, + 0.09156434391719269, + 0.16882844086200707, + 0.17864878075413976, + 0.1498350533948387, + -0.06397678214854921, + -0.053617531165496723, + 0.020686275880803677, + -0.16204855987939812, + 0.2659494603370818, + 0.2640428526454412, + 0.2591962105363545, + -0.035354663809445415, + -0.09344013698193068, + 0.2859977321956759, + -0.061109966356524166, + 0.05265353537771628, + 0.21028496283777937, + -0.02976959536413468, + 0.27258837407627495, + 0.08140756501083148, + 0.011443678363636332, + -0.23412387360631595, + -0.011038468104720431, + -0.2722422376226567, + 0.04679071096736351, + 0.160559007281159, + -0.28922455252658913, + -0.11183654336222149, + 0.03693481556858395, + 0.15751212450084634, + -0.09301276216018863, + 0.25184037634648476, + -0.21089829324171633, + -0.25243891750900377, + 0.09007962604839395, + 0.03874618944984715, + 0.203782820764916, + -0.1256997667624153, + 0.10793380757392236, + -0.07714121277706448, + 0.02921660430199562, + -0.16762319253987445, + -0.050474653571439744, + -0.1776051932284728, + 0.14720660230436222, + 0.06438672135200003, + 0.1494903642751695, + -0.19677277863888898, + -0.0457523508500187, + 0.17711367997955083, + 0.2837255406982413, + -0.016686709179510692, + 0.020776127561078647, + -0.09982652497024193, + 0.20564258438224492, + -0.24591513707165932, + 0.22800836616313885, + 0.20959831696221662, + 0.1522974479955524, + 0.19173772615109178, + -0.2454786262442825, + 0.2658368941311453, + -0.2250499927362206, + 0.2223507276273891, + 0.15849467764896485, + 0.017219325395554003, + 0.03215714435545877, + -0.09510526129369039, + 0.24335368340318986, + -0.11684062421584833, + 0.29211335056882237, + -0.11526515000598249, + 0.07111857805991198, + 0.12698042981205335, + -0.1315348125411252, + -0.20365732666064842, + -0.13995849067505078, + 0.15781055001906294, + -0.19158448704805445, + 0.2545395602075859, + 0.03449789886977447, + 0.2676559832506146, + -0.01799732126709371, + 0.2615839866374909, + 0.1941502601014192, + 0.05187300556182572, + 0.07288873729410521, + -0.26048820843020676, + -0.0539107528118207, + 0.2819604335396405, + 0.1951968453254402, + -0.14069182152018422, + 0.24304529325538243, + -0.08391845184652308, + -0.08894772458722135, + 0.059753002541296285, + 0.13385172990070832, + -0.11145937911464361, + -0.15932725955733334, + -0.1387188118226692, + 0.11880812453178644, + -0.013577303415451646, + -0.10028575493037753, + 0.29260846343957064, + 0.26592487057139735, + 0.0729191823577023, + 0.16897343849627278, + -0.07187587935694736, + -1.8576886672939428E-4, + -0.18620496837577952, + 0.09805818573999965, + -0.159508080962831, + -0.2075778046135607, + -0.13092539979034115, + -0.2706886417075702, + -0.06420882456395538, + -0.11989200528108349, + 0.08965142157071473, + 0.036191369016431156, + 0.13675699820520118, + 0.11464704321979456, + 0.298280515941897, + -0.2915297748149148, + -0.29895490842960565, + -0.00909692838848363, + -0.03846610149443339, + 0.2948282626787407, + -0.20287022792807954, + 0.2257628946695416, + -0.28844887347226417, + -0.20810800175677294, + 0.08226817126755609, + 0.004352974661682879, + -0.024578917884590497, + -0.1661327249504877, + 0.20479549672346928, + -0.10826119721281383, + 0.04318260156337155, + -0.2565637495136715, + -0.09346127479343602, + -0.05235748392036066, + 0.2922802804128211, + 0.05832198517714014, + -0.2457584094719911, + -0.0848444259044726, + -0.16507180131741825, + -0.1386315608238764, + -0.2551392844309313, + -0.011623920395739402, + -0.05532827543107057, + -0.12628184525396183, + 0.052918651842936044, + -0.29729799329304846, + 0.26082022775202607, + -0.21692178356557462, + -0.28039381252824663, + 0.05333242477222427, + 0.0758017531025517, + 0.2126491957316969, + -0.2639056681572746, + -0.034115576326049744, + 0.21752001726085993, + 0.06434220221814324, + -0.23540409105769763, + -0.1642857537576837, + -0.05871357189862046, + 0.1562851996599551, + -0.13305884480993238, + -0.14144382437806657, + -0.08258943181055575, + -0.2087152873795519, + -0.09628417383114732, + -0.09396280786793765, + 0.23759868366380765, + -0.09842051975978378, + 0.1426413198938961, + -0.256263205175265, + -0.13023311841188007, + 0.18367166171497015, + -0.014544526623362043, + -0.037594357363016334, + -0.0880164830648845, + -0.20525341485170853, + -0.29596279784196794, + -0.1997170840479388, + 0.18642651481552638, + 0.11234593524266262, + 0.18638248270574126, + 0.0515041312363921, + 0.0029128219319029505, + 0.28225530529714554, + -0.04812710609796596, + -0.29195443045164027, + -0.1732580026140346, + -0.020027736800481862, + 0.061067226969168956, + 0.1590032647430508, + 0.1444251290525204, + -0.06318185558126901, + -0.29456275383940106, + -0.024287771457435256, + 0.22558872695833415, + -0.28505748403755665, + 0.29015960212193037, + -0.04302575283731248, + -0.22758789876132912, + 0.160296040603921, + 0.19033484966578298, + -0.05524608466756932, + 0.25327286386555387, + 0.2478274843297765, + -0.13203672486356843, + -0.20195504491958227, + 0.16945687809467372, + 0.23144322653059207, + -0.2589524766019729, + 0.15115570510006546, + 0.19692471214791646, + -0.07725740659703725, + -0.043714262071513854, + 0.11793639530327207, + 0.021395766343625867, + 0.24883423356686907, + 0.09095790523671209, + -0.07969341772845717, + 0.20234943998096921, + -0.18696276606451726, + 0.1377140666843975, + 0.1309816238952388, + -0.004179770152917327, + -0.04972061545815932, + 0.13782428135217245, + 0.22319773219585817, + -0.26365653674916245, + -0.03568997403043396, + -0.029062022788515128, + -0.063327975052939, + -0.06627435746142155, + 0.14121638797241473, + -4.2657237087075897E-4, + 0.21438350100991652, + 0.23686385136929594, + 0.04595019381968933, + -0.298246940621892, + 0.13926211767887198, + 0.03577434625789343, + -0.022520225477257814, + 0.29515648494199354, + 0.017089166891028046, + 0.08958993804490077, + -0.005069742904723684, + 0.2970992652700244, + 0.1236373697880785, + 0.19422815254164333, + -0.11240726706143377, + 0.13642981216666125, + -0.08917297775566796, + -0.02334945215484893, + 0.2097970220259686, + -0.2665446137996673, + -0.2598493540138736, + -0.11194343995470978, + 0.2892886677329639, + 0.05465952555047612, + -0.07205498320483104, + 0.26765218184923817, + 0.022346389696027962, + 0.1471404402244773, + -0.22361969265615989, + 0.23659460736653765, + 0.05126400947598367, + 0.1821443609569353, + -0.15399445727546368, + -0.1682491205719939, + 0.16611177364577676, + 0.1818065916195569, + -0.2863877625879325, + -0.269615573347901, + 0.04197310404486775, + 0.043006156149429466, + -0.08030922371248887, + 0.1871662181296577, + -0.11178308709996797, + -0.17410003694498918, + 0.12110363379270037, + -0.15895677268330413, + 0.14912931267666094, + -0.12580059218899448, + 0.04373030102415428, + -0.1573626798975654, + 0.13816537421191338, + 0.06866798844558578, + -0.15654642073451516, + -0.015427412816619267, + 0.0419119220043353, + 0.13386936105216285, + 0.1160968151702895, + -0.1872296079103012, + -0.15949470555587889, + -0.009781580071081476, + -0.19344098789742534, + -0.12072733316860908, + -0.052337191481686245, + 0.2686471934847177, + 0.17655186583734644, + -0.16253136469771676, + -0.2253663714508, + 0.08762153414285673, + -0.035991424485876854, + -0.06524999258377916, + 0.06237986733627737, + 0.2808537888248608, + 0.25954929867457666, + 0.009278825696265394, + 0.22014506308528042, + 0.28649412645443195, + 0.12449723265322225, + 0.27918567641306463, + -0.016859401845710466, + 0.1692944623957262, + 0.08959926064939869, + -0.15308852675218945, + -0.003913664196340598, + -0.12597941055183595, + 0.23349989412961467, + -0.27056262929079966, + 0.03872080731756947, + -0.19000476448706158, + 0.2644035495157382, + -0.14312128803217827, + 0.06787914164209218, + -0.1617917564028234, + -0.14796487385930485, + 0.14109692338375, + -0.1657811284823217, + -0.2356455592988266, + 0.12140096390747196, + 0.1226694525931418, + 0.08452613909115338, + -0.08029464229262197, + 0.2461185736797547, + 0.258527226622412, + -0.29329813473606736, + -0.09299804316141891, + -0.06448672744381338, + 0.27634129638651717, + 0.10841260047353841, + 0.01907933862405047, + -0.24607102374096396, + -0.021426786202228168, + 0.061433617887197825, + 0.2586388711137581, + 0.28720566992616353, + -0.03916260970802068, + 0.20914960160299087, + -0.22280992068071254, + -6.838382759255282E-4, + 0.026316268021308816, + 0.05986189977522727, + 0.06901459719682682, + -0.22409145431370614, + 0.1344055011310801, + 0.01240514705237498, + 0.047218911660629324, + 0.1761344267110714, + -0.2446271507584217, + -0.12777730459684802, + 0.16032586874131105, + 0.0484322074413153, + -0.008780924949725915, + -0.2189593011795935, + 0.27036347894271723, + 0.2074436142523902, + 0.03201149254601311, + 0.07469005990119243, + 0.07690200595432639, + 0.25816367147291613, + -0.042463196138421325, + 0.06740553998138439, + 0.17727148810296198, + 0.07629333039471572, + -0.04283550548281631, + 0.1739526866716068, + -0.05335274519209605, + -0.16518689671380032, + -0.029400178834870797, + 0.21556776327224153, + -0.15274771262816425, + -0.057162692229220276, + 0.053938199639096254, + -0.19853297857402402, + -0.2895924561252049, + -0.14693187960413226, + -0.0863264314110623, + 0.23538976306011475, + 0.19092535105099154, + -0.14190193796426795, + 0.11036158443996269, + -0.00790995663043666, + -0.18015235647684372, + 0.16442455013527923, + -0.10358007660372028, + -0.11849716911294465, + -0.12177048884146442, + -0.015852817308309904, + 0.01592968724163312, + -0.1462046435268412, + -0.14007072179014574, + 0.023684197491069564, + -0.019418691876015425, + 0.0461915319938319, + 0.25070718076959786, + -0.009911985806405295, + 0.13433964443901678, + 0.13826627002855432, + -0.04826404741960722, + -0.06676412682558637, + 0.24262439451389273, + -0.14870314688281627, + -0.11901846279223655, + -0.25137862114046383, + 0.199163446939798, + -0.286707333565076, + 0.2359920515905854, + -5.778206730702705E-5, + 0.25934571695053943, + -0.25589746102775723, + -0.14618073088955547, + 0.16990957121639017, + 0.2874269065164857, + 0.22589770299024314, + 0.25753804781822787, + 0.2796987573354492, + -0.2566313407690688, + -0.2149816691074459, + 0.2802688826378672, + 0.14567580587076018, + 0.2308576064588993, + -0.26483933133012133, + -0.06473716192764346, + -0.08435146371301055, + -0.14855107897265715, + 0.12068025963850636, + 0.20047662439409708, + 0.12176912739667875, + -0.26443237009160725, + 0.26804468932306924, + -0.1875380856112239, + -0.10509411446614918, + 0.19948248247319092, + 0.24148821565367243, + -0.02029129476389144, + -0.05486987770122042, + 0.024676335853540742, + -0.14265139918551517, + -0.2463622903983552, + -0.1200776171735749, + -0.2894179873066176, + -0.04416647389830224, + -0.0150611182221623, + -0.019694271389707623, + 0.008150669659220056, + 0.1665878407824695, + -0.049301830551083815, + 0.08948790917845485, + -0.24007558305088025, + 0.209911027562731, + 0.0851590331373912, + 0.025199589612523422, + -0.2817762579786668, + -0.17495382303269574, + 0.18831633178912013, + -0.16071729315369213, + 0.2455120605579199, + 0.0871866111090259, + 0.0745274490173754, + -0.06117121372934435, + -0.12351841457265812, + -0.11766556644227148, + 0.04722614143171007, + 0.07658077504019387, + 0.11585470125425353, + 0.13502589236548057, + 0.2336960098188973, + 0.05331768300326811, + -0.12523222880949395, + 0.041450205329529095, + -0.12870804391780216, + -0.19460342615534404, + 0.08729375444011675, + -0.19721027697118362, + 0.07714696214731231, + -0.28152831249803223, + -0.03558852288640485, + 0.11734160638184571, + -0.28049174079877326, + -0.07262404224220434, + -0.15346163285248035, + -0.17782141979585947, + -0.09348821574319484, + -0.1578564046387697, + 8.809956566865067E-4, + -0.13688916845527732, + -0.007496892064939216, + -0.030954282390134494, + -0.010721841897079972, + -0.08727138469361645, + 0.07025915172045973, + -0.2651733315347826, + -0.022695829172829366, + -0.17147766019730584, + 0.007116274092766101, + -0.025476971555499564, + -0.22195902542916987, + 0.22208756408147765, + 0.1390129178510172, + 0.28073338569270284, + -0.1765830133764129, + 0.18343635821451781, + 0.0971217087418104, + 0.007965056561661849, + 0.10542832568055245, + 0.10025292781661281, + 0.01817786673204376, + 0.22314005004721887, + -0.19905655916088233, + -0.0078114722075646945, + -0.22563975405102205, + -0.17423188007585644, + 0.1949575248464513, + 0.040442001308472225, + -0.17046993175503805, + -0.24858812178459502, + -0.22937780539836453, + -0.24655523715168146, + 0.11036991339165553, + 0.9637497250658765, + 0.37439152546584004, + 1.0253627675661883, + 0.8801878544902934, + 0.4580119467771612, + 0.5933837479721088, + 0.870059040916167, + 0.5164632891090156, + 1.1787329201075294, + 0.6372054072772395, + 0.3552626862242948, + 0.7300716957108782, + 0.6552693165453213, + 0.5987430332484402, + 0.5047194894394501, + 1.1935910949216786, + 0.6388030442932592, + 0.4555197532879503, + 0.8751568213502022, + 0.6324922294152369, + 0.8067446512208091, + 0.37651009299931787, + 0.4562804208431067, + 0.6906267954384943, + 0.7123936352549433, + 0.32125297706786565, + 0.507461322884648, + 0.44064709530670776, + 0.3452098396281929, + 1.1390881204217762, + 0.6106833420282519, + 0.5816543784514485, + 0.4123921383263966, + 1.1681240594648659, + 0.9532349945614176, + 0.7923951878911891, + 0.34028878259069856, + 0.32084240358481814, + 0.3280642874801967, + 0.6507894699293758, + 0.3420778019939399, + 0.5408153917377354, + 0.9901077959442245, + 0.6478116081689134, + 0.940497491439847, + 0.5701086911459994, + 0.62801056041149, + 0.4339303611722616, + 0.3546294457760096, + 0.4608913349854312, + 0.4385583702813049, + 0.49747434123029904, + 0.5894183433520922, + 0.5556882522471863, + 0.348144945666397, + 0.8228318270587429, + 1.2910671880905948, + 1.0612429937865506, + 1.1918862192417594, + 0.8628947196569019, + 0.32814061806356226, + 0.38755944082325416, + 0.4790309524916709, + 0.44762870554208317, + 0.6783402532968317, + 0.7563598374443531, + 0.5245206749310929, + 0.44123561639264447, + 0.5814625876924568, + 0.739056176189108, + 0.5347949222154795, + 0.35098863660134, + 0.784715376972858, + 0.3333600975326182, + 0.35877986077618024, + 1.0402780650867451, + 0.6530402413154465, + 0.4433443230726534, + 0.3361209076538193, + 0.39062098361645964, + 0.4353415393159647, + 0.6279178653520348, + 1.2823612176116732, + 0.7339375253520293, + 0.6616149625885571, + 0.5555681962163987, + 0.43944083221625163, + 0.5348699696790826, + 0.6548485748843214, + 0.8650504248822237, + 0.4090697563500463, + 0.4035427060593178, + 0.6641503703551099, + 0.42875189957661225, + 0.6034959159482429, + 0.45984857767180176, + 0.35832781178489576, + 0.48772733482699, + 0.3172423629917707, + 0.5556024070202528, + 0.4287461075439393, + 0.7999272496316654, + 0.36264271577320173, + 1.2476604748387448, + 0.3774419364703851, + 0.9831541029250522, + 0.42046146924543426, + 0.40854882984734175, + 0.6304267043989596, + 0.34914935550512455, + 0.6404818936667408, + 0.8987397207302404, + 1.1812123022784946, + 0.4012272599789458, + 0.715010116710167, + 0.5126533900767326, + 0.3225677439313108, + 0.6737332235067357, + 0.3143135192375102, + 0.32772297776716686, + 0.4869118543173932, + 0.4681329994771701, + 0.45324555107056996, + 0.6894856912024342, + 0.686807745606591, + 0.8121039307933318, + 0.3558962468845341, + 0.5954893298838247, + 0.9550192435917074, + 0.3968383271352944, + 1.0047722734291813, + 0.601613904315484, + 0.9933974649494535, + 0.4987701328303148, + 0.4215965927163117, + 0.5145629854891186, + 0.6670624792711534, + 0.789961133218301, + 0.7173399803647331, + 0.8055954045014591, + 1.4554295263711978, + 0.3590869005870154, + 0.8718270603993096, + 0.49325069552647766, + 0.5008743774851406, + 0.782634180127246, + 1.0057818405065806, + 0.3752241471030757, + 0.40590856845049406, + 0.48990314012031877, + 0.7654095487399009, + 0.30079857307335006, + 0.842614960806863, + 0.3817594098555301, + 0.4403909261140591, + 0.7387895295713117, + 0.5779605650383779, + 0.7019711273885483, + 1.3755154108121217, + 0.3494017608061006, + 0.8632187821658703, + 1.1628365272003205, + 0.7126310100849559, + 1.0155320898682971, + 0.6461282797405483, + 0.6527122551151332, + 0.48304315823018446, + 0.6897618751833883, + 0.3942410854496715, + 0.6230300578082992, + 0.7047819489479165, + 0.4713216030344645, + 0.5997109765286138, + 0.7447533233780903, + 0.41208660321013696, + 0.3300507627950668, + 0.36386232393176515, + 0.8331056900642524, + 0.8575008632707365, + 0.554992498623033, + 0.5278981288861758, + 0.5390949699797161, + 0.871137803070785, + 0.5021081237562882, + 0.5734320463047702, + 0.840176073476798, + 0.468993930826125, + 0.53309261833061, + 0.34107200922858966, + 0.8507009893078139, + 0.4860429818919641, + 0.8994093940282349, + 0.3356260370306133, + 0.6210054996764088, + 0.6541362083653638, + 0.6960554950700194, + 0.5174052870790653, + 0.6444020447357851, + 0.6914401380121147, + 0.42414696178380795, + 0.34718233891966593, + 1.1128681166666727, + 0.7230589723106042, + 0.308699580922585, + 0.5062445938517246, + 0.6649719520199067, + 0.6281096304179224, + 0.5408120521887222, + 0.38071553529518076, + 0.35516116303541856, + 0.8734484607183176, + 0.5888600039416633, + 0.482644168309403, + 0.4311342855172164, + 0.45698992239164865, + 0.5819373680533901, + 0.41767016791308254, + 0.3673689162669231, + 0.8936942343003784, + 0.326209025181563, + 0.532059151055968, + 0.6845019628627832, + 0.30457769264562035, + 0.5325801444708534, + 0.34690818003167695, + 0.8313108107608361, + 0.3035775020265102, + 0.4198132574885354, + 0.8669490445639589, + 0.4077403642974495, + 0.5418592033445839, + 0.7703282537159228, + 0.35466828715971566, + 0.34908879703613493, + 0.3387191343582057, + 0.5633905130392146, + 0.5528332969827697, + 0.7016069975877788, + 0.3293183193267729, + 0.6741703798765933, + 0.31930194986814225, + 0.5964073587600441, + 0.43734029859596074, + 0.4872081095123795, + 0.3007931571786386, + 0.5284620582377783, + 0.46623571898551197, + 0.3943201504811138, + 0.3332609832228382, + 0.8369269935389584, + 0.3602509062918994, + 0.6697896105119134, + 0.4613094933101247, + 0.5038829730515867, + 0.4653871778168942, + 0.6343532566965426, + 0.3497880230115942, + 0.7515192341677057, + 0.621124612515432, + 0.5455901695911035, + 0.4461346820919793, + 0.8054574336827064, + 0.6825641811327063, + 0.8990213947396996, + 1.1429351925862121, + 0.9111160424630923, + 0.7159029689935367, + 0.7713743170083446, + 0.3646131655856102, + 0.7016431843514411, + 0.3124047617208024, + 0.49011790242088604, + 0.4711554354559574, + 0.6876691793024635, + 0.7155778628488364, + 0.6499461594858837, + 0.7912015188971898, + 0.5229423609682766, + 0.35263849721669543, + 0.7810483470638135, + 0.42203075356945885, + 0.6377770511177667, + 0.36082806572167236, + 0.307427884477191, + 0.44228204548911404, + 0.5992261152993008, + 0.4462965268234662, + 0.8638796467602913, + 0.5976837910293127, + 0.5410476973595273, + 0.6779934552685445, + 1.0168082266148215, + 0.5003446277290438, + 0.4562049149707794, + 0.47893044878375324, + 0.5143466798786638, + 0.6394794937502852, + 0.855382574625903, + 0.5428700498278378, + 0.6406253197371047, + 0.49118787045653967, + 0.8340676101771841, + 0.4713542352472427, + 0.49023535281028097, + 1.3798744031848382, + 0.4089453267548538, + 0.9734953325910141, + 0.7775825504707581, + 0.5272282492349195, + 0.8954107658686028, + 0.6776834633634531, + 0.723515641994345, + 0.5224580844791658, + 0.47940527316880954, + 0.4852804737829124, + 0.5934846307020755, + 0.6668603088448218, + 0.4350905111152129, + 0.4940671006425421, + 1.189563455601881, + 1.4326420862545128, + 0.8103180261270398, + 0.5267529715859517, + 1.0051897404402974, + 1.516695288638894, + 0.494532568346687, + 0.9029060882171372, + 0.4777831635769977, + 0.4213084884743307, + 0.5534347943880402, + 0.7252322616856397, + 0.5552337174922014, + 0.3017018432408101, + 0.40981761438900927, + 0.41876105443615813, + 0.5715040899175233, + 1.0091513554956875, + 0.7332796775202988, + 0.5002902361127571, + 0.42366866667468034, + 0.4499249715651633, + 0.49147990663842717, + 0.8795707651951669, + 0.8719925137408935, + 0.606121880782316, + 0.5020014441108361, + 0.9909774067950189, + 0.5957924888826494, + 0.4588211975261476, + 0.31905411849493415, + 0.3106591751736872, + 0.43330839410453753, + 0.7595568454471398, + 1.0347288144072588, + 0.30289297135486565, + 0.5684862224229683, + 0.5187593176030372, + 0.4191412473582581, + 0.3348159832741211, + 0.34010175767206463, + 0.503555963120378, + 0.6867883462373429, + 0.8689013740953219, + 0.3760417747804243, + 0.7927762070324734, + 0.3702396786848435, + 0.5446009788128635, + 0.7149456451179739, + 0.43814500773329484, + 0.48080909328620114, + 0.33366786078909355, + 0.3470938787580587, + 1.2134170644533082, + 0.37925508300210153, + 0.5072724599154276, + 0.9296935515086455, + 0.30541692793483405, + 0.3638528116881168, + 0.3904876151400703, + 0.4533227074855644, + 0.44739303578016076, + 0.5824929505604942, + 0.3161277976045243, + 0.5705737033541967, + 0.31871379895401225, + 0.34858152769013834, + 0.5877269694930496, + 1.3940041620378043, + 0.33574592372670375, + 0.6555413881229114, + 0.3490319190857379, + 0.7073016494802669, + 0.3688632097432938, + 0.36718387147756704, + 0.4558465632142712, + 0.8017293389960696, + 0.5718529017222397, + 0.5638347985215719, + 0.4388277166181953, + 0.4043715126726043, + 0.5311263474256104, + 0.5534241030250153, + 0.47463828717359813, + 0.9403503879212847, + 0.39263071483916046, + 0.5067602591132221, + 0.3119704621208126, + 0.31464737839879225, + 0.5617442149078687, + 0.7096047510446042, + 0.328096225847771, + 0.3528234083721763, + 0.4545192048277013, + 1.2239528014762988, + 0.4345145844722871, + 0.7943708710236237, + 0.6102020372873519, + 0.9568904515481856, + 0.7734386847519679, + 0.976894395949379, + 0.654323999336481, + 0.6159068837574708, + 0.4011649952749088, + 1.056070873945403, + 0.6698212372972328, + 0.5381160489961783, + 0.8503012076574463, + 0.6803459218705544, + 0.939988439113859, + 0.5258758590165215, + 0.5868033138763158, + 0.34231360256214244, + 0.41420352902962504, + 0.7931723818540322, + 0.4438146881332915, + 0.34437357798238566, + 0.9459790364859677, + 0.409971659958607, + 0.37648370673855974, + 0.43574674054536044, + 0.5439662976762252, + 0.5463110280582484, + 1.27532304786349, + 0.8700776478179844, + 0.4826840779677054, + 0.4118120411364431, + 0.6908133617470614, + 0.72919620036148, + 0.5258880950264679, + 0.8281367100610751, + 0.8865407470829126, + 0.4348374041957573, + 0.5658879075239088, + 0.5652022086143927, + 0.44996958770599055, + 0.41495129220093907, + 0.5746566900183648, + 0.37862369140025665, + 0.31972107105617537, + 0.3780991662784728, + 0.778577707640942, + 0.37452133573564844, + 0.6194402667415476, + 0.8294825603469154, + 0.316155833914874, + 0.7504787262736599, + 1.3892891340991607, + 0.4712038363954712, + 0.6928328484740819, + 0.3853407774836594, + 0.8473710130281505, + 0.44781366181859283, + 0.7732579335205377, + 0.6690372207215609, + 0.5962225361401828, + 0.4760070322176302, + 0.3745205268128759, + 0.45431551982513546, + 0.8597870987579899, + 0.5457421952573008, + 0.6995359738998833, + 0.8388721018842564, + 0.49135106479646845, + 0.9964924136410249, + 0.8145626074074495, + 0.3741854612076564, + 0.6278838646858385, + 0.9437992037764446, + 0.4746011127102984, + 0.31467745089252047, + 0.4270528378838061, + 0.8422706958416255, + 0.4672822266396729, + 0.4248519148740906, + 0.502115290336549, + 0.5741579698127798, + 0.8273249226385796, + 1.121930385193414, + 0.8852912057343935, + 0.8228058582460676, + 0.3034571871727749, + 1.0396724596610207, + 0.875805610736765, + 0.3479197548438209, + 0.6857369873532266, + 0.30654004605818214, + 1.065757334034588, + 0.6776406042622338, + 0.41532401228889426, + 0.7611847201641035, + 0.4345251825972486, + 0.30493147488389205, + 0.4626584290795239, + 0.37363972737224355, + 0.7605733056811596, + 1.227830678417581, + 0.6393662272286502, + 0.5385969192116469, + 0.7882967353419705, + 0.3155057926247342, + 0.5010617922636942, + 0.3948316030885205, + 0.3746177251615387, + 0.6976513830392089, + 0.4686857383229899, + 0.5117987396070943, + 0.4755890388817152, + 0.5182897339023461, + 0.732422218074913, + 0.44352093989125135, + 0.35711974632111065, + 0.5819066615266207, + 0.806933418499264, + 0.9733072132395648, + 0.39672396857358244, + 0.9812217024681534, + 0.4029053464666203, + 0.33037611490227725, + 0.6428697124339143, + 0.3320486815347384, + 1.006682822131604, + 0.43613069578722335, + 0.925160712577854, + 0.4636368422807474, + 0.5280185740997749, + 0.6326534186612446, + 0.3593930417789375, + 0.7074646047656821, + 0.36885376326566527, + 0.9320416473815636, + 0.5094460763459749, + 0.7371271522963524, + 0.3514411692837866, + 1.0241900708843952, + 0.35757895095376274, + 0.3903884755405625, + 0.3190099633393905, + 0.6435531833407224, + 0.4399367260973652, + 0.6599462621407486, + 0.3362635542381754, + 0.43995455266552685, + 0.500916402355216, + 0.38550020325504786, + 0.7585400144479829, + 0.5972613343705061, + 0.408351815628294, + 0.31638772015911326, + 0.31693924006799706, + 0.46349958038703815, + 0.38136752114146166, + 0.7344211944195437, + 0.811121316826974, + 0.6794404082175095, + 0.8036388176145528, + 0.47797779449199224, + 0.6497221036926395, + 0.4110757340329621, + 0.4033646985044663, + 0.8811481988651266, + 0.9090038891046676, + 0.5039541114722093, + 0.8624897826255401, + 0.40145757936095067, + 1.051655883783268, + 0.38722732368131685, + 0.8084075249095726, + 0.9134667979101029, + 0.40787886227432474, + 0.32718576991584614, + 0.44495933081858535, + 0.3220606104991281, + 0.8006757682863876, + 0.3861599998326034, + 0.33311798969514783, + 0.7607320632393233, + 0.4780568040582003, + 0.6925447860958996, + 0.8975227506328395, + 0.7086406123506999, + 0.41295023397954644, + 0.7312428433229385, + 0.3674165798665417, + 0.3480293787599122, + 0.527207265067558, + 0.5714533938653192, + 0.3370495523555764, + 0.5269319928159965, + 0.5344341524243256, + 0.30893051510588865, + 0.44628522821510963, + 0.547754314904091, + 0.6435255400711717, + 0.6067793821730837, + 0.34483020709978646, + 0.4712865656791496, + 0.4670266752306906, + 0.49234150906296914, + 0.3478354390624323, + 0.849632933453736, + 0.7699393668050065, + 0.4531365168877361, + 0.5037884413488686, + 0.657564946791937, + 0.5977277329918863, + 0.3609161418521626, + 0.619659123653819, + 1.0554669075759335, + 0.5493112590250986, + 0.6996543151665856, + 0.8636406734586077, + 0.6155444413042274, + 0.388636641368971, + 0.3661130057839285, + 0.5143636132140345, + 0.4881517807380524, + 0.370415481460058, + 0.40713781461796206, + 0.6271308130415674, + 0.3207594111855909, + 0.315928105489774, + 0.39361176300739387, + 1.036228678111548, + 0.39182080744875675, + 0.8066531839281653, + 0.9193884088712748, + 0.489724729376382, + 0.7074623932835655, + 0.4692287394987099, + 0.870249805997725, + 0.6970653321194941, + 0.3201476944840356, + 0.5717832445032667, + 0.7093636374248935, + 0.7784505704301962, + 0.620941077270866, + 0.9998659730267192, + 0.37766125601870004, + 0.6675480611708979, + 0.6241148353008349, + 0.6939075835199106, + 0.5251837227226581, + 0.5537595021747852, + 0.6874385400122539, + 0.36906048174813244, + 0.9736896761323086, + 0.8485050320598563, + 0.35311732143303615, + 0.5473492549670913, + 0.45844682320410673, + 0.397961449985774, + 0.9249501485129408, + 0.43969429918375014, + 0.6616838172368844, + 0.6396860315281686, + 0.5359773773634505, + 0.6510253519489504, + 0.5796390900340908, + 0.8576387150781412, + 0.701674141807197, + 0.5243078839221355, + 0.46459748123064826, + 0.8129237654652052, + 0.3960074042022859, + 0.5107283778715416, + 0.41964743182413916, + 0.34170587056232926, + 0.5649071337148088, + 0.47069001452438225, + 0.5762557204122573, + 0.40349823089659076, + 0.6500506447587114, + 0.8985878360522861, + 0.548982119854672, + 0.6847731076786484, + 0.6269670114378026, + 1.0572468604786818, + 0.8439621349162608, + 1.5396624734527167, + 0.3720129447236681, + 1.086480965192571, + 0.33540371389479723, + 0.3867727363881359, + 0.8426538150242255, + 0.5867423751899623, + 0.35547713443859014, + 1.0613948790418783, + 0.7723246563673352, + 0.33508903253343464, + 0.7192706241135682, + 0.8554590896505606, + 0.37340460789374197, + 0.7398027315295079, + 0.37886460530588484, + 0.4401829654924351, + 1.2391123854749535, + 0.8974815776238105, + 0.4252715289215427, + 0.3232863404453896, + 0.776302381785428, + 0.3866550953137896, + 0.7067701928214342, + 0.6358518212359641, + 0.30186283045401047, + 0.6214380740287465, + 1.1499215464582084, + 0.5541668892757119, + 0.3833798169591441, + 0.49543921271308533, + 0.46532810983422346, + 0.938316477849709, + 0.39391952589350016, + 0.6470898556807951, + 0.6271186647645121, + 0.40995900317165535, + 0.3501323780878483, + 0.816623058957621, + 0.4507686060510346, + 0.4210300507775448, + 0.31890854190570805, + 0.3669112179189202, + 0.3154487541800741, + 0.5070240265163858, + 0.708485785209362, + 0.33660121295516415, + 0.3454341579388302, + 1.3346147961402497, + 1.135979802471813, + 0.7436220594333813, + 1.0054852126538223, + 0.4600782099227869, + 0.6684571428535769, + 0.8996625612122953, + 0.6735907893136867, + 0.42835685800149625, + 0.6924549416166179, + 0.40371690422257717, + 0.6493615204174678, + 0.6432440941374411, + 0.3837424343434788, + 0.4799761593272947, + 0.6923999694687808, + 0.5703396992865064, + 0.5887405609130257, + 0.5459712272088975, + 0.36604357919993735, + 0.45494934689073446, + 0.5418035650313525, + 0.5585050106017768, + 0.4263034044601889, + 0.30783935836293463, + 0.47537136007482206, + 0.9764485275437795, + 0.3198710250169517, + 0.6792017610965251, + 0.45170343888707437, + 0.6244711443285168, + 0.4992004835903743, + 0.3093071465667814, + 1.2319877106129105, + 0.7184177504227086, + 0.7841463751928657, + 0.7157806904415328, + 0.6022027678264439, + 0.5479334943816984, + 0.9947590775829908, + 0.34138351250858573, + 0.6352117339764377, + 0.32520999651872445, + 0.8749816489301657, + 0.3890896915997894, + 0.5469444059055688, + 0.8129743654707975, + 0.679006612648992, + 1.7659659019161686, + 0.6792500417392007, + 0.4307109289604428, + 0.42109224308452187, + 0.8042807918839127, + 0.34772569065287406, + 0.5214272442815432, + 0.35096108784163466, + 0.4282689484194858, + 1.026490503148184, + 0.5944051268475498, + 0.3269072095060966, + 0.36289374865032564, + 0.36001462960725833, + 0.3239464609267388, + 0.4841543928524447, + 1.041755628448255, + 0.3251695757562171, + 0.43156282798357287, + 0.55081505528678, + 0.42290181350031975, + 0.31547975372235204, + 0.49193213243988565, + 0.3005506972157189, + 1.3206529674836678, + 0.6363066993945742, + 0.3785656597373017, + 0.5587204056571987, + 0.48451417705347766, + 0.38942212011923155, + 0.4410745620907406, + 0.6732156477607123, + 0.4811186452342444, + 0.9858382299725538, + 0.6890133869830147, + 0.9171821418079672, + 0.8303476733982035, + 0.7009389713977316, + 1.4033463136152677, + 0.5907712783228926, + 0.636070390882299, + 0.3425400273489041, + 0.4655145437167862, + 0.4704207525321032, + 0.8984390673171352, + 0.8901383847807903, + 0.3876981586885459, + 0.9240625157834514, + 0.8058076578730593, + 0.3001505098341895, + 0.43466407712328703, + 0.5453780590743365, + 0.4186379699892371, + 0.6708565254854871, + 0.8977587619103301, + 0.7662604655251846, + 0.5780700742686408, + 0.9330040797922573, + 0.43509767797480037, + 0.5905599670800805, + 0.6300956407165031, + 0.90490193231616, + 0.9086383221931733, + 0.42160370173554823, + 0.5565252358110274, + 0.7658638177357842, + 0.7718125769121816, + 0.44147512952704226, + 0.320305311879452, + 0.5107444509324809, + 1.0934954250409716, + 0.5476252935551038, + 0.3086167585489004, + 0.4625648183501688, + 0.5096780151864955, + 0.3202920961136819, + 0.33571079248457225, + 0.4458212838142359, + 0.8328883335693469, + 0.3248325738703372, + 0.41543722948305434, + 0.5000099493506543, + 1.057555627559394, + 0.6553613439838789, + 0.46389226682408563, + 0.4585606260087707, + 0.44942443495452766, + 0.7788739585743466, + 0.41003349927580673, + 0.4440400293922363, + 1.0384053476943766, + 0.7949451500019677, + 0.5083183607190129, + 0.30951497765810493, + 0.5083640316441167, + 0.4935576586193241, + 0.5564944292306749, + 0.35309586899951523, + 0.3990938798424436, + 0.4086753632649686, + 0.9220445663309815, + 0.5900689451901363, + 0.6440245571333965, + 0.32481998372782567, + 0.30112973951539523, + 0.31225531966923264, + 0.4457191295880837, + 0.3979795692465028, + 0.4976268973934831, + 0.7302911598224153, + 0.3929381889705167, + 0.48176032244709094, + 0.47271183020604085, + 0.3565849311899501, + 0.6218433921067938, + 0.4492685376096771, + 0.38061466696208546, + 0.5606181733559814, + 0.35621897769462896, + 0.4707887069843128, + 0.3573059764378415, + 0.9277221857790371, + 0.30546840353154386, + 0.32156672713424533, + 0.5528684887750658, + 0.6968207987691353, + 0.3010476475976033, + 0.3637560063392373, + 0.9246157594618059, + 0.35228787643109377, + 0.33891482114778143, + 0.9760643030155819, + 0.8820943588513425, + 0.8644522094196646, + 0.30787280329596095, + 0.5313417921095113, + 0.35072666126276236, + 0.6463592159477576, + 0.3073483674890213, + 0.34867719251052437, + 0.3229747339443488, + 0.890146558333098, + 1.2780246890042948, + 0.4791088393812234, + 0.34451444217488075, + 0.6458253800508658, + 0.3250912338525316, + 0.44223756102928724, + 0.46421678966997054, + 0.440718485170821, + 0.3516823337951508, + 0.5208953675565385, + 1.1094055787414385, + 0.30861892570736826, + 0.7883466750966057, + 0.48732092742761646, + 0.33580815886064874, + 0.9615957204811614, + 0.5066964442938292, + 0.8689760060277796, + 0.8035858225161251, + 0.5537517431550919, + 0.7085313442044232, + 0.6453187075076335, + 0.6393191842368465, + 0.9772489010406915, + 0.43177384072004305, + 0.506906747235708, + 0.5390416340531876, + 0.4715292946121722, + 0.5223497468869461, + 0.7369521781336624, + 1.6172096049866143, + 1.0153789394059478, + 0.40170738639316406, + 0.4935143713716552, + 0.7745375487036157, + 0.7343611733484781, + 0.5594567442879341, + 0.45435643004716586, + 1.2146198531223755, + 0.36895172562453654, + 1.0705605002212732, + 0.8267894586494504, + 0.49067421962898283, + 0.7814160659171814, + 0.8477212421611092, + 0.4151291040994635, + 0.38013104067909753, + 0.6361124065443348, + 0.5823103365064509, + 0.7480366460867663, + 0.3144397223371164, + 0.493147764412017, + 0.5761731389683259, + 0.4780528019817806, + 0.3833648696565305, + 0.5317122656003213, + 0.3238554892704464, + 0.735506997006655, + 0.37688102139801205, + 0.3538088182419161, + 0.4574730092740382, + 0.30848898999725705, + 0.9920049500129586, + 0.6033375864203461, + 0.3840085947723294, + 0.6887118654299123, + 0.6002159699315156, + 0.33833260840512996, + 0.9019024144791331, + 0.6721841322691353, + 0.405685510023232, + 0.5728444766020263, + 0.33619555296957554, + 0.7016535511020536, + 0.5403229508376532, + 0.3464900857458122, + 0.47913462175655236, + 0.4780274456292806, + 0.3896000023369048, + 0.6075147344686929, + 0.5340949352101666, + 0.7373751769806821, + 1.0809285024294661, + 0.49356726923047295, + 0.6360294558708384, + 1.253650236217803, + 1.1367191927949696, + 0.5262923159420994, + 0.32021078432210953, + 0.3986573104138108, + 0.48913469871082405, + 1.1717430774532689, + 0.8425754322249797, + 0.5125303287370114, + 0.3964700346757583, + 0.9618206555283295, + 0.32939517528704915, + 0.4659475568484402, + 0.30317659495306276, + 0.35997054743114965, + 0.6660526000242885, + 0.6169890667584926, + 0.8760375389432568, + 0.8750930080404549, + 0.38500915518714235, + 0.37528270726308854, + 0.3966938492644863, + 1.2705841536888967, + 0.5686014378453499, + 0.4916899856917146, + 0.5843510789236757, + 0.8724199526640648, + 0.6665980856590338, + 0.9709884211600891, + 0.8059064002723192, + 1.1582207145305687, + 0.5221443878067284, + 0.4797652787865441, + 0.3897209562643417, + 0.7535424647732258, + 0.9475966512882739, + 0.7535643721420185, + 0.39640335375419905, + 0.5370870562940916, + 1.0933328215488525, + 0.42919215200840816, + 0.6616567665930776, + 0.5340072164463403, + 0.5250639017673848, + 0.36076115330243763, + 0.6770782313726773, + 0.6349858160060547, + 0.31805095035051567, + 0.3971369273223006, + 0.3157186546240337, + 0.3001774386095834, + 0.35537386539540355, + 0.36394761189723746, + 0.8913659894377357, + 0.3846609407345027, + 0.48306652608018114, + 0.6034365024010244, + 0.870719322002097, + 0.40510095464025925, + 0.3515550504951009, + 0.9212274098793649, + 0.43308725521902947, + 0.7160598382644648, + 0.6512830278932369, + 0.5431252289637543, + 0.7217090075967225, + 0.4294542872848691, + 0.6732050374534488, + 1.42389714397984, + 1.1167698267266186, + 0.4504390553168114, + 0.45341054268162895, + 0.5570238208154082, + 0.9022980138669273, + 0.4161475121606548, + 0.6632050020268503, + 0.410096638454879, + 0.48349168814504623, + 0.40419010122417515, + 0.3011898940455489, + 0.32410403371556096, + 0.3645522349172435, + 0.8463501546391436, + 0.5139557725290322, + 0.7507097862446059, + 0.4107238083857057, + 0.4771207440136797, + 0.5200939151673616, + 0.7517082251116319, + 0.6588557381228093, + 0.7349637162428219, + 0.7671144896212575, + 0.9944650548930059, + 0.8250086434031983, + 0.9764659654822794, + 0.8038014681395157, + 1.2187462565762295, + 0.8314891846591869, + 0.5840606319059253, + 0.5512710392696852, + 0.4139205326029602, + 1.17178957996986, + 0.6726258524141572, + 0.4113950389365735, + 0.33787087768005636, + 0.46847941521373365, + 0.5817981612679046, + 0.7349100824757377, + 0.6355514811925495, + 0.7404844079460676, + 1.1536316688776456, + 0.9523100954222202, + 0.5475199677655965, + 0.35397035276856326, + 0.866060885107977, + 0.5207277685518205, + 0.41927130196359563, + 0.7402523495456725, + 0.8123873688158605, + 0.7262337156256302, + 0.435842879916997, + 0.4821184885311748, + 0.8895638382751501, + 0.5743243760199696, + 0.7430962345764639, + 0.33928554691792173, + 0.6000921259694411, + 1.2708749426324826, + 0.31767669516722236, + 0.323189746467119, + 1.3624441162785765, + 0.37240709617247664, + 0.3565216302156676, + 0.7868883820382491, + 0.5390853080677364, + 1.2162643399815074, + 0.335039923511057, + 0.33076757500001686, + 0.9020799839699216, + 0.5608056945213614, + 0.3230847790449201, + 0.9363307496871441, + 0.4193628237490202, + 0.7547370223888332, + 0.3960785270906601, + 0.5835593705411626, + 1.0257305021859326, + 0.5207507097866979, + 0.6394110323385561, + 0.8493674747646417, + 0.8089739955799722, + 0.6861699061357834, + 0.8832769995692428, + 0.7776798783544778, + 0.36222988943128226, + 0.5753135368646447, + 0.40321941853255766, + 0.7706585263864446, + 0.635924592899787, + 0.434898454888927, + 0.6409929013628879, + 0.3538035257044731, + 0.48546426756900046, + 0.8081834026159702, + 0.4991703640033489, + 0.4820388560210786, + 0.30045162525590735, + 0.6677757536582917, + 0.313059979398501, + 0.8057380801161761, + 0.647517583440584, + 0.4039057491301049, + 0.3451876686262727, + 0.7700679179444166, + 0.4056199931138709, + 0.8127675414205692, + 0.6379526722067873, + 0.5240415228177094, + 0.8398764001113543, + 0.4517753538488794, + 1.2470589323621708, + 1.01667410775435, + 0.4540226213419001, + 0.47954089002756173, + 0.30713323794491404, + 0.4240694475031207, + 0.49436480473572236, + 0.5241319588995597, + 0.8912283705631561, + 1.6337148575554363, + 0.324861917313201, + 1.0792901554630583, + 0.35353260723711033, + 0.7623716114299086, + 0.4778243456356442, + 0.7840458392767076, + 0.3030945405784029, + 0.8859781661028467, + 0.8132451889670955, + 0.3455087326145029, + 0.3001184290963434, + 0.4014119274496236, + 0.3928131927577786, + 0.4441609709203386, + 0.6823633538137157, + 0.43541769789287593, + 1.1172230190070505, + 1.051654338081118, + 0.4340616304383389, + 0.7813357719231995, + 0.37210630892714275, + 0.3122447931213655, + 0.8136261978289906, + 0.8965321962432203, + 0.5055407066124298, + 1.0072299755658847, + 0.5308346569008108, + 0.44265472426689156, + 0.7324503180838764, + 0.7744957419854842, + 0.37808368392327624, + 0.6002132669283471, + 1.1987052453047347, + 0.4485171309437839, + 0.5171724307806591, + 1.0492316557098045, + 0.7531866069447954, + 0.3513780643055873, + 0.44408777555462936, + 0.407291691490547, + 0.5436518465730694, + 0.5353031646631188, + 0.5574116292197056, + 1.0621277218159668, + 0.5941475020685784, + 0.6724428097423292, + 0.7369025917704255, + 1.0606210514792118, + 0.9398508747594123, + 0.3532944645017434, + 1.7219646210189294, + 0.8269888120226064, + 0.7315899991963811, + 0.568111703414209, + 0.3884531875517278, + 1.0973276389981481, + 0.32611615330031674, + 0.5450151256090287, + 0.39918058381242444, + 0.3043280612000559, + 0.4514236687074404, + 0.6381445322367413, + 0.5676972129601666, + 0.501322943045291, + 0.45419420695596807, + 1.21667716308554, + 0.4039102819847477, + 0.7931986645726914, + 0.9669973255918851, + 0.4947646411791843, + 0.626165527009841, + 0.5701612047137723, + 0.5607074602453713, + 1.0381745651326924, + 0.6112015316751076, + 0.5002436049563288, + 0.34742608118738827, + 0.6163828398829705, + 0.4250444807833477, + 0.4435761282055689, + 0.7900948178259284, + 0.34393509500236485, + 0.44717733942899923, + 0.6777795610988423, + 0.8410727131028068, + 0.586819756994818, + 0.5085796430180636, + 1.1955854477576127, + 1.23640886120711, + 0.5641907926023317, + 0.38400530886250933, + 0.5058141980485644, + 0.5460133122459386, + 0.6221884344247501, + 1.0529228040448497, + 0.7166999037068374, + 0.4295478018109508, + 0.9325098474110226, + 0.6056050801424603, + 0.46415504928971896, + 0.693815770314621, + 0.9328890472150752, + 0.7425564989535303, + 0.3602695845153101, + 0.343386859608848, + 0.8900032195678376, + 0.8675556302730797, + 0.45475716213262685, + 0.6355024978849516, + 0.47160838743753486, + 1.0005442107309679, + 0.3395209822684848, + 0.5076813632905901, + 0.39306959059965585, + 1.2558975499355436, + 0.69438482748227, + 0.7258669790259733, + 0.38276542682538234, + 0.7962869304243816, + 0.39079466996564605, + 0.5567391261451611, + 0.387498705447393, + 0.5542464073282349, + 0.6677970579877841, + 0.8558062069345306, + 0.37269807974693103, + 0.40685224432960115, + 0.7193864651803797, + 0.9270080646113535, + 0.5821977523582647, + 0.44305083327088307, + 0.812398979150658, + 1.1156265642207206, + 0.4803512293720379, + 0.3597713964200089, + 0.40804728645538996, + 0.4263871813766326, + 0.3382110592709593, + 0.3454396477712989, + 0.6871855261200585, + 0.33720521369173684, + 0.4856902240259425, + 0.44949087021883816, + 0.5130128876963206, + 0.6498298908705493, + 0.6927163397367586, + 0.8882350335206605, + 0.36486521736650424, + 0.8780314412503119, + 0.523535517741003, + 1.2094672129773834, + 0.6993524822436169, + 0.39506271898356443, + 0.36194651995322863, + 0.766376032303196, + 0.3870845817835864, + 0.4626179471034849, + 0.6024182418935627, + 0.49850736039478094, + 1.0048493813317563, + 0.6269158543518351, + 0.7523647731240789, + 0.5263004212435436, + 0.49853610404534443, + 0.6543777278512617, + 1.6319737528486424, + 0.5269301359457848, + 0.518863652904464, + 0.6918075158711402, + 0.3006038540469834, + 0.47847811476136215, + 0.9755635810633424, + 1.0481078608201222, + 0.31675782810023073, + 0.5764630678167859, + 0.5112789416758646, + 0.5003511104411801, + 0.6871024287766764, + 1.4562187561793751, + 1.3621610167896396, + 0.6336791704422187, + 0.8692711373296914, + 0.7093090138369055, + 0.7546589432052367, + 0.3181562299228839, + 0.6506479677226858, + 0.509585290941241, + 0.776864394217059, + 0.47232241517684836, + 0.4750914863648878, + 0.3130958296594064, + 0.8833039696046054, + 0.43127154730228934, + 0.47840363644331035, + 0.9296064373458198, + 0.528338503802638, + 0.5049338911411877, + 0.6063682906702555, + 0.4033081648321334, + 0.3002733133436113, + 0.46192685877211753, + 0.7355078067795671, + 0.6098933212549776, + 0.4713410578414066, + 0.3125596724021527, + 0.4740311877777538, + 0.6245767725765667, + 0.5196927483800325, + 0.3042627820257416, + 0.4375132172835963, + 0.5162650790988607, + 0.35178594165184535, + 0.876763251605144, + 1.0282485835889161, + 0.4552975231604172, + 0.8007835853996775, + 1.1710826349906334, + 0.43616871299783083, + 0.7401503707554818, + 0.4429242176369363, + 0.4789331649557332, + 0.35945061312039545, + 0.4228695363919978, + 1.6755922953193447, + 0.4569437369893437, + 0.4771578693491212, + 0.587342423355793, + 0.6468884469806095, + 0.4426382391312335, + 0.5015629854680688, + 0.36991819567690704, + 0.3215723690655714, + 0.5015878852154083, + 0.760870660654934, + 1.123530004205868, + 0.4258816167635316, + 1.4348131298274303, + 0.7817176107525745, + 0.6373324553831036, + 0.7792940135522292, + 0.33443906087186165, + 0.6660102371446198, + 0.49273346007263913, + 0.6813809010966452, + 0.40399871887247096, + 0.957539521543815, + 0.6219350980508823, + 0.4421136592783524, + 0.784114456696436, + 0.5547225043563148, + 0.8989323614658923, + 0.9112465490573488, + 0.5030511011495824, + 0.3990619715019977, + 0.5583530369121501, + 0.4299181266503178, + 0.5526440068128057, + 0.6211649021245383, + 0.7801517109313177, + 1.3628882910882159, + 0.9347831020364732, + 0.3307843259497468, + 0.9924474172660762, + 0.8193352317221949, + 0.6033832795766084, + 0.49340532604801407, + 0.3842645898348768, + 0.3369666543589769, + 0.4760986486259121, + 1.303214080575453, + 0.3773537523729732, + 0.9384585997072875, + 0.8532189213459179, + 0.7081625696778191, + 0.72122193748468, + 0.8310903927799321, + 0.6807522514154996, + 0.4528787292731965, + 1.3467995020295742, + 0.6242738270923432, + 0.3789698040720611, + 0.5783093774004243, + 0.7887450641335556, + 1.0929723062916294, + 1.0741787703528063, + 0.3450060983436794, + 0.9238033064413079, + 0.9538959619884932, + 0.6404435049157461, + 0.5402302554256521, + 0.3716298596454528, + 0.33319592541347165, + 0.9349553180660524, + 0.7989052053664473, + 0.5427040531851435, + 0.31501486133816725, + 0.5242997152123481, + 0.43185050765190514, + 0.8154205448383574, + 1.3753508227260098, + 1.3014378298361913, + 0.6142021001529909, + 0.5181905966065897, + 0.9007133266477917, + 0.7241289415613675, + 0.9655699966328495, + 0.34085966867489326, + 0.5215967691980689, + 0.5703756881954443, + 0.37975531588964245, + 0.3412830914356865, + 0.3761612231249044, + 0.6501342120270411, + 0.3346416357792064, + 0.5381057750753957, + 0.34043402678183876, + 0.8621831912809121, + 0.6208937670352833, + 0.8273097243741832, + 0.48080338555213104, + 0.5200755855920574, + 0.3948734721956834, + 0.6581922129969915, + 0.5433249156110246, + 0.5571999560930548, + 0.30660162442813504, + 0.682955941764534, + 0.41547354803237274, + 0.416203674869043, + 0.4802142227877437, + 0.6402678584408975, + 0.3081308452751191, + 0.34483187169001905, + 0.621667587738332, + 0.42162719576747126, + 0.4688751162479056, + 0.5604839471967737, + 0.37727785672443137, + 0.3699648813846198, + 0.4798863930962139, + 1.1621314188383425, + 0.4971283238620806, + 0.32738125601269186, + 0.4818735051651566, + 0.6899896027409502, + 0.433941871008206, + 0.789780041680022, + 0.49129323008699155, + 0.7671597836410247, + 0.8175021833495547, + 0.5364271433020579, + 0.48119717612934687, + 0.6427466843665334, + 0.9599097438584941, + 0.47753998013721866, + 0.3500377693322236, + 0.3225622140313897, + 0.5214210721157279, + 1.1241218707720868, + 0.620913041466745, + 0.6351183987762494, + 0.38653831551682877, + 0.786546820700744, + 0.3642973438127525, + 1.1634599493632398, + 0.5116578629907459, + 0.40248090375913664, + 0.3507610926602286, + 0.41973362610361586, + 0.39013416466954887, + 0.5348436192804947, + 0.3211321940112803, + 0.7995874562435332, + 0.5045851950409019, + 0.30265732537668877, + 0.43327726726040644, + 0.762539165672133, + 1.199044745656641, + 0.939070963322694, + 0.48703448409476496, + 1.1258685109931215, + 0.36601417848000145, + 0.6711063613535638, + 0.953799464881463, + 0.7777287135373517, + 0.8797631857210196, + 0.8019171820157758, + 0.3675466101879529, + 0.3778180483279532, + 0.47238471520299313, + 0.815595176227911, + 0.6575819265900842, + 0.5231733136280083, + 0.399963142396837, + 0.3452858315053158, + 0.40004430860291684, + 0.3104361496540356, + 0.5474321565165734, + 0.3652593542187082, + 1.1912043663457839, + 0.5735355016377794, + 0.36047662704293626, + 0.5558740795626121, + 0.32483331011065447, + 0.4222924095061402, + 1.076637819419083, + 0.4661428562867631, + 0.5942016571912682, + 0.7621153340063892, + 0.34312556393919535, + 0.372400527600785, + 0.7790990197709176, + 0.8003317286119385, + 0.5610990203401685, + 0.7019334851076225, + 0.37636464385903556, + 0.45059041252908427, + 1.0564409330197932, + 0.48267243011951544, + 0.6337825052627112, + 0.41186241611239627, + 0.6769272720327829, + 0.5430142514013973, + 0.302790990984313, + 1.8155082252534684, + 0.6063616238650608, + 0.5829467469450829, + 0.37421787852293414, + 0.5588125906544557, + 0.4022900963806505, + 0.6729582804774553, + 0.3687946271037373, + 0.5467275742418658, + 0.44013230178523505, + 0.42249568024849216, + 0.3719491534404881, + 0.504532428739946, + 1.0437221991722816, + 0.5856424230896978, + 0.7205549551371029, + 0.3971544201973064, + 1.5460865371231622, + 0.3150262891479799, + 0.6144391020127525, + 1.0694896114614134, + 0.5342083804285098, + 0.41706644032392903, + 0.5195006491031073, + 0.5948644817742086, + 0.44694731769677515, + 0.5879105809021378, + 0.452068143407414, + 0.34869013084003475, + 0.45196925478292577, + 0.5196139457949686, + 0.6510458698464539, + 0.6529147556559424, + 0.4264143822633286, + 0.7170852818872141, + 0.6045732031933838, + 0.5968499928324598, + 0.524492982707565, + 0.4225570265765066, + 0.47017479239605603, + 0.39126840362672444, + 0.7958359921038408, + 0.6501347312743664, + 0.745261798139212, + 0.5262401753930448, + 0.6234514436652834, + 0.3282246620111184, + 0.3343059450418461, + 0.7860872936629537, + 0.4723403714877292, + 0.39977548758396053, + 0.41305560327509455, + 0.6138848757811988, + 0.3790374853971414, + 0.48102792523270577, + 0.34416906085975996, + 0.37457840245011875, + 0.9734329670635732, + 0.8399192858488007, + 0.5588475508985097, + 0.6860317668538867, + 0.4788499492820616, + 0.4514906305947649, + 0.6688462137694836, + 0.5195066263666163, + 0.5823945396254288, + 0.7389298690633894, + 0.31890250029265993, + 0.818281812693031, + 0.6102274352607848, + 0.7665996483702527, + 0.5029937780789577, + 0.5189342857212342, + 0.6290289939687679, + 0.760435865990402, + 0.7230894831499132, + 0.8783281195082866, + 0.5688486563819174, + 0.7608776486216966, + 0.336101397666394, + 0.33426516793956845, + 0.4245823325336578, + 0.7920724642444065, + 0.8456423964975232, + 0.5952581394771597, + 0.36553081388440184, + 0.8945100988077721, + 0.34130343118144074, + 0.3132812296333597, + 0.5586197747939474, + 0.8855384234867774, + 0.4036206023068047, + 0.3843199135494576, + 0.4139556015464458, + 1.3651396794158426, + 0.5196148480758156, + 0.8829914777285885, + 0.989721513229895, + 0.7017192167019695, + 0.5940442710687491, + 1.341791894013279, + 0.7430392163611297, + 0.37178085651032794, + 0.9969410764183023, + 0.7361378473083102, + 0.9281544243990149, + 0.3602160061938984, + 0.5063831577735921, + 0.5068191054320617, + 0.5347603302225105, + 0.44327498098303, + 0.6312307655205087, + 0.5113004820936887, + 0.718062647148467, + 0.855413919303971, + 0.41211460494987234, + 0.7373687949298713, + 1.1893894688516795, + 0.34306912546591006, + 0.5543869103617629, + 0.3314863490214117, + 0.6686759704072545, + 1.3235114131728813, + 1.1244261010474523, + 0.43986014323586214, + 0.3272348850858107, + 0.30676152101807436, + 1.2625331466490735, + 0.47047907184735976, + 0.35624150404804616, + 0.9337153667582059, + 0.7031740840384283, + 0.7727721090720027, + 0.4859394199631713, + 0.9381942052723302, + 0.3468939857248228, + 0.9253840049845256, + 1.3604113530188038, + 0.6833129257734578, + 0.4328056545844314, + 0.977382776168306, + 0.7618344394038092, + 1.0623167035025083, + 0.38019971511948436, + 0.3135719645726194, + 0.590789808156966, + 0.3380969144713143, + 0.7760069885152728, + 0.9548186240802192, + 0.8511886050270514, + 0.5363348683409644, + 0.44617002528375, + 0.373555110419952, + 0.5549775949203588, + 0.5210938198019611, + 0.5013749754976812, + 0.6723287138821121, + 0.5781406230641775, + 0.5324739378990652, + 0.3574889340421101, + 1.6109282855123892, + 0.3043710369100896, + 0.3263294285379419, + 1.72597787768359, + 0.5874664094385813, + 0.5278673397574458, + 0.6426324007578924, + 0.3117669954409832, + 0.6068270065685537, + 0.40128288474575247, + 0.5024386512056982, + 0.8647351393262643, + 0.6596509156909772, + 0.3689109096165495, + 0.6113710231270681, + 0.8535053923118926, + 0.8697032105587442, + 0.6835067283346797, + 0.3969075686078671, + 0.7477030531870947, + 0.3721546606601057, + 0.4833205603154281, + 0.5081225453535178, + 0.7316500562554541, + 0.3024096124859677, + 0.7276329928299552, + 0.48425415416600154, + 0.44857493814555843, + 0.30400261356139835, + 0.5413219306272768, + 0.6988548461549065, + 0.5839240274306216, + 0.48175855932391254, + 1.0263584415713032, + 0.4247888187153868, + 0.33352904868432715, + 0.5001366737393708, + 0.3880112618628044, + 0.35838931105494615, + 0.8094127421110476, + 0.43193462464701166, + 0.7210748534477377, + 0.7097340700363564, + 0.646422921779534, + 0.39615355473833724, + 0.4584610873889915, + 0.4705788783838045, + 0.6853107155388425, + 0.9378434788193386, + 0.8140665433350327, + 0.6014439183333201, + 0.3285459865683376, + 0.3111326824595555, + 0.41616784378859223, + 0.6015227101970985, + 0.7771426348419386, + 0.7484725937914118, + 0.6790224837997453, + 0.9259138543522563, + 0.3886024309248054, + 0.564037966199542, + 0.42840408173961825, + 0.7817999482705719, + 0.8339173274083549, + 0.5525819518922596, + 0.875196806676663, + 0.5562627608342844, + 0.4478940651167171, + 0.42908203905924247, + 0.3533296486976854, + 0.5313229300963168, + 0.6192302643455022, + 0.9134391509972387, + 0.7923070656308216, + 0.4228821199219055, + 0.6309676538377226, + 0.8638074129752195, + 0.7601146576138166, + 0.5964472251465318, + 0.6662142796826661, + 0.43619507808602936, + 0.5606643680824075, + 0.5286533860621931, + 1.3619654439488789, + 0.8960052155838796, + 0.35997207235519746, + 0.5263564575398296, + 0.63109574690609, + 0.8796056797532398, + 1.066340154008302, + 0.6047624629988447, + 0.5044096140524433, + 1.2179756939216395, + 0.48735637403574145, + 0.8260036232898644, + 0.39749537710435096, + 0.3785596242892396, + 0.5674217768104454, + 0.9104538480732328, + 0.3191495947723715, + 0.5351079674472419, + 0.4401364001405294, + 0.5629373536996247, + 0.6751294695173766, + 0.5577003574372642, + 0.7567123376189344, + 0.7882639522825803, + 0.5216523265340874, + 0.4523759443731693, + 0.5103718142068397, + 0.5220313580915754, + 0.677958006901022, + 0.7267244191317277, + 0.30072768707045133, + 0.5949451240167274, + 0.4342131926969456, + 0.31108738692969456, + 0.3427951207363482, + 0.3883611147398887, + 0.6192889271824924, + 0.8048906021490989, + 1.0417485535994484, + 0.6334854963363734, + 0.3888958381365675, + 0.6431597276058993, + 0.4724445238647627, + 0.6826527265320425, + 0.8273169196861314, + 0.8326039980399571, + 0.3155172541541202, + 0.71799314505732, + 0.8001362010954235, + 0.6008121922142401, + 0.30235408081605974, + 0.4492304279774091, + 0.485001118100709, + 0.5055299668105081, + 0.912834858456509, + -0.7271803631038984, + -0.717880716081516, + -0.32817913680494915, + -0.3875023217256354, + -0.8575876504829165, + -0.43330493730559133, + -0.40099678994006216, + -0.5234974161724243, + -0.49914037926109983, + -0.6157194888379177, + -0.9546188910773608, + -0.38551219265736564, + -0.4109527271728949, + -0.5273476859410076, + -0.8353687078864189, + -1.032389241127257, + -0.6705718879757181, + -0.8745160446651374, + -0.5849619161604345, + -0.3643697610695151, + -0.3034516477800214, + -0.4680123144913916, + -0.5695383919686806, + -1.2162277298778505, + -0.5042241563173553, + -0.7177086588140771, + -0.775119612012728, + -0.554528157774539, + -1.2138395293414534, + -0.36227711854007116, + -0.5950121647968631, + -0.6696304837354967, + -1.0535745888931527, + -0.32133144784753853, + -0.8358384267243969, + -0.46613769104725455, + -1.0044335702130727, + -0.43447386113247605, + -0.4752342180571493, + -0.5029219925880855, + -0.3624939465370931, + -0.35778226113973377, + -0.34224454286093325, + -0.6607587884751092, + -0.7795594888276556, + -0.6082037330884582, + -0.3422884861677925, + -0.35387768930402896, + -0.4593356649152279, + -0.66600401538054, + -1.23431455826504, + -0.3521733689746291, + -0.6620904405476359, + -0.5597807934991061, + -0.5049738083094921, + -0.8163081858432041, + -0.8592715351048783, + -1.2448727522732066, + -0.4550945383413984, + -0.6627590115261042, + -0.3954926292060997, + -0.42528419421431823, + -0.510021864440762, + -0.7272327737320429, + -1.1031294039871637, + -1.0201893344111714, + -0.9620273972585522, + -0.5989803723358923, + -0.40613570117334863, + -0.5338609245985699, + -1.0096895060774154, + -0.5406788600768617, + -0.3873854058028487, + -0.8703182705991682, + -0.45585337863303727, + -0.5584490524625557, + -0.35666915075050526, + -0.6971631250228104, + -0.35776890536674816, + -0.6698340209461172, + -0.36860850913409454, + -0.5850375097987573, + -0.313707072674689, + -0.4891734401511519, + -0.788711719150679, + -0.3840633264450048, + -0.5527067950487617, + -0.5685261894323071, + -0.357676945734358, + -0.7835343986369548, + -0.3042648168940948, + -1.086330673119799, + -0.46864559077311696, + -0.4597441227301516, + -0.3442318228651175, + -0.7349672694225864, + -0.5355554392190413, + -0.6742706821810133, + -0.6953177985411341, + -1.0756753893169402, + -0.31587997992756595, + -0.3708147265640947, + -0.34074880943070157, + -0.5615241264860454, + -0.893534694683106, + -1.499202751717107, + -0.5158413096285762, + -0.5277945793662444, + -0.8052593792233161, + -1.4311707268870781, + -0.7578862778229615, + -0.47400039852123454, + -0.45427293929002677, + -0.8037246004332317, + -0.5650071137537896, + -0.4616221559200375, + -0.40282447707912616, + -0.6141796900064658, + -0.38257882309675173, + -0.44547738927886077, + -0.5762354020050233, + -0.3537106549490818, + -0.6672101764085272, + -0.6040187090662889, + -0.6763832493663268, + -0.6360610457868844, + -0.32136867595207524, + -0.5541420842812604, + -0.4677842058591462, + -0.716710801069558, + -0.8449565651002796, + -0.43250795507643836, + -0.5057515369279351, + -0.5990588856163, + -0.4796963433563548, + -0.9628945641340337, + -0.3956030632721428, + -0.31998710281652937, + -0.5084701643717998, + -0.46914745849541223, + -0.48229583509371593, + -0.8422293879242253, + -1.0927856930217164, + -0.6579645009826625, + -0.6791260743976324, + -0.6947734477270449, + -0.6208406989883168, + -0.7307527849767846, + -0.4140562421760275, + -1.0854512421996907, + -0.9231857770202988, + -0.6655021395966151, + -0.49101018677904135, + -0.4277811072817308, + -0.3771294217852804, + -0.5613411812567515, + -0.41885460343774966, + -0.4905507825072781, + -0.8609217370411828, + -0.6235486018206183, + -0.33415896793504996, + -0.44945984829279806, + -0.7844145317626675, + -0.43898752303109473, + -0.4842572333960205, + -0.5431104267513169, + -0.6181278122326314, + -1.0702248844138964, + -0.7231410048188655, + -0.5223250711128921, + -0.7407180750871081, + -0.6087843145282259, + -0.4984267091146276, + -0.42175998489670724, + -0.5458675175095182, + -0.7392043280125702, + -0.3238163932579455, + -0.38898729118153685, + -0.7264673957256705, + -0.6997157948880871, + -0.41696712246256046, + -0.37875272697771717, + -0.8950510231392316, + -0.484652689971398, + -0.41671964077370094, + -0.3426473857794548, + -0.5830233771093083, + -0.5909126286738497, + -0.5623836054056951, + -0.6911945080654526, + -0.5482857174732195, + -0.5168702768184145, + -0.32477491342238773, + -0.5222982427089137, + -0.6983811540113908, + -0.44862230667169267, + -0.3640885009145042, + -0.558862078934158, + -1.3230002331984052, + -0.3670931477533839, + -0.9707630219262946, + -0.396664989925945, + -0.35191442484341295, + -1.360374884194897, + -0.3919418517618501, + -0.6304275424132646, + -0.6106139644501443, + -0.5152573450184856, + -0.583853776143316, + -1.0137931802753122, + -1.1937125671706978, + -0.6465925839840773, + -0.42036713833580625, + -0.4068390731718734, + -0.7329712439699526, + -0.6261816399780065, + -1.0464094724232085, + -0.788166603649369, + -0.30489377628953895, + -0.5693064955653705, + -0.44274547679861415, + -0.34647846096650886, + -0.7720865515521833, + -0.6621144690451644, + -0.44558777622869544, + -0.8122422870104503, + -0.4255372974214097, + -0.8860500872781929, + -0.5759650427508268, + -0.7679828807777683, + -0.5024029510420434, + -0.7326657384188927, + -0.6010131413911388, + -0.44760945598379176, + -0.3070328094493915, + -0.30717605305822304, + -0.3625600158401516, + -0.31233464132268274, + -0.4224747847288571, + -0.34824786846852246, + -0.42019790220304243, + -0.6766824715147796, + -1.1672088941405994, + -0.4945419467007726, + -0.6107461580776665, + -0.777329369451264, + -0.7704724564903378, + -0.694210547270412, + -0.45662236260821404, + -1.3879302016903918, + -1.0772595887004286, + -0.7235063925648078, + -0.3778154922539497, + -0.6827395684767769, + -0.7730103572919653, + -0.40940794756302407, + -0.39222133950412363, + -0.4651510321892535, + -0.4335776037612047, + -0.7719193423461207, + -0.582534966338889, + -0.8205629898918396, + -0.5438378624556329, + -0.6042932135639402, + -0.7088600124174074, + -0.6068253134485487, + -0.883806330298844, + -0.5017472697914579, + -0.4214504274950648, + -0.7568209322749571, + -0.4311322969521034, + -0.6626323057312415, + -0.32007166322449576, + -0.4715875382073256, + -0.5160824252473153, + -0.9362448295559356, + -0.7599700133194234, + -0.853105379356179, + -0.32682110413525006, + -0.4272617215912891, + -0.4690914803824602, + -0.3218501599040152, + -0.6440640624147541, + -0.34957253476091976, + -0.5389205768277497, + -1.0828722983907157, + -0.3573449571826522, + -0.3495352519149701, + -0.511227704564094, + -1.5374071537582539, + -0.3720397433636571, + -0.34260965006404637, + -1.0170464620461053, + -0.6513919182901331, + -1.2443429580764358, + -0.4275316505964446, + -0.3300271533576091, + -0.978994772781748, + -0.3801057874682222, + -0.37814534322694093, + -0.5854683657711718, + -1.0338210582403795, + -0.3900936689485844, + -0.5428516585570613, + -0.43969474174349876, + -0.687249053340027, + -1.155953461589887, + -0.8454590103404518, + -0.8974641536253265, + -0.6305386866417315, + -0.427895694699034, + -0.4306398305680589, + -0.4192221175105108, + -0.6644391475196881, + -0.35914101798378456, + -0.9478754335370078, + -0.7002504519993435, + -0.6222968957983288, + -0.8674080706761866, + -0.3457014310303956, + -1.0734678454085, + -0.5904611497299831, + -0.33766675182055733, + -0.44458836041364236, + -0.3273234364577327, + -0.4737839629283392, + -0.3958212984147691, + -0.4547906102363773, + -0.3812988147861655, + -0.3048449473297319, + -0.6156802055475966, + -0.43517057494892125, + -0.3491373600914586, + -0.906503950144293, + -0.8028834333397692, + -0.6689733154041773, + -0.524265872270907, + -0.45988054265821743, + -0.7230032039941969, + -0.4802619622018492, + -0.5311391696040276, + -0.6798599564239672, + -0.4674634199073091, + -0.43318304247535605, + -0.5314760067870143, + -1.081963055312045, + -0.9417050681458754, + -1.1283593931930185, + -0.5403603685805288, + -0.6782751711557868, + -0.4192600188559737, + -0.405356499282883, + -0.7627585387546606, + -0.4826195263319053, + -0.3421272020061577, + -0.42470869232573305, + -0.546022607836576, + -0.8435422781852953, + -0.4304909043195828, + -0.6291074421954532, + -0.741088296489253, + -0.42693677909223854, + -0.6545368075556485, + -1.1359559237495624, + -0.7585159047274956, + -0.4367008037597517, + -0.46351378624014483, + -0.3365547690899378, + -0.3653985715983644, + -0.725115444057064, + -0.7090135805344713, + -0.4468544039910663, + -0.5830226556333216, + -1.0998735823901165, + -0.9106598318123127, + -0.3104647469041273, + -0.8347503351732606, + -0.34821187754374167, + -0.4068653966478248, + -0.6930297380788106, + -0.8991713912865135, + -0.4449286701042526, + -0.7734100495039298, + -0.41952191806280237, + -0.45569415857508283, + -0.3437489823535613, + -0.5687886226936841, + -1.0884539199763372, + -0.7394397255891207, + -0.7658733904814364, + -0.5579028133967656, + -0.6070699852334054, + -0.664930688781917, + -0.9870021601181816, + -0.750771915361304, + -0.5148476153611575, + -0.36928013241017477, + -0.6256518388752045, + -0.31602785205428846, + -0.48515953698440933, + -0.5415346596333998, + -0.6447560831316974, + -1.0270893195251056, + -0.37755459271880404, + -0.606068964739875, + -0.6896894512531669, + -0.34483534455043496, + -0.98582303145885, + -0.5381118936854165, + -1.0937040044703945, + -0.3765505618071246, + -0.5438598285330521, + -0.9206167622790044, + -0.5075286426612373, + -0.435702792881276, + -0.31185399167546307, + -0.8180661367589833, + -0.8530152545839971, + -0.30998787812647455, + -0.33870080593239454, + -0.6456377750747653, + -0.4545719622366457, + -0.34377264978630095, + -0.933237441050582, + -0.672877386496891, + -0.7123894936744972, + -0.3221708589513251, + -0.4140578655817657, + -0.3914104981617566, + -0.5927455795424598, + -0.6330167758081069, + -1.1555372501460401, + -1.155362530944276, + -1.0240552835510859, + -0.5281087492730835, + -0.30910110789813733, + -0.34733439304818475, + -0.7692069120953838, + -0.7283898757888801, + -0.326321284323947, + -0.36080023642797077, + -0.41360143903556773, + -0.3184606026830459, + -0.3018180052906508, + -0.5292835320600162, + -0.36977094189549375, + -1.186892031432336, + -0.3660081263551571, + -0.7449211648355254, + -0.6059888074760417, + -0.864974473704465, + -0.6887559568642183, + -1.1126140981272779, + -0.8279517530406681, + -0.8379002345179092, + -0.3414354233066608, + -0.3169238607555006, + -0.7150130483081714, + -0.3445478895012449, + -0.3494380227626152, + -0.6629683944455049, + -0.4095291814557216, + -0.7981102858584567, + -0.3631751332400478, + -0.6712770009035864, + -0.7903840234489898, + -0.7468447716079143, + -0.8602862353606918, + -1.0631741208145737, + -0.6592303147178609, + -0.6060720986798658, + -0.7773601730752218, + -0.4032917742115772, + -0.6334332335270735, + -0.7113586496914612, + -0.44041318739343194, + -0.6920616568418164, + -0.4108832165018125, + -0.49282204170168753, + -0.3882531789175196, + -0.6870636768401274, + -0.9807864775057087, + -0.9745933142415497, + -0.33706588618068567, + -1.166742635285667, + -0.3234974460655258, + -1.0266847398524477, + -0.7945943991700822, + -0.33676717747897505, + -0.873490774683234, + -0.6363400993107594, + -0.40240168270935484, + -0.38964500013635384, + -0.38027656892973005, + -1.164553335115874, + -0.49519264986680506, + -0.4410317463229828, + -0.5684050613602091, + -0.3826322409446682, + -0.3744535988616164, + -0.5222725985123609, + -0.36213584256873566, + -0.5376064960997282, + -0.3526482720361191, + -0.3307466262610852, + -0.412739977066704, + -0.36415532664848194, + -1.0025684762912974, + -0.7312415701018663, + -0.6745470340761099, + -1.098272729543899, + -0.3407369497534974, + -0.37176090412127255, + -0.9928011899921406, + -0.5577263276142427, + -0.7970595086230978, + -0.49725096943370134, + -0.317252328755166, + -0.4752863756146344, + -1.1151280037253362, + -0.47736046497727436, + -0.6775668379372054, + -0.3311916097168508, + -0.3745996803511044, + -1.2909189759984445, + -0.5301755105287096, + -0.32467008617804616, + -1.2131687534642495, + -0.5519535166968453, + -0.33991269887569486, + -1.251014489094783, + -0.4705644482545124, + -0.853720618294573, + -0.34545130564543247, + -0.5187162014105027, + -0.6009571650426354, + -0.890289766682477, + -0.8317462104649047, + -0.6638975347439626, + -0.5456683726497112, + -0.8313095451383969, + -0.33215324024067, + -0.3020240077496254, + -0.7071268611860744, + -1.3654660421300278, + -0.454450905357232, + -0.32025027263703626, + -0.6681402868848253, + -0.9708108337850382, + -0.6290064975093602, + -0.7654551358806605, + -0.35916366761933893, + -0.4441400261203282, + -0.3797932859014723, + -0.3335868363348949, + -0.632190333235107, + -0.8972282463477693, + -0.3641719675766804, + -0.6642621883400377, + -1.1935084361869575, + -1.3345567893007266, + -0.8387375522132535, + -0.31264357756894007, + -0.5756505666448553, + -0.4839983831160852, + -0.6541768985365032, + -0.40742297580019704, + -0.563638241742966, + -0.9217579084159717, + -0.612995995625251, + -0.5159768993895902, + -0.35730359508176396, + -1.3380963411113842, + -0.312955492485927, + -0.4581752830177252, + -0.49799382542120907, + -0.5656112290545104, + -0.5762151074006172, + -1.118819916444306, + -1.0965429714657777, + -0.6213026301340926, + -0.5218603311479827, + -0.9419282825948626, + -0.5379625861559099, + -1.0869766625345085, + -0.4720441486428212, + -0.7279795277504744, + -0.33795919421727794, + -0.5529031979519398, + -0.4107167245717126, + -0.3883374038521594, + -0.4440493435319532, + -0.8779635856169378, + -0.6216251471270111, + -0.3585697485183669, + -0.36480370199643686, + -0.7003110718025656, + -0.7752871248424104, + -0.7963413151814535, + -0.5101221165289525, + -1.1169710596713631, + -0.7171987323931526, + -0.4410055843997786, + -0.32785185508193576, + -0.6771246711561384, + -0.46203624795217313, + -0.721414596289216, + -0.3491730583269196, + -0.5055276801121521, + -0.6968928264118774, + -0.31191059117789804, + -0.9831472687811347, + -0.3889986652446068, + -0.3819527524186487, + -0.5652506534045851, + -0.44205786592174695, + -0.8745492834136225, + -0.9085496149272012, + -0.6227604066962835, + -0.5327852951300284, + -0.8285391519510574, + -0.3443373520906949, + -0.47334302502805986, + -0.7525312458846106, + -0.6396886354376458, + -0.39563834596950936, + -1.0260169646819943, + -0.4330867302113173, + -0.6128941607068885, + -0.7774218058027665, + -0.8521209154277463, + -0.4333289941038002, + -0.9712316235264037, + -1.1248789278561515, + -0.6363638815889874, + -1.100587127786055, + -0.3878299557392087, + -0.42416178864600435, + -0.44657170864850076, + -0.4112992373260374, + -0.47610559632473526, + -0.38244062844265886, + -0.5297966926301374, + -0.7899244500945799, + -0.47672851718846987, + -0.4625285588774078, + -0.37015764041376364, + -0.5150409692419334, + -0.6944608798702142, + -0.7088816335364915, + -0.7338735042700886, + -0.4383453742695464, + -1.02414705769924, + -0.49534342118669666, + -0.6133487923853147, + -0.7194340337346149, + -0.31395636295422963, + -0.5730843533053481, + -0.3591542678453226, + -0.4614375208982309, + -0.4939965359897433, + -0.3327777137479985, + -0.4584406158407063, + -1.0648656220318529, + -0.7298244338036114, + -1.1776783621879987, + -1.0514320333473441, + -0.5867188947879203, + -0.7076777727490039, + -1.2413296988249132, + -0.5836405129158858, + -0.3551678196672032, + -0.7166122129452647, + -0.5419454488820679, + -0.7138001653706493, + -0.9433194481050224, + -0.38399928089180874, + -0.4628423526800003, + -0.3025580337092336, + -0.4690381573616304, + -0.6545456777848966, + -1.062479850545109, + -0.3507405760391992, + -0.4801381095385122, + -0.8561529070385488, + -0.4130448844081916, + -0.5350819143124629, + -0.8223791679504607, + -0.428887557579567, + -0.3860302318431797, + -1.2051975589134907, + -0.3220633021047459, + -0.46167458823969726, + -0.6153340188685443, + -1.245218246428991, + -0.6126790206166437, + -0.6349397427084287, + -0.408830248304469, + -0.49362583841687996, + -0.472677651313557, + -0.4548132460065502, + -0.41662690543135855, + -0.43406869515610996, + -0.962298938605334, + -0.6596640343127687, + -0.6246063661479774, + -0.4879917054473546, + -0.5759842515187384, + -0.639755479522131, + -0.736340653510346, + -0.6936983727582408, + -0.723300107573761, + -0.5588430670901875, + -0.43849458113135237, + -0.5947310965282324, + -0.6632562189367065, + -1.0836863383321886, + -0.8404257651890186, + -0.4134430019729833, + -0.7761416885759096, + -0.5070388233316923, + -0.43169305231368565, + -0.48972179532683485, + -0.556347286990504, + -0.8182203229536865, + -0.5117027944724502, + -0.5977642632398565, + -0.9586683932206294, + -1.3263535063841447, + -0.3563807515108836, + -0.5404797731656902, + -1.1436447294478178, + -0.3418022034971488, + -1.4896307705860747, + -0.7643264019622132, + -0.904625852391966, + -0.33041711009724306, + -0.5329114143541753, + -0.47378063093764183, + -0.5497538994345299, + -0.878606843383284, + -0.9169874664718403, + -0.47315695296463567, + -0.37531842871267923, + -0.3454113273341508, + -0.698009731368274, + -0.5527430945773115, + -1.0049118437426456, + -0.6936200658752363, + -0.31980571762746546, + -0.3920356230780369, + -0.5598073235828444, + -0.4435547443851435, + -0.4427075206878959, + -0.5661268345937908, + -0.375306273336426, + -0.36981103545409216, + -0.3916544221933198, + -0.5772078099913674, + -0.39521503839758443, + -0.3347783229180836, + -1.0841141013244846, + -0.6589842171372707, + -0.3621888519276125, + -0.6423944748024852, + -0.67352563509007, + -0.7481203586911348, + -0.5345466502638866, + -1.0051684235395935, + -0.4064560618418491, + -0.4288063579465482, + -0.6752482205881131, + -0.8022961770498845, + -0.5495139321253085, + -0.6786367694032, + -1.3932688594126257, + -0.44069349885959774, + -0.7581648784771541, + -1.4329907508999098, + -0.33385291239551546, + -0.37731329681948794, + -0.41054357121549584, + -0.3642010852951944, + -0.8222831313241119, + -0.49449002316144025, + -0.5094851104471025, + -0.589655595376762, + -0.31008357078461496, + -0.3962356250935937, + -0.7244600339950812, + -0.5270439807411504, + -0.3282120561495648, + -0.4327316424364512, + -0.3501491875104229, + -0.5929503822325718, + -0.34919882761201587, + -0.7248747339807775, + -0.5470459641853459, + -0.6264052856061817, + -0.36061394620624376, + -0.4286656053516497, + -0.3420599195572436, + -1.0498169477161678, + -0.5870943402388535, + -0.3843515025978651, + -0.67857234972765, + -0.4362953343358389, + -0.9883100824987676, + -0.4216735481261241, + -0.7517265310197435, + -0.3170200118447048, + -0.6730272282794607, + -0.5457739212397735, + -0.5105804926605578, + -0.5257819441204189, + -0.3935309074946195, + -1.1642982801832031, + -0.31255961631891754, + -0.5879864627292581, + -0.31350654884833973, + -1.1989278246844486, + -0.8016922273008817, + -0.39279990419898875, + -0.48835852105913097, + -0.6452057004384553, + -0.991575841383446, + -0.6868252979269203, + -0.6735167103926587, + -0.6708286923769484, + -1.3537202908780905, + -0.6163366850741802, + -0.5297652250375509, + -1.0935333107982719, + -0.37424749886849396, + -0.8230191595852122, + -0.4010095993717189, + -0.8161763332368496, + -0.5102258793632545, + -0.7711948415960823, + -0.34202781499310797, + -0.6257871962687288, + -0.45171040174103017, + -0.32376014579628243, + -0.5006008931136408, + -0.37989200383071353, + -0.6269696374687772, + -0.5111274088612725, + -0.48047525657288787, + -0.4866404007446929, + -0.8256647118123688, + -0.3536487711868675, + -0.33352915048906506, + -0.39560232293759284, + -0.4342098621075777, + -0.849627299501639, + -0.5732062599285194, + -0.4797697406808903, + -0.324522051245036, + -0.39301279177563725, + -0.77222545780614, + -0.3003674481637931, + -0.3280836236401232, + -0.4603500270610861, + -0.5502336167121343, + -0.4451492855412098, + -0.5452258363219109, + -0.44545205875703886, + -0.417081708446906, + -0.984025654399687, + -0.6668008019599976, + -0.4700470011746812, + -0.4822155071334849, + -0.6639236181207793, + -0.4911812121789274, + -0.8809570598604389, + -0.3463866547816749, + -1.070922902752799, + -0.561830241301428, + -0.35229469129463714, + -0.40492067248719354, + -0.4060051383910359, + -0.3801834586107577, + -0.4776461963639417, + -0.9179015286678724, + -0.3087090743993891, + -0.5470521843306039, + -0.5726459491838728, + -0.43651877489708174, + -0.3294352541031194, + -0.4058938637041902, + -0.569013688712406, + -0.720529427214959, + -0.4851718074962113, + -0.5540196090298704, + -0.721777496998089, + -0.7402962334152023, + -0.5741451214130124, + -0.5105760051451412, + -0.48701502759820997, + -0.36581835149085723, + -0.4539054238403564, + -0.9971092967440849, + -1.4549511805038422, + -0.658617735266179, + -0.7177042292004524, + -0.6558151590929675, + -0.6829649601843145, + -0.46935338635279267, + -0.7803139215822064, + -0.3564049057542323, + -0.6655225666612695, + -0.3350480529752218, + -0.506917115515847, + -1.0966040611471797, + -0.8715962548544369, + -0.9945831837763736, + -0.6558714132317693, + -0.6805744400973213, + -0.49765480560597986, + -0.6343556915327716, + -0.3377692871138183, + -0.4700992693931425, + -0.4024430453185063, + -0.45632723455882285, + -0.611620649953363, + -0.4516356675154357, + -1.0451245210092286, + -0.5452270005852815, + -0.9220997969548783, + -0.5050550930624722, + -0.8744741443497117, + -0.300913457075809, + -0.32743456363760925, + -0.4346441796133129, + -0.6366468812914591, + -0.5999784488494488, + -0.38028444565335884, + -0.5485981238948873, + -0.41557624775824786, + -0.32564906547177347, + -0.5982623606637728, + -0.5511786942795185, + -0.6127357662085018, + -1.2015129627947616, + -0.3437925644852536, + -0.3902109814746926, + -0.8575498199756626, + -0.7221405066290446, + -0.7007513646518903, + -0.5884690839597729, + -0.5760336826462259, + -0.9525079023675976, + -0.5622715307045018, + -0.3155871832123905, + -0.36273866049765996, + -0.31293633588319664, + -0.3026263188595569, + -0.39752160560008015, + -1.072032995035983, + -0.3952031777239324, + -0.600660467284752, + -0.3578507249192694, + -0.658194160896988, + -0.7560750812642542, + -0.3264138532032296, + -0.36050304408913597, + -0.6671326461304349, + -0.3378177863248677, + -0.5243725721386662, + -0.9409921085466127, + -0.7182329803437959, + -0.5296188266419716, + -1.2037666545247117, + -0.4664048741477725, + -0.7344934941737687, + -0.5700396324574278, + -0.44125754430290337, + -0.5668030356816361, + -0.7774654320354526, + -0.5826122967594065, + -0.8228674248150983, + -0.4148964304083018, + -0.9190191446525701, + -0.49522529830303835, + -0.5432040022526565, + -0.6767766088473354, + -0.43771389371160546, + -0.4085793890763328, + -0.36257499974399154, + -0.32161135332257074, + -0.33122660323258535, + -1.0379022080568752, + -0.41207134824019737, + -0.4067103946379186, + -0.33939178479629556, + -0.8718987618008883, + -0.7739447339704042, + -0.6597179382169868, + -1.1204414595694454, + -0.4995365144917753, + -0.5455477374546495, + -0.5560839738688447, + -0.6417659315107365, + -0.4295570604222737, + -0.5244041188773214, + -0.6791552005870013, + -0.5101023037564503, + -0.8022656760627548, + -0.3079018434837718, + -0.6257101862057803, + -0.9078516868137897, + -0.4969605767859956, + -0.7537079128544845, + -1.2951532351764679, + -0.5902192273045022, + -0.7325162302311398, + -0.5049675869675747, + -0.5680389259062324, + -0.3434113331734262, + -1.083530475871985, + -0.3064078211178855, + -0.34082923350271804, + -0.4894302484884003, + -0.31317448123791536, + -0.5997606242246006, + -0.8159117002335431, + -0.3224599034550602, + -0.3445714131569071, + -0.43126903601903516, + -1.0164838742077102, + -0.35242337560636045, + -0.6251729195191987, + -0.8425421775568879, + -0.34847899089542395, + -0.36330668831501817, + -0.6199839192378286, + -1.0666904498409686, + -0.31425493970173785, + -1.0739781136470634, + -0.36347778420059534, + -0.711714617434701, + -0.41848332678501204, + -1.041580487316723, + -0.3773782375736633, + -0.9807199409000263, + -0.5823498930305783, + -0.7487995901078227, + -0.5447932814988014, + -0.34120764736289805, + -0.5114742975350366, + -0.5691545630171037, + -1.0348760476894276, + -0.5441617067853496, + -0.4887226327153915, + -0.30904104313782366, + -0.5769858678269069, + -1.004342768321442, + -0.34950351727887435, + -0.41460771648276956, + -0.5204909239628258, + -0.3475856078267561, + -0.34606292994671206, + -0.5696093821637718, + -1.0555797072586153, + -0.9815372216147344, + -0.5348787523001429, + -0.5547965648864612, + -0.6788977581656087, + -0.9990555713901634, + -0.45560085981890075, + -0.34880962969080226, + -0.39110600097191006, + -0.4968923682241327, + -0.3868581903630055, + -1.0792541511070297, + -0.43917092948098646, + -0.4831150485945484, + -0.8726421340326905, + -0.568405210545153, + -0.7227829346209601, + -0.3077000942307927, + -0.43601857141903333, + -0.4523337656471019, + -0.585603300415977, + -0.6771912575659461, + -0.4244073831893084, + -1.1548511607476357, + -0.41552569869368733, + -0.548392320612701, + -0.7788764507271422, + -1.0341637170783164, + -0.49554486484886917, + -0.48973336118272603, + -0.7749246066887695, + -0.3733069885816282, + -0.47884676843963175, + -1.7623138000904048, + -0.3759533932957682, + -0.5674591541545351, + -0.3310279354104217, + -0.5846286182243502, + -0.5978471216872423, + -0.8723119976877957, + -0.46590355582973464, + -0.5242159747270053, + -0.8910205071948355, + -1.8143722793585264, + -0.35682417212493617, + -0.3662145101924434, + -0.3860531393365235, + -0.473210932119639, + -0.38861051105144817, + -1.2671101127853186, + -0.5459363893408465, + -0.616335315380249, + -1.2482477368012754, + -0.35648177757505456, + -0.3858203216008641, + -0.5090501638056232, + -0.4905503703579747, + -0.474527232944551, + -0.4866202087447405, + -0.8570728425745608, + -0.5598648159358383, + -0.8511604258265613, + -0.5592160602731101, + -0.4118819269675754, + -0.5527851740933224, + -1.2300392801012903, + -0.6732476674583356, + -0.5019939604579687, + -0.48203077058944505, + -0.35077634406292196, + -0.8075747894335503, + -0.34531709006543754, + -0.4397181868000196, + -0.4381017326597115, + -0.4054738392716279, + -0.5593848717871993, + -0.35045705046298686, + -0.5235606403675722, + -0.3247401375163662, + -0.370593073058488, + -0.424411731498103, + -0.5284414716310825, + -1.03617339217326, + -0.9938194082366812, + -0.7178781065490358, + -0.3999924596849886, + -1.0333157000459097, + -0.5366115751507556, + -0.3870664500821078, + -0.4648652150715738, + -0.6070650152245064, + -0.5370443908805723, + -0.6553702869965489, + -0.8076446282025102, + -0.6472435470797246, + -0.31645086754463864, + -0.6712571262609017, + -0.7037627898042009, + -0.672454276083028, + -0.38870206714185407, + -0.507504901797806, + -0.38555933710504553, + -0.35985913162952265, + -0.7917678199737311, + -0.40400893647911496, + -0.9470571998110028, + -0.37064403815855074, + -0.49287857237247323, + -0.7085509658182805, + -0.38060638428947535, + -1.0416821955654405, + -1.444443679477916, + -0.35481071163184896, + -0.4271092310141466, + -0.43898824882718906, + -0.9539297357958345, + -1.1378577972147639, + -0.6006061406356733, + -0.37002237038509733, + -0.5475932382415414, + -0.3015104070007731, + -0.4169414826881997, + -0.678476024414827, + -0.4680712858522336, + -0.7855705629004001, + -1.071668388964705, + -0.6901177484004277, + -0.5550373372410563, + -0.5698377430344099, + -0.5904011360768894, + -0.3294637707168365, + -0.6624345759683352, + -1.03080405302774, + -0.3072435009445707, + -0.4263006739592248, + -0.3088185600768097, + -0.30919744633490787, + -0.5075020094597793, + -0.6160779476673319, + -0.30353601077376, + -0.48452887826226376, + -0.8063895607458905, + -0.6214111928093984, + -0.5631262673519851, + -0.6797041066533661, + -0.918449999053835, + -0.594489177104204, + -0.8229571846034847, + -0.9791460762067851, + -0.358882977024026, + -0.5836488783548258, + -0.9499098681137067, + -0.3707931601979492, + -0.7332414360400712, + -1.5135316236389118, + -0.49202541810033007, + -0.6359459569004505, + -0.688895080429729, + -0.32437832025832036, + -0.4234218856389356, + -0.5858430973349008, + -0.3222240373057212, + -0.4169556159625329, + -0.425718071656632, + -0.3543030308467935, + -0.3877632390132717, + -0.388382647107126, + -0.6907907027941657, + -0.6383845472297853, + -0.6854576627930085, + -0.41745189029658103, + -0.7476942940922606, + -0.6766923795411867, + -0.44466952892837414, + -0.47584591239544594, + -0.9928142614237573, + -0.7192415247936106, + -0.6299526998354473, + -1.0632730023164454, + -0.8454159089052778, + -0.4547490140552634, + -0.53077812589922, + -0.9202759605655724, + -0.34017021762610666, + -0.6234564332071261, + -0.5791601433270767, + -0.5964433128388988, + -0.4374566532314716, + -0.5192136043324956, + -0.5375520541495753, + -0.4150211051823893, + -0.7762051157049793, + -0.5986844252203011, + -0.42385151820301664, + -1.0157332886699855, + -0.5199701265801359, + -0.4720856917767168, + -0.39742713421762477, + -0.5002417692760611, + -0.7381802797546918, + -0.35595627085129533, + -0.7569065325071769, + -0.36779968449076417, + -0.43772308936049703, + -0.31708712745428164, + -1.2249914287805028, + -0.38698414854649577, + -0.8147747675747113, + -0.6220492967022018, + -0.6358688931205544, + -0.7097844935520192, + -0.5801794635816098, + -0.8446245211323591, + -1.0871905318575372, + -0.917944776102498, + -0.5552686413246383, + -0.3068121685451983, + -0.5703048065638393, + -0.6678798417475518, + -0.5530852862462904, + -1.5425935991551738, + -0.6631323125266607, + -0.4057896231336814, + -0.8752066411880004, + -0.6466008236337184, + -0.8510786993515633, + -0.7071803686176781, + -0.7875941418553415, + -0.6339514422271502, + -0.8879197060465788, + -0.3748328201548593, + -1.0024952581451185, + -0.8350617533205285, + -0.886020239827327, + -0.31972453364947256, + -0.5094989592663318, + -0.7531796513408114, + -0.48082043723429857, + -0.30596555347764964, + -0.5130188625843353, + -0.3419170178238914, + -0.8549554301618576, + -0.8496702946874185, + -0.6414541341098694, + -0.6275543801312344, + -0.503086544262161, + -0.3863693800613148, + -0.7183787233833909, + -0.7127325550619485, + -0.47450721789491435, + -0.8773482487687148, + -0.5029585029314598, + -0.6115858938335709, + -0.8263166706173106, + -0.717322948461021, + -0.3024619388624841, + -0.5604045022506476, + -0.30875627655356797, + -0.5979609589335532, + -0.5214957285215521, + -1.3582446803005548, + -0.9497900382886283, + -0.589898341907866, + -0.8341349434707293, + -0.6472420104362622, + -0.8771668451137752, + -0.6314942354936456, + -0.8499801448362809, + -0.9217537054151891, + -0.3591295131657151, + -0.7374106539927713, + -0.8444141405824656, + -0.4867917081828766, + -0.34579984101142236, + -0.33826403825580226, + -0.48901999574914606, + -1.5367771703418456, + -0.516561899772497, + -0.4295812064234408, + -0.3716723617880512, + -1.0437756355624255, + -0.3784903196089067, + -0.3188123670994187, + -1.0717994383247234, + -0.7178584220958008, + -0.37613159754832576, + -0.49819895188443175, + -0.8840549359164901, + -0.7322226926412082, + -1.1087207522779094, + -0.4244581537399223, + -0.5958501039044072, + -0.42535400173965504, + -0.3242577125815214, + -0.33797069206967667, + -0.3094412490870281, + -0.6075258508662326, + -1.6455029498177995, + -1.2046476648772109, + -0.41552892125908675, + -0.5390204264254472, + -1.260577616958366, + -0.5605718635887255, + -0.46900998744910544, + -0.7674657756303611, + -0.31426932256367796, + -0.3437641643858777, + -0.926423664910779, + -0.31069354924552234, + -0.7874924607800374, + -0.48531387290903366, + -0.40417800282316213, + -0.5834185614601815, + -0.4282453008059335, + -1.2347615211363354, + -0.806408810658661, + -0.5750447742292615, + -0.41850615617217213, + -0.6950961053196367, + -0.7246382983650356, + -1.5177818873129463, + -0.4190098750592038, + -0.5480096528989766, + -0.5047419247249963, + -0.8721660661502773, + -0.6553436992707412, + -0.8060840133274836, + -0.5860236041563006, + -0.4017203874239044, + -0.8272787245771547, + -0.43755079742224245, + -0.5951594585765029, + -0.3706926890098963, + -0.3659236415981714, + -0.7169574550286455, + -0.3109286425070638, + -0.6784017092482962, + -0.7695934515890093, + -0.8043019646469097, + -0.36708579596733193, + -0.6199219288875866, + -0.4972237413508728, + -0.614291168856682, + -0.44138512100285604, + -0.3402753919234887, + -0.9067092522958626, + -0.6235798632435137, + -0.532295680438594, + -0.6696056185003332, + -0.45975867131721626, + -0.738613623246378, + -1.0606144016914716, + -0.3943212917443509, + -0.42306565704279003, + -0.4408444646761496, + -0.5743540405516192, + -0.3324538265854121, + -0.867437238298471, + -0.3179609766333306, + -0.4796051792900019, + -0.6538994118714436, + -0.7584483069059332, + -0.8154112303293793, + -0.7183511695722817, + -0.8287605957354499, + -0.3548875575690484, + -0.4600509581604476, + -0.6742854405458921, + -0.47461550848796213, + -0.30594675291868656, + -1.05072854330428, + -0.4606593928227896, + -0.5822933094763203, + -0.6450524799582277, + -0.5104621312962876, + -0.4844099248764983, + -0.36982347260615617, + -0.4323397402029631, + -0.8951582287307793, + -0.7807067886348177, + -0.5525278408934872, + -0.8207745073744238, + -0.5053267427225825, + -0.477663783556688, + -0.6494310129911722, + -0.5309616162349965, + -0.38105521496213124, + -0.5169941106853703, + -0.7811875404926566, + -0.641877914595958, + -0.4397748345251761, + -0.37011534120032574, + -0.32537860230279597, + -0.5040983105292609, + -0.6935266741590007, + -0.4948557494662777, + -0.30027374861714234, + -1.1405757131011278, + -0.3059133551370264, + -0.6291422676557311, + -0.31050397488280523, + -1.1179693372994144, + -0.33892437062969044, + -0.6657415951606075, + -1.2201234650680755, + -0.5789469967816103, + -0.6053336232153299, + -1.1231480825179925, + -0.9871355650496104, + -0.586097834610585, + -0.37818673629424177, + -0.42691266844022463, + -1.1026644974589364, + -1.1327403294057001, + -0.3536050322221874, + -0.4362430859025264, + -0.43149517002614046, + -0.3943452642419358, + -0.6485081887875512, + -0.40329298591006046, + -0.5227725930980284, + -0.4066410840421685, + -0.7350414298343723, + -0.6810034930028482, + -0.6097710929415792, + -1.4707173024436557, + -0.4030252836699486, + -0.41202250147452657, + -1.2240850204817926, + -0.6557559086612644, + -0.3295576123271812, + -0.8933451221588966, + -0.48817849265882585, + -0.5423347329793943, + -0.8523533226630631, + -0.3530064550165866, + -0.6166712566966559, + -0.48808723752831407, + -0.6690155510505277, + -0.3625261036279214, + -0.960214839913407, + -0.5695362427715339, + -0.5853621918653601, + -0.9908200817709921, + -0.6319269243183125, + -0.3326581022928527, + -0.33573275109466727, + -0.9342678700634266, + -0.3445788330815108, + -0.353152181844298, + -0.631788002074833, + -0.4365796441240138, + -0.49017078300878236, + -0.37459194462157075, + -0.6603579991160942, + -0.34877651931609455, + -0.3636857508357074, + -1.2801952231376432, + -0.7238695025502706, + -0.6093298081111603, + -0.34957932685501275, + -0.5919027782545387, + -0.3522961176425243, + -0.49875694473471327, + -0.41157305368346947, + -0.9049644721067985, + -0.7433022233040607, + -0.38426428569827964, + -1.1233782863291466, + -0.5079964596564124, + -0.8756255593553943, + -0.8938513776548961, + -0.4454665737077158, + -0.6030174602268947, + -0.6387799531817655, + -0.8306804086803429, + -0.4606386695803979, + -0.5307385572050188, + -0.36136684552793374, + -1.0759031212943875, + -0.4177704102706139, + -0.4331892130913801, + -0.4457880702398216, + -0.7319458003685034, + -0.6290444063229133, + -0.4128194446015059, + -0.5788847440677014, + -0.39013391597304925, + -1.0783139439630745, + -0.5703780531447027, + -0.7404809240209403, + -0.5937634237157452, + -1.437605103814046, + -0.633373646531617, + -0.381417053031802, + -0.5249879766830802, + -0.5561894695411757, + -1.0853925168428324, + -0.6518963578407758, + -1.0455961720219609, + -1.0668980438509414, + -0.5895975553681164, + -0.8912937663021523, + -0.45301835478181957, + -0.6065603589929414, + -1.0672854343832017, + -0.7401616926347544, + -0.4977756196236921, + -0.7654253503796349, + -1.8192783768029517, + -0.47168332809006774, + -0.3694274280386384, + -0.5763381915073126, + -0.7570994081537586, + -0.3079061958022412, + -0.4739310454843709, + -1.1461183216366877, + -0.4628304339195771, + -0.6775081022733915, + -0.45887830291739845, + -0.515754144384304, + -0.35199948607445075, + -0.33370667636936785, + -0.9523383546340258, + -0.6077497599325822, + -0.3601243512425179, + -0.5117958748744011, + -0.8342966504697729, + -0.32077804736591553, + -0.4119034100014891, + -0.5943561770651263, + -0.524678439889764, + -0.759115852327601, + -0.45466632967127696, + -1.0163304448745116, + -0.3114554283853622, + -0.6983621863580372, + -0.9110007361007504, + -0.8940736446218475, + -0.528526844871828, + -0.5063137283832029, + -0.4826806252667413, + -0.7255989360981285, + -0.7617969691555165, + -0.37472030391547556, + -0.33920406498807004, + -0.7518279585556961, + -0.3441418651045626, + -0.33475353035789274, + -0.40233951321065825, + -0.3744591574892968, + -0.8179611174591567, + -0.3935489437055544, + -1.1696756573678921, + -0.5525823406868284, + -0.41659041514732736, + -0.3357452405614082, + -0.3978971162707539, + -0.7002548607903339, + -0.6055888404468185, + -0.8401413864626364, + -0.6746497362227092, + -0.5145012751953038, + -0.7158819234746723, + -0.4334644855298968, + -0.669897712653068, + -0.742727049931739, + -0.5265034125284689, + -0.3918908437862007, + -1.1763323269408938, + -0.5210726649989876, + -0.38259119006832404, + -0.7484112243054918, + -0.5615818396942401, + -0.9522455131729799, + -0.40086062738920325, + -0.4238801914106176, + -0.5822596349142594, + -1.059934047452849, + -1.074938982167295, + -0.5246931915560752, + -0.592960677231941, + -0.5801080366643923, + -0.9359906089818182, + -0.4221088626223143, + -0.5160996931590444, + -0.9516614291167775, + -0.3508239711329496, + -0.3370043512049849, + -0.37303019737508764, + -0.3208211340536856, + -0.6856234075123602, + -0.6497555819714864, + -0.6348313192513076, + -0.7856299627899512, + -1.149675121127609, + -0.7498448273630482, + -0.4839152151994145, + -0.39989590278177106, + -0.38861051323192963, + -0.628214110772627, + -0.8556447453863544, + -0.46501141389997647, + -0.43919095507733275, + -0.624161031131342, + -0.7060572140771415, + -0.46537936444928385, + -0.4743778373779306, + -0.40659478832894125, + -0.3386797023423085, + -0.6177987232501628, + -0.8017564024156352, + -0.3465273869069731, + -1.0205357953556147, + -0.8621947184101969, + -0.467666194837107, + -0.7237474155255186, + -0.9311087204731029, + -0.518703972329676, + -0.6999132288408365, + -0.36446383100618396, + -1.2260072686590244, + -0.5112462674782976, + -0.7928853889350054, + -0.4526565963363877, + -0.7437353106310121, + -0.5981676658940211, + -0.6626183676834246, + -0.47730090834758665, + -0.46926426021980067, + -0.4016119092392903, + -0.8972371391385918, + -0.5510181777668837, + -0.6384377770199269, + -0.32882829946613495, + -1.1009406439230789, + -0.5540338199060699, + -0.3203080808168663, + -0.5291030868035697, + -0.5664767737061673, + -0.6820758656236244, + -0.3961834207753529, + -0.7609719194917188, + -0.34904743411115174, + -0.5060375558616165, + -0.5438973690525342, + -1.0383376602366299, + -0.5881726712312744, + -0.379827667713705, + -0.7866424144346419, + -0.6863182543748098, + -0.5926855874279512, + -0.6264718232980278, + -1.1196578028852395, + -0.6158165905959833, + -0.47534095689318856, + -0.38419379494999784, + -0.42418143984868234, + -0.5066783591449102, + -0.5020317719334462, + -0.5319545876669016, + -0.3804401414750446, + -0.4836930544911935, + -0.3748707489517888, + -0.47974930317116105, + -1.0664270743807076, + -0.6728790583654732, + -0.5247074212588764, + -0.5052926611919761, + -0.9359727047758892, + -0.9571030557111819, + -0.6769628484289549, + -0.41423306252127623, + -1.5138802239380893, + -0.351790455606892, + -0.3834473583357401, + -0.3250629940702916, + -0.8243415751136756, + -0.3614926810736142, + -0.9693230797112214, + -0.5185231762124907, + -1.0672331575647178, + -1.171885995838207, + -0.3022593083994556, + -0.5571555353946565, + -0.9079981194206979, + -0.5215379368887271, + -0.49045872324099704, + -0.35022979113404673, + -0.5573726904478874, + -0.8050150421798935, + -0.4474357783506384, + -0.5249745104712922, + -0.6104688131866076, + -0.8997891854714334, + -0.9281090832848012, + -0.32727034927440024, + -0.8276847484047847, + -0.3254130349030715, + -0.3597167709060092, + -0.7991650548911821, + -1.048012367316398, + -0.45105072329189355, + -0.7373908171727493, + -0.7060244336925279, + -0.45272889714967446, + -0.5694807174029647, + -1.3426322933993922, + -1.1092045401404171, + -0.5326596206537398, + -0.372337568841448, + -0.3688660438478964, + -0.41394205719216143, + -1.173381287667975, + -0.8985076487310123, + -0.7490076385346968, + -0.48494359301011847, + -0.915615318755418, + -0.37522530584366637, + -0.552598347453095, + -0.38489668038869174, + -0.745280154564457, + -0.5950472639201418, + -0.7452848555020379, + -0.3703647948897843, + -1.4673171316326086, + -0.6272108033074145, + -0.35280519277673617, + -0.35594956528207805, + -0.5126231445587521, + -0.4496778998787575, + -0.907856034838631, + -0.4552808298743758, + -0.5249432896805879, + -1.104427614043529, + -0.47118414216928195, + -0.5537521340997332, + -0.3679683041931535, + -0.3643482551506248, + -0.6794138628079637, + -0.4873428498036782, + -0.3886885257679746, + -1.1501146959211106, + -1.1104132521775851, + -0.6947394472786774, + -0.31617758997275175, + -0.38230985596462, + -0.6772688302248738, + -0.5253411311754976, + -0.3118705760139282, + -0.38667992008428315, + -0.5829105410216683, + -0.3125765986184319, + -0.6338672699367394, + -0.9094989606949406, + -1.1840160892580187, + -0.6984638823853558, + -0.5703246112900949, + -0.4190031091891477, + -0.313138237279322, + -0.5298700644418148, + -0.30390742178283375, + -0.4441677952702411, + -0.6941252788908809, + -0.4423163563465713, + -0.7427940465314533, + -0.38429293869465103, + -0.38341376962111356, + -0.41972966445601245, + -1.12200225630631, + -0.6958383172920164, + -0.5399178144740993, + -0.4256593154176148, + -1.2407526226799497, + -0.6040598043196417, + -0.3949384992215741, + -0.5827488895689458 + ], + "y": [ + 0.6321635925922198, + 0.9381277323745892, + 0.3549793576406559, + 0.43192147627703276, + 0.41744038759114044, + 0.315008938357396, + 0.36620838950172296, + 0.48277964997530676, + 0.9339129406915232, + 0.8976773722933802, + 0.3731950912215457, + 0.40782523563692613, + 0.8785075078383506, + 0.3278992650383153, + 0.7675605573163815, + 0.3535403798501216, + 0.34962061661438415, + 0.3130636571240175, + 0.6144434388649557, + 0.44264946620763773, + 0.48489716615255785, + 0.6074787607199704, + 0.7358631880903093, + 0.730688739935591, + 0.4166275048639207, + 0.4570288790939826, + 0.4308582220386339, + 0.31955442859218647, + 0.4454373329017746, + 0.6408037483754261, + 0.7392306887563715, + 0.6791540902785278, + 0.5339882313059326, + 0.7343697912215967, + 0.6193369212721387, + 0.7651147595558434, + 0.5337213106612838, + 0.5832409502223157, + 0.3846136485877794, + 0.6700424776095706, + 0.3881118496971866, + 0.8138391201331763, + 0.3958069075619428, + 0.41111567830789253, + 0.33328964237689673, + 0.5733833510150684, + 0.6684238258547587, + 0.37838515501891257, + 0.5314249580380627, + 0.5593188021262584, + 0.5965990921791783, + 0.6101855533796905, + 0.3177711607690122, + 0.5808927927351939, + 0.30447390748129727, + 0.4183779246698277, + 0.6740804264057262, + 0.4725057429971624, + 0.4327326758341172, + 0.6667757819165243, + 0.6412942495163474, + 0.5019630669806368, + 0.6355975584860241, + 0.48013118457943826, + 0.48399503895219254, + 0.44446977167824786, + 1.3374037775197796, + 0.7339554123934257, + 0.46380811318458653, + 0.7048684590092037, + 0.5478673512088404, + 1.2644870791102987, + 0.6852880500034872, + 0.4103947100039897, + 0.7674637625182366, + 1.0455811489711981, + 0.30395270680216274, + 0.9478727142543009, + 0.5852054494715245, + 0.34540560554845984, + 0.6227810498855864, + 0.4559369990621801, + 0.5553302866749235, + 0.33609274912197834, + 0.8362090941107341, + 0.3920207380714136, + 0.4484238038347015, + 0.5059660874024864, + 0.973784754300618, + 0.5788062584410594, + 0.5089883030619455, + 0.5594261472657053, + 0.32890622117390483, + 0.3851892827428022, + 0.583370097250051, + 1.0137582001578476, + 1.054608354583933, + 0.3883445337936467, + 0.5465787881506446, + 0.39575658175451106, + 0.671535913504619, + 0.49166321393727597, + 0.9336216658463434, + 0.808723731937643, + 0.9647167700187487, + 0.5564360267574533, + 0.353022940670919, + 0.5768445138108504, + 0.6763869152466777, + 0.6789817403174624, + 0.430382871846964, + 0.30312990640596194, + 0.42215714272510474, + 0.8897507872353503, + 0.6021882360596749, + 0.38823530937500417, + 0.4431885054413401, + 0.5530088593227656, + 0.5347350987166547, + 0.4105922348587445, + 0.7448481437891499, + 0.5347727261192375, + 0.3343663431814757, + 0.40494233339092456, + 0.6033177989551353, + 0.4959436456672456, + 0.6706362832199553, + 0.33096880755186747, + 0.9948074170870038, + 0.636203099842775, + 0.7987482821807598, + 0.8848112297624893, + 0.31173541569731056, + 0.6217422672294215, + 0.6344090407453725, + 0.6315308552764369, + 0.48911795522947843, + 0.4186374002255527, + 0.9550266930167837, + 0.6709733160582378, + 0.3568906215964482, + 0.9224933495518384, + 0.36339877093284373, + 0.6336154516771142, + 0.70679859408965, + 0.6909048239833636, + 0.6406865459508978, + 1.1223738806047936, + 1.2246135740748647, + 0.5663847224939732, + 0.30289743620001125, + 0.9352029803534755, + 0.3647068135175287, + 0.45958055095688116, + 0.34838178209522935, + 0.6885920419865889, + 0.32744427410731325, + 0.8869354259552767, + 0.3693713954716395, + 0.5188923017655199, + 0.3061558003386535, + 0.7838753381797658, + 0.4888057133645521, + 0.7050992781165631, + 0.794354217644344, + 1.0596742945745412, + 0.7934796105422917, + 0.5471306710774433, + 0.47665405865157795, + 0.7564106491399418, + 0.3118195816714367, + 0.7852339395207496, + 0.8282022082462791, + 0.3402868137164172, + 0.43454625268222413, + 0.38093932293652627, + 0.49288987343679314, + 0.4849066653305079, + 0.7021869350393671, + 0.5267390435447998, + 0.6955166271013801, + 0.3971209390462454, + 0.44355049992957063, + 0.4960139486081596, + 0.9098047704917027, + 0.7171440663943001, + 1.0163850318239729, + 0.6464779529098549, + 0.562889517199159, + 0.44511052395004713, + 1.223208334428415, + 0.43196397284188587, + 0.34355768667765557, + 0.42103722703929375, + 0.9710361451306261, + 0.580154166003413, + 0.5066331379719202, + 0.845101769852861, + 0.39766964653222064, + 0.5853811040217735, + 0.4968607934420108, + 0.6364956933519557, + 0.39712657578167776, + 0.4259404003270511, + 0.38151646582001913, + 0.3548464285999682, + 0.37600688804113597, + 0.621600166345788, + 0.3015894241356637, + 0.5913925923069516, + 0.6759548131107167, + 0.6158289865769532, + 1.0034859177408866, + 0.3902056884854597, + 0.5381954893964329, + 0.44800334625467253, + 0.7689484583085168, + 0.35680482772527333, + 0.781008154586283, + 0.6047595341673577, + 0.43097148726490553, + 0.9022686617532204, + 0.6913836810994537, + 0.6746504401854798, + 1.0088190630542913, + 1.1958601041632964, + 0.9624183658584523, + 0.3966495873951097, + 0.3770782817296954, + 0.3817957757872777, + 0.40679659412287367, + 0.3111927114542618, + 0.36505644329626347, + 0.3708258430461197, + 0.5403401308916568, + 0.605180800915479, + 0.5887068820355622, + 0.5702776136555463, + 0.3695188969296449, + 0.6550733074062396, + 0.3628697422520504, + 1.0178073057992851, + 0.6535437979059033, + 1.3820901357082322, + 0.9059326657541115, + 0.5328261607328276, + 0.5364848472677964, + 0.6422753878243039, + 0.5984104360699763, + 0.7450776797087728, + 0.5909563363689397, + 0.3966589424490302, + 0.4816983178148598, + 0.6223570696343064, + 0.7351500535239743, + 0.6073843539143006, + 0.4074986132949307, + 0.4639069630857709, + 0.7528955233321871, + 0.3510869373138026, + 0.8754534504576446, + 0.6742355280080321, + 0.5379699813896475, + 0.9149665054088976, + 0.3156170753580056, + 0.5055022695957817, + 0.34143717221019837, + 0.9779533064035637, + 0.4037885069441944, + 0.38976968610732793, + 1.2721451276643092, + 0.6645513753271642, + 0.6835700538992108, + 0.4959213015302803, + 0.3120136228419298, + 0.5102309375478344, + 0.9195797330983794, + 0.6524797895651426, + 0.5476480143653629, + 0.36727823264561216, + 0.4229572956986933, + 0.7229454365205722, + 0.6090870415438893, + 0.8297558721523328, + 0.45239843840190525, + 0.48568293920950767, + 0.5012055855249236, + 0.49310518442095896, + 0.45849545235361494, + 0.7026946892692927, + 0.5148088856445967, + 1.0024648113469583, + 0.9378731399764307, + 1.1879838002464105, + 0.37920216111958666, + 0.37588448704628696, + 0.35964219429003663, + 0.50417206545811, + 0.32606526291183247, + 0.3997049710148296, + 0.6475527596065697, + 0.5682448460669317, + 0.4057787027966324, + 0.7913463063828183, + 0.41496559717679793, + 0.5807955016606317, + 0.4100330521751927, + 0.3858729281947766, + 0.5818449072065582, + 0.5513632747519596, + 0.5215066467133328, + 0.3111129795425174, + 0.5652409471720807, + 0.31125388834174, + 0.5761756961702279, + 1.051209231908969, + 0.3827041105890299, + 0.42058045105538755, + 0.6897161505093181, + 0.46842260520836926, + 0.7638041368046075, + 0.5139423267536358, + 0.5261652961721346, + 0.422406450161951, + 0.7676328251870518, + 0.3064929444648376, + 0.33484994671925833, + 1.0064907891689332, + 0.4244434148710951, + 0.751933373852183, + 0.6619318331169954, + 0.8597150195698817, + 0.7603857499465333, + 0.3367158418802775, + 0.8185001884846752, + 0.4214229754786999, + 0.47462100242521565, + 0.5971072635840224, + 0.46848583505969504, + 0.3876653318332694, + 0.44123041042405975, + 0.4007159554713334, + 0.44179158554510684, + 0.5726843014723269, + 0.3364635778836691, + 1.316009169844948, + 1.510607795771669, + 0.6014557208796951, + 0.7777841129798063, + 0.39954259609903564, + 1.2419711168092118, + 0.3036368504019732, + 0.5144644211281887, + 0.9036617111901603, + 0.4184086039828483, + 0.4198315165660949, + 0.6077886801140089, + 0.7780024867572788, + 0.6920006360224634, + 0.5172629629107204, + 0.7503140945165484, + 0.9139302681027778, + 0.3032780828991661, + 0.34053887728063065, + 0.6982436013597577, + 0.3934001864561951, + 1.6775824065590172, + 0.43233602732618714, + 0.30320136549181304, + 1.0615029068450936, + 0.5945296583691527, + 1.0723911699502675, + 0.4305029411888568, + 0.7619510386729503, + 0.4132747849244319, + 0.3039587155710014, + 0.6484357329531197, + 0.5888042672793734, + 0.31047111063140054, + 0.7787246149462108, + 0.5096198730775003, + 0.43889828249636725, + 0.37058497426599013, + 0.44317049524351154, + 0.6214381238030607, + 0.6942608851649434, + 0.7750053133428766, + 0.6707821620579121, + 0.42127529420936644, + 0.798744598383574, + 0.806516307136041, + 0.854419421124256, + 0.3467004805669943, + 0.915044401967976, + 0.344031470702673, + 0.3452450919249516, + 0.37262000493999775, + 0.40683861765795726, + 1.2019066044000917, + 0.3942041299091458, + 0.3506412852108477, + 0.30385269477130994, + 0.4412830594595792, + 0.9108178996805006, + 0.4943828878595566, + 0.834515510784857, + 0.41620931496550456, + 0.68083263336548, + 0.4025569304010754, + 0.7480107416364525, + 0.3654059099289762, + 1.581914214581062, + 1.1205464455856577, + 0.3277973298716779, + 1.2491748020679496, + 0.7966318454128493, + 0.6070924134290946, + 0.4079264214724558, + 0.6322596907022477, + 1.2281427084254661, + 1.0637367357089655, + 0.37207680522142317, + 0.5781678595997, + 0.6371014090894501, + 0.46936059657715573, + 1.3077295457704936, + 0.6300434235721339, + 1.3562775856870042, + 0.5471996684382232, + 0.35168357618805646, + 1.3327059188081019, + 1.1500977171359092, + 0.6668824384216119, + 0.39698828291269045, + 0.959777782770607, + 0.6390414807004761, + 0.39600296091990095, + 0.6565826532419158, + 0.32438136287946484, + 0.7108022713632985, + 0.5522953595395907, + 0.5103470403876431, + 0.3430774709722437, + 0.77826213042763, + 0.8023279758854712, + 0.45353976487486103, + 1.2294951257651623, + 0.600056709896817, + 0.46248506437906195, + 0.4056959644583853, + 0.5732298840144504, + 0.8431586413824517, + 0.40275326148638235, + 0.9253132377714427, + 0.8908341191435244, + 0.4077345866626667, + 1.1271999792899945, + 1.1152179317945754, + 1.4924797192337294, + 0.31447623174279365, + 0.8091795100511417, + 1.2689201812269868, + 0.41085993471916504, + 0.4089144927053898, + 0.3718251132849203, + 0.41300153498742165, + 0.5743661706540606, + 0.37076986014075153, + 0.5033732452702505, + 0.4629369906867036, + 0.306906970246064, + 0.48518489032333845, + 0.432275201062957, + 0.8853694267261142, + 0.611796007224914, + 0.3492771770513244, + 0.36958115067119446, + 0.8082409771961184, + 0.5328881140422602, + 0.34735964075457937, + 0.9114038365025188, + 0.48587623682560765, + 0.3282493499598979, + 0.41515277527278294, + 0.4100190398590242, + 0.44349955086306286, + 1.1128971644902381, + 0.5232081884244024, + 0.3327800191274718, + 0.8136499489731673, + 0.40189670696108165, + 0.33265558897471137, + 0.7530041978975659, + 1.1077644777537727, + 0.9194816082191938, + 1.2002684741998049, + 0.8877782537552199, + 0.9862871155443282, + 0.5052947298862769, + 0.3107482858877611, + 0.9927172086944404, + 0.691029017289982, + 0.3337570769347056, + 0.34308663037779097, + 0.4073506173633453, + 0.5408663690048011, + 0.47623488956001386, + 0.5181798503227604, + 1.0369998030828227, + 0.3171734752565845, + 0.3954162453189912, + 0.7589002978434336, + 0.31713021518144646, + 0.3187898875766603, + 0.4441536081090169, + 0.9509389240807925, + 0.3646500669455774, + 0.7295044193323962, + 0.5339514566601138, + 0.5352378954635285, + 0.6771681624520687, + 0.5419775838385714, + 0.5321518425037318, + 0.41636516457804823, + 0.3702219853356928, + 0.6998583492049614, + 0.7035365203798596, + 0.7698383643435073, + 0.44978371879107754, + 0.6999245681855626, + 0.5304187436190573, + 0.5674365925136975, + 0.3395432811793784, + 0.5450057108440649, + 0.8782918670455133, + 0.8908054684976554, + 0.4058192532683079, + 0.6061874773124551, + 0.4986442187718748, + 0.32394335861915424, + 0.7589361519134535, + 0.31404393646436085, + 0.7533316693457546, + 0.3792977528381061, + 0.7359847895298113, + 0.39447964450310574, + 0.3223071494241528, + 0.7187815222007099, + 0.6345558920222384, + 0.4949515267137448, + 0.36338036214441305, + 0.6241101037679238, + 0.4408692262166851, + 0.7184632768036943, + 0.341227771563056, + 0.36516907427927464, + 0.31260924384233035, + 0.7632411600397473, + 0.5445825472850807, + 0.7565883822176214, + 0.3689163112676799, + 0.5829281033618658, + 0.33116485385432626, + 0.4061475108126768, + 0.6338954924242823, + 0.39062855557258236, + 1.0863268029505062, + 0.48825111727560677, + 0.5838581296427281, + 0.4726385698017489, + 1.1892958094198933, + 0.4963373064758556, + 1.1649774627377778, + 0.7332778381020565, + 0.8149835816904777, + 1.1660687286077827, + 0.34276298112628123, + 0.36820453048032986, + 0.7014165925769622, + 0.523062091526872, + 0.4809878230650511, + 0.7506517311866997, + 0.8623259780330652, + 0.7532282336587633, + 0.32039154557234856, + 0.3284428478162176, + 0.9638837825026857, + 0.5307778173123469, + 0.4449682443885557, + 0.44580070317312914, + 0.3967817346945694, + 0.7946538097783871, + 0.5310234333706003, + 0.3509989169085189, + 0.7271977563049112, + 0.44080010171173706, + 0.3829541547804289, + 0.37416266987924746, + 0.3557524102269303, + 0.7845801009267601, + 0.6043191270757954, + 0.9004494199570483, + 1.0768175781796654, + 0.5871487460063843, + 0.4307976443647579, + 0.34278374393374544, + 0.42132677772931776, + 0.4510729443107253, + 0.32673770380972084, + 0.47089193474348745, + 0.4108374320485222, + -0.3048234239430776, + -0.8504544535647919, + -0.4231171477305315, + -0.472499275819666, + -1.0225043563653606, + -0.39333131814643046, + -0.4226930345396317, + -0.7874387959443526, + -0.5410181816806254, + -0.5744185300704718, + -0.36756696600433103, + -0.5102313379286543, + -0.46465235419685447, + -0.466593538260553, + -0.31517186317930845, + -0.5576717963427854, + -0.46332121848812646, + -0.49801208000614017, + -0.5020542869297954, + -0.41528984551519216, + -0.5529634363423711, + -0.49374886305668625, + -0.5340489441243066, + -0.44507271409572685, + -0.9698169363897031, + -0.7682310567917453, + -0.6809809517060941, + -0.4893432399940653, + -0.5866512401347252, + -0.6310559923996012, + -0.7174852338770457, + -0.5000985592687409, + -0.8562827040077287, + -0.3021361294808637, + -0.4790163368324943, + -0.5685434868451459, + -0.860753780457039, + -0.4905668819940514, + -0.40440431444836467, + -0.7113855315633436, + -0.3401374304422938, + -0.5489211107418888, + -0.613709803022365, + -0.7838962976162248, + -0.6747586731522579, + -0.5531797578167985, + -0.5899488035189046, + -0.6892327949471739, + -0.687156473989456, + -1.5032720126123313, + -0.38564458541923985, + -0.39635433950199517, + -0.5412985636864027, + -0.567738834098363, + -0.7101167176881946, + -0.4318832619793943, + -0.435039474708461, + -0.7688766856010097, + -0.4375327962560729, + -0.4909218537578558, + -0.31183295754825435, + -0.41882475452141815, + -0.7214386836995893, + -0.8531872206836821, + -0.6091351112018265, + -0.7599895220764079, + -0.7553932567439074, + -0.9860227843315685, + -0.4127559279057665, + -0.5553816574116662, + -0.4710928993152298, + -0.6473400003319956, + -0.5257501248171612, + -0.44528368247435685, + -0.5756225350438973, + -0.4909731222192462, + -0.7458834580004193, + -0.4738638326816256, + -0.3068522431283172, + -0.33297869834598287, + -0.49362760912567255, + -0.8749228808728433, + -0.6041468095777046, + -1.0970357699456827, + -1.2625314992882062, + -0.674439703793232, + -0.9801789585965602, + -0.5232550926349518, + -0.35492006179278535, + -0.5773279049029197, + -0.8376488507212323, + -0.31651729293866177, + -0.4993654712783422, + -0.6098289578535275, + -0.3536287117007069, + -0.40565818047624375, + -0.3689866793592892, + -0.7110619053821107, + -0.4076829164119852, + -0.7559047628165673, + -0.5736082145978192, + -0.36050857435885514, + -0.30850876438295777, + -1.2671568611852424, + -0.4180628062343073, + -0.7293122912366371, + -0.758285739537861, + -0.3778353531198537, + -0.4082659075587953, + -0.5516914124182526, + -0.32259389057116516, + -0.5645989837425908, + -0.37342543014715207, + -0.7323928029094374, + -0.8312111703682877, + -0.3527217098384552, + -0.399148774281808, + -0.35350864360451817, + -0.6540869970003265, + -0.38848327756736284, + -0.3884710594082744, + -0.42289088170550815, + -1.2116744363179055, + -0.6087555079864924, + -0.4471653076353345, + -0.41424736322156325, + -0.5701231701002641, + -0.6476645550871366, + -0.42605828625384995, + -0.462471273026917, + -0.3743464668902835, + -0.5040284537500573, + -0.661666060734418, + -0.5687607679314466, + -1.0780253993918758, + -0.35856219373294507, + -0.43808177727013836, + -0.4310898649679079, + -0.4059238748306313, + -0.3096323674315957, + -0.45519235177899403, + -0.5400720682566739, + -0.7160767962316845, + -0.6675521713768982, + -0.6994064777938906, + -0.30160453005030413, + -0.3328087802647243, + -0.35446000388931476, + -0.8843620169289793, + -0.789796796461597, + -0.8334109006854628, + -1.2002513160792836, + -0.39541885198264504, + -0.819777309190724, + -0.4674550221235194, + -0.9194915337861931, + -0.3385648646308564, + -0.5135025573625812, + -0.5060069454471434, + -0.5575558256742247, + -0.6206683447900297, + -0.7513353440544601, + -0.42767707348981227, + -0.746444386461124, + -0.9705467171626743, + -0.5676302785729984, + -0.6334192638146801, + -0.38160398251634364, + -0.7329675159363478, + -1.1575049711988459, + -0.4089262260303421, + -0.3667564192678433, + -0.3729052505966959, + -0.42627331039635274, + -0.4703664168266932, + -0.429567334598006, + -0.32633366213026965, + -0.7429289164260794, + -0.34601481099281595, + -0.7589166510826711, + -1.2717459712724242, + -0.4081874285158486, + -0.36563618074555826, + -0.4591113213032324, + -0.5456041598664009, + -0.3162676417703023, + -1.3610635954114207, + -1.1849783790204418, + -0.5350515088444278, + -0.5736122885220221, + -0.447265373552002, + -0.4410632774669657, + -0.43975363833542214, + -0.37291409116976454, + -1.4554724412640407, + -0.3628909725236367, + -0.647945168231984, + -0.354872655214412, + -1.273763375530291, + -0.5768488888883452, + -0.7023168258848517, + -0.3121399016875894, + -0.4642023649564933, + -0.9464845613845021, + -0.5955263783196326, + -0.3903469260573576, + -0.6211969453565507, + -0.494472359827998, + -0.3090963258146722, + -0.4612172967502698, + -0.39678699057777517, + -0.7251303630906987, + -0.8806504067172094, + -0.4507524234529641, + -0.3436219591245091, + -0.7062204223683879, + -0.6170708543203417, + -0.6257493922267318, + -0.5214106214630981, + -0.37529260572907, + -1.1194339561345101, + -0.36225273875019726, + -0.5144003491783448, + -1.0812389524110386, + -0.4753686646596528, + -0.9526926131367337, + -0.5694185984721343, + -1.058498587868277, + -0.4713412522178841, + -0.3880527343504544, + -0.8654156489791047, + -0.3645825281752938, + -0.7882610300251095, + -0.639863555941316, + -0.7344488203579609, + -0.6796253808521283, + -0.4967428831026859, + -0.7275528370780558, + -0.3102732816151977, + -1.146138774797936, + -0.3238557150666502, + -0.6122522485137201, + -0.37912509337174416, + -0.7888317181441837, + -0.5284272712269535, + -0.41165040802357694, + -0.9492003549683705, + -0.7821692737292355, + -0.8147357404729165, + -0.5621523003026105, + -0.46921681394459513, + -0.30667296440880565, + -0.444016546598469, + -0.4916166408758244, + -0.5378738156848044, + -0.4762506564812103, + -0.44577412326764765, + -0.8235396327938271, + -0.4654088921266701, + -0.7633274630746554, + -0.3455403723412918, + -0.3103644172154024, + -0.3207854948901537, + -0.37533729514450875, + -0.6623252312510147, + -0.9411679749964352, + -0.30945736262517226, + -0.4237472007952603, + -0.37466399012384266, + -0.8724830622706912, + -0.9082896217076865, + -0.5492804222439999, + -0.5701706359189354, + -0.5128571039826517, + -0.35241005723546054, + -0.529229300122161, + -0.7211637905387732, + -0.9279617480842046, + -0.3970052128516429, + -0.5073199772330862, + -0.35534972554272953, + -0.8617373158802616, + -0.47538436771416587, + -0.47035795269537994, + -0.8568546320134052, + -0.6550380767933902, + -0.9842284494483708, + -0.8252321868904029, + -0.5431771608970318, + -0.3244831486961129, + -0.3918238515891378, + -0.327647133175461, + -0.4435031239699141, + -0.5371650127716916, + -0.46685896865759097, + -0.9857229148680321, + -0.43392489016659963, + -0.326019100043699, + -0.4782897183998958, + -0.3908341130016623, + -0.47652202490727325, + -0.819138668134172, + -0.4880891870872363, + -0.48749194439720367, + -1.2854406177508262, + -0.6545520203898963, + -0.3819830851158938, + -0.3353342603741174, + -0.6119981243723606, + -0.6549707476588379, + -0.49221585208629914, + -0.41047418579580747, + -1.2219781864886046, + -0.40130300903859595, + -0.3342485325179047, + -0.47754844872481456, + -0.5840780242992192, + -0.4286071455982247, + -0.3872812932761785, + -0.5634284434060287, + -0.5343975060550864, + -0.34894914683515915, + -0.353998744801538, + -0.5358959659981296, + -0.700328070115413, + -0.5563361730590782, + -0.6751178123147411, + -0.397401705824806, + -0.3885958393242526, + -0.776860909691483, + -0.5077557624463078, + -0.5001921858881705, + -0.5938259800982351, + -0.5934252505547575, + -0.41471665498216254, + -0.6482759010208033, + -0.7216790550390267, + -1.0530511016055095, + -0.80548161969487, + -0.4577028839805935, + -0.3974348586773277, + -0.4475915306553168, + -0.5836860673469415, + -0.47170854879586693, + -0.3886513829631182, + -0.40107739036076095, + -0.8139186614651596, + -0.6038549735938558, + -0.38127719548770084, + -0.3525168032714722, + -0.856817008970301, + -0.8845978117703032, + -1.3877635793144203, + -0.8208237868845517, + -0.9323543198861963, + -0.39360482991049295, + -0.39712653889389016, + -0.6838871990458009, + -0.8681773989981472, + -0.7442682675409693, + -0.7305649285904487, + -0.5796659534216095, + -0.3474037399250542, + -0.4335078723806261, + -0.6951791494565412, + -0.4091936942095568, + -0.815694189913213, + -0.4924609473297159, + -0.7048874018495657, + -0.5657399386517348, + -0.9659134006045308, + -0.45282409201405527, + -0.5656546309154283, + -0.3722486776146825, + -0.6319974607426206, + -0.4956634481977187, + -0.7575866012311926, + -0.3290854089479707, + -0.6658925944702805, + -0.6270255655695053, + -0.3467428716950211, + -0.5135529415241558, + -0.43829703771044554, + -0.34896750340710087, + -0.5548636247292356, + -0.41821649038234204, + -0.3055843765421475, + -0.5119754172996369, + -0.61431337546003, + -0.7762076790152088, + -0.3949103574135438, + -0.38236319686241477, + -0.9107975951347722, + -0.39535849374153775, + -0.5349114702198001, + -0.36298308903455584, + -0.7855806831314108, + -0.4141910926097267, + -0.9528829334324744, + -0.37192865149703025, + -0.3278765993163856, + -0.32747198629543883, + -0.5725171766466456, + -0.3273611751460678, + -1.1413606797289488, + -0.3576626963882334, + -0.6979654112729993, + -0.7938077020813973, + -0.40217110319337224, + -1.211824016520899, + -0.38842072301131786, + -0.3371437459837474, + -0.6698509147618718, + -0.6999744660214355, + -0.44413181611295727, + -0.3243982721920643, + -0.9332710935352133, + -0.3843656379601394, + -0.47303096739746797, + -0.30613599156166243, + -0.36391678576185926, + -0.9929026749559483, + -0.44180036150417235, + -0.8860706787110334, + -0.368872496217614, + -0.702067045659026, + -0.44939398608584097, + -0.4584733805419286, + -1.4762583115890897, + -0.3704664138408627, + -0.3333964765023839, + -0.6760941000955836, + -1.1612817430376379, + -0.32016265142413747, + -0.6020819172444684, + -0.8871619475462064, + -0.3623839239146552, + -0.4953226012640814, + -0.31463402582701283, + -0.4796221191776785, + -0.6966285636774195, + -0.5196905942445298, + -0.6021270177308861, + -0.5495664455838567, + -0.49268060174739675, + -0.8029564976815146, + -0.42873167511584753, + -1.1330307898575083, + -0.7168587995144826, + -0.46724945271117696, + -0.4454877442869545, + -0.6742047981761048, + -0.3514299684253822, + -0.9676737884062717, + -0.8247803080068791, + -0.5732724346149402, + -0.5480688968392677, + -0.4788969030412202, + -0.40406989943029553, + -0.6509405066047613, + -0.7686120142288774, + -0.4710142878680376, + -0.48147216897959394, + -0.7345984091287174, + -0.3704268816307402, + -0.7555031692920514, + -0.3955301403447412, + -0.43130450966705086, + -0.8533532494016233, + -0.3073678591179073, + -0.5925208888305626, + -0.5769005902841005, + -0.45157619578101604, + -0.40617413014022036, + -0.39692269339089753, + -0.4001906189845986, + -0.5760984686495879, + -0.850399854810329, + -0.6322670276843063, + -0.31243651704613545, + -0.7823295765745971, + -0.6600120855720469, + -0.5850082437122083, + -0.8583630053853539, + -0.5037503206624978, + -0.7743209801861212, + -0.5208765387823129, + -1.4662999355568709, + -0.9701698696971753, + -0.36415221688849864, + -0.4201311529897843, + -0.8263268581814035, + -0.6138369276356836, + -0.8582442292919928, + -0.7230453688536363, + -0.6456371525397067, + -0.5933734789509602, + -0.7480947783220477, + -0.681624092057426, + -0.5522426387963565, + -0.525442472606758, + -0.8893026542538968, + -0.4174728271388822, + -1.0017449106989527, + -0.45945503213142963, + -0.43066175789029676, + -0.39479744354465723, + -0.4820246263600496, + -0.5977073578512158, + -0.5722512802858493, + -0.47027683463410874, + -1.136482750154589, + -0.7240199429654551, + -0.3372531459673621, + -0.7440371970221711, + -0.9181938849082605, + -0.6017330110767531, + -0.504022609536869, + -0.38735992831945343, + -0.339185033619221, + -0.48053376090726696, + -0.6306297426731465, + -0.4874540681285223, + -0.7035271003916119, + -0.47736760928741595, + -1.2856815357738611, + -0.8077425513270057, + -0.3225594881092143, + -0.30955556482194674, + -0.6242732798725475, + -0.3369347653080057, + -0.48505664952605076, + -0.5261893505728737, + -1.1268957035031024, + -0.4246178756707742, + -0.37507156690743104, + -0.3115004482126374, + -0.8915912349799993, + -0.519556685231878, + -0.4235335453840059, + -0.46053052110852133, + -0.4916013253109219, + -0.6066551638835536, + -1.2268217696803483, + -0.33783985545456685, + -0.47160983826616937, + -0.8060835787833328, + -1.05840337434172, + -0.9333651308716755, + -0.6414802907060079, + -0.3405517502129751, + -0.5777239450446757, + -0.867853735810244, + -0.640202611505431, + -0.3160114432096583, + -0.3357664144803282, + -0.38530064287529886, + -0.31630436542202556, + -0.7983172037955071, + -0.662052431496028, + -0.8701340379908272, + -0.6919609705741063, + -0.8253112662852747, + -0.4510707924962234, + -0.5199181392441425, + -0.37876889193663804, + -0.3981429195079896, + -0.43180829848666946, + -0.7428710504208984, + -0.7021189842015322, + -0.7856690884698447, + -0.3411151299117735, + -1.0735360562849705, + -0.5855582286108246, + -0.731675332139956, + -0.581126822127548, + -0.5741579691321836, + -0.3557534971248339, + -1.0699632681764246, + -0.5840584658369538, + -0.47499572453144173, + -0.33667061025440065, + -0.39357958581635705, + -0.3080532890998188, + -0.6052598791302527, + -0.3616528818822244, + -0.4339293833757269, + -0.785992120249986, + -0.7344314476697401, + -0.5282043432547215, + -0.3600602931653806, + -0.6032778923993665, + -0.9491315050226888, + -0.5817714267627797, + -0.8573914640894875, + -0.4052046455446269, + -0.8393014421858848, + -0.5212820186373786, + -0.3432159331440409, + -0.3028696946214693, + -0.7653278516815597, + -0.6711842954312439, + -1.2284152453625143, + -0.6364465162290571, + -0.5561519026014691, + -0.6326670293114854, + -0.32240366566602435, + -0.3783061670438671, + -0.9081961551918013, + -0.8495301952318799, + -0.4742240283401535, + -0.8651461768160661, + -0.6426862573621167, + -0.47416177940755555, + -0.34542224599849664, + -0.7430678612104682, + -0.4506997791086426, + -0.501515135297616, + 0.2110499858448572, + 0.42620030087791355, + -0.4157932126601725, + -0.25621419540428314, + -0.6254262094433054, + -0.4271629638129584, + 0.16328867096759173, + -0.7317178713614401, + -0.27306672595161646, + -0.17180518367333847, + 0.34506259810368123, + 0.06018527476424026, + -0.231670085370849, + -0.059577170082269294, + 0.5611076731197205, + 0.6127158274649936, + -0.9930896608471106, + 0.5528810725867013, + 0.7961138526393596, + -0.17126482415552108, + -0.4188900938811416, + -1.0240354311229334, + 0.28691278693811983, + 1.0860888339885257, + 0.4188789765769194, + -0.29114129727888377, + -0.6237650496096635, + 0.8489578415426077, + -0.1719868991378976, + 0.3343039573203308, + 0.36811722859577756, + 0.8533667336552853, + 0.6583835704718524, + 0.7844964868411332, + -0.388549275971764, + 0.05463065744504855, + -0.8249575249385505, + 0.6118055537098175, + 1.3466750276356523, + 0.23425873365456112, + -0.5013258234961572, + 0.6906232155880794, + -0.47848872832442685, + 0.23032999071684845, + 0.17776490157289057, + 0.35671719525244283, + -0.506981602604594, + -0.3347843011875719, + 0.47774262971418274, + -0.5540095125017617, + -0.5164055879913438, + 0.40500233048797957, + -0.22756734568618317, + -0.17015652073692358, + -0.0814536171610193, + -0.32384278001856603, + 0.4986861582790344, + -0.08936725015745473, + -0.034007096595369234, + 0.5344798537397522, + 0.14470547247595558, + 0.026259414347158085, + -0.42495912594759405, + -0.5394187016450505, + 0.3633664888761084, + -0.807528179720654, + 0.2548910489426702, + 0.10146372126925603, + -0.13953689705439257, + 0.2324492068463971, + -0.36231573368625664, + -0.02694609667739184, + -0.10345692128467585, + -0.3826130350663298, + -0.1269113713786922, + 0.38156457282932343, + 0.3915359752569436, + -0.8626063985935817, + -0.22474758370202713, + 0.29768248115028995, + 0.4900038819639598, + 0.46773260130671507, + -0.7717023896950559, + 0.34127244549073327, + -0.619263222844997, + 0.25972703865991353, + 1.2683675168363455, + -0.2667106306407057, + 0.5216579538372802, + 0.3233528638543231, + -0.8391375110966295, + -0.15103424335677015, + 0.3566325331274418, + -0.017218871800641446, + 0.6790633094488211, + 0.16520285245895974, + -0.7101118983442976, + 0.2932781811585658, + -0.6603575852456508, + -0.3786074183388271, + 0.20610367019792183, + -0.9520467786284975, + 0.5091938702481095, + 0.14813027815705088, + 0.10878961636774556, + -0.08057035728410801, + 0.4143051390457347, + 0.17150693758488714, + -0.7674530878542306, + -0.12530574274474449, + -0.26031763422645204, + -0.2898732356654505, + -0.4771036795691372, + 0.6397815044103153, + 0.3167760600338122, + -0.08874286834133296, + 0.5427771420232567, + 0.3198520782852606, + -0.03398489829859101, + -0.2273140102015976, + 0.538534948685968, + -0.02144238130671624, + 0.0397153564569233, + -0.08321237743298887, + 0.22681535874246733, + -0.341339599067403, + -0.2733195999876511, + -0.41004259113273733, + 0.5431891608189477, + -0.5721176706754023, + -0.19427469882923476, + -0.13820985496714072, + 0.5218080448316528, + -0.2524392299133815, + -0.3182183729557115, + -0.6596413562048329, + -0.33039425182911086, + 1.027150617402052, + -0.544948535807787, + 0.18129562126596477, + 0.3810252764314755, + -0.7280026834557102, + -0.19049754766650764, + 1.0387388630025898, + 0.34437771778496, + 0.2284374649115987, + -0.37707048995899356, + 1.0135488526601146, + -0.45268976439506936, + -0.06512447438619083, + -0.10023694128408686, + -0.3413937409372, + 0.28454718376263144, + 0.5879999807558651, + 0.24323088119625821, + 0.08890922023916469, + -0.7691397762953848, + -0.5903560066405292, + -1.1090796530914475, + -0.5549505474354713, + 0.5499888590094641, + -0.41771465596075263, + -0.43893376552589003, + -0.4787911497072357, + -0.2799188175879233, + 0.8244843770407291, + 0.4019977326037417, + -0.4996372505176554, + 0.32679316254192287, + -0.33802611276743455, + -0.10263556089314994, + 0.4027878964801185, + 0.06066934684137394, + -0.24359855675082556, + -0.9567549031230501, + -0.30057713811620024, + 0.4563618142721085, + 0.1534740376725157, + 0.7275390664222031, + 0.08872045388054102, + -0.14885833729992812, + 0.8114638035178485, + -0.27338888720350835, + 0.5146117705604585, + -1.0008556110348477, + 0.25255897200324257, + 0.003738427460650158, + -0.0590870124285238, + 0.6321452536387882, + -0.268496801704723, + -0.45879095837287154, + -0.2668771935514975, + -0.0934194978239568, + -0.4281116701742188, + -1.320418165499127, + 0.768651262259777, + 0.12725524836763027, + -0.14086579471535904, + 0.19316813080796455, + -0.18158888275373514, + 0.8239283203061271, + -0.3081253623562105, + 0.09992024931688082, + 0.3139953939046132, + -1.2686218006308632, + -0.12887611160370988, + 0.27298016388766666, + -0.16600908543553178, + -0.16758626608937613, + -0.3033959645941213, + -0.9553871632637092, + 0.28986340233638735, + -0.6039933028846305, + -0.4393019846609759, + 0.11609376308918164, + -0.38551755412208355, + -0.8427461528158027, + -0.3417638447039184, + -1.114316658805472, + -0.6477232158424843, + 0.45464029707486964, + -0.5075166998990257, + 0.16121233140083774, + -0.3481419537459604, + 0.4751116823717722, + -0.00386380710268964, + -0.23257818606264608, + -0.7770879742617463, + 0.8241943984561751, + -0.39995558689059973, + -0.27084850433130014, + 0.008122321540902321, + 0.6116484859825423, + -0.37908698434476784, + -0.09686437879541354, + 0.7292694723804479, + 0.12922665703608893, + -0.14210822807336695, + -0.8814125537461198, + -0.29233942405906216, + -0.07679926834671968, + -0.5273935946759803, + -1.4985049993115058, + 0.1294662632853207, + -0.4586700992515846, + 0.5296524473885728, + -0.265905746194361, + 0.3851164197467648, + 0.3261773832754988, + 0.08313010306923045, + 0.5488038623062554, + -0.351015374535064, + 0.15638433763035842, + -0.6935064100542304, + -0.24176295215043972, + -0.41423118948017285, + -0.1803882053339496, + 0.3829244413667374, + -0.11894305555516331, + 0.5697547257062816, + -0.14019521429648454, + 0.4322041897200824, + 0.5315470248734658, + 0.1388413225058262, + 0.2212764277043116, + 0.691504588409624, + 0.42639059287381337, + -0.45375505731233656, + -0.15373033698986502, + -0.20421432129932166, + 0.0763600360031057, + -0.4003924226238843, + -0.5005171137677816, + -0.4151480977717672, + -0.32427315096912906, + -0.42985977409771037, + 0.6791726951307625, + -0.2967497877665186, + -0.8502345334705146, + -0.21733908796375737, + 0.2079695322764887, + 0.024732229221180194, + -0.12977835885406055, + 1.2288636097220302, + -0.08553891113564152, + -0.13672760709741463, + -0.4905905768169092, + 0.30457148032215087, + -0.35856658210325176, + -0.04619901563542348, + -0.17112002816255903, + 0.556532266918093, + -0.012323757896508001, + 0.4240215509594417, + -0.3940860727151569, + -0.022308210073280856, + 0.35260892661507387, + 0.7151029865678165, + 0.1262379992095837, + -0.14149428215121268, + 0.32279812900372323, + 0.12895394244670885, + 0.6582058238619952, + 0.4364574339343075, + -0.012827158004707052, + -0.6677542972013167, + -0.3128933936637871, + -0.641900503300176, + 0.32197373070408275, + 0.14355837764322835, + -0.47999239084776013, + 0.07818286564276825, + 0.24783372633922016, + 0.026332410295227395, + 0.5594886068272603, + -0.10398315249768991, + 0.8063527002777353, + 0.7171239212841521, + 0.08489992283168225, + -0.11643803594409041, + 0.3679361500485408, + -0.6096903148373503, + 0.20554875183070279, + 0.4911078014229125, + -0.23373618857029277, + 0.6006054106728124, + -1.3120634938690994, + 0.32412666856613565, + -0.28062454470808607, + 0.22265170486064337, + 0.4216115953036957, + 0.1607259966288211, + 0.269778948064501, + -0.37701864281194114, + 0.06644156230981152, + 0.20253434843074405, + 0.13294755091334545, + 0.14664956124597592, + -0.6328077594779329, + 0.9385479665508455, + -0.7543452877935767, + -0.4104220521307745, + -0.15691256741196846, + -0.2476734551730555, + -0.16892144763444952, + -0.8175122526084472, + -0.13156251953519674, + -0.06676118259089983, + 0.5465429968127722, + 0.16448953201934163, + -0.15982729112581898, + -0.0713668828400648, + 0.28246400013283673, + -0.21573265676583936, + -0.4328537093192995, + -0.34066856700470655, + -0.11927363335560075, + 0.10476699862417038, + 1.028658959817338, + -0.3572665463997741, + -0.16012749482450897, + -0.5712278190775316, + -0.5683809135265432, + 0.245960795963524, + -0.9360654293591985, + 0.9962727259653613, + -0.5625046595136699, + 0.059505143515040056, + 0.09749882624191758, + 0.10934261046208849, + -0.18812756241462059, + 0.31977318826132883, + 0.4121379039977645, + 0.0424198156914578, + -1.3475607271915995, + 0.27941021880753547, + -0.3651448869252367, + -0.22567007162013286, + 0.45117771140508744, + -0.33545307748538755, + -0.29453414467803324, + -0.2230307352486395, + 0.5281727567773771, + -0.424064647391417, + 0.10986539655379558, + -0.5513163853373848, + 0.5014038174378553, + -0.5090319048065315, + 0.04934249719549867, + 0.3501896001199102, + -0.09068445890531539, + 0.6279551814499418, + -0.0030486136007396073, + -0.21621206549939298, + 0.7402594611756861, + -0.7130773465581726, + 0.7613834240213175, + -0.8888244580022762, + 0.061172204060953556, + -0.12449589568103302, + 0.07389302651402013, + 0.8036640979677336, + -0.7664908467724597, + -0.3509257090476938, + -1.064278151673456, + 0.03525411859673603, + -0.45767484890311627, + 0.17093571235388777, + 0.9743317988725125, + -0.27885782639562234, + 0.29853883549959215, + -0.09067958511266692, + 0.1307189517456919, + 0.2121860656415578, + -0.3211110418371247, + -0.8117422501045152, + -0.130484853733857, + 0.025602141072558912, + 0.06538164039989719, + -0.6678112626776224, + 1.7592281535014906, + 0.4153502282961965, + 0.20877728823834635, + -0.588126276437829, + -0.8000029436945686, + -0.2113892267124391, + 0.7237087825661149, + -0.14848436019370068, + -0.12706150887166434, + 0.24561490476257775, + -0.08638490296947923, + -0.5106242870487495, + -0.22060390989971776, + 1.1454687778289019, + 0.14820575772073052, + -0.46625717862401184, + -0.15395341635437979, + 0.1975728652832799, + 0.4294657760044256, + 0.4178216045123066, + 0.5124128932260921, + -0.10220315756619094, + 0.02590647417764564, + 0.3049910328069734, + 0.31063514540547504, + 0.22379889393204574, + -0.2178620099540545, + 0.38775283876453953, + -0.16865893966507103, + -0.24051310742041015, + 0.3277202924371939, + 0.9099609211444049, + -0.40614959168775167, + 1.0608644851508007, + -0.6736671889396478, + -0.34909871928724956, + 1.2369584195598842, + -0.012920719998972808, + -0.15440024979549558, + -1.0222619248904121, + 0.182483688704856, + 0.33833512408586147, + 0.628225289941426, + -0.3422933387592239, + -0.29395584960095855, + 0.33358644372200885, + 0.07856095284038504, + -0.06620021843148143, + -0.09413092751797915, + -0.2772943033414439, + 0.30223431548934326, + 0.6132944971046322, + -0.3257325193079779, + 0.30530290345843564, + -0.9788319378477819, + 0.07122193505356146, + -0.2816518961650823, + -0.11071862819246707, + 0.40107252791295567, + 0.7326087949601966, + 0.14552310419488085, + -0.4962859580892233, + 0.41229272019275237, + -0.4417831251479237, + -0.37432515144172834, + -0.5455994035895182, + 0.4553951301800332, + -0.08392939462467669, + 0.6113348074644341, + -0.3005334529120925, + 0.3498090558263461, + -0.0354162771045653, + -0.3559268472179234, + -0.027180008890302407, + 0.20137629445857347, + -0.5422748293320975, + -0.7396823201340922, + -0.1715551377107232, + -0.16297238158163252, + -0.07126530227517264, + 0.34868425240343914, + 0.6866665100571577, + 0.1557565569864459, + 0.27676637514992164, + 0.3891288944247346, + -0.31264975136382633, + -0.43816408757786013, + 0.8111866855181045, + -0.13668477720451197, + 0.07202718363850795, + -0.24172138343435565, + 0.04543818971326035, + 0.4982363100541874, + -0.2082458409280248, + -0.018117348189063878, + -0.5373990055859811, + 0.3600088740130466, + 0.9003957083863747, + -0.4081106909759515, + 0.4224102869504182, + 0.1584344375512478, + -0.08926622131515156, + -0.025151833320859716, + -0.05283196207736423, + 0.43888878089580696, + -0.12455281693491317, + 0.19181451737848448, + -0.6744881239709636, + -0.11962583783075341, + -0.5732660087035927, + -0.05532452937279989, + -0.06459817910972093, + 0.2876950831001954, + 0.6775333062436929, + 0.12265009382703662, + -0.37876727326369564, + -0.20125288070903852, + 0.4404460902437793, + 0.04706459153368173, + 0.3352497986288063, + -1.1318179690226025, + 0.12936448053764826, + -0.3226343451001604, + 0.5839193955088487, + 0.06341235872835621, + -0.06729985313454231, + -0.7936638706756742, + 0.20983558462839122, + 0.36396134636644245, + 0.1490061234406359, + -0.04587327289310324, + 0.7647635658697923, + 0.02965055499147975, + 1.0872273981112284, + -0.09817950408952787, + 0.11796966101531892, + 0.02842718688219637, + -0.15749756320677308, + -0.1600903518006323, + -0.6358400129070109, + 0.31214889297428017, + 0.07536744165439142, + 0.49308797026288553, + 0.18037069042784618, + 0.3463310353486366, + -0.7885440474988343, + -0.33443257967009643, + 0.8174758936801447, + -0.7215816879053809, + 0.7421096816808562, + -0.271289841032045, + -0.30594065587478664, + -0.6846695931015945, + -0.45828532360015856, + -0.5983625446015082, + 0.28946241231315095, + -0.2640659020427767, + 0.6497524426519787, + -0.36892414396851864, + 0.5024881875752447, + -0.43416825436388345, + 1.4806712278476561, + -0.15472966175704927, + 0.5206750811289379, + -0.17322708566409387, + 0.4277283353540764, + -0.05004295796397838, + 0.9063070668616678, + -0.06210555812990371, + -0.9367961336189257, + -0.591141123929487, + 0.28746099536732184, + 0.6281621412517643, + -0.3611999790229263, + -0.067658217184946, + 0.02552483809543511, + 0.17886851595952846, + -0.3461630878046319, + 0.5101005085487661, + -0.12389252714722093, + 0.42285439860194896, + -0.015866595402855174, + 0.8215630388738498, + -0.9445990612618937, + -0.03447925901129451, + -0.8692182439255888, + 0.40139016614788176, + -0.9178979408195591, + -0.6513561311760812, + 0.7029910439373045, + -0.30312850179888157, + 0.3653033400424275, + -0.5570249333003489, + -0.7005823048882435, + -0.22675427850491897, + -0.3849120269419198, + -0.5106693758841758, + 0.2961690262088185, + 0.12786994848937275, + -0.25164888528277835, + 0.5924506226427195, + -0.5496937620813284, + -0.05382107408237112, + 0.5830051440033897, + 0.1958634637780834, + 0.3733210964227159, + -0.6193294934037125, + -0.762602185767477, + -0.25801515867326313, + -0.16635106239502112, + -0.6047881015438444, + 0.2767079913698062, + 0.23039076368185926, + 0.8162207955864029, + 0.10460662535109279, + -0.21229874010535166, + 0.30145581868253957, + 0.06823980122950118, + -0.2846716948096807, + -1.1207974769602902, + -0.1713667358792071, + -0.12258689583719816, + -0.03183181115353744, + -0.0897514225922536, + 0.09822940252395394, + -0.08246483820581259, + -0.3610138446601097, + 1.2180932746885498, + 0.41323586370310506, + -0.7746013577332056, + 0.42366749204369736, + 0.11662421371143539, + -0.07137960825021444, + 0.14534280702266855, + 0.5430347769590735, + -1.8097624341828903E-4, + 0.5268860746877443, + -0.2387055740896461, + 0.5716577177227902, + 0.49808011975108096, + -0.288829878452775, + -0.02824541235034422, + -0.42273173564745986, + 0.07451889521917503, + -0.1721604873711983, + -0.664046080094363, + 0.10254747179969591, + -0.0505181512219806, + 0.2660797692281215, + -0.5574343866324087, + -0.10631415569434141, + -0.3884465858317963, + -0.8171312724792916, + -1.1381159453249736, + 0.6790199899828915, + 0.2961488366125804, + 0.11514185294697442, + -0.325275263412094, + -1.0487252278432044, + -0.060018257184772814, + -0.0794686770360482, + -0.09473449151893269, + -0.2832178499929537, + -0.1532750612314701, + 0.45594484224053416, + -0.5420949257100024, + 0.4625531971405018, + 0.25395110525665643, + -0.6787404248569844, + 0.5567157574740296, + 0.0359533804908211, + 0.6497486574085463, + -0.3627244744878546, + 0.3515027922728772, + -0.1736201153888026, + -0.07802690530317188, + 0.14723062862996655, + -0.49750947702808035, + -0.09194116195578265, + 0.6289266433955629, + -0.11974041853002855, + 0.027612892715469628, + 1.3485476778682708, + 0.08971759481093437, + -0.07185848751096048, + 0.3749862909590912, + 0.8058660271654643, + -0.4434211331190375, + 1.0360007748246458, + 0.273658464334128, + 0.8878883677042336, + -0.235823828164625, + -0.13515813071177543, + 0.3238913008986686, + 0.72867732404377, + -0.9339202684960973, + -0.29757505348633345, + 0.30631705973433054, + 0.20215295205167924, + -0.20483750493925681, + 0.26281318736293546, + -0.08183933041366792, + 0.16395804807766698, + 0.23741290443978869, + -0.6776805666136271, + -0.23693632739899093, + -1.0248896287345861, + -0.18743359688649744, + 0.7668233129101536, + -0.3450511041459851, + 0.08838994244156254, + -0.08904496920791898, + -0.3357127013145814, + -0.8659425721056992, + -0.7587708413750841, + 0.2215363867280212, + -0.5489253757612904, + 0.07369380995826454, + -0.32311205223556677, + -0.5215258450696976, + -0.6395963216302852, + 0.22230718748176206, + -0.164054598900991, + -0.1380551623043537, + 0.2022179535976376, + 0.6583497483508969, + 0.68843143578456, + -0.44095139503221, + -0.06366756360424654, + 0.05825545801700659, + -0.4516333396504925, + -0.335855284427905, + -0.20781221022135402, + -0.039016337840489385, + -0.3035777791910659, + 0.6226065857476225, + 0.22524476646098812, + -0.05704003061352959, + -0.9782276124866408, + -0.30739247893273736, + -0.4963807974001867, + -0.05938078565945291, + -0.475201117093431, + -0.5259724311666399, + -0.5613813876601261, + 0.24807683674394665, + 0.4195266561635064, + 0.3552100168055545, + 0.1257342827002142, + -0.3947619883728347, + -0.30421014034994287, + -0.3250316364038643, + -0.07639509588284417, + -0.16519386546336287, + -0.8014122851043072, + -0.2897884727459011, + 0.016004164184395885, + -0.8354567893688153, + -0.5098306742211988, + -0.738795908303663, + 0.310479711454913, + -0.4940787090163397, + -0.06008853664592638, + 0.12967749171506843, + 0.46700283295274436, + -1.2583998862390762, + -0.428503483345316, + 0.025282407652871763, + 0.03790894888362555, + -0.943188048486117, + -0.5188912530420862, + -0.31290322473804627, + 0.4366031454804373, + -0.030975885617496552, + 0.7588943739654831, + 0.5938755575328057, + 0.7357026646263928, + -0.0832830427838789, + 1.0795466720290916, + -0.5511432028949151, + -0.6910232025944232, + 0.01366184942479538, + -0.4779082866574467, + -0.43924929507601074, + 0.8525723242193411, + -0.023357099546511044, + 0.8561944092025612, + -0.5095706037455382, + 0.10681538580569039, + 0.19688226969277714, + 0.23618396475390643, + 0.02984786392916455, + 0.28642604664573323, + 0.49690610267349294, + 1.0054677392661682, + -0.2847666908431131, + 0.5947441473532312, + -0.39463739125498587, + -0.30491473904198985, + -0.023815494184391203, + -0.5073290873428979, + -0.12085563402076824, + 0.6592371482772605, + 0.22952813103239997, + -0.7168792311629947, + 0.16382234588941388, + -0.6582105053418938, + 0.45391944110224147, + -0.5449760758369516, + -0.4296878601162794, + 0.12126801475697065, + -0.3402399539000925, + -0.009397281080744021, + -0.4898535033820452, + -0.3269805698046844, + -0.05711751226174, + 0.004211076871968339, + 0.9163436673210162, + -0.5706384728106296, + 0.08127935613300638, + 0.055186141184503774, + -0.3105285603652188, + -0.04501525171981436, + 0.43053750718241657, + 0.1656775650637618, + 0.6761085265961593, + -0.944290112006576, + -0.9191272955246104, + -0.5540526290820523, + 0.2362790605917811, + -0.8084710796745599, + -0.5091628367511883, + -0.11096635342307608, + -0.8492261740927639, + 0.8556659049151011, + 0.051675935075098746, + -0.7881995100095299, + 0.3034368814667146, + -0.6886775916154608, + -0.5088055829597674, + 0.4239853540954365, + 0.5597823369578128, + 0.4545589121523313, + -0.7150640446587819, + 0.4362124510484275, + 0.47886966592975727, + -0.4209008231218874, + 0.12949629641984306, + 0.20761794214678164, + -0.35945782094463113, + 0.023435619347815708, + 0.029252142408245706, + 0.12539846406751634, + -0.11731206178916248, + 0.11233514712028005, + 0.5089821144454754, + -0.3364045839428105, + 0.26145447602026367, + -0.22679520373251932, + -0.18607636180278558, + -0.8037095418852506, + -0.7201558393345945, + -0.37646242608225466, + -0.6976975297918185, + 0.6662917656886559, + 0.3221544900722932, + 0.5233402242296338, + -0.04777824908190484, + 0.5586429677001621, + 0.07392198986429223, + 0.25709497154298483, + -0.14661938560615537, + -0.3495810228176034, + 0.7213908731196649, + -0.5410872489311334, + -0.9403429322470764, + -0.31599745154044234, + 0.2886939157773085, + -0.18538872598521683, + -0.5850503934568597, + -0.36014740534266987, + -0.36281635629728276, + -0.5602519985287201, + -0.621102846445583, + 0.20076217791101844, + 0.37733228956395765, + 0.13154284697255547, + -0.440384941331376, + 0.14881854540667586, + 0.2676869494762304, + -0.7527032517831578, + -0.7737269192235587, + 0.2161922019829116, + -0.20868300335851359, + 0.03911233702012932, + -0.17665348042734041, + 0.1766561001715066, + 0.14883735068011877, + -0.4326825433736565, + -0.13989516898668522, + 0.3118525444854999, + -0.5864959267364619, + -1.1209749665599065, + 0.2178196733660722, + 0.7950179524355185, + 0.2731233180057358, + 0.1553857942398676, + -0.0830187826840091, + 0.1281929684985854, + -1.1114466606093214, + 0.13169843115746607, + 0.7959797790132934, + 0.9931634030252559, + 0.13028079778297727, + 0.1958696913989694, + 0.3820745429854751, + 0.9209594040093684, + -0.14862393612611127, + 0.38907358015011656, + 0.48857451358044324, + -0.12940326729065146, + 0.08942196337930419, + -0.3568924383212771, + 0.395528518952455, + -0.021527128137671995, + 0.10153381198862081, + -0.18383736064356945, + -0.02269624664143112, + 0.3810342407806038, + 0.4510998430728193, + -0.6949400678640273, + -0.07982338016717114, + 0.24601201793798289, + -0.9513596568495625, + -0.15645145732297586, + -0.5753961125968043, + 0.35607848628154415, + 0.12583184353387078, + 0.21083084912083963, + -0.4622073931374296, + 0.10374431177005242, + 0.277446909900994, + -0.09075232701642383, + 0.03907789025877724, + -0.2203016774078691, + 0.02866822509918736, + 0.5236653802598434, + 0.01860280998185342, + 0.8333078144383401, + -0.12138014979219691, + 0.253717537585178, + 0.09392997205817775, + 0.5510005875091281, + 0.542850939083223, + -0.33986651031767257, + -0.2767739209355193, + -0.1413467952892897, + -0.31825177865115795, + -0.5227942941915942, + -0.150801963310256, + 1.3842678711395866, + 0.3148566249098681, + -0.03393002102112182, + -0.5138283474641171, + 0.5264821349939228, + 0.2516173363421229, + -0.1621631105650439, + 0.541653617180277, + 0.36948827596759554, + 0.7395246103691783, + -0.2539991629831097, + -0.24700618467414684, + 0.11469685693666462, + -0.14104437551129242, + -0.48894325310450787, + 0.011208503667299008, + -0.3035282472347137, + 0.03858382382265856, + 0.5947785935446477, + 0.34583216073247336, + 0.3305301210206959, + -0.08903286561826898, + 0.2129771748153902, + -0.5808063846851719, + -0.37453926387628367, + 1.1371842123872895, + -0.17238534658594012, + 0.5802326271743665, + -0.624182226066981, + -1.0319140511060114, + -0.471620981996211, + -0.8715432692733409, + 0.41124525764991954, + 0.19631859105392716, + 0.5564082105676413, + 0.7169073165715348, + -0.3804021472169014, + 0.3165963701718069, + -0.28349128308010146, + 0.5958247416421477, + -0.48485624640912794, + 0.05171903668947336, + 0.09730712352071816, + -0.3988998552762154, + -0.17399496350039534, + -0.7701453967075308, + 0.27526728240186754, + -0.8159763209605293, + 0.0349111334200192, + 0.003470119309771899, + -0.30670623615793635, + -0.5139934492239898, + 0.6023785124671783, + -0.3379805564024369, + 0.5642390325694413, + -0.35806656774562506, + -0.2369675216136623, + 0.33333502121060093, + -0.6468765812653616, + -0.08167609135035725, + 0.7615032675741559, + 0.22177260504665847, + 0.6448811038385092, + 0.06149080143208869, + 0.4136130564923131, + -0.08336204310157395, + 0.35413862760838566, + 0.7795819158222561, + 0.40282623030720205, + 0.08550768062663418, + 0.47041244897246626, + 0.5903145699795223, + 0.002466392485384874, + 0.08581914738591818, + -0.24823539178320134, + -0.6915427845482558, + 0.035052520754803466, + -0.4745662813315564, + -0.24010350522618737, + -1.6006570434442426, + -0.44063970084762116, + -0.02484168405062059, + -0.18033215050196486, + 0.36570016987897025, + -0.14746736853741582, + 0.6538308811678755, + 0.9324062899712227, + -0.8517885092053193, + -0.03709819446456665, + -0.003973780045762813, + -0.21352942243357678, + 0.1506379352798054, + 0.40181788534050716, + 0.3595276008182195, + -0.6311712058762643, + 0.8063786125667505, + -0.4280763979423024, + -0.5827462168468066, + -0.5167998962575684, + -1.053791493025888, + 0.44140581019664216, + -0.32874612777239093, + 0.16472167872463503, + -0.28838536342348986, + -0.8572446676124157, + -0.013391141413992195, + -1.8816082114583632, + -0.06740705058965916, + 0.16872736711409436, + 0.2567482285532557, + 1.280647748701119, + -0.24306303782705854, + 0.5066167255026878, + 0.04617595047821626, + 0.1457759909672803, + 0.21338812771723825, + -0.2159274684974311, + 0.3320594689841113, + -0.03836159851406403, + 0.7725845574398894, + -0.517121316829939, + 0.53303317040926, + 0.1563606402138042, + -0.8599862797414322, + -0.1545552846035798, + -0.2689216360067056, + 0.14832859072466412, + 0.03247425165169496, + -0.30348830437942964, + -0.006459135788635269, + -0.2944791748100941, + 0.19215442889120227, + -0.043557134640076295, + 0.188538581415955, + -0.14542301295960416, + -0.4921070077293613, + -0.9109121745876637, + -0.4142285228182321, + -0.05368087290673946, + 0.20265320043623797, + -0.191654538884673, + 0.6278367683929502, + 0.6165013119510282, + -0.21667380197459277, + -0.1016411496410225, + 0.02861855830457847, + -0.18119337895190793, + 0.21009915739808407, + -0.6911712675740322, + -0.0014011694356141347, + -1.2902857710281934, + -0.36430832382012646, + -0.09794089063478575, + 0.4021928530037024, + 0.07334146608967262, + -0.038555787270797545, + 1.0576258148331066, + -0.079117535946979, + 0.4176064077035839, + -0.5126816655241476, + -0.10966443740181443, + 0.5397845017348873, + 0.0013965675541889047, + 0.13241428374905248, + -0.93376788617159, + 0.6997198832978184, + 0.09019094860198806, + -0.7080298699610688, + -0.13757970053218835, + 0.2716535202531011, + 0.32809510477884174, + 0.36333405031472615, + -0.2832782274607326, + 0.21075184228781382, + 0.5038984579333279, + 0.8620350470616597, + 0.16631571331620695, + -1.0663239162850893, + -0.5137099027372973, + -0.6869924819781886, + 0.38014687812300335, + 0.46193446465221955, + -0.8137193795551975, + 0.5201359704177297, + -0.09450334235877732, + -1.0154546188089004, + -0.3622380783662246, + -0.196561523901152, + 0.1806509208728367, + 0.469864825198497, + 0.8951645133121141, + 0.6280223412832944, + 0.05139120423185219, + 0.18549406187157555, + -0.46714077926387915, + 0.2835741135864347, + 0.419409229588534, + 0.48382115513480073, + -0.035692328859432736, + -0.4440690023943076, + -0.2877006968917387, + -0.7790031549082989, + 0.6183666401892534, + 0.7419216936126387, + 0.9711756109730578, + 0.2569510796586897, + -0.12834957324674884, + -0.44297907543767967, + -0.12793374905014296, + -0.5128111673498348, + -0.23896342728057215, + -0.7555424899105989, + -0.28778214526567875, + 0.2959793990886678, + -0.01616963329911572, + -0.41325599655766915, + 0.4005207952162317, + 1.0188051061493646, + 0.5102966979872879, + 0.6734436412408001, + -0.38651565831560986, + 0.6899419893769787, + 0.3967236931841341, + 0.8999585316241475, + 0.6840855864621278, + 1.2769336588925067, + 0.3898128757465988, + 0.10021855598806752, + -0.54776934981321, + -0.13209964085764941, + 0.8605331876849119, + 0.24330727291791238, + -0.15571947697929897, + 0.4068074134970485, + -0.34142520652327557, + -0.24155738091589118, + 0.33496071034533564, + -0.353007382655274, + 0.3917693855976409, + 0.7390823429318074, + -0.08748341139805532, + -0.22318450601020545, + -0.27173121588048804, + 0.321496150459878, + 0.45910509048776005, + -0.49297364703743485, + -0.7020898497473292, + -0.3463425722991704, + 0.10078975203117306, + 0.11338846488993204, + -0.4890436513669071, + -0.04607748052369422, + 0.7874422969858837, + 0.2273793419600591, + -0.16019596920952797, + 0.0269886030204676, + -0.6470538865655187, + -0.6790993052390719, + -0.12427791137019256, + -0.5221993786735951, + 0.16042229033062028, + -0.2629451846171667, + 0.4925501300311875, + -0.9597895833086874, + 0.360943990634084, + 0.005887689375031211, + -0.27525162417579324, + -1.006370220600119, + 0.28010903136552245, + -0.576108293283392, + 0.3159434335384174, + -0.4158450090426671, + 0.46776465251810667, + 0.24510815188504756, + 0.06104953571714768, + 0.731794499219922, + -0.77790273904801, + -0.35424933567476996, + 0.7255754299072138, + -0.04615856748590781, + 0.22635633006574352, + -0.46913313355648983, + -0.2834277449397551, + -1.3852824927866174, + -0.28903687475133333, + -0.7259951682933794, + -0.04885584202469074, + 0.6554044628825384, + 0.48896117803341815, + -0.8165784229999056, + -0.03863593489655057, + -0.3111165757072814, + 0.657614251371422, + 0.2633317835080035, + -0.107395205654997, + -0.3429737187870754, + -0.5082028984817225, + 0.6834760663015444, + 0.5613867062163261, + 0.5135043281515163, + -0.6977857094270838, + -0.3807460540612913, + -0.48332154243683456, + 0.3550759245137817, + -0.6807355724183778, + 0.3263394630445428, + 0.2899941214765777, + 0.0845933119555791, + 0.7967676761724062, + 0.7657636165897563, + 0.642680351750586, + 0.5307009922794903, + -0.48506956062531587, + -0.668460072693867, + 0.7406775779041944, + -0.6964015879730869, + 0.11973503495162525, + 0.5959022238897754, + -0.6554121580169145, + 0.05456348596963757, + -0.026754425671440752, + 0.4227827935621255, + 0.16188281701340326, + -0.19685555743730154, + -0.18445983933812615, + 0.0028482009368305345, + -0.00843965571941356, + 0.4907889507406118, + -0.13280191625487256, + -0.5490942179117023, + 1.1416440056627963, + -0.23824769711274799, + 0.3761670162309367, + 0.7193392414426139, + -0.10693243628353696, + -0.414688071951323, + -0.5389103914632526, + -0.06355093151501047, + -0.7518526713886825, + 0.31163942251505317, + 0.43090783311116737, + 0.12640406967809575, + 0.42984154062270075, + 0.2123540250178392, + -0.28844747044777075, + 0.35444775654563665, + -0.5197561970844456, + -0.3501050596533284, + -0.32470898714244, + 0.4689803898764972, + -0.4756182996734624, + 0.9864714742476929, + -0.1757418990472665, + -0.15630283745887924, + -0.284872412552382, + -1.1392472374227316, + 0.8604996091942595, + 0.7840181090029431, + -0.9443313306480062, + -0.55387665951346, + -0.3933962639726677, + -0.2177998401214084, + 0.6914221548515483, + 0.8971549631776234, + 0.05326111996840626, + -0.592072758159301, + -0.35615506073736425, + 0.14695421157162245, + 0.7938888894339565, + 1.0360580163727244, + -0.36724723153470923, + -0.8606356399611802, + 0.11680479803498907, + -0.14587942304126444, + 0.3775961102778459, + 0.03886774423179407, + -0.48194444522876706, + -0.26132136915238796, + -0.521497399369086, + 0.059809042870644626, + -0.6157097305109076, + -0.7610223730518161, + 0.34213571069959786, + -0.21960243003625318, + -0.15520712359020136, + -0.5069685354387546, + -0.12470088884201543, + -0.11770571073737818, + 0.9104120785604047, + 0.780256966330715, + -0.22868698714609553, + -0.2708316148012118, + 0.2955044714110247, + -0.46933192101355437, + -0.377606711538762, + -0.07224784083681335, + 0.03897005637345873, + 0.6468211477096071, + 0.2901928727619407, + 0.7115251422647753, + -0.26755777719836427, + 0.21172261099554676, + 0.4608962376185694, + -0.02818141151433887, + 0.08262235485616465, + 0.214550310138542, + 0.31793738264118593, + -0.09752558903401413, + -0.7949659931267914, + -0.4058999085576534, + 0.08111555494280971, + -0.08496898906486527, + 0.6147129709542619, + 0.16577955358478516, + 0.6228798302300956, + 0.5310448623060056, + 0.02857809657591958, + 0.5326807905181823, + -1.2232451774216455, + 0.6461614022398804, + 0.47785548472637185, + 0.42010359336318553, + 1.0039621978703261, + 0.11065923899714876, + 0.21868080066647258, + 0.36594351838789585, + -0.5847905485076124, + -0.19522694998169707, + 0.03613591883824765, + 0.06474101905157284, + -0.3130086968498404, + -0.5509467483829301, + 0.04567582437409976, + 0.11028888914898229, + 0.26292703419846497, + 0.6624394509439796, + -0.2135555453955407, + -0.38125391263540326, + 0.7993525009593141, + -1.0882624738331739, + 0.41490670612298647, + -1.019258548328374, + -0.1687687721705572, + -0.3359882105450316, + 0.06667069904421079, + -0.4967450272188255, + -0.12174976798172539, + -0.6341597684100857, + 0.10928659326247624, + -0.37679044464942885, + -0.2915700244616676, + 0.16091274460733204, + -0.1109126755056546, + -0.32837379242696835, + 0.16801386808431001, + -0.6650815464931916, + 0.3015747021321843, + -0.15361427213591392, + 0.18319181900127482, + -0.3124804509692331, + -0.5369797922533317, + 1.2230342925905937, + 0.8792620354946391, + 0.16030526307533857, + 0.15965486755212702, + 0.09809313516845541, + -0.048028073034470424, + -0.22553289403981316, + -0.9574518363593059, + 0.3077104020168734, + -0.09104451432610101, + -0.13553267346625614, + -0.18341760143470978, + 0.011941825949769752, + 0.1765411018896747, + -0.3600851149041499, + -0.9509204310319184, + -0.585623976009847, + -0.16287588033498906, + -0.35846490321029945, + -0.3214891194169931, + -0.03737840366285909, + 0.37589245516990016, + -0.4359686002390747, + 0.7033355544691727, + 0.3132576260344879, + -0.8889903118295244, + 0.0803532714047713, + 0.6435100828419594, + 0.08350172887068896, + -0.12693371150674837, + -0.4299424578735063, + 0.8708189506692524, + 0.22643856995469872, + 0.27279093578447555, + 0.14090316275291478, + -0.6087808474636246, + 0.334460757728289, + -0.3170364398533281, + 0.08625203468204452, + -0.45442255528513076, + -0.27921864152665893, + -0.4530598281075038, + -0.19817905053027526, + -0.4985254998741575, + -0.12089826091857096, + -0.5036483164306714, + -0.5656392770111147, + -0.4759638505537391, + -0.19071006313785774, + -0.2684205741237195, + 0.26458431324507153, + 0.22084436896035076, + -0.0930797404053455, + 0.321342036477244, + -0.18572467840658702, + 0.09245726982086001, + 0.3775605079708818, + -1.4956361315517093, + -0.0704527710230369, + -1.3921012403676443, + -0.11966656621487978, + -0.2528831875015759, + -0.5632246211658973, + -0.23207881401650174, + 0.11860586173329737, + 0.038936181891424254, + 0.32109257288211523, + 0.1958255768886279, + 0.13596483524731642, + -0.26338942565915185, + -0.4371371105958646, + -0.17343192876983837, + 0.011198369312149615, + -0.09860062902401577, + -0.03184974239581293, + -0.23508520103612318, + 0.11714656494930709, + -0.7224735574573798, + 0.20043050860691, + -0.4728398009238381, + 0.767890951047822, + 0.5224971838467685, + -0.7518378631517151, + 0.15762720920795556, + 0.29258267273582605, + -0.08450694350125006, + 0.8412539704285962, + -0.013112616759314332, + -0.42039561691031224, + -0.11662470092612588, + -0.046731267020009855, + 0.0017907609076426322, + -0.5298101691246927, + 0.11063584961434164, + -0.6824176718942228, + -0.7586647472485806, + 0.879047504189492, + -0.8252558093656505, + -0.2256137045820668, + 0.42171649493758845, + -0.222365640810201, + -0.10684236201855303, + -0.025554589785615315, + 0.3099096597690366, + 0.09627951354920786, + 0.7941578178326737, + 0.3683500609107082, + -0.35116410900222667, + -0.2947329568536956, + -0.29329178743097883, + 0.201751125066881, + -0.29718061189399947, + -0.8673063503486297, + 0.8208753380278301, + -0.36677808090296293, + -0.2590004593686021, + -0.4444164226069438, + -0.029964994987629695, + 1.075017460609858, + 0.8502793650730468, + 0.1414359343740054, + 0.3623877057410004, + 0.34236548520316934, + 0.5706075746891369, + -0.41482211414951164, + 1.2645132896885387, + 0.20974474198289028, + -0.1023189994938565, + -0.3312919523624328, + -0.07300901541912043, + 0.8189371799145057, + -0.39688850588971064, + -0.10600506836045408, + 0.21760948576825484, + 0.8061577720655907, + -0.2781461647537158, + -0.34988767852198405, + 0.40208223897330725, + 0.7616872564482122, + -0.08828633000873357, + 0.9174604121918316, + 0.26512226571082487, + -0.06909675505944231, + 0.9250537149796435, + -0.02415190121500857, + -0.035423820446189275, + -0.2181199430534131, + -0.06988215355230701, + -0.5663976584902419, + 0.2112751363542655, + 0.235749596675208, + -0.2780359555692551, + -0.7416589670555791, + -0.5761786060058567, + 0.36172180213876187, + -0.10271041060950857, + -0.554175050446249, + -0.7277374400261386, + -0.15996493961792635, + -0.46568807599051454, + -0.3994987547387066, + -0.1897594812264694, + 0.06695506939564776, + -0.06934200926843662, + 1.0406278314461799, + -0.128106603108681, + 0.5360656901266786, + -0.03803720580960865, + -0.0429145804304284, + 0.6625428462947109, + -0.09326581986632028, + 0.1516237869892924, + -1.0501207302896751, + -0.47252759190243276, + -0.44636742929051765, + 1.1108792264673548, + -0.06293306899268072, + -0.5066477859177725, + -0.3205835885658857, + -0.46707879965493987, + 0.20160170171867592, + 0.19841825820241707, + 0.6887598148164904, + 0.008521779877603088, + 0.1062429978109105, + -0.2976237881701904, + -0.98153407402906, + 0.5164567275209444, + 0.4872773627502231, + -0.38187260355762637, + 0.7300675392837629, + -0.30306745511368666, + -0.1429423706046361, + 0.13172391006402012, + 0.2675269649490115, + 0.5971126795797234, + 1.3674226297352765, + -0.6056524294835779, + -0.7216999395219951, + -0.39780871763116793, + -0.2655518533835182, + 0.09580946959328879, + -0.14641209051003315, + 0.5617992991507499, + -0.06443581723383818, + 0.2703481551632011, + 0.3215119413055228, + -0.07457495560453298, + 0.2338970844927608, + -0.13855009267206922, + -0.18227497132103906, + -0.13883187466710242, + -0.7396712192724344, + -0.17737194809901793, + 0.40002967582924537, + -0.2968646863385267, + 0.17845596076132766, + 0.9940160088346636, + -0.17774664200826337, + -0.36843297475363834, + -0.7791838011594783, + 0.403859070699685, + 0.533800161554264, + 0.7963021371721405, + 0.16214668625071116, + 0.7273956085638833, + -0.12555699633862671, + -0.604749354365689, + -0.25458675452297524, + 0.7070899380875182, + -0.008581813268572743, + -0.9511668805552544, + -0.7034556544704335, + 0.18439541489578976, + -0.4836281809619081, + -0.12906578541953534, + -0.9571820097743202, + -0.6856349216479957, + -1.1797753311446122, + -0.3154456241421431, + 0.23453459426658266, + -0.42494346110011577, + -0.23301149317982492, + 0.3143624296259315, + 0.6866584477260308, + -0.32215103232003744, + 0.08456649940808755, + 0.08340562449843815, + -0.06181287812876806, + -0.03184111344556618, + -0.6879087624991409, + -0.5582354573696927, + -0.0970214666442831, + -0.6598857619730211, + -0.3243155614109818, + -0.1619730367105765, + -0.07222307402753228, + -0.29222228869128913, + -0.619276056681218, + 0.4514988868225191, + -0.2508550727682037, + -0.6389919724878512, + -0.8178328852967531, + 0.5362904839126351, + 0.8045849675300408, + -0.4382536465446328, + -0.40668914540830853, + -0.31331128267986147, + -0.23373934348038594, + 0.1329233896660298, + 0.28732965129435567, + -0.12955254845401315, + 0.11347477884372247, + -0.2476955977918175, + -0.09299189326287191, + -1.294425818064771, + 0.10266876513551572, + 0.649448493562771, + 0.8463345652938514, + -0.9102158458068059, + 0.06938341323032458, + -0.21996285788572698, + -0.03271393871532494, + 0.3480114495128493, + -1.3164216865882878, + 0.6234618672020347, + 0.31794048307257505, + 0.12912264444739863, + -0.6210463059433075, + 0.3420774720635168, + 0.17252641087615067, + 0.9365942943686073, + 0.518824848392818, + -0.16012666645918608, + -0.280599498007953, + 0.6277351258362927, + -0.01837130703210297, + -0.8683557048902658, + -0.8815968050549186, + -0.21965059610962911, + -0.47671381440806004, + -0.27378977121738884, + -0.30852853556353577, + 0.6449484227670542, + -0.19641723656330534, + 0.015528998813749273, + 0.4767460799683823, + 0.4773596262253645, + -0.384718177399725, + 0.44079331452814174, + 0.004736638182784573, + -0.21919117276903177, + 0.4823658278608428, + 0.39179445663910817, + 1.1286130687371965, + 0.4495160169250897, + 0.22705579055731365, + 0.1577752115391083, + -0.03222261650713381, + 1.005331380675792, + 0.22789968626436757, + 0.3502461119560133, + -0.024951609752197727, + -1.093504671925102, + 0.14471121927359104, + 0.5628844936010778, + -0.17921454113168037, + -0.046588245564804676, + 0.6582198616599352, + 0.4678855855595665, + 0.40303551833954, + -0.2799470651185393, + -0.32327714002729185, + -0.359980865895231, + 0.568754517189096, + -0.7378478129761861, + 0.06142000172541232, + -0.18777277798333314, + 0.45157176202300137, + 0.24757500871914628, + 0.008419538897251281, + 0.1955357147286907, + -0.06291376959234192, + -0.2581883415973252, + -0.3033196793568833, + 0.7498787912959904, + 0.19910292372310623, + 0.2624666490748274, + -0.17252057184624184, + -0.8920091310468008, + -0.17480202038181886, + -0.40855888437020293, + 0.11818062193424932, + -0.08850920971883529, + 0.47346871981877997, + 0.7246175185103927, + 0.6577109555607226, + 0.07192734806465577, + -0.5001123780588933, + -0.6331187088992554, + -1.1382356030757934, + -0.24777800584592544, + 0.1312832264812646, + -0.42833633347100086, + -0.1550136938954118, + -0.3578402683164373, + -0.5983221651946803, + 0.6154782025543818, + 0.038272218101503545, + 0.5569982054443781, + 0.03910614025142103, + -0.20029946071436192, + 0.5849411055500876, + -0.5902663220580024, + 0.046321426903560156, + -0.3615429853073636, + 0.6236882699043679, + -0.08741053637684956, + 0.3667300389897474, + -0.15656713156550336, + 0.4410896029243951, + 0.2032839309196896, + -0.13610479377341633, + 0.2508181194003413, + -0.45452676413210097, + -0.5463562719704392, + 0.4872895026811989, + -0.6094371008004968, + 0.9019840855208315, + -0.6824850306561189, + -0.30653782478805136, + 0.8334797626050874, + 0.4199397862834705, + -0.27795450551744477, + 0.37494608624888437, + 0.2443484080814103, + -0.5771869970475518, + -0.0040479200561172905, + -0.2893143498252631, + -0.7510528671504252, + 0.07607874805671244, + -0.3289562915880646, + 0.7260249766588232, + 0.3700708224912622, + -0.3431673174130815, + -0.5887011920992591, + -0.5146687247292354, + -0.13705091300838715, + -0.4755702215458856, + -0.6741838372481186, + 0.8113600661802982, + 0.12888336740382272, + 0.22024457024405406, + -0.8457418493334441, + -0.541269891228891, + 0.4081135759109108, + 0.12637773138669772, + -0.20793472159352253, + -0.3575268243392322, + 0.19887778596735117, + 0.3226665575822866, + -0.3310252106679661, + 0.41212106452665925, + -0.02231103216205929, + 0.29801701849698026, + 0.16848309131945782, + 0.28133823878573827, + 0.12890151660067375, + 0.23216787675384598, + 0.37322539386334774, + -0.6854979522871797, + -0.7815778459603394, + -0.3186001632574446, + 0.590108250556745, + -0.2689860814748252, + 0.4141172403875448, + 0.33021891174553164, + -0.4734757650681003, + -0.2594773146083379, + -0.20202043333433803, + -0.3430367275491683, + -0.06621465042427074, + 0.07558789948077146, + -0.03244207831823566, + 0.13399780941441264, + 0.002300929108019091, + 0.6224312525440708, + 0.9105448648583303, + 1.0083685823350894, + -0.1401050254692726, + 0.12299654128071617, + -0.09721986388648829, + 0.4053788375872105, + -0.9923830374245973, + 0.014482524118753719, + 1.0882555904539162, + -0.3017166805251211, + 1.0099898266435563, + 0.49476011285906607, + -0.6286578562085455, + 0.5972634660250874, + 0.01059356557461526, + -0.4380406372714907, + 0.23831661405761947, + 0.15867330840916463, + 0.36346027340339515, + -1.0729289045880899, + 0.3374566331885378, + 0.17216528555320576, + 0.16754430199598264, + -0.10116613365600949, + 0.5637269075382554, + 0.7394679372345659, + -0.4293927179742164, + -0.5453577145775285, + 0.981658407721695, + -0.19594819960186824, + 0.005111453928840476, + -0.17510954378162197, + 0.669592431840307, + -0.4689095814062196, + -0.7635402580505665, + 0.12333094878651205, + -0.38030670318711113, + 0.5976417215428129, + 0.8915658729372016, + -0.48574745309494466, + -0.4333339953504151, + 0.9110927093641327, + -0.04215665410413704, + -0.2577992415718363, + 0.23234861331747161, + -0.001647963763217758, + 0.11977145820313496, + 0.5185781304879099, + 0.05300577326813025, + -0.6171437983950341, + 0.5416944406291508, + 0.014050449080936143, + 0.7261174804781817, + -0.19900267873035984, + -0.7103459029896897, + 0.23936920003496162, + -0.7491409344669747, + -0.2062291352834982, + -0.04995535458465599, + -0.009343659278235765, + -0.24519548313879336, + -0.944458699935972, + 0.2507933735876061, + -0.4601521918596444, + 0.15761082321115616, + 0.6953910258837127, + 0.3738356202750641, + -0.8726130045534765, + -0.2728036827651962, + 0.09620729626125814, + 0.6657713540797451, + -0.37305730928900516, + 0.5236807041694774, + 0.6979123235918399, + 0.28503364993542524, + 0.0843500743116184, + -0.2067337025728278, + -0.47250882220434215, + 0.2160087642531865, + 0.47413884833300274, + 0.28067762464345347, + -0.16778129174063933, + -0.9245360556312353, + -0.5107387282585755, + -0.19950571963275185, + 0.8070985504357199, + -0.3218900969787237, + -0.32977542282177746, + -0.0496987408636455, + 0.20473439439003038, + 0.07870764575138274, + -0.3295503013935924, + 0.2297322930095004, + -1.15236402516706, + -0.04751648116889761, + 0.3625256670340242, + 0.3252652672567468, + 0.12748052789754477, + 0.1806485361366871, + 0.08123880580867562, + 0.7538830584684374, + -0.062342356480710535, + 0.2775813986535667, + -0.10318386518390837, + 0.2645184803080892, + -0.1180263273556307, + -0.17554826034013274, + 0.04202813103695127, + 0.16449730680826996, + 0.8634462645299915, + -0.23954907210109655, + -0.17386725571052766, + 0.35591863779362054, + 0.5580940436697364, + 0.5399300110096227, + -0.40427132855434456, + -0.21937527648152944, + -0.279293279072863, + -0.09790516963774011, + -0.0626411227061788, + -0.6086448335064242, + 0.8145028286432049, + -0.824040920510266, + -0.017998778013813534, + 0.37250629835455923, + -0.23270648518096904, + -1.0565780466787624, + 0.3966945432158073, + 0.2092714088330943, + 0.039885999415130595, + 0.5982648623148067, + -0.33800134233466905, + 0.06472676779868083, + 1.0901512544513634, + 0.2888846640102879, + -0.3677112440734192, + -0.10279678309395089, + -0.1266059259641946, + -0.08185999699048457, + -0.6493678320755621, + 0.8722708636292561, + 0.2434179249471845, + 0.029314810453880454, + -0.11400243830664487, + 0.34148833708698456, + -0.2882815423814361, + 0.02336502935467306, + 0.020641754494653886, + 0.2712683729853975, + 0.43235737513600586, + -0.02817238476013433, + 1.003146432195273, + 0.7223459150325753, + 0.06907483674327906, + 0.7796797475867099, + 0.35084951232867345, + 0.1329861809593595, + 0.21881333434926784, + -0.46708922471658765, + -0.04936073354564595, + -0.764775014421946, + -0.6548049418924111, + -1.0383508208746486, + 0.11268296310323803, + 0.41942563419348083, + -0.3938051490637394, + -0.49167208298009635, + 0.7135794965537702, + 0.13912789289085517, + -0.8042406689190351, + 0.2877623745383792, + -0.042976850406273887, + -0.25984465628140474, + -0.05932689367951057, + -0.2862752902609264, + 0.2762864748350375, + 0.14701605132739382, + -0.1719547551792096, + 0.3834010323586625, + 0.03055116841520445, + 0.4045585740670746, + -0.5253478071348835, + -0.24695488312062067, + 0.40743002712014376, + -0.2889108668674144, + 0.44343917111821446, + -0.5326670849733501, + -0.01699398833546559, + -0.09390966969912298, + 0.7813614674120755, + -0.054219814128922, + -0.4330484931007176, + 0.6096157329482353, + 0.03750725249734667, + -0.114088091690373, + 0.28151224517551143, + 0.45412195230877855, + 0.263518306529042, + 0.04278619481077944, + 0.2692011158260185, + 1.6066908046546164, + 0.27160268729227904, + -0.5386196142366445, + -0.44728387416059023, + 0.6160385620131773, + -1.0286683326121149, + -0.49553967868706084, + -0.5525332755537853, + 0.8792628981346295, + 0.16698831911523432, + -0.3153300353710633, + 0.7741048095319478, + -0.20103507703721393, + -0.3708478234042409, + 0.362358905918169, + -0.14911712313078, + 0.49205554321585093, + 0.6154358223794414, + 0.13100536904776233, + -0.3709123614583962, + 0.2708766773262833, + -0.1322201872443697, + -0.5120802888103511, + -0.6632408437651883, + 0.7671951376231799, + 0.1925300899382175, + -0.08529185968737313, + -0.10209119993566139, + 0.4355490966405857, + 0.09396811274066144, + -0.10377149258551605, + -0.088269197372795, + -0.07708033755745676, + -0.31386473841333207, + 0.22078589533144605, + 0.13376245469920653, + -0.8239079738541163, + -0.7353721111430911, + 0.18002471596336914, + 0.19122881748361018, + 0.139244521257312, + -0.5193166662950124, + 0.5989108073441322, + -0.15759921471332294, + 0.9200192923212767, + -0.3107471366233964, + 0.6995363601849461, + -0.10532602015893183, + 0.324408630467551, + -0.07712329853035946, + -0.4458899963219313, + -0.44194651883002695, + 0.09908154087979236, + -0.5295248580787238, + 0.5413725444343513, + -0.6894774926328422, + -0.3380352291194672, + -0.23425341490364682, + 0.07614896763865224, + 0.29177295468736936, + 0.4021215167457517, + -0.24601522721111047, + 0.320747540285817, + 0.38309768211388884, + -0.017536640747928663, + -0.7154532445817109, + 0.30521359556216426, + -0.7036461634096196, + 0.15810996359840232, + -0.4755466623264165, + -0.33291286782491064, + -0.04655970829186734, + -0.14400800665482322, + -0.6968352284647766, + 0.06982476168991467, + -0.05379342484872895, + -1.1019334510311192, + 0.18612452005116945, + 0.30775316427330396, + 1.1964834590444295, + -0.4627872660673701, + 0.24854843735667906, + -0.3427246088200402, + 0.923773852330942, + 0.9155298184506526, + 0.29922992288116823, + 0.7822330493460706, + -0.19661561133374572, + 1.1646445290090464, + 1.249773879699896, + 0.03862834396706982, + -0.2895974374840807, + -0.2906390446834013, + 0.4893240155722635, + 0.20474491351727855, + -0.18152834787667688, + -0.038595164841981625, + -0.37410246340403913, + 0.6154733468287418, + -0.1335799155485501, + 0.41887007654533404, + -0.8039771421251558, + 0.3182451699808918, + 0.12658170748713657, + -0.49077289293748255, + -0.2312732442841021, + -0.5995945521208328, + 0.2196100714850288, + 0.9013647128552673, + 0.6837372310184925, + 0.7283394465513768, + -0.6349780808664262, + 0.20322957236538308, + -0.1979398236315283, + 0.3975595332561987, + -0.12880523752648582, + -0.5864067056891633, + 0.5320728080482255, + -0.8762492069026306, + -0.43419858569861025, + -0.4505467695178736, + 0.9219123806462882, + -0.34666683383256003, + -3.9175776022702007E-4, + -0.5882576956710538, + 0.002291900784413608, + 0.03615761910558808, + -1.0307112379228167, + -0.12588670578448094, + 0.9833808389356176, + -0.12990638401119997, + 0.047041240727800845, + -0.4506824293912977, + 0.5911408528157203, + -0.28626426985367076, + -0.4090555756005233, + 0.42322614062026176, + -0.07225103186056665, + 0.22040520726324989, + 0.025138008729966077, + 0.19579975279236908, + 0.40222592514420885, + -0.6391918511656149, + -0.009889898133442343, + 0.14911029825610903, + -0.3809980511128946, + -0.23527584116327122, + -0.727825823078564, + 0.2912491447255478, + -0.2298294732792132, + -0.2735162954224469, + 0.28178042830482536, + 0.31542669242981247, + -0.4729321345640619, + 0.7248424813698343, + -0.9961609871800632, + 0.7397513416316535, + -0.46795277966501825, + 0.3887530436943637, + -0.2640923825562555, + -0.21293423208683532, + 0.4104307131666029, + -0.41756736333731004, + -0.7259691530814576, + -0.34993251602634584, + 0.46244868485809404, + 0.028319256904358305, + -0.5331283428096292, + 0.3231432619328408, + 0.3124802629608512, + 0.2462721384770423, + -0.03357183236897454, + -0.4299294031726956, + 0.7714199093213758, + 0.12042597687025156, + -0.1522746840349954, + 0.6561269336028568, + 0.5613103560069503, + 0.2874751456029539, + 0.48228308910119994, + 0.9711607281040295, + 1.3446608489429346, + 0.8290629377808413, + -0.6360984272356087, + 0.5028586957253394, + 0.17641702307271617, + -1.0272535742491051, + 0.34321134086750343, + -0.08258675055862197, + 0.12963329062059026, + -0.79721232753211, + 0.11910788474250893, + -0.13955399343058383, + -0.3528338636919641, + -0.5549261738054487, + 0.03649178892625784, + 0.5577684926879272, + 0.2494658951625034, + -0.8394289990318008, + 0.05189526768070696, + -0.0779016912232848, + 0.7550520110525656, + 0.06588741643394577, + -0.1380523440015115, + -0.12521443349913963, + 0.2333621229299668, + 0.12792134972052494, + 0.8409897659786231, + -0.7030161401716848, + -0.12586446708646998, + 0.04264826311026376, + 0.807753960496058, + -0.050341008630568077, + 0.20285460252045157, + 0.4651641492641196, + 0.8101854186539698, + -0.017266574134520846, + -1.034343993282436, + -0.47492578640859, + 0.44229849980095176, + -0.04143525239035054, + 0.4756126801515191, + -0.6022374767894095, + 0.6340920197121857, + 0.15470203915775835, + -0.08309028934269833, + 1.0306215921180757, + 0.5494192688607117, + -0.5216588227449559, + 0.3009557161936297, + 0.6139831516272483, + -0.44770257933508356, + 0.11345746519612071, + -0.8216870028942554, + 0.8227758947822771, + 0.033709305229276496, + -0.23229458515753917, + 0.5572138957739009, + -0.38147446202192464, + 0.13246594884601715, + -0.466278119737319, + 0.1583886734390265, + 0.1523094759979024, + -0.37733915948069957, + -0.2403724593678043, + 0.2522774970134757, + 0.4940947041117809, + -0.8806879724925022, + -0.07288487940043382, + 0.6866270507173733, + 0.04307915094971339, + 0.5215923900151598, + 0.23988410425306148, + -0.6172790422318479, + -0.3711490801716098, + -0.7054288772581888, + 0.016013716814726634, + -0.15952111369909516, + 0.08941939514422606, + -0.08553240205626256, + 0.7250173915641064, + -0.25237673621130846, + 0.7529086104023196, + 0.19627107118723525, + -0.13362697184573671, + -0.2145081311364607, + 0.2802467995558699, + -0.2999076594039313, + -0.6547613649671055, + -0.5721090335165396, + 0.40794481435615054, + 0.7094636784658899, + -0.2816842370232965, + 0.4843033590563868, + -0.29022991851936536, + -0.17978381979572208, + -0.6458471565221302, + 0.2970669347014812, + -0.19542117950703725, + 0.8040238536219497, + -0.5223561090698994, + 0.3039416113096667, + -0.0636587328621184, + 1.1285851059770313, + -0.41674170842318947, + 0.502463834093926, + -0.8100556973798271, + 0.27854939944454443, + 0.6814294797330414, + -0.6872720859920597, + -0.2674714257158696, + -0.20614440206453413, + -0.3841571290064748, + 0.2994892405851967, + 0.06601500232671302, + 1.3641458715544543, + -0.6986444647662408, + -0.08595651717480916, + 0.21660934956764713, + -0.5171540292011035, + 0.16405391487987434, + -0.40314299679944876, + -0.04436051664986538, + -0.4446567439839729, + 0.8753629162852175, + -0.7113998347759171, + 0.5039430856915474, + -0.6107778856623638, + -0.43873315460381934, + -0.2142830991415406, + -0.13858516454801262, + -0.8456235465466468, + 0.118813538767295, + 0.4154390666586272, + 0.5274006454905316, + -0.3956250082287962, + 0.19637377638484382, + 0.4043149786825292, + 0.5539441243334704, + 0.4793514059448011, + 0.9174624680079821, + -0.38179091624180506, + 0.1912196804322906, + 0.5392561203417388, + 0.5193810205354954, + 0.5687730135245262, + 0.11869035860387829, + 0.9267733950739856, + -0.2078849860963266, + -0.01749619435345369, + -0.397097316861482, + -0.21669476387788925, + 0.9635110605998516, + -0.6669877189374577, + -0.35205911045974186, + -0.26437849460750934, + 1.076914295643637, + 0.15025191351992995, + -0.36785006746718896, + -0.049477265210616635, + 1.6378023470872431, + 0.13296766573717705, + 0.5332908160058456, + -0.49223047394619984, + -0.5792709506064478, + -0.4415761946968042, + -0.23028838619605563, + 0.2331508649686445, + 0.13606884270149996, + -0.2806982084274159, + -0.1724980502662195, + -0.5140162302573902, + 0.11153963413437878, + -0.057437192767876365, + -0.2684588168665937, + -0.48007848402413, + -0.23424840599841207, + -0.1234959879956632, + 0.181310067383081, + -0.29909967251222996, + 0.5423660971123029, + 0.39636215457849017, + 0.455848326476788, + 0.30751677298935376, + -0.24511588167113427, + 0.17521959143335225, + -0.8852218361375115, + 0.8275224362261951, + -0.26834626644376247, + 0.05294882076356854, + -0.6795836952003408, + -0.12244221687534271, + -0.2708635363493339, + -0.32684805471611206, + -0.24155124331718938, + 0.6696613230040452, + -0.07847574330080748, + -0.4679713117928577, + 9.754349112178156E-4, + 0.6001857037134147, + -0.03681549485782743, + 0.027391164022654835, + -0.09723330108074137, + 0.4282332360092177, + 0.013523031539361997, + 0.037999870714118554, + 0.22515038225891737, + -1.2752815634758852, + 0.2816658628313259, + -0.005422632367823797, + 0.46099069915359403, + 0.37506873891244247, + 0.0715368038303741, + -0.08665146327478174, + 0.21982212067676288, + 0.02786196326075752, + -0.11846051010809848, + 0.5992542084534059, + 0.09168603449196461, + 0.15330352632018415, + -0.3128356251287147, + 0.10982419669542468, + 0.25478198816560166, + 1.0641405947439666, + 0.042449635266400575, + -0.7756733936437301, + -0.7471183964391503, + -0.13258102708036756, + 0.29633097661651303, + -0.3997901137861086, + 0.7431771088656259, + 0.6029002047017129, + -0.03866436134990443, + -0.4046272785050143, + 0.40658150379524494, + 0.1128298306162702, + 0.02924159878290504, + 0.1669495592826481, + -0.7761241851646085, + 0.21694712221072113, + -0.3079081046215399, + -0.4487105286271551, + 0.8387689438543567, + 0.6379385010415236, + 0.6208742393277935, + 0.40504560385217736, + -0.47137853322270135, + 0.18041464968095314, + -0.04470624443524764, + -0.6343351391929244, + -0.32285997622842144, + 0.18070322691038637, + 0.1935166147920042, + -0.7466774898436375, + 0.26209070938645246, + -0.05712248024675566, + 0.3494185277978714, + 0.9285497772109765, + 0.9966710061935482, + -0.5387010122826781, + -0.4946960164178811, + -0.23134125141909948, + 0.1525865413664947, + 0.028411212359180756, + 0.006247570582542973, + 0.3812855739062924, + -0.7001555438751982, + -0.7688714378103335, + 1.020693416183341, + 0.1526511172676047, + -0.6183678077718935, + 0.1762326560153356, + 0.42783586077184466, + 0.4884413205737867, + 0.5212515859301707, + 0.3336072826100083, + 1.1130751834829038, + 0.6715395257186505, + -0.37852327770793753, + 0.6335023466771528, + 0.10975946272968361, + 0.2663512207924014, + 0.3595422034840498, + 0.2519294706533992, + -0.0569074417428122, + 0.0042148358649522185, + -0.11323242780256869, + -1.3775201377669195, + -0.010407455635264356, + -0.7745354858967013, + 0.5137575578447378, + 0.16195011250737262, + 0.017037356542978582, + 0.23279444523675477, + -0.06916931207130772, + -0.9509342032443486, + 0.03456634544140683, + -1.0424170988795123, + 0.023281261456757463, + 0.27292596270504993, + 0.04167005715450338, + 0.13120312784525684, + -0.2653853968765589, + -0.38665791869934324, + 0.5721470595570942, + -0.33375871670245577, + 0.29950400282578676, + 1.0018841930577977, + 0.6108699948215663, + -0.1363819173220052, + 0.2737512669064636, + -0.38822356314322426, + -0.32854679883194676, + 0.5193409054373019, + -0.09365656551577284, + 0.5623422976943442, + 0.14110548829940295, + 0.07948920246130603, + -0.49608893700259044, + -0.5421731390239032, + -0.10827414604853258, + -0.1082197935672551, + -0.29145340943966436, + 0.15147146398101596, + -0.1934750391679599, + -0.6477446784816339, + 0.39531726018470514, + -0.5731818723029265, + -1.0140144933528272, + 0.9402129230660792, + 1.2899229195258972, + -0.5016644355768322, + 0.48103829013257104, + -0.700007108624695, + -0.20936275975772392, + 0.5444234225219996, + 0.048230400176354674, + -0.3105738738296211, + -0.4795938337075051, + 0.7825604555730471, + 0.875031722113389, + -0.5031669764866818, + -0.618972515742534, + 0.18979611501163715, + -0.8347136998252379, + -0.47758110209598004, + -0.2927077977713963, + -0.036522873353535726, + 0.5915558295344403, + -0.7599839850484486, + 0.5162792761745297, + 0.45353462809242756, + -0.2989060711305028, + 0.9617197363491226, + -0.29031819227712913, + 0.41843745355684026, + 0.09404856154549521, + -0.29617229767269604, + -0.8359821935704402, + -0.044265764605702855, + 1.6211291734843507, + 0.8994961874692793, + 0.307321658968602, + -0.47188539746727726, + 1.325634805470433, + -0.3421283256443459, + -0.1561904509353524, + -0.47552799785207833, + 0.5087154363130406, + -0.5764179619426828, + -0.8290519989646378, + 0.30906155656827167, + -0.3647709230702757, + -0.25879933599912924, + -0.19551892213982264, + -0.9484530462857899, + -0.35881721222440227, + -0.3937618402463989, + 0.005079792653888407, + -0.2927657453273622, + -0.03695200253432862, + 0.6178410212030631, + 0.8867816544270913, + -0.16539980378993946, + -0.482635017568509, + 1.127597573981731, + 0.5940282799666194, + 0.0012206200020064143, + -0.35167534938217654, + -0.12441057468188688, + 0.21300489547045529, + -0.14746837180303227, + 0.8627292314534662, + 0.11621786072584583, + -0.5794649350400142, + 0.2521247155141674, + -0.5159700319579701, + -0.33409513260107593, + 1.1701114999015372, + 0.2535840120255673, + 0.9859677413837001, + -0.6876600197104761, + -0.15737625012200204, + 0.1855097241809429, + 0.2719685923269355, + -0.9661311224676729, + 0.09599664209503803, + 0.24833550877526758, + 0.06733458289476384, + 0.5147865111001653, + 0.07206329543507489, + 0.18406443151951238, + -0.7446075907950955, + -0.38716888369913227, + -0.37452815684430835, + 0.07288716630951717, + 0.6084927965030186, + -0.8068701890605824, + 0.004538770420265162, + 0.6062485455728349, + -0.4625092758194845, + -1.1576239609784085, + -0.43620196131569494, + 0.650974402540229, + 0.4003518859416292, + -0.16764115801894272, + -0.22812338243229743, + -0.43087278063455337, + -0.8898012206944844, + 0.5124677306885248, + -0.06405660192184194, + 0.20644965637673518, + 0.5823466813242637, + 0.4336061069145805, + 0.5815348723381467, + 0.0798773743047764, + -0.6018966037905178, + -0.29503838002600313, + -0.041578005921950247, + -0.12189006691698334, + 0.4763962542136905, + -0.15165517766774775, + 0.1057233579961552, + 0.10435689054437035, + 0.02505877158098478, + -0.39877958325598944, + 0.8949580742136777, + -0.7379238589059461, + -0.5591644955297904, + 0.09157487680247264, + 0.9767715190009985, + -1.0611399314792243, + -0.4860414296002821, + 0.40814221192454486, + 0.8900497698053205, + 0.023039828618035493, + -0.15788226160440846, + -0.4497889743753512, + 0.7370952325262624, + -0.01083897357628957, + 0.35933662033849123, + 0.1995486050489059, + -0.014890674030503313, + -0.4320800840981557, + 0.028791536472493603, + 0.6631960990252879, + -0.2569318517677789, + 0.17032493436057874, + 0.6388546473691836, + -0.4273294969681452, + -0.0415181888348913, + 0.09172934287307025, + -0.4410614972756432, + 0.026114474390302917, + 0.13323352056969218, + 0.03658682157111002, + 0.4306558304699305, + -0.2721112870058785, + -0.5978000192863492, + -0.5089402973357123, + -0.6224405151519251, + 0.2677983291489069, + 0.022344084355275868, + 0.4775107072853256, + 0.9686099064215974, + -1.0735933840060028, + 0.09060713404542078, + 0.69723100418298, + 0.33514331371756667, + 0.015573437389814471, + -0.4383715647037948, + -0.4550334090531901, + 0.4878553398211609, + -0.26487393394351955, + -0.19597734062770972, + 0.13138658139001397, + 0.03367694781315745, + 0.5742532261340674, + 0.2361470238379245, + -0.0067760330989350085, + 0.13798974902966563, + 0.49041322053638325, + 1.4949515912686595, + 0.05744113847255203, + -0.9788385026022345, + -0.6878837770118048, + -0.5771815400370284, + 0.12454903194322504, + -0.07311740338046717, + 0.08787865885809525, + -0.6906708293984815, + 0.42439347931431975, + 0.11668058244903513, + -0.04073756929081634, + 0.6737379518431904, + 0.09639587440064486, + -0.48369490790326714, + -0.5712544009732533, + 0.035030314731169965, + 0.00779148592345888, + -1.0913528433058985, + -0.7680280412002578, + -0.6164506166341334, + 0.540063131677196, + 0.6222140185554906, + 0.9123330571766458, + -0.7189017185383763, + -0.7703286957674095, + 0.09729499350560157, + 0.6708376357029713, + -1.1340940617467943, + 0.8042753710647852, + -0.763636908800302, + -0.5316184598081909, + 0.3460778698520772, + 0.2845023553865436, + -0.7737812787733508, + 0.024348057332772788, + 0.16036929265109914, + -0.8340282471836206, + -1.0532360299696235, + -0.22251974870754135, + 0.39611404934068944, + -0.9055584956343349, + -0.43405585538439706, + 0.22939800452282974, + 0.5651589278280641, + -0.6156244605222377, + -0.22693339381584532, + 0.3180408088149104, + -0.15941983630761214, + 0.3507946817004647, + 0.1499611421568206, + 0.2059792058198678, + -0.05937519860946998, + -0.03999730783090425, + 0.07325476466923207, + -0.16777266130839735, + 0.09832178331056947, + -0.08118981311095115, + -0.10629538797559386, + -0.9123571290644099, + 0.24997942536044637, + -0.31289612842681025, + -0.17881632252197077, + -0.08141584114206063, + 0.323092870702055, + 0.1662198515157654, + 0.16596908764119567, + 0.22099933961980706, + 0.3593769676316027, + 1.291503682784776, + 0.6339555472089534, + -0.5382248684931463, + -0.6866630114278608, + 0.05827771878343978, + 0.36591664382188893, + 0.12921085430480655, + -0.032262231617227806, + 0.04893897531262605, + -0.053537104513353244, + -0.46624218612961255, + 0.21520476389613125, + -0.5372848089685492, + 0.04942483844033288, + 0.05460953244157252, + -0.3405234603208978, + 0.2575231614406303, + -0.31799180425382373, + -0.1663075126037707, + -0.7457480604689845, + 0.28504589586268353, + -0.3747571831552307, + 0.28022093208455373, + -0.21582584576143532, + 0.6535583230474687, + 0.26755567126037394, + -0.30563969888433284, + -0.8715512043128792, + 0.28161538528581237, + -0.46638941423464975, + 0.5282966657764238, + 0.2688455175769493, + -0.3020883224065556, + 0.11045008594301989, + -0.32698982651279596, + -0.24088431287517223, + -0.007685143220966135, + -0.26823141538242745, + -0.46207932822384185, + 0.3212155980582619, + 0.48793340094017884, + -0.5162672294349917, + 0.4924526287272646, + 0.4745258997448086, + 0.2702772449650516, + 0.16737047766555754, + 0.07434348825846876, + -0.12359566692225105, + -0.6514028483579636, + -1.3976449276480831, + -0.8113283620398878, + 0.18325647017652524, + -0.19449054659580509, + -0.06449615022336579, + -0.9585255815641844, + 0.49710601301291624, + -1.0574718752727863, + -0.6358196466616389, + -0.16219801337405051, + -0.042561447016337246, + 0.4531198347044763, + 0.645008090032581, + -0.03795221469997563, + -0.8983319211691911, + -1.3701116777018256, + 1.0538569787305236, + -0.36351770259132743, + 0.44269588390673925, + -0.39024383091814807, + -1.17466712311404, + 0.1754031520322295, + -0.12722779341599183, + -0.012723962392628588, + 0.5465037693179838, + 0.3327592395870781, + 0.6234943068573771, + -0.297525778769647, + 0.45259632982123454, + 0.07953211094582188, + 0.4828737354738407, + -0.19405782247683306, + 0.016486925490723416, + -0.13263768891894925, + 1.4245150957702715, + -0.4126173605393897, + 0.46704955707648016, + 0.5419692562717787, + -0.4393236600412016, + 0.07584022155791394, + 0.6776500360434548, + -0.9872825618354969, + 0.5785413805578912, + -0.28992640053655944, + -0.5197495023175203, + 0.7071491394957181, + 0.4786479310569092, + 0.1548256232245205, + 0.13208469047323088, + -0.0822380730671231, + 0.28744004236334997, + 0.13279726526998356, + -0.12467317395221343, + 0.004792198645495679, + 0.5428289722450585, + 0.13875283801038393, + -0.8337918132630543, + 0.4937854068669228, + 0.22557350322190442, + -0.7439190407967377, + -0.45585754540679935, + 0.3502213117580234, + 1.3064381138955177, + -0.22131894923014434, + -0.14219211972972398, + -0.21754292767736882, + -0.4954972755897491, + -0.4790253072981904, + -0.4964149139860912, + -0.1894305513980036, + 0.05973973511853244, + 0.31376075963686856, + 0.6798241508152917, + 0.5546185507500028, + 0.46679300233065474, + -0.09545867148088606, + -0.6202454642873249, + 0.4692883757497695, + 0.40527444707986876, + -0.3143580428443062, + 0.46539689203812773, + -0.3116019679795409, + 0.4453344199987599, + 1.4900358379790046, + -0.6287942921100046, + -0.038370879500167876, + 0.3000504770315387, + -0.5116658698242975, + 0.3180625889902141, + 0.16987231942283107, + 0.08959530998030481, + 0.24016214185166082, + -0.3744169008291593, + -0.4798309081946553, + -0.12135622483032707, + 0.24495440338776983, + -0.11172204805370732, + -0.01275356172617819, + 0.21298837870031603, + -0.22410211139610173, + -0.12267612060681947, + 0.14572936586265514, + 0.3784577948371631, + 0.48085358970765407, + -0.47094566567339397, + -0.3844684428416118, + -0.19457433038724287, + -0.2546484300749451, + 0.5207507542513576, + -0.13353976479338966, + 0.7352691584348576, + 0.08220847744807076, + -0.35603469032108626, + 0.6799706926699878, + 0.20343105324372385, + 0.14634832490102384, + 0.14200147278861525, + -0.44395928857686645, + -0.4414119673850588, + 0.301130966108014, + -0.4277408309429125, + -0.9253156116042144, + -0.4680882133218765, + 0.20252318090989208, + 0.04697825078377828, + 7.46884901547655E-5, + 0.5003504713481021, + 1.3988454829909764, + 0.4364938437287607, + 0.5403867169578487, + -1.1185248186370618, + -0.6330829714967211, + -0.6116245467427426, + -0.29228092017910995, + -0.13105371337043292, + 0.5915374516976616, + 0.20526272164807938, + 0.11171848078521086, + -0.1566211694410466, + -0.3373210092969075, + 0.25609531665388274, + 0.3161859371705347, + 0.13850656332501154, + -0.55237756377883, + -0.1990027092143385, + 0.4948994841598545, + 0.02905835114595512, + -0.3652983116374902, + -0.03452078951623658, + 0.3423576567299348, + 0.7665633138405779, + -0.5388625049544059, + 0.76730274590885, + -0.5212932307458271, + 0.4112504454455677, + 0.20099972829994708, + -0.4173374049106327, + -0.7673561233247055, + 0.6381771355705853, + 0.07536348365296619, + -0.21619823067896216, + 0.15095459097638786, + -0.030838203714380057, + -0.24993362511442493, + 0.3470001149979188, + 0.07884965382113739, + -0.03805022342074594, + 0.2899694576828827, + 0.07261266135219241, + -0.5284708115256496, + 0.14603667804030243, + 0.4746278719995695, + -0.11356873248912419, + 0.49800569821403595, + 0.5197599986718254, + -0.054768948438692976, + 0.5589777413097079, + -0.3291968087462161, + -0.26597622880855554, + -0.6685188220901849, + 0.16078578182715544, + -0.028968310828390804, + 0.0894811885774969, + -0.13292433786246086, + -0.019049854712519673, + 1.079472949921073, + -0.3643774139887517, + 0.29427405336306023, + -1.5751604505856371, + 0.01774504578920784, + 0.29396457992216896, + -0.16641861275822492, + 0.24085742882706052, + 0.14014690307244543, + -0.5345038072793362, + 0.7254094580904162, + -0.8299149695845733, + 0.3417248185005669, + 0.06246721872077247, + 0.48521726226944556, + 0.27129441906494395, + -0.4267317274885314, + 0.8829215342481502, + -0.3891203737608272, + 0.41627124704215557, + 0.04099321986286278, + -0.3575766478355028, + -0.37171022042771285, + -0.11737244752071273, + -0.35214853617366637, + -0.7336928388645546, + 0.5706959475388181, + 0.8327232790854711, + 0.5602992107986671, + -0.2577813446256627, + -0.09548821589590313, + -0.48306434885363675, + -0.07673318665361205, + -0.06057744815736919, + -0.2509072348398724, + 0.13048587168705092, + -0.05980299511721002, + -0.35798203074593254, + -0.5758474987734921, + 0.25895400627650816, + 0.28783633775206, + -0.4723790748847081, + -0.1850524851879721, + -0.3220665292571111, + -0.27611391977674177, + 0.788621676327104, + 0.7635040126792271, + 0.39422045058302224, + 0.9630371604809045, + 0.1252911408360815, + -0.04002939545384907, + 0.3373493285882568, + -0.08430899540978863, + 0.3852303223949029, + 0.2733893678789854, + 0.9053324770818991, + 0.7273727355665554, + -0.01819919027532022, + 0.5917495264174921, + 3.8914025773193E-4, + -0.2973603692626767, + 0.4010332452203583, + 0.4559370882149254, + 0.9173889562933237, + 0.3991568345437423, + 0.4176085883788727, + 0.12280587339931733, + 0.8177935409975555, + 0.065895032167471, + 0.13603716655443143, + 0.1383732539239339, + 0.2849719121668754, + 0.32780396440464726, + 0.13856869854963708, + 0.6308099276718184, + 0.18015002826955767, + -0.3984987649319367, + -0.11217239356372402, + -0.4987160732525953, + -0.27167735064586385, + 0.2835958769056847, + -0.4088514118426226, + 0.2731184005697917, + 0.6006062895224518, + -0.5228031250853172, + 1.5011519572070353, + -0.1719136315033014, + 0.0906459084430736, + 0.07614143568573488, + -0.17545111904937755, + -0.8188201067517626, + -0.3896031019382067, + 0.4044190439472092, + -0.6478181491497632, + 0.6282848177029914, + 0.24079423874602154, + -0.9148965060925647, + 0.07388756971363615, + 0.41450287719199486, + 0.24286755420275946, + -1.0473073985613055, + -0.29953329472391393, + -0.25660601670679095, + -0.10480173498671316, + -0.16126840956384114, + 0.07736480560358415, + 0.4183110079417174, + -0.059896579838567866, + 0.36333699927871915, + -0.6886156738633746, + 0.8235036268026398, + 0.18413856053992195, + -0.13121947522118013, + -1.216569877930923, + -0.28484332771192294, + -0.04852835719960637, + 0.40857420230958663, + -0.7275579581730058, + 0.46403490056557717, + 0.2694729272352056, + -0.09341926928268751, + 0.1038506654339934, + -0.10404340330116661, + -0.07198400283245175, + -0.12070457510793405, + -0.8004641414551881, + -0.22972011377493834, + 0.8329271540383204, + 0.892027314600582, + -0.011610799338299319, + -0.1471722038552373, + 1.282410718748079, + 0.017667198292126342, + 0.7115364572339714, + -0.478246827360764, + 0.9172304428176716, + -0.14682292489488782, + 0.03811233910323543, + 0.22094966840122096, + 0.4010919025265714, + 0.033499792275543595, + -0.11022954464112074, + -0.3052653213227988, + 0.44360562853571056, + 0.41923896331523164, + 0.12663672064001846, + 0.35050763219345515, + 0.17831315108952162, + 0.7502895824775068, + -0.582425451493792, + -0.27370566742454894, + -1.2443839397872747, + 1.2921574231085287, + 0.23775373621389775, + 0.8198179778020801, + -0.1058170622785678, + -0.0824800988387761, + 0.25580909796463697, + -0.5350742596903193, + -0.14704212698802585, + -0.6138289430564736, + 0.4174989546124273, + 0.19877702794603333, + 0.9885366671663993, + -0.1511855934246577, + -0.3978149309833404, + -0.8794785449524708, + -0.021729745530116036, + -0.4331339651505176, + 0.2529498483086498, + -0.23517696183241893, + 0.9807355832217846, + 0.060404389466932315, + -0.132955607985099, + 0.07063854739863537, + -1.0783757964099505, + -0.20519672459388677, + -0.14638517762463255, + -0.8892679214624369, + -0.41256559666483184, + -0.11885334923691294, + -0.24034675534391267, + -0.30735703784121915, + -0.5551368223933059, + -0.07948764501685568, + -0.4172136684009546, + -0.647819420940278, + -0.755523060586893, + 0.04620222475416507, + 0.826635677786291, + -0.11720968563679689, + -0.11876151733261354, + -0.1642606153836091, + -0.17426254147873063, + -0.17878258053087304, + -0.4574663178926084, + 0.12931080226262634, + 0.26323870715309156, + -0.48966480787225297, + 0.04675351129457731, + 0.3581654982651271, + 0.480652941812785, + -1.3040987847878551, + -0.16256174061873022, + 0.1315002629415894, + 0.23276963231621942, + -0.495063049987597, + 0.3620631277693885, + -0.3767120598982932, + 0.4453841655647416, + -0.004779606092011665, + 0.701344028569692, + -0.35067161619134846, + -0.16998153065929628, + 0.1386067239786545, + 0.06911345763486361, + -0.5324126114423838, + -0.0854345866593026, + 0.7895920587569374, + -0.33131276501036694, + -0.36304058568146513, + -0.21947309505004375, + 0.015912745071709467, + 0.33540302717051007, + -0.728257662841511, + -0.3911622236260404, + 0.1596239124888306, + 0.7551123864572682, + 0.3244503314766926, + 0.4750246014009806, + 0.2820522229274021, + 0.0708728684046525, + 0.5172432714949412, + 0.5395080797418966, + -0.12311692957297611, + -0.32039132752103777, + -0.005480470143201294, + 0.8582967995172395, + -0.4547850837017835, + -0.21613848049757167, + -0.07998633775749786, + -0.5291215794120553, + -0.5860816848783894, + -0.16392183203183108, + 0.10025133117496521, + 0.4526609975757733, + -0.12705962138934904, + -0.7151424988579308, + -0.42754728015013693, + -0.040057810015444326, + 0.18051866986826867, + -0.5137589698737562, + 0.20649065182321122, + 0.03228402649107925, + 0.21947806531515238, + 0.3381696642459479, + -0.27381195938487773, + 0.34135890188721946, + -0.5317062154139678, + 0.08568458945998512, + -0.5979922783736377, + 0.4453426842386824, + 0.8297284363666215, + 0.6086753016288791, + -0.01878263011131349, + 0.16592791637895188, + 0.6304994199422979, + 0.23185304488552347, + -0.15418114755072682, + -0.35145107447683843, + -0.3074169638521454, + 0.6910428602896213, + 0.830024343173092, + -0.38318753566934866, + 0.6307947699738536, + 0.33352785688271, + -0.05925867428463332, + -1.0545461626750432, + 0.3176293725613033, + -0.2307500834945172, + -0.0460783923327097, + -0.052223422709219564, + -0.4059999410438261, + -0.36457382987878906, + -0.2302770046368547, + -0.18809133022106905, + -0.2795180014377424, + 0.476606300853943, + -0.29948345093546547, + -0.5217014441742742, + 0.14014278979913541, + -0.2543327209446512, + -0.34630448212850135, + 0.23548363497882208, + 0.1595270762151129, + 0.2788187027390017, + -0.36712078232669576, + -0.38299839412091985, + -0.3241598271570938, + -0.2606335847596077, + 0.2682346065117546, + -0.43690375178070084, + -0.3723768750877737, + -1.105392541243904, + -0.08547055734920929, + -0.06813765411100584, + 1.2408293811473747, + 0.331586178760211, + -0.18976252030614219, + -0.2510037802553271, + -0.6129683754850499, + 0.7250337208711548, + -0.26181694411602857, + 0.14417392426150716, + 0.5568512314846634, + 0.6121715097299446, + -0.4803813331603824, + 0.11505051298718409, + -0.24890284563540865, + -0.16874175617822587, + 0.08595012263861639, + 0.0394712779463668, + -0.2818383589202768, + 0.21266619737018502, + -0.6498954629720569, + 0.2870949109650559, + -0.2753519740360105, + 0.08851426684821813, + -0.359165296778847, + -0.5691325468198342, + 0.06899825965917311, + -0.48072795352459935, + 0.14997236566255756, + 0.18933582927611398, + -0.015183655289318051, + 0.020506573020178928, + 0.4053771873862706, + -0.31804232965385887, + 0.8068881852711014, + -0.18298857112636072, + 0.08874084865266953, + -0.10355884872921804, + 0.011836098763983187, + 0.5002676158921527, + -0.07641330888331209, + 0.9776378724561674, + -0.04147755268123701, + -0.7512572292278367, + 0.035621432284427997, + -0.5727396740930305, + 0.7145868746775992, + 0.09422392877383641, + -0.11249514237364588, + -0.5218824535360836, + -0.0023152516253604582, + 0.15623020663680537, + 0.22398907755728378, + 0.31607003524002014, + 0.2649241104438123, + -0.4531053263192589, + -0.47697719763052504, + 1.4415657770226464, + 0.16593451705311218, + 0.4642882413431395, + -0.4106694640363516, + 0.4090755054442553, + -0.088926610289899, + -0.1749624140983561, + 0.5403200492301555, + -0.2946386255615285, + 3.4662894382455326E-4, + -0.46840337309902474, + -0.42840342536127857, + -0.5009469956176358, + -0.32692345421464464, + 0.45496509684056824, + 0.05286493339962285, + -0.6055545658944754, + -0.27965984300822727, + -0.013012811459537997, + 0.07222924355507304, + -0.17499024336249785, + 0.10718318035514969, + -0.23221927137390835, + 0.7484343034144111, + 0.07466524621157199, + 0.2114879312595478, + 0.454977837531993, + -0.7406645018766358, + -0.22571704073727936, + -0.3141119008840141, + 0.17417077631695999, + 1.110316261907256, + 0.08483695604376412, + 0.18380385104369312, + 0.3843203189596987, + 0.12115856714786538, + 0.21578094895623182, + 0.2484373621847908, + 0.6745655877213764, + 0.6826815880260514, + -0.006666839579949646, + -0.033294227355035504, + 0.4499679762928747, + 0.8558862547282169, + -0.1460257254020539, + -0.21007352725578032, + 0.3946314365887018, + 0.384127519140787, + -0.38517105573633875, + -0.6117422312321543, + -0.6457029597485769, + 0.6799213164032711, + 0.6680664650877813, + 0.3716218242163918, + -0.536497856174935, + -0.04125778551473433, + -0.09501059531321175, + 0.45401152751248786, + 0.04387246964159945, + 0.565824110445511, + -0.11531102447390865, + 0.010190479430779675, + -0.8773426322540513, + 0.3173177609329245, + 0.21577736927004243, + 0.7643485968646436, + 0.5809400238657518, + -0.5961634774441021, + 0.38526356587510824, + -0.0806213117208969, + 0.2300407940206995, + -0.07539692932918628, + 0.035410471287992955, + 0.11797968197621454, + -0.18548588088008455, + 0.6552884570927515, + 0.36713767893612226, + -0.7714953988300738, + 0.12913112218852027, + -0.26346623512236517, + -0.08753785721182056, + -0.26569105493237055, + 0.14347249973605558, + -0.9424360075401658, + -0.11407970194331213, + 0.23661335863918667, + -0.2552345235465726, + -0.5317865556201886, + -0.3280996002650919, + -0.7631799801320145, + -0.27346983612921194, + 0.3280034597399733, + 0.2252448063841152, + 0.3954855537703991, + 0.6794064794140479, + -0.35120658420893264, + 0.4754509803248281, + 0.34158755722762824, + -0.059986186731505756, + -0.3002045461761001, + 0.46308070845148386, + 0.05842995944097245, + -1.2908413799705651, + -1.3034204466993113, + -0.3087382090682205, + 0.9444087784369897, + 0.19796629942944305, + -0.10737395384694878, + 1.029779829709048, + 0.5574595405731282, + -0.7636940108583373, + 0.0018674891627096562, + 0.15190995927182527, + -0.04870252202140099, + -0.16195129176470627, + -0.11807873572758872, + -0.7766960373416141, + 0.003340530950654228, + 0.13461744888337882, + 0.15623458074057944, + 0.4317828277877008, + -0.27288990874354146, + -0.14443834290776567, + -0.21638488510880743, + -0.292230598755522, + -0.6475511921337895, + -0.11096761829613593, + -0.7880712028016298, + -0.7090985404416223, + 0.5714826371505272, + -0.43316231364024693, + 0.22762535499312542, + 0.10020564987987224, + 0.05491911940918195, + -0.4973454448419408, + 0.14013606517755758, + -0.6515602336892716, + -0.6454575645731534, + -0.12960598186797234, + -0.015468818185217914, + -0.4740739399855193, + -0.41833884226212265, + 0.11329428545716942, + -0.6621139932729024, + -0.011884092219678809, + -0.27222884836269723, + 0.2703515903549881, + 0.13788655883908854, + -0.23292864158453838, + -0.05906838086411572, + -0.4896567528067522, + 0.11850214401068271, + 0.314404565909488, + -0.13798374357774432, + -0.5832565621860936, + 0.01131720871435799, + -0.6290246710101379, + 0.7842525087632013, + -0.2535780252377829, + -0.23680193582120987, + 0.5229488675482223, + -0.5750135234683464, + 0.5204374646674186, + -0.35719870962728767, + -0.5653662444655859, + 0.21739389255616093, + 0.8122217890582246, + 0.03444240890844287, + -1.0340707774284872, + 0.6257048383626574, + 0.5607620067277518, + -0.22762945223396985, + -0.8721642109021674, + -0.03773558837143347, + -0.3174188156569696, + 0.24092045914185298, + -0.8135231679780639, + 0.8214649337394374, + 0.47919270927544905, + -0.4268459325543301, + 0.7989860697890181, + -0.32322110695808925, + -0.42749545957612095, + -0.11617674254706692, + -0.4130650434835668, + 0.5328401366251947, + -0.016695372860466243, + 0.31229644043123267, + -0.2727036821113084, + 1.1467203284007053, + -0.06896921279034343, + -0.4341730200362535, + -0.4941851592233558, + -0.13870723876803548, + -1.015064367939072, + 0.660113827492601, + 0.6814764352580962, + 0.15154938964153175, + 0.1729576664442744, + -0.8713410952234344, + -0.3127325102424342, + -0.1862700639044447, + -1.1673387484192155, + -0.2859176959213948, + 0.035319823590211484, + 0.8254490900047207, + 0.34012208604821687, + -0.47317632794296643, + -0.13499025355072894, + 0.15939256426239398, + -0.2002575636933677, + -0.0920984560369398, + 0.04458773293445081, + 0.07838008355823396, + 0.31017723872666675, + 0.12213584831745615, + -0.7524337336178814, + -0.5814905513333063, + -0.9998885119870279, + -0.24216703257128555, + 0.38576713871317986, + 0.05969998551981454, + 0.028438805460387587, + 0.20798301842453323, + -0.6119649535501439, + -0.6012184983554143, + -0.11110076952055387, + -0.8449947571555152, + 0.3639590114475627, + 0.009001031636655013, + 0.16812461084020316, + 0.08324761866606935, + 0.21173115167745052, + -0.27531144221454434, + -0.2833334419723894, + -0.08115959102287539, + 0.38345846879966144, + 1.2171646441807678, + -0.5359084333343799, + 0.7813972471538876, + 1.1251316912503266, + 0.1587763308023793, + 0.6674159991094547, + -0.3816921447148485, + 0.2526598362575702, + 0.7901075859844239, + -1.1186277821915107, + -0.585380367250793, + -0.09582330671547275, + 0.41201481318870153, + 0.38392128049075014, + 1.1342930074138073, + 0.09076451452357018, + 0.2697973481618977, + -0.220940107671034, + -0.35272239270574623, + -0.4754539141707341, + 0.6895216371820947, + 0.2972916416446892, + -0.33811647486257407, + -0.4823177196080089, + 1.2774074045827657, + -0.5964835086667415, + 0.10939879050793538, + -0.9480336669735151, + -0.2163565693624523, + 0.5107330862272955, + -0.3574689082191348, + 0.5528005113833824, + 1.3956034147434775, + -0.34189474660354674, + 0.534683460582225, + -0.8130848369809611, + 0.7375434403608374, + 0.03833291515016622, + 0.4578679779436536, + 0.7095824164659392, + 0.5714503759636893, + 0.5187337152470044, + -0.27703445910150964, + -0.08045414335590995, + 0.6751875464991081, + 0.33676779806088164, + 0.32858290811914054, + 0.18900219499434964, + 0.16585713294110507, + 0.2223044487718706, + -0.32971135302287125, + 0.016118912617986012, + -0.09399689273172585, + -0.09223361064493017, + -0.6399678578586007, + 0.00988002431176838, + -0.7689543975166769, + 0.3668743895360832, + 0.45493557067433743, + -0.028715698254055292, + -0.5588067292356038, + 0.06004541676654352, + 0.05138839480946316, + -0.6085224924884665, + 0.261055125701704, + -0.056293308049766635, + 0.25323138182548505, + -0.9281550051581525, + -0.6802787469535524, + -0.5581511439937492, + -0.9766216963405995, + 0.25411232557937863, + -0.5457552652274839, + -0.7355957466925005, + 0.44592416643196847, + -0.3100073468629975, + -0.6771561713341793, + 0.5456186003754221, + 0.099953571667505, + -1.2394086986782211, + 0.32541179902195877, + -0.4356859457295891, + 0.29762707708191094, + 0.8978461783832692, + -0.03285883037432912, + -0.6127792102521119, + -0.47641318175415964, + -0.5038978008550159, + -0.33983252607648506, + 0.7572059259328351, + 0.008152669854239087, + -0.22531400646573715, + 0.7402620446363829, + -0.2016980928999906, + 0.22075111041245646, + 0.3424832763415876, + -0.3644020746862396, + 0.4843643119356216, + -0.20975055394761727, + 0.16412304905956912 + ], + "type": "scatter" + }, + { + "mode": "markers", + "name": "Expectation", + "x": [ + 0.0 + ], + "y": [ + 0.0 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines+markers", + "name": "Mode", + "x": [ + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.3, + 0.3, + 0.3, + 0.3, + 0.3, + null, + 0.3, + 0.3, + 0.3, + 0.3, + 0.3, + null, + -0.3, + -0.3, + -0.3, + -0.3, + -0.3, + null, + -0.3, + -0.3, + -0.3, + -0.3, + -0.3, + null + ], + "y": [ + 0.3, + 0.3, + 0.3, + 0.3, + 0.3, + null, + 0.3, + 0.3, + 0.3, + 0.3, + 0.3, + null, + -0.3, + -0.3, + -0.3, + -0.3, + -0.3, + null, + -0.3, + -0.3, + -0.3, + -0.3, + -0.3, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + null + ], + "type": "scatter" + } + ], + "layout": { + "title": { + "text": "DecomposableProductUnit" + }, + "xaxis": { + "title": { + "text": "relative_x" + } + }, + "yaxis": { + "title": { + "text": "relative_y" + } + }, + "template": { + "data": { + "histogram2dcontour": [ + { + "type": "histogram2dcontour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "choropleth": [ + { + "type": "choropleth", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "histogram2d": [ + { + "type": "histogram2d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmap": [ + { + "type": "heatmap", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmapgl": [ + { + "type": "heatmapgl", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "contourcarpet": [ + { + "type": "contourcarpet", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "contour": [ + { + "type": "contour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "surface": [ + { + "type": "surface", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "mesh3d": [ + { + "type": "mesh3d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "scatter": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scatter" + } + ], + "parcoords": [ + { + "type": "parcoords", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolargl": [ + { + "type": "scatterpolargl", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "bar": [ + { + "error_x": { + "color": "#f2f5fa" + }, + "error_y": { + "color": "#f2f5fa" + }, + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "scattergeo": [ + { + "type": "scattergeo", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolar": [ + { + "type": "scatterpolar", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "scattergl": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scattergl" + } + ], + "scatter3d": [ + { + "type": "scatter3d", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattermapbox": [ + { + "type": "scattermapbox", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterternary": [ + { + "type": "scatterternary", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattercarpet": [ + { + "type": "scattercarpet", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "baxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "type": "carpet" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#506784" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "header": { + "fill": { + "color": "#2a3f5f" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "type": "table" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ] + }, + "layout": { + "autotypenumbers": "strict", + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#f2f5fa" + }, + "hovermode": "closest", + "hoverlabel": { + "align": "left" + }, + "paper_bgcolor": "rgb(17,17,17)", + "plot_bgcolor": "rgb(17,17,17)", + "polar": { + "bgcolor": "rgb(17,17,17)", + "angularaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "radialaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "ternary": { + "bgcolor": "rgb(17,17,17)", + "aaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "baxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "caxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "sequential": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ] + }, + "xaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "yaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "scene": { + "xaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "yaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "zaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + } + }, + "shapedefaults": { + "line": { + "color": "#f2f5fa" + } + }, + "annotationdefaults": { + "arrowcolor": "#f2f5fa", + "arrowhead": 0, + "arrowwidth": 1 + }, + "geo": { + "bgcolor": "rgb(17,17,17)", + "landcolor": "rgb(17,17,17)", + "subunitcolor": "#506784", + "showland": true, + "showlakes": true, + "lakecolor": "rgb(17,17,17)" + }, + "title": { + "x": 0.05 + }, + "updatemenudefaults": { + "bgcolor": "#506784", + "borderwidth": 0 + }, + "sliderdefaults": { + "bgcolor": "#C8D4E3", + "borderwidth": 1, + "bordercolor": "rgb(17,17,17)", + "tickwidth": 0 + }, + "mapbox": { + "style": "dark" + } + } + } + }, + "config": { + "plotlyServerURL": "https://plot.ly" + } + }, + "text/html": "
" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", + "fpa = FunkyPickUpAction(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value])\n", + "relative_x = Continuous(\"relative_x\")\n", + "relative_y = Continuous(\"relative_y\")\n", + "p_xy = fpa.policy.marginal([relative_x, relative_y])\n", + "fig = go.Figure(p_xy.root.plot(), p_xy.root.plotly_layout())\n", + "fig.show()\n", + "\n", + "\n", + "samples = pd.read_sql_query(fpa.query_for_database(), engine)\n", + "samples = samples.rename(columns={\"anon_1\": \"relative_x\", \"anon_2\": \"relative_y\"})\n", + "\n", + "variables = infer_variables_from_dataframe(samples, scale_continuous_types=False)\n", + "model = JPT(variables, min_samples_leaf=0.05)\n", + "model.fit(samples)\n", + "model = model.probabilistic_circuit\n", + "arm, grasp, relative_x, relative_y = model.variables" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:42.335372Z", + "start_time": "2024-03-12T16:15:41.248751Z" + } + }, + "id": "24bc79646157a9bf", + "execution_count": 4 + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "text/plain": "0.16896551724137923" + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "event = Event({arm:\"left\", grasp:\"front\"})\n", + "conditional_model, conditional_probability = model.conditional(event)\n", + "conditional_probability" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:42.343561Z", + "start_time": "2024-03-12T16:15:42.336652Z" + } + }, + "id": "825dceb35326faf7", + "execution_count": 5 + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "data": [ + { + "hovertext": [ + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 1.0514755717245656", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.6866927513594758", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957", + "Likelihood: 0.8581162797598957" + ], + "marker": { + "color": [ + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 1.0514755717245656, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.6866927513594758, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957, + 0.8581162797598957 + ] + }, + "mode": "markers", + "name": "Samples", + "x": [ + 0.41744723227877073, + 0.23213241679023017, + 0.3984301168903955, + 0.33732878887177614, + 0.3111569836217093, + 0.17568905342874647, + 0.16851756331741402, + 0.21688136567771754, + 0.2921736285404647, + 0.18070297417510778, + 0.3531694058956206, + 0.39366150820142737, + 0.11746473957442337, + 0.21689168925069374, + 0.427657545053645, + 0.4207527082830208, + 0.14455947883052828, + 0.13533906098393023, + 0.3414398822497842, + 0.2434932250293248, + 0.31782745394551226, + 0.1605637325424223, + 0.10732302942508813, + 0.2700243359234801, + 0.32886266618275645, + 0.25879223504916316, + 0.22027523802640786, + 0.3148862804086173, + 0.29011505974534724, + 0.2000717315400602, + 0.3900509569608099, + 0.1560551735624492, + 0.3096736064762478, + 0.16250650719146958, + 0.3069761251040846, + 0.36663485148167685, + 0.23232260224259998, + 0.16523355114490512, + 0.20130354179182933, + 0.24183624414545293, + 0.11884036650380625, + 0.15881128173534173, + 0.2648677195654897, + 0.33439283055423463, + 0.396716512522918, + 0.16534732997807827, + 0.1790122137626483, + 0.29106958312196984, + 0.2020292207164628, + 0.16997946479270643, + 0.22459443560846531, + 0.19356701598412546, + 0.2686034554037906, + 0.33202667237433525, + 0.21542716164939102, + 0.4272501933552264, + 0.33388478703609303, + 0.11667920405704175, + 0.16784789192673416, + 0.1751883061120198, + 0.2343143847867061, + 0.2956628842035833, + 0.23492304417305002, + 0.11097105097118706, + 0.4070197968642514, + 0.15490089054411918, + 0.19818653532438274, + 0.10496856662492285, + 0.16599190048342083, + 0.2048046122639664, + 0.17326470310676045, + 0.1691348037393077, + 0.41064708108294196, + 0.29428053172590796, + 0.2629698645788633, + 0.25028556470257696, + 0.14339590820778308, + 0.149791702778231, + 0.2586204161508881, + 0.27552400100801533, + 0.12522286012909067, + 0.4205857728305656, + 0.22793617010567768, + 0.10260479568819343, + 0.1375160364275951, + 0.2995164324095715, + 0.1365458179069641, + 0.11883654369477183, + 0.31400704368456256, + 0.17954995144093577, + 0.20543687206661554, + 0.1989887300492087, + 0.317730336348897, + 0.3538287578716448, + 0.10644417563035459, + 0.22761297412831255, + 0.22259724088965777, + 0.4220353962367303, + 0.2233770727141596, + 0.3622308202418298, + 0.2174656369709349, + 0.2367595548636201, + 0.40209305839327736, + 0.29331073268290675, + 0.2012100687004096, + 0.21311180464811352, + 0.20299224796648846, + 0.27865850068391096, + 0.33231837038272205, + 0.18041414183550655, + 0.31097982640242805, + 0.37553768066478704, + 0.18100382777785132, + 0.33748860400884984, + 0.36050070443612325, + 0.35415459186408893, + 0.22729956864277417, + 0.3683784676517707, + 0.3549333954343528, + 0.37305042828792107, + 0.4186077919072952, + 0.23659411527048096, + 0.29679428896278803, + 0.15168967453856466, + 0.10591084606582063, + 0.18899150993149383, + 0.27984036361552217, + 0.15611476400158553, + 0.2733484377511148, + 0.42036740885352414, + 0.20879860004775613, + 0.25757877678507113, + 0.12358873276290355, + 0.12423847809462489, + 0.42851852350642855, + 0.3778738966797693, + 0.2658249468324164, + 0.13906811981085854, + 0.3729714299529552, + 0.32311729605162715, + 0.2780341790787316, + 0.2949345294663914, + 0.20521992419462684, + 0.33536332616584563, + 0.25075053169958406, + 0.40606287165337684, + 0.38613749903239275, + 0.35140870003642677, + 0.2650104119389458, + 0.4002226778333782, + 0.3735529144615472, + 0.2174414876620535, + 0.42277610952607064, + 0.2664912305732733, + 0.21699632446243083, + 0.3932769534774596, + 0.12748177535127928, + 0.22259588925633697, + 0.13916730909102926, + 0.26440597530067866, + 0.23399445238014882, + 0.22372944043970006, + 0.24594290911408662, + 0.2727250786321572, + 0.10885068447211697, + 0.13914393374429554, + 0.29928724134886203, + 0.20499395909860776, + 0.1844117164016814, + 0.2936520520921924, + 0.17288777982415274, + 0.31973935103905127, + 0.12504647509055364, + 0.1381451451400751, + 0.33367519317280875, + 0.4006558747755889, + 0.265664598798815, + 0.40290649009299395, + 0.37636404207937624, + 0.3646261506659694, + 0.12281400114756955, + 0.21773246018555312, + 0.3628948844953884, + 0.16961330411900677, + 0.24430511095416915, + 0.32167749478837065, + 0.42827016126729334, + 0.1694557759595211, + 0.20047486304908557, + 0.251197591707743, + 0.2806610820344435, + 0.29738654625719074, + 0.25551264320804745, + 0.19879764497376534, + 0.3131501948880837, + 0.3259798128011095, + 0.2845334632662757, + 0.3559272371648311, + 0.2995765598126491, + 0.1227705736611866, + 0.13728780472747001, + 0.188720515947508, + 0.41429574183710893, + 0.12667372098548707, + 0.3741351076455084, + 0.16225425518241415, + 0.4095040295775199, + 0.3864307553983312, + 0.4264433144445654, + 0.40146994320582485, + 0.31862621198711, + 0.13632308754358388, + 0.387913042608469, + 0.11780590199886191, + 0.2697541865522548, + 0.30710136943308863, + 0.16828452321923423, + 0.42112612226237367, + 0.3753680885225615, + 0.3231012913527934, + 0.10281746255646682, + 0.24821071072379552, + 0.42810020002902177, + 0.3791710899839819, + 0.4283807989459727, + 0.21073238704040637, + 0.3260010904881271, + 0.3628451641695753, + 0.38797446984613027, + 0.2260050577494893, + 0.18874054126854056, + 0.3925698080032557, + 0.2577960892767853, + 0.42118768411770197, + 0.19853033646112483, + 0.33894219717841145, + 0.19214003392302076, + 0.3494358786719802, + 0.1578553799405086, + 0.2523240990112809, + 0.41657960978362335, + 0.2635514806704205, + 0.12814683531788906, + 0.10439794920051876, + 0.23124574943119708, + 0.4052153540022053, + 0.3856280549255634, + 0.22538779234312661, + 0.39637625834987256, + 0.41583635151656434, + 0.3309216624604924, + 0.3370222312517922, + 0.1581051913956418, + 0.3429701520417786, + 0.25889220662129875, + 0.1812721946437925, + 0.29969676052043154, + 0.35975012519387456, + 0.25089234631820706, + 0.2508239611372943, + 0.3916458897688029, + 0.13053943420558176, + 0.29463553378333784, + 0.3685500957612474, + 0.3501331703047733, + 0.31473748112480704, + 0.3038154522374473, + 0.39488230339665503, + 0.2688706115824474, + 0.3402273150008998, + 0.21174677274320508, + 0.3134535969344707, + 0.17893547231557289, + 0.29360209371993345, + 0.12841594278756974, + 0.16948370617846126, + 0.2864761095498157, + 0.2812549108510426, + 0.2538293396449668, + 0.1685541448373794, + 0.37901327455896994, + 0.3934731019623551, + 0.11544359836341198, + 0.3162199339280797, + 0.3366471157294083, + 0.2111425512419902, + 0.40419965953991677, + 0.3432356632113004, + 0.09889974852189307, + 0.22693692938941418, + 0.1563394570107817, + 0.32308607265109546, + 0.13425373486261571, + 0.3513436994235351, + 0.2584106977371875, + 0.147806591820903, + 0.3394582886640507, + 0.11236789019544875, + 0.3398242527910697, + 0.40188511089034573, + 0.24882754000868454, + 0.4124876140817718, + 0.23084283623483617, + 0.10797313683489479, + 0.14964877371461793, + 0.402397401248991, + 0.11770407034471059, + 0.2736902138661076, + 0.3778296677177699, + 0.29958733616218064, + 0.3230008204143872, + 0.10674986387076155, + 0.33905394570494374, + 0.26908497190581304, + 0.3005569044731663, + 0.16678092664908056, + 0.2906271301984962, + 0.428308395649697, + 0.26096013559409287, + 0.15304906278373728, + 0.12641865037245842, + 0.2018929182867472, + 0.1988243722944621, + 0.19246570287528497, + 0.13880272460599988, + 0.2672388013776057, + 0.39271741852607817, + 0.2455852059763256, + 0.2517653671859674, + 0.3585325177292023, + 0.3735963172184964, + 0.2913867890361105, + 0.3847812386653155, + 0.34880448878573966, + 0.3271840726971186, + 0.4028148535409611, + 0.2719428681014505, + 0.114094109751036, + 0.11149604281434917, + 0.26798098924701963, + 0.31334178400231283, + 0.32658518153692584, + 0.16413711024525687, + 0.3150233653043504, + 0.20802097990802415, + 0.24766967029461473, + 0.21964310127719947, + 0.18206591095823318, + 0.11974479068163355, + 0.41878069689212893, + 0.20648070285998307, + 0.37161459849345874, + 0.25557373617408097, + 0.2461638544577608, + 0.2749600547399827, + 0.26291767342265404, + 0.2130459269027662, + 0.3520011879909265, + 0.10941358293994227, + 0.24841699832773162, + 0.18722559849589668, + 0.11894941834450681, + 0.3934990329963456, + 0.12920992023536945, + 0.18575132652078305, + 0.40190033452819074, + 0.3907150312721053, + 0.22116529616781683, + 0.25263813850271954, + 0.3633897846158813, + 0.1947241222156323, + 0.3856172359377512, + 0.3110451786926528, + 0.25726958007644996, + 0.2922879463733003, + 0.26112493081312177, + 0.11941152471396228, + 0.22141398556821526, + 0.4002057366213337, + 0.24052270313711438, + 0.13951076573155635, + 0.18585411744094837, + 0.3881679426673186, + 0.2524589473804049, + 0.15198686716099236, + 0.1830565009418857, + 0.40583648957192975, + 0.30083168097121027, + 0.15390267199733543, + 0.3703104551549583, + 0.2428468851046927, + 0.3487644629630858, + 0.17953779951260823, + 0.2099902427959921, + 0.11667996680231266, + 0.2687096483107255, + 0.35669022157979524, + 0.2305284562298926, + 0.38212084303181093, + 0.2111205716525986, + 0.13990546963160966, + 0.11008688680361589, + 0.3083685843248434, + 0.16472888603120933, + 0.12664824334077657, + 0.424839408052584, + 0.173168555063542, + 0.21541706675498754, + 0.13458352456780043, + 0.2736207304411208, + 0.18836532344328194, + 0.11107410930144244, + 0.3264379159369793, + 0.33392930793506653, + 0.15004829443592077, + 0.4159959114543817, + 0.15038830381217355, + 0.3232713916986013, + 0.30939742165360495, + 0.23804564909208217, + 0.34869267866349196, + 0.413165137771016, + 0.21855018510738644, + 0.14662222918284282, + 0.25804532288191817, + 0.31900978492993987, + 0.32502297638281896, + 0.21597786592235163, + 0.11344205384964375, + 0.3955164539540007, + 0.21001979846065044, + 0.19229731416161192, + 0.31735574965400426, + 0.10179393987694962, + 0.2020740497487405, + 0.2322942543591911, + 0.29644397664068545, + 0.4044252928128523, + 0.31898200703264035, + 0.3072646947032501, + 0.2861708752502975, + 0.12680956791202957, + 0.3070068253889161, + 0.2046291226856996, + 0.34480593037079577, + 0.26340307467434326, + 0.37411912974967654, + 0.12383239392223654, + 0.3892949860183439, + 0.1580344865185015, + 0.35601824579443475, + 0.355042182035038, + 0.31814425999909324, + 0.32265378818769136, + 0.3179936697201482, + 0.2879759255787966, + 0.1502234374144242, + 0.4210993009639981, + 0.27235445518401635, + 0.21184332672511275, + 0.1094291186348138, + 0.27090697519751894, + 0.27095808737227667, + 0.37632897931753895, + 0.37296528437810594, + 0.10254719303605127, + 0.34017740043221234, + 0.29541703506260397, + 0.10045694359112667, + 0.23158368882463806, + 0.36598151580259186, + 0.10754222437252585, + 0.36167920775330226, + 0.1344510161080252, + 0.21886336596885125, + 0.1098465672406071, + 0.35005953750052254, + 0.40283570178989686, + 0.17433455037289736, + 0.2931752980790516, + 0.23188255440693686, + 0.39741109357118637, + 0.2978656298183605, + 0.3536774557705278, + 0.1565471089155846, + 0.28085988570402853, + 0.11401780166830851, + 0.318871493200042, + 0.3455459859584728, + 0.17317534796091638, + 0.41335265239266816, + 0.39458116159360174, + 0.382692553594718, + 0.31453868695684173, + 0.42145228888840763, + 0.25781143404443185, + 0.21644864648289963, + 0.4015108775652591, + 0.32541885970423956, + 0.11780521525084542, + 0.31771746986132343, + 0.31676094919061193, + 0.42256246659340807, + 0.3587908871719652, + 0.40095484693559125, + 0.4213293986168707, + 0.19224758841716205, + 0.2809006988182371, + 0.19761019477336073, + 0.3389956450586501, + 0.26540730142640157, + 0.25339596438447026, + 0.3612693651904746, + 0.2767876942580317, + 0.427852328938376, + 0.21657546138242104, + 0.2931293639484118, + 0.3197057239519082, + 0.192545177920166, + 0.24678631743267915, + 0.12468024620215276, + 0.15654951484919152, + 0.401018563461276, + 0.1266148074017086, + 0.2531158259219015, + 0.18483898397973356, + 0.3544576441589325, + 0.32187067708666856, + 0.41157721183300716, + 0.303469605814624, + 0.2699087589774055, + 0.24624346542837786, + 0.21826373028288293, + 0.399837489679775, + 0.15892668537692822, + 0.12521211528235188, + 0.36809365411301936, + 0.40949629241389074, + 0.327925299039819, + 0.1355294886894593, + 0.27874449911088994, + 0.2595646760402451, + 0.3248079359544661, + 0.19888793765572055, + 0.1275957370615913, + 0.42828121234387645, + 0.34029139056254853, + 0.416774112264047, + 0.10972141253167282, + 0.09870233632838657, + 0.3269693589139644, + 0.11153792490937797, + 0.3481907473399778, + 0.23605976672144566, + 0.1545789636200885, + 0.31366586644633654, + 0.3048516524468238, + 0.11870202583275008, + 0.34267612183086626, + 0.33615958492867926, + 0.30302694482404746, + 0.11329167136965959, + 0.2047899492532777, + 0.2262281802218787, + 0.20807510846645869, + 0.324195846094177, + 0.3953056879877715, + 0.3986099350861617, + 0.3229123255670094, + 0.20567148546764577, + 0.20530389211066558, + 0.23670370323277679, + 0.11047922740539884, + 0.2915660639678904, + 0.23413299289336645, + 0.2802539949457681, + 0.33405192975940257, + 0.12831821710956223, + 0.21513050869422956, + 0.1359987796136643, + 0.12285151901747755, + 0.36333390889798006, + 0.11441760857393454, + 0.40465410512813493, + 0.3493077248198267, + 0.41490349431675266, + 0.3785823446141775, + 0.3584808360577195, + 0.11340997985633941, + 0.2180760672992527, + 0.20056094560353682, + 0.37385423674078894, + 0.30293944324695865, + 0.2558228420029691, + 0.3210760498793451, + 0.1690185491706786, + 0.2559257603795686, + 0.27708117323683046, + 0.21929004557166942, + 0.2362615882202114, + 0.2230765256285033, + 0.3070942206087215, + 0.41600898660400887, + 0.1401061636182266, + 0.2970822300241619, + 0.3831415970714433, + 0.1872875547037921, + 0.19875947298179103, + 0.37251706433314663, + 0.14673221231124206, + 0.31565698469086656, + 0.1901598940292682, + 0.33420916322228333, + 0.1874686202800256, + 0.31154562301342165, + 0.19133142286412202, + 0.2675957627820217, + 0.3625348487937785, + 0.3748708014866189, + 0.1161120090412749, + 0.26365857913701835, + 0.15648907969411932, + 0.3749463642473593, + 0.31385720999317346, + 0.11020897186747548, + 0.2371360538701783, + 0.17278616233926053, + 0.29542387945730286, + 0.35854945619906203, + 0.1368812102573561, + 0.137979859953096, + 0.235563468629057, + 0.24754308182855808, + 0.22755571948091166, + 0.2872577456528981, + 0.38875990512499087, + 0.4283782234012334, + 0.18022082980604245, + 0.197907819734288, + 0.3873208983182626, + 0.37791625960921843, + 0.369020807341481, + 0.3068200732273403, + 0.18864307136579334, + 0.12867237808106421, + 0.11228435239250294, + 0.393088585850439, + 0.1853894832855982, + 0.38158088908487153, + 0.2695375734072408, + 0.22867120100518362, + 0.10364907627277221, + 0.4223414117502742, + 0.18379605643266622, + 0.39022833300293897, + 0.14256617159684098, + 0.36410225450868305, + 0.4020759156864393, + 0.3143981839917427, + 0.39840004462273115, + 0.2849672010194336, + 0.38801726902612427, + 0.3011567390406127, + 0.39080088538174795, + 0.3855367098946663, + 0.26154725518677224, + 0.31166708576982005, + 0.2535073591293773, + 0.3727942742152881, + 0.26547436901609556, + 0.34985355677347263, + 0.3081331162977572, + 0.1975037376292969, + 0.17648001578160166, + 0.2683407989784384, + 0.22206121491311576, + 0.20975561316561492, + 0.21534763010932043, + 0.22780549634519276, + 0.1530372070321257, + 0.2677171529295468, + 0.38002725299140866, + 0.2575635630341675, + 0.12343941949061493, + 0.3045465034705569, + 0.34996602906975943, + 0.40707035554482535, + 0.42978093362410436, + 0.2485562290451617, + 0.31506569217959307, + 0.33725516665277966, + 0.1646097097179063, + 0.20178477874301692, + 0.21170284980198123, + 0.13103086164249908, + 0.27289977336037957, + 0.42781921657499444, + 0.28586549844702547, + 0.40422122262757343, + 0.1449257065191809, + 0.38595117029244674, + 0.1865067128777484, + 0.24251751054263385, + 0.32470912428490656, + 0.1523093578795898, + 0.27089330710268444, + 0.13532364821261808, + 0.13825755557178446, + 0.3839080679033439, + 0.21258964908349226, + 0.11305575861244367, + 0.3632601704390946, + 0.3872621920454222, + 0.39687174219229016, + 0.12111210538707198, + 0.12794737614396676, + 0.137064433215538, + 0.29732063926513896, + 0.16252753708720385, + 0.1363311804286956, + 0.11604329260857227, + 0.30890304918433, + 0.35532672083131134, + 0.3124218750083089, + 0.18728890965225248, + 0.3926331491988323, + 0.18470212225995813, + 0.19248145283639295, + 0.2880786361156107, + 0.3047611539296913, + 0.417235991510573, + 0.39059097246598473, + 0.2431002443684911, + 0.33036436780332407, + 0.40416876275962027, + 0.35791119281884465, + 0.22842801284129297, + 0.3784543121014308, + 0.23234322271562965, + 0.35528519549299364, + 0.1978430192088355, + 0.2509678256008346, + 0.1492017547254672, + 0.21449270451841163, + 0.3660835275103999, + 0.1702723961309865, + 0.39503193012130294, + 0.234896245622019, + 0.30851227815173143, + 0.2863755631205608, + 0.30024074739004025, + 0.14897423535892892, + 0.3781093537895238, + 0.42345705429417557, + 0.3141198759227754, + 0.17900805281833299, + 0.11527418692006378, + 0.22599694336335646, + 0.1808570679875168, + 0.1525690726373632, + 0.15033511758777632, + 0.3022587136384396, + 0.2502001038194944, + 0.17481886510954603, + 0.19154609180554197, + 0.1589425903054936, + 0.3370434925772038, + 0.3244599087892668, + 0.23140322181663062, + 0.34536935220351744, + 0.1474666542590104, + 0.12191125818835988, + 0.10177505117062761, + 0.3394308110426607, + 0.40392575793970775, + 0.17568264608161382, + 0.41271387172421287, + 0.16792442033469163, + 0.17996436932209597, + 0.2817628156294836, + 0.276667842426792, + 0.10747711370522187, + 0.3449465409125452, + 0.3299049613514157, + 0.1837554274448753, + 0.42185726540380974, + 0.3296720856188142, + 0.23003763945496136, + 0.34843003695239033, + 0.12286213445233665, + 0.3807809285928901, + 0.3942991699347708, + 0.23042329803606054, + 0.3814504494609684, + 0.3023274215868633, + 0.17979405237793936, + 0.3911926340887006, + 0.3304336932167523, + 0.31407665759805725, + 0.3323063481143581, + 0.21234963514708655, + 0.32421058167316186, + 0.14248851960438869, + 0.17879093801381563, + 0.34127190162898, + 0.4109712878179507, + 0.2678320848193252, + 0.10985635851725933, + 0.13253335888766038, + 0.3874563815670088, + 0.2946421570280694, + 0.39107911930094447, + 0.36556493438422244, + 0.33479745707309305, + 0.13695013603817563, + 0.10998662722137509, + 0.17166779580183242, + 0.22087724061137776, + 0.40878021384137236, + 0.12055656056374642, + 0.3014483189535385, + 0.2623732162859929, + 0.31431075945873077, + 0.25702378296884465, + 0.2974577211904564, + 0.34524551850307134, + 0.3337033639381611, + 0.19099050934227402, + 0.19544888395849824, + 0.18077023412593463, + 0.32511585517048547, + 0.18739314271020435, + 0.37733311473393627, + 0.42915830253241616, + 0.1843173919056738, + 0.28398396384165164, + 0.4063113507612852, + 0.42671036494139575, + 0.1393195740303167, + 0.41239643127784276, + 0.39570898968358226, + 0.23382150470929422, + 0.16796220448532476, + 0.3365213764880585, + 0.2673944215877574, + 0.24829573470297467, + 0.3298894737933215, + 0.116828333891506, + 0.2003088587640823, + 0.23295703683991414, + 0.31130098498440056, + 0.19387334113865454, + 0.2080087944877108, + 0.23898287722073672, + 0.17204850773077027, + 0.31013886392565504, + 0.10084487773871345, + 0.1904530174400898, + 0.2711506688064088, + 0.11769657209722321, + 0.34174632909720415, + 0.308707612903522, + 0.38309066340850456, + 0.151592303498198, + 0.23471544981282247, + 0.22624550289438716, + 0.2939238744518584, + 0.2622915839371229, + 0.21729876206965537, + 0.28037068428421574, + 0.14104105249577953, + 0.37895073069346674, + 0.22097695339971563, + 0.34133246731458683, + 0.26287087919696706, + 0.385735732768566, + 0.276872606216889, + 0.12828112842464823, + 0.41697040013279596, + 0.3622116934466712, + 0.34473685777401597, + 0.28105041443986056, + 0.2905378202662565, + 0.15565772011397747, + 0.2709172956771992, + 0.24871908535062048, + 0.3966309862758353, + 0.3895023426293861, + 0.11672434350225339, + 0.19912189178911363, + 0.3885873577452961, + 0.4250510155857999, + 0.426997071524037, + 0.36631058935088734, + 0.26419239717298515, + 0.3518574205497663, + 0.11257659705209848, + 0.14346129909900326, + 0.412387601686004, + 0.3644797153665873, + 0.1067741866496056, + 0.2186575981281263, + 0.21371993524228644, + 0.15870006211059606, + 0.22127972423536352, + 0.17432648954656527, + 0.2642694470089064, + 0.10580989158385622, + 0.38906109507500414, + 0.3731199542153916, + 0.09993912095634606, + 0.3650642905598732, + 0.3370406449717155, + 0.30770606659462596, + 0.24552826724399715, + 0.2512373365185232, + 0.10204844887162481, + 0.3022592713902531, + 0.105361341741698, + 0.1978213171992671, + 0.12125415012371556, + 0.307325579576646, + 0.1937969183926374, + 0.26617735896599215, + 0.39129320904019244, + 0.16687264168894977, + 0.13121489111028017, + 0.14018771371148764, + 0.31278892418251814, + 0.1879516555503154, + 0.19709450169721301, + 0.3812614893143626, + 0.3571330137882415, + 0.26789232010617087, + 0.25670470552279134, + 0.18802990358909583, + 0.3692773627204558, + 0.17986523037237107, + 0.2030678722734233, + 0.35371114051008157, + 0.10186087339989908, + 0.3127899177466482, + 0.12443887110639766, + 0.40872370201650604, + 0.34536006200108504, + 0.320071993364345, + 0.10515699201093781, + 0.10186285823373922, + 0.1607735727531578, + 0.11281780066734487, + 0.1547062553060935, + 0.32794617731697673, + 0.24522333325463982, + 0.3294608597173964, + 0.16992247960307022, + 0.37239264096661634, + 0.20530479540493277, + 0.1550469672124911, + 0.18551369841951942, + 0.23941645420769145, + 0.3648056777415622, + 0.13898460370047355, + 0.36661960492390644, + 0.32210304346095386, + 0.3621993929308217, + 0.22401170925214495, + 0.3811796586845952, + 0.4260486057026653, + 0.19591470737323863, + 0.340495117889454, + 0.2687222196903377, + 0.40006209072273624, + 0.14631536547959623, + 0.3278611170801509, + 0.1951592949816328, + 0.2979985480692994, + 0.09897573292085601, + 0.34799680907784525, + 0.19776988369400997, + 0.33313889044679146, + 0.40083550809394164, + 0.28693979234797073, + 0.257122715395125, + 0.30773692001824154, + 0.19756621569542251, + 0.2235122903714905, + 0.21139055021254022, + 0.36822079770748023, + 0.38851015424213414, + 0.16132191296635057, + 0.157684048638499, + 0.3020824717292746, + 0.4158387283202257, + 0.10787384495988146, + 0.1766023709101065, + 0.3595244244937886, + 0.16628647122309986, + 0.11616093644878431, + 0.1423632620898573, + 0.31013628377768904, + 0.34763285736895544, + 0.2192337448930037, + 0.14588847967859478, + 0.38863212016282844, + 0.321745263593415, + 0.13611775872350904, + 0.27880334549126196, + 0.36621410781329294, + 0.13377983030995483, + 0.20136266174248324, + 0.14612208909588797, + 0.16146274848421965, + 0.20471438102977677, + 0.2568320942258709, + 0.17603675778879202, + 0.27886845167360397, + 0.11147043672933936, + 0.1806750542068608, + 0.12117547815424243, + 0.3786805794367242, + 0.23425738264486085, + 0.26743970927702365, + 0.19033775972681682, + 0.2659652645511245, + 0.17456321848242762, + 0.24111478992684177, + 0.41135481223476655, + 0.2895632099366868, + 0.427540821065612, + 0.35435597870908264, + 0.3354556752995498, + 0.2718477887273958, + 0.3886055543575918, + 0.2590661814398999, + 0.36880853021655624, + 0.22315308152656066, + 0.1330242284872749, + 0.20194133005061832, + 0.3306092204632235, + 0.25122862000648827, + 0.15317804041855257, + 0.2628943633964163, + 0.12530056645744558, + 0.28757633070022115, + 0.40129009767280516, + 0.21978111629883762, + 0.27174905019343076, + 0.36750785512618034, + 0.2394973317042752, + 0.2071293486430396, + 0.23011333739836115, + 0.17193439760674684, + 0.18999938116304052, + 0.11568120151038226, + 0.4043003360779576, + 0.1449739443585531, + 0.20046065645590505, + 0.11515235828578649, + 0.13060359665410531, + 0.4127435529293135, + 0.35986533936576925, + 0.17000545307302967, + 0.2886297440287784, + 0.3744061886081477, + 0.12300550366592566, + 0.12539867490779216, + 0.23549131594291453, + 0.350204112724882, + 0.3962679052131229, + 0.2056518810000009, + 0.1412373606946175, + 0.2957214305602084, + 0.4118989981112451, + 0.27901218569106573, + 0.23209727634310448, + 0.32223074242406774, + 0.1827615756588304, + 0.40219625517295715, + 0.28251601593158426, + 0.13649721509834686, + 0.38130065850439926, + 0.19492439337586537, + 0.29712279086980087, + 0.25541570028980676, + 0.12893805683842424, + 0.1420925168220867, + 0.21556839319419027, + 0.3565402251935201, + 0.13500101482602084, + 0.35319528972574027, + 0.18747599349764776, + 0.11678971575023979, + 0.2639709948420465, + 0.28869993944063754, + 0.31377330051826685, + 0.3083241848415335, + 0.143909153366649, + 0.2632837165163212, + 0.35422943226758064, + 0.33923995191334977, + 0.31238773493355354, + 0.23497643131310061, + 0.37642819572553476, + 0.21689990866435466, + 0.16069150858252784, + 0.42110355603617927, + 0.3349353639507615, + 0.38906971511511884, + 0.40770159351279883, + 0.21136515720526253, + 0.1605797023662666, + 0.3147299887112508, + 0.2340007613367144, + 0.36102055935980665, + 0.29285437198230146, + 0.3164045771525254, + 0.24334899032729512, + 0.3974142060967923, + 0.13680530145078673, + 0.3492001340938075, + 0.10965096858840695, + 0.13451204611630876, + 0.19000598466884627, + 0.11844697711847568, + 0.2552765569397325, + 0.11896134621948383, + 0.10115908460338162, + 0.24796060466780753, + 0.3877964936608319, + 0.1588794713820806, + 0.23788352905760596, + 0.2769046566872163, + 0.40316818646926267, + 0.22944471697335117, + 0.10591816452697143, + 0.36682719237431216, + 0.2905851769734655, + 0.20139497381627547, + 0.21658978014561567, + 0.23240427697451999, + 0.3961720798327488, + 0.22737306446435457, + 0.4024130868982765, + 0.2881138683111578, + 0.1645793245413487, + 0.15871316967408183, + 0.4206054527375133, + 0.27949442253332646, + 0.41107226792660484, + 0.3779408814423246, + 0.16767637785676814, + 0.26346809110185465, + 0.1360866739849988, + 0.1672430555490566, + 0.3670581975319115, + 0.3301891036844814, + 0.24854267659662144, + 0.15365531724732298, + 0.28016360187964273, + 0.2034713630385796, + 0.3042652208354848, + 0.3325920016238848, + 0.18838221834483768, + 0.34301154028154124, + 0.2854571187225807, + 0.297424245923416, + 0.39864566393933, + 0.3604484669905343, + 0.3607872067136694, + 0.21586707182126774, + 0.3639205240659639, + 0.3154881733971403, + 0.1372587510119173, + 0.3658039236531579, + 0.13104850692904355, + 0.41933119078588704, + 0.30457293957893516, + 0.28618871880318486, + 0.10620851432449464, + 0.25230416831419655, + 0.1292360409565615, + 0.2911800112241671, + 0.1029416977906903, + 0.2984226866341258, + 0.2364114471338638, + 0.1739562289750852, + 0.4226112662774253, + 0.3167447049469947, + 0.34867854930970055, + 0.2297860796308035, + 0.4156618020572685, + 0.2334793596560286, + 0.304650524033529, + 0.2877875213772723, + 0.289223855828581, + 0.2957279267314967, + 0.34798654818773356, + 0.24799242234663055, + 0.295647410615751, + 0.2327267168134993, + 0.11717477618505226, + 0.09926565613967764, + 0.2160419985489173, + 0.34092995996445696, + 0.15318611873228338, + 0.2694171571835632, + 0.1774893417237241, + 0.41709193562306895, + 0.25878707596830886, + 0.3142511046237021, + 0.1296202044611961, + 0.22200139473272346, + 0.39533906338815494, + 0.3102579792761897, + 0.16522970206697266, + 0.3244472452748285, + 0.23197321311158303, + 0.24809620645055236, + 0.42401341565084644, + 0.30767232693775126, + 0.34428184672280504, + 0.25959043789693315, + 0.27328649138351313, + 0.22899029647929334, + 0.30328314783602583, + 0.13641734235047942, + 0.33319903518523253, + 0.13707935288907355, + 0.3113575639352708, + 0.12821307565111306, + 0.10586260139902019, + 0.42287797922083536, + 0.31195425245861563, + 0.38910015585575664, + 0.22439988330718383, + 0.10800100360554363, + 0.18466097386249036, + 0.303039681547857, + 0.3176634088672594, + 0.32848615076087484, + 0.21048072908636112, + 0.1343403328602027, + 0.2428209886793674, + 0.2113401542513359, + 0.19984101777504468, + 0.3942866064018247, + 0.14198901857495813, + 0.3529338290188156, + 0.2851965480206943, + 0.4188774412706533, + 0.31950168275129576, + 0.2431852488172072, + 0.3760804505323179, + 0.19515798227404915, + 0.38142170147176147, + 0.29819587758617605, + 0.12143503978749098, + 0.35491723095505506, + 0.17267702474782964, + 0.3149515330025532, + 0.23780210403643587, + 0.29815334915736147, + 0.3732815881569289, + 0.292109958583029, + 0.11118645633457803, + 0.3796703951068473, + 0.16609153069164828, + 0.3614978369151487, + 0.38122594359495815, + 0.36891810080993487, + 0.1698186031902501, + 0.16831272553145885, + 0.11691358804502658, + 0.2800321213114977, + 0.24461508372588006, + 0.26173710667720773, + 0.19078758818146513, + 0.4017556633705134, + 0.3511962345834495, + 0.40572265934049734, + 0.1420534436182145, + 0.3933019159409373, + 0.3620772336068881, + 0.3749992369360854, + 0.4190640112191919, + 0.18245002932448456, + 0.3415841880136701, + 0.18122160846834118, + 0.40589204044579075, + 0.3904925174548626, + 0.1895301288940432, + 0.12350766972728881, + 0.198442501181195, + 0.1404627447171937, + 0.17819702454706565, + 0.23746255410793513, + 0.29594280442757537, + 0.24937398489125773, + 0.1358232908925549, + 0.18080681836656692, + 0.2141771981648154, + 0.3816210555099668, + 0.2842619616029195, + 0.2761607013433104, + 0.4203390763967362, + 0.39748819756541703, + 0.27396544043054827, + 0.4117822738843956, + 0.36843839793751615, + 0.14120627897439492, + 0.415219696427435, + 0.29563476701122343, + 0.38667475628873565, + 0.17812467086515177, + 0.12685540939655757, + 0.1192128441206246, + 0.3044388152735693, + 0.3509893283292217, + 0.23892486466539023, + 0.4038152894633718, + 0.18742383967630943, + 0.2936560818832553, + 0.19080947303891294, + 0.31728887533586136, + 0.39742595229621, + 0.2756553135015975, + 0.1383627128454346, + 0.2830770217867179, + 0.17478420141348916, + 0.3308282494126511, + 0.3776153840413772, + 0.12400318684625701, + 0.21531048565944488, + 0.15525761292235227, + 0.40623632040478996, + 0.11361264994317881, + 0.3477174954603666, + 0.1678169924613761, + 0.17545693129523604, + 0.40063548436063834, + 0.2855919855447918, + 0.3611670085859026, + 0.16164113795941143, + 0.2499203046038782, + 0.27390982916577566, + 0.22157130480428505, + 0.25145598072267256, + 0.23951607055530924, + 0.13998541866070635, + 0.22322428450331447, + 0.15969726480533858, + 0.24754922678959262, + 0.34701395506377386, + 0.2142442115949283, + 0.3981483719319317, + 0.14901908816898748, + 0.21492991988975643, + 0.31051992708774284, + 0.2763009888604768, + 0.4297875851739327, + 0.19700997254641675, + 0.1212165991460932, + 0.2546637777909912, + 0.3095275730826777, + 0.3884747596027634, + 0.3684821018314632, + 0.2033247093467146, + 0.35428020452780645, + 0.20724200456321257, + 0.2671248879985687, + 0.10811946225219572, + 0.11183179622598852, + 0.1824251387120338, + 0.18265238529080946, + 0.13105275466046354, + 0.3166003007714391, + 0.28793724078826244, + 0.21498429229884555, + 0.15223702272985498, + 0.16965754322966664, + 0.1687276411585783, + 0.18538754549202605, + 0.17492752301438386, + 0.3996497940469914, + 0.1271646280560017, + 0.4267843466165395, + 0.23550048100431212, + 0.38010315905200026, + 0.2055128248960563, + 0.38263817887370033, + 0.38742527759075013, + 0.38498646110735596, + 0.23022331908727456, + 0.2742072426639953, + 0.2565867019261133, + 0.3982357437769145, + 0.268430027127675, + 0.1358920607611211, + 0.26392646754416127, + 0.42318447967838224, + 0.24150784886432544, + 0.2492036057443122, + 0.3284517195968128, + 0.27692473422771813, + 0.33951284279598043, + 0.36784697762078367, + 0.2964599944162506, + 0.1911497885438156, + 0.11672664932751924, + 0.22419449577704825, + 0.32554708130951976, + 0.28040621351373163, + 0.3250241980980996, + 0.38850725623760174, + 0.24847082502622764, + 0.1904937808103267, + 0.11932189067402929, + 0.3268514276464647, + 0.1547739864980925, + 0.09899989936090518, + 0.3074390483271163, + 0.35319557107704547, + 0.17803535008135846, + 0.2136882856483336, + 0.2279476282582365, + 0.24922240947840893, + 0.39864446497864897, + 0.2117947858911814, + 0.19718360074566496, + 0.13816677499351873, + 0.4218311553345329, + 0.20118752714095606, + 0.17907787769195294, + 0.13336400865942336, + 0.11485556127191235, + 0.3571160700472151, + 0.10083448552900441, + 0.2607407017125238, + 0.22984072071200756, + 0.29663330069418736, + 0.276313401994555, + 0.14230875834430215, + 0.2962011828718204, + 0.2601580406105813, + 0.3944557158147862, + 0.2523326463247315, + 0.1420535888734656, + 0.22215638503670582, + 0.21731807440031592, + 0.3582145741305846, + 0.3653757451569741, + 0.14676217470558722, + 0.19073845201397704, + 0.3434380988185403, + 0.41916592875175956, + 0.14071807137820186, + 0.2341849866585199, + 0.2978095013279814, + 0.27405198338085013, + 0.14428355494700437, + 0.17183631690438517, + 0.32911041224745546, + 0.268913179232683, + 0.11281025378776798, + 0.10257248189418637, + 0.3721917135130975, + 0.26259046098213323, + 0.2110073925536395, + 0.33427565222800937, + 0.3072059186223791, + 0.16473327654420208, + 0.32691263665391035, + 0.3396058258680557, + 0.13096077103506212, + 0.1204917852218213, + 0.39114828944695434, + 0.37107313437015044, + 0.22920601667644203, + 0.14421165953236095, + 0.3333800903141788, + 0.16659923866769127, + 0.30296735772716676, + 0.41799800238955076, + 0.27805349346555686, + 0.37472490548802706, + 0.20520920859681607, + 0.32093404304882894, + 0.2603511216440024, + 0.20037841539097617, + 0.29071249599933435, + 0.206327138858686, + 0.2207325946274524, + 0.1747015990145373, + 0.40067022568874106, + 0.14852202333384829, + 0.19242303931717678, + 0.22303009495365567, + 0.26839821502418176, + 0.26237640415739083, + 0.22391368688453211, + 0.2392520534066842, + 0.30584454725936017, + 0.10037104881460049, + 0.3130023320936678, + 0.20979296624353674, + 0.32117007918368407, + 0.228864409808464, + 0.27659836901189194, + 0.1709217733155593, + 0.16891479182692784, + 0.1806965533004506, + 0.18524666527097822, + 0.319998747109961, + 0.31312750719092547, + 0.16045714987924603, + 0.31842137933262016, + 0.23130773881949174, + 0.39107156798169046, + 0.40330751138801124, + 0.23715972924376136, + 0.22419507777441935, + 0.1728488167057658, + 0.10911430731309314, + 0.24777035552834367, + 0.13100344531434824, + 0.158204234325099, + 0.11185598483620937, + 0.1850943002668826, + 0.38571056794212316, + 0.3630224103154799, + 0.24079304570574037, + 0.24965886293515818, + 0.1629685730511973, + 0.32141539139564923, + 0.17532388129194917, + 0.13919305494165926, + 0.17486845318347022, + 0.10279800838489377, + 0.1782151621362092, + 0.16967287192543645, + 0.31186561773700583, + 0.16535236763449856, + -0.6085351916502546, + -0.4534713526995688, + -0.5364468438205988, + -0.793186921668666, + -0.4963871929692635, + -0.2351558648597597, + -0.7402713558520848, + -0.6179963645290963, + -0.5864864675022867, + -0.4997483589853752, + -0.18709987738312894, + -0.6585544116079601, + -0.7985501298108431, + -0.3810617019836491, + -0.5506838584933718, + -0.1437672271379431, + -0.7529239610828299, + -0.20662285261601, + -0.19851977622644712, + -0.6175827326249789, + -0.3820278980192747, + -0.7230007679739977, + -0.48459157922839796, + -0.48833241827283047, + -0.3939698290847586, + -0.6448458980940712, + -0.44678578277513353, + -0.45289284259340473, + -0.5478564219742315, + -0.6013212116572688, + -0.7166572626930239, + -0.7623333125422446, + -0.2003823598416945, + -0.7389758530804491, + -0.22815769623955418, + -0.6437047738918245, + -0.6857183900192345, + -0.34053284022371794, + -0.1516477076833319, + -0.66385324243893, + -0.4544900952844484, + -0.47809894362162814, + -0.45829498384016765, + -0.3666495086738576, + -0.44366658577630275, + -0.3650604866282936, + -0.4825165983602309, + -0.7187019153959397, + -0.3297410196736136, + -0.12095915544045577, + -0.1255624561863744, + -0.1057960893079446, + -0.633475112789538, + -0.3408679733862799, + -0.18732924404898432, + -0.6353579346887662, + -0.4006757153565659, + -0.1603298764025285, + -0.13601822343208758, + -0.4027329662264841, + -0.5758966504476031, + -0.7122742165058038, + -0.7269977138751839, + -0.1256798589161362, + -0.3294985673126664, + -0.5234223475571453, + -0.762057735721429, + -0.7221846412146564, + -0.09690429407419754, + -0.7784047817665974, + -0.7098232146548087, + -0.2212488423632829, + -0.18904531029389238, + -0.5665434811189427, + -0.7523977188018495, + -0.27414544476110114, + -0.31588693711071386, + -0.4286701971120516, + -0.10937742558942032, + -0.6181373817511423, + -0.712287768974202, + -0.4204216657696721, + -0.14224485576569146, + -0.6171755140522357, + -0.29007511560247323, + -0.5221003891421967, + -0.10348655611706792, + -0.4565305046803286, + -0.5222071118179687, + -0.5802593970917223, + -0.6535954571245174, + -0.6100149557071751, + -0.634979746991576, + -0.11308025548277567, + -0.5930815404314207, + -0.35887178510539364, + -0.3399248869559814, + -0.38438049469935476, + -0.5174325471803054, + -0.33431229151638225, + -0.7183359224684762, + -0.7011414664425359, + -0.25478109924275416, + -0.3407446550517252, + -0.0930298315748932, + -0.32169274310199464, + -0.5881103040555693, + -0.15549368268209252, + -0.1489717618609231, + -0.14697435799320635, + -0.4825667402884856, + -0.5963966307155077, + -0.21676134507498934, + -0.2333979486759521, + -0.7577836053948446, + -0.3481875739973763, + -0.34639220455906844, + -0.5796728725918795, + -0.3855767359861388, + -0.4132708200849922, + -0.7589012543608877, + -0.18096455102729536, + -0.1359212685413982, + -0.5884147421417598, + -0.36825145376686613, + -0.1700421993586818, + -0.5304433312635739, + -0.6310183592346432, + -0.322441949242111, + -0.15667356048497494, + -0.19011132039508172, + -0.7341792876996639, + -0.10603349177595434, + -0.3323984970206733, + -0.47032823859929285, + -0.3763375764559204, + -0.11751975183909036, + -0.3101075453542754, + -0.7729200208085096, + -0.5214214312982124, + -0.23204133825837092, + -0.7397585929908713, + -0.35810555192677407, + -0.34069942751146864, + -0.7550105721199484, + -0.25516812368345876, + -0.19529804622076485, + -0.09242229915111011, + -0.11372540699075395, + -0.32171275277355593, + -0.3052865037840513, + -0.7291471952615898, + -0.17912899987833664, + -0.13474134660537118, + -0.49779836957692947, + -0.5612260640485112, + -0.7741163003201172, + -0.10569318002109085, + -0.32557072833777584, + -0.3366617457056094, + -0.29645222022407125, + -0.4264131068899221, + -0.5693226521747676, + -0.7221651019640203, + -0.7505826607842722, + -0.5072685886909565, + -0.4514268011848177, + -0.5045003550965237, + -0.604432983622436, + -0.6416834007522707, + -0.1836703169892926, + -0.252245151105679, + -0.4227061232760515, + -0.6015036969512865, + -0.5822839820764248, + -0.3078070920044231, + -0.7472483734995929, + -0.24271813472200043, + -0.23717800717021886, + -0.42948684084455313, + -0.3368086456473459, + -0.7913857658001071, + -0.3772947258267371, + -0.5090484419809416, + -0.6988221809761425, + -0.6206602486377899, + -0.5721745362450186, + -0.7930258956506555, + -0.36000829783086685, + -0.3532217449042171, + -0.16340462129785716, + -0.31414427188489924, + -0.22339785335965145, + -0.629702172575573, + -0.42752491671495724, + -0.6014115565839417, + -0.7753078092040525, + -0.731989875605601, + -0.17923392518755543, + -0.656326448391567, + -0.3116945430960046, + -0.7253876267185816, + -0.651969021419032, + -0.3692545864026298, + -0.34752206335309693, + -0.12025487726356421, + -0.6816637212178216, + -0.1544145494640362, + -0.4666106095246712, + -0.44352913445158554, + -0.2889648813182124, + -0.28640621964518975, + -0.5328709004020438, + -0.21293102054888113, + -0.5022363961667615, + -0.2527565269305593, + -0.5824792547681779, + -0.5339851793941885, + -0.45570060244568433, + -0.6308656696457425, + -0.4622427736769257, + -0.28764567494609217, + -0.3675179762711833, + -0.17838873407240918, + -0.3069405186210808, + -0.09072600933063946, + -0.20229003819301938, + -0.6972857556229716, + -0.08721725035010697, + -0.543907087215489, + -0.18063065822252566, + -0.758820957118962, + -0.420129268056298, + -0.4558432400545988, + -0.2914164647226214, + -0.5389497049922014, + -0.12743994589416874, + -0.2469297109324724, + -0.460510172325023, + -0.10081726731225416, + -0.2595476521264679, + -0.37526368329921567, + -0.09512258110635563, + -0.6333105595414369, + -0.10276914751252719, + -0.6576236872728133, + -0.2954398502737341, + -0.36725812338428826, + -0.6482439044873467, + -0.39828576077624295, + -0.544673642395358, + -0.6603994315473953, + -0.5323930317617473, + -0.41214117440051057, + -0.41536675313152943, + -0.20164687530550396, + -0.18859731177448436, + -0.6586019657804364, + -0.2965466336861421, + -0.5628362558344764, + -0.29258433128391503, + -0.5164352477718619, + -0.3951678459372906, + -0.6122325076788256, + -0.27640615655102285, + -0.7468716848066453, + -0.3233378971392864, + -0.6573555228515571, + -0.2867700164316964, + -0.631357314950372, + -0.12066233226842138, + -0.6500059280572169, + -0.3824099246113974, + -0.10550214348520814, + -0.5623494723303732, + -0.6438929922623371, + -0.47379425007660286, + -0.35281433876927865, + -0.5974509796002809, + -0.20389615479173606, + -0.541549782790768, + -0.5672443084133199, + -0.20153917003225352, + -0.32847540275497694, + -0.605022949736354, + -0.4232479064191625, + -0.5034945818769674, + -0.547257211050681, + -0.7577129981564157, + -0.7931959416007439, + -0.7883677961002385, + -0.4886445194358259, + -0.25545364025860884, + -0.405876572848583, + -0.7711284477701987, + -0.22504208150819882, + -0.7848569382941031, + -0.6404871454924528, + -0.7198364057201909, + -0.6776237154469636, + -0.2215704755749337, + -0.7025394537627686, + -0.5811759893001291, + -0.7149306236558857, + -0.5837983118425899, + -0.6896552659674238, + -0.29830194183365155, + -0.11966340123531438, + -0.3545995863257699, + -0.4812597150516569, + -0.25874235874414675, + -0.5461273402592441, + -0.4385853730665787, + -0.3183057704001628, + -0.20965310797716896, + -0.08714577237384802, + -0.4551125712933774, + -0.173927283320907, + -0.5142739623738715, + -0.5361706032661812, + -0.45634611690752735, + -0.5966335839415083, + -0.4525254246799064, + -0.6962259334216804, + -0.18983087879115068, + -0.5452023967986366, + -0.7322272570810155, + -0.31668069230115736, + -0.08328640370560514, + -0.25487505506354835, + -0.401485394853011, + -0.7168212436543471, + -0.4873787134992148, + -0.31153163179495924, + -0.11761390998445753, + -0.14250877539718054, + -0.16790993824241085, + -0.5090804387423848, + -0.653890834320382, + -0.5110194757425526, + -0.5302245380437036, + -0.1586966208891708, + -0.35395486997185216, + -0.6611864700719848, + -0.5172397436201676, + -0.518549036681407, + -0.1225876325683577, + -0.355415403071279, + -0.568114071098023, + -0.38227060828306275, + -0.19445085023560715, + -0.0875013387236131, + -0.47763571752605793, + -0.6954453816333059, + -0.1914070538749233, + -0.6911859529179856, + -0.769457972373803, + -0.5322703268055229, + -0.4628321163441318, + -0.6505566519429754, + -0.3016736873322337, + -0.7549523433264376, + -0.17973221396830885, + -0.3771581554605596, + -0.6658398481365159, + -0.12934991610033386, + -0.18292051223575234, + -0.3590464414066933, + -0.4144493086288245, + -0.384504262203564, + -0.12023776955818899, + -0.49800080743267516, + -0.6887839345169521, + -0.5833469041579763, + -0.5082611610637071, + -0.7344571705995057, + -0.629121415937667, + -0.517261473964286, + -0.14743567289785353, + -0.47917147071718186, + -0.413997530050827, + -0.26515163537687414, + -0.42388472976595465, + -0.22268045303821982, + -0.628375395035557, + -0.5934853576068937, + -0.5905511557615533, + -0.1338497231874356, + -0.15153738788637205, + -0.5776991564633909, + -0.5090885641429452, + -0.7552407372649924, + -0.268709852350708, + -0.3757715121337437, + -0.24488958527051174, + -0.7130276075798886, + -0.7466981353519284, + -0.6625322177129145, + -0.230533529600348, + -0.4084030767081878, + -0.4567656715185556, + -0.37147614421633235, + -0.3589596351512008, + -0.6758261698551509, + -0.6204761305643056, + -0.5018583185347634, + -0.2687015489430956, + -0.10299684798609965, + -0.5685036162308248, + -0.09507310622520904, + -0.41009934464403, + -0.24004965419650526, + -0.14022999694720917, + -0.44079898476420254, + -0.46972485790904056, + -0.7013232375568017, + -0.38595131031964097, + -0.16114065450568615, + -0.2771342423408474, + -0.41186107772496017, + -0.4996031740684015, + -0.3312901849513773, + -0.6860931926398864, + -0.12487183114097644, + -0.7211862387683785, + -0.1943583327832552, + -0.4523983298908485, + -0.4703566077456144, + -0.47411677685521614, + -0.7564952429042398, + -0.5065982548135745, + -0.5631064707222864, + -0.3674234450570997, + -0.39574605516728895, + -0.5563205652016161, + -0.3537178011413451, + -0.43180232046324113, + -0.3417675834436557, + -0.4961493392438717, + -0.3447590428761452, + -0.7646003028156131, + -0.3341887185051965, + -0.1894107269480727, + -0.6927249403340313, + -0.08674131868713819, + -0.48260642629908923, + -0.3742756432317222, + -0.58251124335773, + -0.13094216947370563, + -0.12113638496381096, + -0.4678093133438751, + -0.2903610935222749, + -0.4475053316643175, + -0.21070044457445225, + -0.18806389874228258, + -0.4163925304748745, + -0.4431417480084269, + -0.7307983184898582, + -0.25660784319482965, + -0.7127214297143493, + -0.31226879940467994, + -0.4065388241778085, + -0.7776390219715588, + -0.6918494181691769, + -0.17014059006443172, + -0.16301029416138557, + -0.7849471823761607, + -0.5259111285433719, + -0.3095907377807696, + -0.45497991597882564, + -0.6298337125070399, + -0.13972390210996444, + -0.46241417181269295, + -0.11092000747121877, + -0.5162045362028029, + -0.7342116862512006, + -0.7847815184779344, + -0.3689993604901128, + -0.22027914774919743, + -0.21791060200450363, + -0.7616273232638723, + -0.534461629866918, + -0.4618371670950945, + -0.327410663386637, + -0.5566856824613038, + -0.4002285686014181, + -0.5186393462362449, + -0.4673741701945013, + -0.6362332242289289, + -0.3463554027819274, + -0.5172465046885177, + -0.2147963101556586, + -0.31021981269776944, + -0.08772854828084375, + -0.17844235915773765, + -0.5046948659206141, + -0.5840092152437003, + -0.6674333504730066, + -0.558188442744873, + -0.17390084198140388, + -0.6729531524940164, + -0.39736845019877637, + -0.4564936606654865, + -0.638562039692766, + -0.6889211500575501, + -0.6836534941682845, + -0.414441009535277, + -0.7686466403189088, + -0.2056644752691984, + -0.3843853749529518, + -0.43333090897409904, + -0.10283307753188542, + -0.45742938883850365, + -0.2514064336920965, + -0.16225516049976085, + -0.08310308915261644, + -0.6854801254188113, + -0.17151784170135242, + -0.2425786281085346, + -0.23336438767996892, + -0.2696829050273345, + -0.7169973955274009, + -0.740771254197044, + -0.3626334640709428, + -0.21416486760035758, + -0.7104147462817543, + -0.7221111793324888, + -0.2784750401498779, + -0.2923856603556467, + -0.3135325174227641, + -0.10173263115678166, + -0.6727146491202131, + -0.1415015965795734, + -0.4260518629219641, + -0.4442628050364041, + -0.11996698753618928, + -0.799128817597992, + -0.3985042610610896, + -0.15136542309670775, + -0.4244759258688911, + -0.5180374442428207, + -0.6148068385661356, + -0.43256450070761965, + -0.3692514430029943, + -0.7806335916934246, + -0.6775217881059356, + -0.17462750516063863, + -0.346437185543518, + -0.596974155237633, + -0.3222481617443928, + -0.35944059042135645, + -0.47446546086686386, + -0.44264070596988503, + -0.4548375179154901, + -0.5679055171297939, + -0.6631288759453227, + -0.2595279013483306, + -0.682307522515138, + -0.3807304875102639, + -0.26667635413329704, + -0.6322833640733463, + -0.34913111035087563, + -0.30637582309321826, + -0.13102032759467086, + -0.6040564330509313, + -0.08997367430640657, + -0.7402772679424331, + -0.4361509548033033, + -0.40787806669937743, + -0.7116570987085888, + -0.4901826058388175, + -0.10832076272360314, + -0.10365108791448818, + -0.09022696552900367, + -0.41829691077846815, + -0.3380626469998706, + -0.767468415306309, + -0.19528962968826902, + -0.7966639424833689, + -0.728755062995928, + -0.4528452097245375, + -0.4679280197522147, + -0.5564036206835486, + -0.3617487292179839, + -0.7987335609488413, + -0.14096373608763269, + -0.40509976406884235, + -0.09730998075426789, + -0.25963518443425904, + -0.16809644804957813, + -0.39692276231817125, + -0.12390973065878874, + -0.09778386156111196, + -0.607626659171192, + -0.21093492197073083, + -0.41018838566792937, + -0.6265355871204477, + -0.16710283379732405, + -0.4288178075427081, + -0.4005971156534551, + -0.6501134734110616, + -0.18199850627064562, + -0.5173490815532075, + -0.2661906870331242, + -0.4204732578150415, + -0.3084136205889827, + -0.11680415111711684, + -0.703935913977833, + -0.7460005755389697, + -0.16597310728371384, + -0.4557178124316127, + -0.5316906144230458, + -0.7109654875263346, + -0.38564645416526017, + -0.38336439908267766, + -0.7538178185482021, + -0.18785688565947578, + -0.7156067196858215, + -0.31504837648056655, + -0.7290129771371742, + -0.29311530611372727, + -0.23339846584656765, + -0.6496122189760334, + -0.11258095971295456, + -0.657016329571009, + -0.7700007989394301, + -0.13419123893961693, + -0.2344829311427611, + -0.7992049814079959, + -0.3370456795565154, + -0.4954329932103491, + -0.1002640652819301, + -0.38447992772328643, + -0.727660386948209, + -0.13368738935905766, + -0.4019594976165771, + -0.0911505955728481, + -0.17293097746903663, + -0.3627171655880487, + -0.34611878170792887, + -0.7643476705177993, + -0.7543165635943676, + -0.1805880584204378, + -0.39261187123703006, + -0.33173851866265835, + -0.5478208932278117, + -0.20125173285779918, + -0.5235608295709335, + -0.7712293679419892, + -0.5259773000116807, + -0.42070513979970964, + -0.7547090185392135, + -0.693488073091883, + -0.1934972519056437, + -0.6758729558309158, + -0.3483793348449903, + -0.789014377015334, + -0.1762836252669412, + -0.5107424399476301, + -0.5781538452951681, + -0.7218623147922872, + -0.796575883247079, + -0.5460847339479824, + -0.09439529417962511, + -0.4636987226333378, + -0.7988394002608332, + -0.4852274859125316, + -0.08338302098362527, + -0.42921676986172935, + -0.5325436257894134, + -0.7793437543552139, + -0.47386743694061273, + -0.26749714040739725, + -0.642345252679334, + -0.5005992740198429, + -0.30852902706500634, + -0.6867156490607442, + -0.4596443422877545, + -0.27189421165282446, + -0.27130849918586963, + -0.2598516940024409, + -0.09089202389769069, + -0.23245177897908387, + -0.3067678537361091, + -0.4544454555337352, + -0.7520596827631935, + -0.644504459356493, + -0.7582095087104088, + -0.33862779343422544, + -0.6116850895081594, + -0.44853472643252357, + -0.2613195240235622, + -0.5655623338706602, + -0.7554824621312357, + -0.6645514063624804, + -0.36419784278232714, + -0.10170382505162456, + -0.6188148244474532, + -0.5234448694230057, + -0.6585936139066135, + -0.5020508418046392, + -0.32133317490077423, + -0.33365799878540514, + -0.5644652611706944, + -0.7572142100412361, + -0.3144770844372168, + -0.46075139593941195, + -0.3463847263137057, + -0.44047354733342786, + -0.32129552976409886, + -0.42020624741039053, + -0.38519016411691726, + -0.12910365225965736, + -0.6759080896934927, + -0.4628851966965444, + -0.4778535191971686, + -0.5181780519508147, + -0.11409246133360085, + -0.14456771435252402, + -0.20197058335156715, + -0.406516482519049, + -0.30766174705957805, + -0.5151176150826206, + -0.4424196835839895, + -0.10537421780085698, + -0.25686950381526563, + -0.09846373435215128, + -0.607500345023942, + -0.41169858643515894, + -0.3386694314529072, + -0.6185416285689627, + -0.18939499780462843, + -0.6663850381745817, + -0.6067219125722387, + -0.599159110280749, + -0.7183700033913668, + -0.17197818151778266, + -0.5633334723523596, + -0.7125766214775388, + -0.2785236775218928, + -0.7498402330141763, + -0.24627013693750277, + -0.4584451665009222, + -0.5498662360780326, + -0.5357228105853347, + -0.4858344786948245, + -0.40525818739199143, + -0.7203529440055443, + -0.7519528985626106, + -0.6137637674017835, + -0.6634754027707027, + -0.5230603867883616, + -0.22764576983258922, + -0.7524202691224511, + -0.3730805559974848, + -0.32528122886773503, + -0.6057638815488342, + -0.29999955683463553, + -0.6860347022811644, + -0.3144349580092956, + -0.7648350641749221, + -0.40387146504566157, + -0.504317256494983, + -0.1819605432023157, + -0.3683451562841461, + -0.1487398823241236, + -0.4457138102385767, + -0.2898338649845258, + -0.35440023998383474, + -0.22762086014724614, + -0.23704765047702103, + -0.29655558956803574, + -0.29537688457167754, + -0.25387160888477467, + -0.5435266028918454, + -0.14119120239551652, + -0.5947557852348291, + -0.26283399916139527, + -0.28442739041460163, + -0.7229371664813248, + -0.4278766775804382, + -0.7898098752915985, + -0.37027123359591346, + -0.7151138405341851, + -0.7501175194457681, + -0.39912043801074715, + -0.7300101325867504, + -0.7630248072445482, + -0.355692087875602, + -0.258525094539517, + -0.5581422132816063, + -0.1006389766318897, + -0.7406958770560305, + -0.3411536358476248, + -0.438233153472205, + -0.7552705923778663, + -0.46293698139815415, + -0.5390746440938624, + -0.08452094196232818, + -0.3483451796052788, + -0.33415241864541545, + -0.33083805039007347, + -0.3471644335969035, + -0.44604948709325803, + -0.7887988749796876, + -0.297683805361062, + -0.48950674757124657, + -0.6291848227751228, + -0.5084002730506109, + -0.746916869108862, + -0.40682986986082825, + -0.43293544125796735, + -0.4292061908439538, + -0.7330415095940561, + -0.3440830644808564, + -0.22058570416478507, + -0.46893181323915345, + -0.33470538811191963, + -0.7900834377720152, + -0.29682560958842996, + -0.7658155552200016, + -0.14241528006596893, + -0.44653918777598384, + -0.7296831698743313, + -0.6332865273844404, + -0.7658366632624626, + -0.3739467909590795, + -0.7875094227472825, + -0.1899097899402109, + -0.1709310787497511, + -0.2427995241266212, + -0.7510118835552769, + -0.6009151971975283, + -0.7312988822658367, + -0.6797733417122772, + -0.6437528767310507, + -0.5940424518941385, + -0.641970315703042, + -0.2584896122358369, + -0.09153606575730688, + -0.3732811950010894, + -0.23633183670843316, + -0.6774482211929537, + -0.18465800735452986, + -0.3201979044292014, + -0.35364694014346654, + -0.3979843329470003, + -0.1346714814932386, + -0.6065936453016807, + -0.2792611889078127, + -0.19100965377393775, + -0.0936206757983663, + -0.514777306264116, + -0.6503874493099155, + -0.27685947801035504, + -0.40032846451114035, + -0.11746191533194017, + -0.30704459242852433, + -0.6582310085090683, + -0.7176865441545762, + -0.525986634053655, + -0.6604769957786485, + -0.5374251312808644, + -0.6576426540600415, + -0.3287018615371444, + -0.31700458741923715, + -0.1132865387113523, + -0.41609666804621825, + -0.27456382368412835, + -0.08867451572222929, + -0.3997360636556127, + -0.414453425029192, + -0.7808650558073191, + -0.2579309594721422, + -0.6088114952972713, + -0.6287072870784206, + -0.5828794180180125, + -0.09969758810232499, + -0.6738079585698074, + -0.09623719237033224, + -0.7676130130929842, + -0.7737103398472509, + -0.34597348295063324, + -0.45790129036088084, + -0.44993123802216034, + -0.2835116895999775, + -0.19213635534784734, + -0.6072785311857705, + -0.2679804434713392, + -0.6329486466164147, + -0.6264475401930454, + -0.19378422398548356, + -0.17337637794118999, + -0.17624738502991755, + -0.6762522867632866, + -0.6787389783141333, + -0.45240172010496876, + -0.16684808093797288, + -0.19107407853528202, + -0.7707616894544028, + -0.29638882877620343, + -0.5299615200040471, + -0.17959039842850655, + -0.2407820367055461, + -0.5117299087610387, + -0.38553717967313333, + -0.16554637110423676, + -0.3878745556960095, + -0.49865513173884257, + -0.12104688766395588, + -0.1312755695845873, + -0.19237677355818916, + -0.39072031199794577, + -0.20192812247633463, + -0.5188832550802616, + -0.5197515973213503, + -0.6653564554556404, + -0.7942194425306023, + -0.4132123870794429, + -0.7755905895321701, + -0.5921098104690499, + -0.5453493032353529, + -0.3187343405017762, + -0.40440785193092693, + -0.26713783718538253, + -0.7377911926946938, + -0.6366462665408158, + -0.5175690652576461, + -0.7594923178376508, + -0.7465752003287397, + -0.19093299180818335, + -0.25572990680834695, + -0.17726829810092715, + -0.48230327947813634, + -0.7324081715680475, + -0.4995741778267182, + -0.10284066544669213, + -0.7901512102610031, + -0.34783063828506944, + -0.10504035495188258, + -0.7148736652233464, + -0.6219014969443846, + -0.6043140188613227, + -0.11330684299892269, + -0.3265718189864549, + -0.7796967439908321, + -0.44009496946780097, + -0.09714281109482947, + -0.44388921580330615, + -0.19166495998942756, + -0.6000928005618062, + -0.29964856376666593, + -0.3293333629637959, + -0.5558831544658642, + -0.3698504858951949, + -0.7292166691684722, + -0.6436244660728715, + -0.2720947557099157, + -0.14924653899049967, + -0.2045659656298935, + -0.41511957159952606, + -0.42700524345583496, + -0.552172891871198, + -0.2307817360885991, + -0.1963611477133056, + -0.705128630568199, + -0.3599497155145975, + -0.1708711199458247, + -0.2481806464956514, + -0.44242218430696245, + -0.7437108468890983, + -0.17521630406522593, + -0.4372836771285445, + -0.6087516750208806, + -0.7034848685128136, + -0.6815304772179598, + -0.2374832899849204, + -0.6565768451743462, + -0.4574606505624607, + -0.3413027909132777, + -0.7484420962137638, + -0.46806339258254803, + -0.7665017051404595, + -0.4144676641474874, + -0.45221698619526735, + -0.28417554664393974, + -0.44587152271983715, + -0.20254636940511228, + -0.1197938553146145, + -0.3648611602360423, + -0.10418648053245227, + -0.6349348730951019, + -0.4941956320381143, + -0.576717994459745, + -0.45285750344997694, + -0.45164169950713295, + -0.22831534888178795, + -0.2033536959163985, + -0.6520870435278008, + -0.38023521666925975, + -0.5974438544558769, + -0.3597689765556962, + -0.4407080673153558, + -0.4073245140640598, + -0.6382409926899664, + -0.27812556072638006, + -0.6589726118414029, + -0.7493822769351899, + -0.33720545109303895, + -0.30040371246375114, + -0.4482217694887043, + -0.43354703569459896, + -0.6318046036806373, + -0.36470028789325354, + -0.7262526192648854, + -0.6475390626550305, + -0.16997723852582958, + -0.5672577514811791, + -0.38469627667510453, + -0.7599831597981399, + -0.1761593422984945, + -0.14807549538859466, + -0.5968645808169767, + -0.4713993074160562, + -0.49986536897115985, + -0.7292217752695588, + -0.20947967676639279, + -0.6804554539367296, + -0.6999871664707953, + -0.5370704822256942, + -0.17386824626548125, + -0.5589404393047411, + -0.1615763308312146, + -0.6614583504194871, + -0.6726412738327159, + -0.6106065527998852, + -0.15242125090314795, + -0.42862677567009405, + -0.4745486987324791, + -0.3404286078033285, + -0.7783900187462052, + -0.45789203422212793, + -0.3263011402690722, + -0.7758583687763119, + -0.1509876708579574, + -0.7373521243097911, + -0.512898874576157, + -0.09422120181707339, + -0.691624227529603, + -0.7577368823171444, + -0.6611563460677792, + -0.20516343787113167, + -0.22838072856088953, + -0.2477817531589669, + -0.1120636010610786, + -0.41730223997016025, + -0.5332949425288778, + -0.5580401336891949, + -0.5179660427102086, + -0.6697925560618818, + -0.791895491300042, + -0.14748076711066604, + -0.4326403236215553, + -0.7077643769679852, + -0.6013105263123165, + -0.4365937725149072, + -0.3777746003929892, + -0.34065875346889235, + -0.08786767127512929, + -0.23177739033153677, + -0.7817354712786639, + -0.4249859680934804, + -0.14597906322547316, + -0.46732869093150603, + -0.5301574759190408, + -0.21736883665305695, + -0.7571060531651631, + -0.7284710081200838, + -0.1354415600247707, + -0.19616989876734248, + -0.3137966997375952, + -0.395932241581999, + -0.3391040628056412, + -0.49909559336164444, + -0.6970869911471712, + -0.653067899174696, + -0.2048181412818325, + -0.5029541869924375, + -0.6244569281417812, + -0.49214181780311017, + -0.7046560831526325, + -0.383829858812327, + -0.19136428585703025, + -0.1516800401520838, + -0.39824787457373606, + -0.38465628799538015, + -0.17714635453907712, + -0.6836835656571069, + -0.4632155106366406, + -0.36456666474419225, + -0.46004508891769064, + -0.24484331095180567, + -0.5323456832265863, + -0.5878295150691782, + -0.6975204303122303, + -0.6755020656924225, + -0.22675037272964982, + -0.6020951669067455, + -0.3433733557683691, + -0.7934987841958766, + -0.5209788839806492, + -0.36964961476241687, + -0.163092817503387, + -0.4073833932809953, + -0.21999740217003383, + -0.34325315286640934, + -0.5837108690629155, + -0.7630034925509945, + -0.5276378630688006, + -0.6977035016904816, + -0.6724066084645162, + -0.5505167593442408, + -0.30345885951636614, + -0.4484286791703807, + -0.5033461771046164, + -0.17002663816497499, + -0.3998493379994792, + -0.19957427293938634, + -0.37527611983767584, + -0.22792332814911154, + -0.3912135622515793, + -0.32047578419543665, + -0.758128871089109, + -0.4060384176976609, + -0.25522913883027076, + -0.13973183314288218, + -0.742966331565037, + -0.40658299571049766, + -0.5094231538855394, + -0.6357474795630408, + -0.4955313604815909, + -0.14908287291695133, + -0.703277241640773, + -0.7372869161084357, + -0.698622110954852, + -0.4065220589230452, + -0.2392215537011948, + -0.34380831943155976, + -0.11926633786569052, + -0.795827259388717, + -0.7999144666848168, + -0.08961523796115389, + -0.3127623290315469, + -0.6465416248598892, + -0.43192319258107237, + -0.47184180025145833, + -0.6551532476769204, + -0.20945366528076204, + -0.413068591013324, + -0.4172662903811182, + -0.7523010759034812, + -0.3046091465637908, + -0.623552944631834, + -0.515927238648364, + -0.23850242098264463, + -0.6891858921072268, + -0.16346562514612806, + -0.49025770952347747, + -0.19550508346127893, + -0.5665666492538851, + -0.26857295517212465, + -0.6146367966741575, + -0.2575251170244649, + -0.5470095084095647, + -0.09701505177322789, + -0.17533210794510024, + -0.11313739038915027, + -0.27163456529996544, + -0.24136156524384023, + -0.7325457896674233, + -0.2434748591145185, + -0.7401938420007976, + -0.5266891117500785, + -0.16104248022154333, + -0.08684192508629318, + -0.17131946965867528, + -0.5051545761916645, + -0.6306697760004305, + -0.5709404945992502, + -0.2746988361499709, + -0.6431538787190181, + -0.4758500971512931, + -0.4074764820003953, + -0.23745144481652436, + -0.32410635706362484, + -0.7083145437122669, + -0.5378600427698097, + -0.6319106821290118, + -0.12334622592484534, + -0.5466200886995689, + -0.10738678596513962, + -0.36901040784614575, + -0.5606032311482206, + -0.7056094346060241, + -0.6464691028207331, + -0.383385198811361, + -0.2700879307997802, + -0.629189642925148, + -0.0934495648428817, + -0.08510517515048988, + -0.7566120389920123, + -0.6345344558475887, + -0.499047308367454, + -0.7002943103561624, + -0.6469489375314812, + -0.7247890352351309, + -0.17643984111083488, + -0.6661204432669164, + -0.09304553259696191, + -0.7153091323862433, + -0.08286052731253568, + -0.4082273222392614, + -0.4988839358906468, + -0.12545837686571792, + -0.3188190355016568, + -0.4958050126941469, + -0.780572158824997, + -0.5103520384520999, + -0.15372822350128734, + -0.28842388149383136, + -0.22342392901976116, + -0.3875731946576387, + -0.1423244820419426, + -0.6744514940178366, + -0.5963784750015421, + -0.18217324337986318, + -0.25492323514104, + -0.5047070201949306, + -0.1351818399070539, + -0.6672765315915195, + -0.22240761131904796, + -0.4410405334806564, + -0.11295165788580419, + -0.1980340295734433, + -0.7035088144238597, + -0.6781922595125325, + -0.284893402177371, + -0.5946113689400991, + -0.7758687994675332, + -0.576249309795152, + -0.1949675034048418, + -0.49423232701253555, + -0.30627059142400925, + -0.3775488254200271, + -0.6094002042477555, + -0.12086579942513165, + -0.133075632403858, + -0.09976774375338682, + -0.46645898627321647, + -0.47575649707476786, + -0.31442377743395367, + -0.2552398354277162, + -0.498216810994683, + -0.20519615727250262, + -0.24258810564873545, + -0.7456917725738518, + -0.24023121264663228, + -0.1518958954394357, + -0.617799186111555, + -0.5400432446053466, + -0.2471578649192795, + -0.29609586449909087, + -0.4683708012850416, + -0.3828878923967083, + -0.45822072460714247, + -0.5889136791757511, + -0.3720994210448573, + -0.2364274690407333, + -0.4764350061960863, + -0.6327297627938813, + -0.635793464173389, + -0.4019013138174164, + -0.19946682879845623, + -0.49341530564019137, + -0.7225602134825617, + -0.5976382624177604, + -0.3123412637981403, + -0.48706648854054513, + -0.17929052082684105, + -0.6330595043394575, + -0.6669962581341908, + -0.30492703146066547, + -0.16921594917237626, + -0.15963520729337266, + -0.5838841565047594, + -0.09373125976142327, + -0.6013567585450005, + -0.4344006184695035, + -0.37237830210682993, + -0.684002221213197, + -0.20752511920725158, + -0.1454609496173772, + -0.5395072544147776, + -0.355301867057297, + -0.2759952922996999, + -0.5714084772824986, + -0.20718787531223648, + -0.33069786259772627, + -0.19965667565599043, + -0.4285638905584309, + -0.3807567113287514, + -0.3501531965764775, + -0.6992574680165832, + -0.5618896096743076, + -0.4652824289762144, + -0.1716378325320106, + -0.7962018499174927, + -0.6191206257779621, + -0.12786025767008036, + -0.24426879692132952, + -0.570272508263572, + -0.2612779538112051, + -0.3289023437981394, + -0.48724961887349, + -0.5134014550731499, + -0.5247191668986786, + -0.3658683894634728, + -0.17416984128976765, + -0.6796457910781535, + -0.7182303378036454, + -0.13962958799126968, + -0.4831674009996435, + -0.6861824706929484, + -0.3708712376215427, + -0.5338796277586279, + -0.6782982140421708, + -0.7439380798553357, + -0.1754157223805829, + -0.7271362574787373, + -0.5464141234065625, + -0.08669959807595351, + -0.6436261141488336, + -0.7210865978863977, + -0.3357104014590779, + -0.4026561967949146, + -0.48220336347719667, + -0.2434330162865439, + -0.1967099582700701, + -0.5107287395740885, + -0.32298182945702736, + -0.11223739165728275, + -0.6984417009268691, + -0.11599304674106614, + -0.19418575895174472, + -0.5147496477932276, + -0.7192983754119646, + -0.6512961176773646, + -0.73298918210822, + -0.5308735985303137, + -0.16561707037022255, + -0.7560644124827675, + -0.326099938948567, + -0.3381296047892128, + -0.39868671450616705, + -0.693327603666582, + -0.44663330659687966, + -0.2596440930636673, + -0.7419478292434556, + -0.31350512358809324, + -0.4574871068518621, + -0.41260205291379304, + -0.5826909090681253, + -0.35176501338297644, + -0.7468870363728654, + -0.37451930860772165, + -0.31151725920963463, + -0.20482354333055597, + -0.4682695800645062, + -0.32638904839382055, + -0.5413060643709253, + -0.6501492409303982, + -0.21661775057000143, + -0.14992679704665302, + -0.4626931391806582, + -0.6168950817048018, + -0.38776011326860343, + -0.26380361241555983, + -0.6870850138470607, + -0.5800281447031428, + -0.3022780351751406, + -0.7882915420146859, + -0.4098869297486037, + -0.3291522904943834, + -0.7415310711082508, + -0.14472433104031523, + -0.42889853651558874, + -0.3253493951557222, + -0.34366356509912066, + -0.3529210156348367, + -0.43337457249714506, + -0.5899987078620634, + -0.58622327999086, + -0.49210556264925986, + -0.11033180569164946, + -0.10249803671603219, + -0.5393167614731296, + -0.38690594243875315, + -0.3033183923336662, + -0.42781639937222304, + -0.3912110713998188, + -0.1425333789566815, + -0.6705196026441934, + -0.2289410401319797, + -0.41767508970377365, + -0.26168986570595787, + -0.32090405395886, + -0.4626552799497554, + -0.5889779475799972, + -0.30346552010444716, + -0.4535533819907084, + -0.5388267845473902, + -0.6916004556850894, + -0.6362634052609557, + -0.7912030749138426, + -0.642849800670243, + -0.11254791362046201, + -0.611109751010339, + -0.7369404571237048, + -0.6987042321355255, + -0.26155794779754604, + -0.7787015936231552, + -0.5163106487887021, + -0.6500752426078973, + -0.6980546217721177, + -0.25060158852171743, + -0.29897562154733437, + -0.7530526989991013, + -0.19535276211305708, + -0.16024759833920543, + -0.31034656405355937, + -0.2541600464776266, + -0.14462666208787622, + -0.3638224359612768, + -0.5622443299738988, + -0.4189896339411016, + -0.2676859829826236, + -0.10043937120788071, + -0.3552942013858431, + -0.4036634144525731, + -0.17580912247529046, + -0.38119807440655923, + -0.3910720519323437, + -0.4570912106258756, + -0.6134421077211618, + -0.4715861124910955, + -0.3772127898841234, + -0.36187039929893555, + -0.2664363380406438, + -0.6018202924504018, + -0.5241050150227081, + -0.43647648331695293, + -0.6074572498015256, + -0.7808903827056961, + -0.2753899553247787, + -0.6258042900451712, + -0.7931112659043473, + -0.455661894624806, + -0.5799714400679494, + -0.12265024916080935, + -0.2301396379122872, + -0.6837264872013813, + -0.5355551595989578, + -0.4030095139593444, + -0.4395574399252403, + -0.14423707370883943, + -0.6199335177031936, + -0.40828854553350746, + -0.7077283388930417, + -0.49922093389796834, + -0.39921871025863803, + -0.23627389493765028, + -0.4301340809749206, + -0.13715367758518737, + -0.22117751723236068, + -0.17100263206484245, + -0.5131179155068875, + -0.5913742799360792, + -0.7160537223812331, + -0.2466403114596064, + -0.48239748259443044, + -0.7673414993885352, + -0.5925328031880006, + -0.13320985771410276, + -0.36024953854175934, + -0.35307587730594714, + -0.1053251037553472, + -0.3676451118217507, + -0.36569750864225453, + -0.26965478058344206, + -0.6494420464602072, + -0.5353740356516703, + -0.3522812204826816, + -0.746511143953328, + -0.12725116316553198, + -0.41335570489436724, + -0.6941260853744902, + -0.48636398845456563, + -0.23950676440220253, + -0.1663471691082018, + -0.6648216395591364, + -0.6373791801266523, + -0.711103712355324, + -0.5261845759326929, + -0.4574864640074604, + -0.7869345077143913, + -0.6845907225184475, + -0.26946031209899823, + -0.42842501394644333, + -0.6385503076175482, + -0.541224186617698, + -0.6066906757938157, + -0.3860968825397, + -0.4472209437673175, + -0.3242159753044714, + -0.5867477361245715, + -0.5335390181474818, + -0.24899537714155395, + -0.7761782188566722, + -0.3227838630165448, + -0.41033508956039894, + -0.6390333119357671, + -0.2702015596972741, + -0.286385739900777, + -0.4788132499354045, + -0.5923145433249595, + -0.3843887439454244, + -0.5635529005528672, + -0.4066617429882232, + -0.6766307952678066, + -0.18175802071874303, + -0.4263744531232733, + -0.5824159678643865, + -0.15102712487154746, + -0.7794045933360308, + -0.3080448410219481, + -0.19996356294920514, + -0.18639670370465855, + -0.8000738785830445, + -0.16780874126458822, + -0.31996968360963174, + -0.3355429380238856, + -0.684889990367853, + -0.4649330465428007, + -0.09022829403462262, + -0.08482893361295607, + -0.11969021991758788, + -0.21477484421354365, + -0.19827684729634454, + -0.6489970614991425, + -0.17119575539597753, + -0.4663400122526376, + -0.7094446817969429, + -0.27803551297154117, + -0.4887757357619509, + -0.7754764352853616, + -0.1389629303626404, + -0.764862826982245, + -0.5635723925970655, + -0.45391663122140274, + -0.4521514530007663, + -0.6176582416065881, + -0.6633968531098474, + -0.26089026987292363, + -0.39923376064984906, + -0.2528737038501413, + -0.4776214646972339, + -0.7669386675695304, + -0.42967705951624724, + -0.34216793060755923, + -0.6976889205569852, + -0.31036305273118114, + -0.7614416889113327, + -0.15386502734501106, + -0.219385898750736, + -0.1974563334593621, + -0.14146004383177513, + -0.16848003583748106, + -0.39600064451249894, + -0.7342421061567382, + -0.34468496967353623, + -0.7610667096404304, + -0.13743553338300074, + -0.1767023527572018, + -0.32360142715592916, + -0.5368974580645022, + -0.24543896425861655, + -0.14392116748046302, + -0.7659452570232232, + -0.09559618090600785, + -0.32359162634103733, + -0.22216958221961836, + -0.573658194163092, + -0.24727567164045838, + -0.44351084893245685, + -0.1233491254422916, + -0.30050384312004197, + -0.6211412954725984, + -0.4971244259513559, + -0.6238381191001369, + -0.11247930614083201, + -0.5294020363535721, + -0.4321026916052286, + -0.7076309758751673, + -0.25650408604382335, + -0.11103306834200688, + -0.5794156500760158, + -0.19690861873342425, + -0.5151781721280362, + -0.25109887147060483, + -0.7802176781097133, + -0.615666441415472, + -0.20100342257900528, + -0.40915133094186384, + -0.3026147473129941, + -0.7913906233648397, + -0.39821023892300733, + -0.6502042995486487, + -0.3669393134853677, + -0.22172659283229534, + -0.24499884051697007, + -0.3916866687844012, + -0.392905979543251, + -0.346911982372515, + -0.800250944121166, + -0.1253210300403501, + -0.3272784727516094, + -0.41761442598731635, + -0.7352351391599029, + -0.6117146722221538, + -0.1429383403174399, + -0.2642147344287673, + -0.5856083374695769, + -0.26072111696555866, + -0.7945057309548055, + -0.6533275650035527, + -0.150460600278718, + -0.16377878342825458, + -0.5494817871090364, + -0.4330138713229226, + -0.7918558419932781, + -0.24585923704383028, + -0.7627772341347785, + -0.5489175659223864, + -0.1536528775446212, + -0.7793319607452506, + -0.6909444866762877, + -0.7948486520894311, + -0.46455163131022925, + -0.46846895487843926, + -0.5713184562137086, + -0.31941155712786273, + -0.410790830371373, + -0.3705397757637784, + -0.2837296563708881, + -0.08462730905466809, + -0.5953809192119098, + -0.752431355151125, + -0.38254406377286304, + -0.6310313133183707, + -0.2287580010391127, + -0.7181406522478964, + -0.20176160146376754, + -0.3072883965912449, + -0.697134205440133, + -0.11113265923805749, + -0.22745524369853398, + -0.38835346552213645, + -0.5565770014911928, + -0.37860239175045246, + -0.7563460540066596, + -0.10862735043135296, + -0.4836829578356807, + -0.46477719453383576, + -0.5231845581290065, + -0.24255157181531484, + -0.5947675664410612, + -0.6758559776789529, + -0.16048516116244893, + -0.5820975850891517, + -0.209783938311638, + -0.5124779308359526, + -0.4730916127481676, + -0.3745004783022733, + -0.17644639240748905, + -0.434123665095636, + -0.7665236904756383, + -0.47021277315835197, + -0.5535434755238146, + -0.48414083311735673, + -0.387539128566767, + -0.3209220094710326, + -0.6717782338182545, + -0.29062351262974895, + -0.31606398808255626, + -0.4830701018236165, + -0.437197566078656, + -0.6653987321218131, + -0.49075059288665174, + -0.7499301044593171, + -0.19576783163454603, + -0.46354583850254133, + -0.14676590354063734, + -0.6290807343748398, + -0.7236124681783012, + -0.7276658865560551, + -0.5212603175672923, + -0.6397874458278698, + -0.6905127188928222, + -0.3123370378835586, + -0.14314335054517724, + -0.7595429774772623, + -0.5234473306438339, + -0.5166387461325392, + -0.23128585169837979, + -0.33965997285596794, + -0.6376913739930195, + -0.22760649944878897, + -0.1420696371420448, + -0.40427879881718964, + -0.3137900879085634, + -0.5199922379471393, + -0.6025176423027883, + -0.4829598704530101, + -0.24778872329894475, + -0.5379206544931877, + -0.588126025007241, + -0.5707787283046785, + -0.12228789031393339, + -0.7296201486421786, + -0.4642648574187249, + -0.09346374777627076, + -0.4739052833700804, + -0.6405841200382205, + -0.12713892614102096, + -0.1283807490351434, + -0.1655430057914936, + -0.1639199604870769, + -0.20680532301866228, + -0.7748933319317606, + -0.19454761941910814, + -0.3589623618351943, + -0.6691411381216061, + -0.6114434733778147, + -0.4976569413790858, + -0.43312179234551584, + -0.32674057473081564, + -0.6861955387955881, + -0.5847395488221622, + -0.3692012261909586, + -0.4438658045895635, + -0.4659241886283738, + -0.14361815726810057, + -0.6569973748115695, + -0.6248363778727819, + -0.42396905406979685, + -0.18388177489336943, + -0.14016030739700147, + -0.7202524015573655, + -0.567962328999499, + -0.4277470613971229, + -0.20519180132564496, + -0.17296121479123072, + -0.5720104624995628, + -0.5427463025910934, + -0.7024598693895463, + -0.5257045577088066, + -0.6010175718298862, + -0.7413152098369795, + -0.20669903374092358, + -0.1425286330161366, + -0.3108506372549392, + -0.5377946433720664, + -0.707884553011443, + -0.3951925942920407, + -0.7287667777811875, + -0.30624358057450835, + -0.728475644431766, + -0.657198940236599, + -0.21996736086095847, + -0.7904695662950147, + -0.683338458043161, + -0.5763862327877658, + -0.1452187637191864, + -0.2514834708030791, + -0.3859357194144821, + -0.739141419315079, + -0.2592687165374482, + -0.24645453610766654, + -0.25513443576984063, + -0.7222833304133486, + -0.3590873575383169, + -0.6394718290368249, + -0.36114984637771624, + -0.5058933695098569, + -0.5928323247430954, + -0.4735720230626949, + -0.7110212855882431, + -0.2664630539098459, + -0.4366759919270297, + -0.286202648493766, + -0.5891807652069525, + -0.7368516869582906, + -0.6728451372007997, + -0.3516066288399121, + -0.6979495651097387, + -0.40997614797162657, + -0.2758881324705833, + -0.4280018811597031, + -0.31109791647262314, + -0.7865310928254463, + -0.15928153979847537, + -0.5860736067385106, + -0.527395205048963, + -0.600843498989499, + -0.2310452295540253, + -0.21254385977851864, + -0.5168569141812089, + -0.5070973849338128, + -0.32410740223014467, + -0.22493034613449847, + -0.28431951493623775, + -0.39119331209697505, + -0.13200364712052937, + -0.7143188720826544, + -0.3104917086078942, + -0.6196439187428268, + -0.6818087080085242, + -0.7763049034175691, + -0.21937086579779952, + -0.6815088296201317, + -0.1857375200073954, + -0.5645558191383732, + -0.7913215727276101, + -0.48115346454592495, + -0.19328802701248382, + -0.7164219950849436, + -0.7404754687693023, + -0.26132899192622006, + -0.6803105215936648, + -0.1546982530169242, + -0.0910655101624761, + -0.6910321154383521, + -0.7767761144657133, + -0.21724978329935796, + -0.611333077721238, + -0.20869538480975924, + -0.4439947884746872, + -0.20220313884920826, + -0.17074097421181167, + -0.47390196510080757, + -0.10505044527939855, + -0.3778712708090126, + -0.5025453784011005, + -0.44246638421654105, + -0.6977702363845788, + -0.5886258816490869, + -0.5215482243975829, + -0.37451001310959714, + -0.1617412746377228, + -0.4128595244425113, + -0.36844450908177634, + -0.17951174651873913, + -0.2628113068980771, + -0.5002369110096617, + -0.3476556234433606, + -0.2167152879790295, + -0.1230977645431729, + -0.5851636162675155, + -0.2732144067804225, + -0.7507680632057, + -0.23998250663552168, + -0.6081745272772247, + -0.5305305596836667, + -0.29346751598273046, + -0.5907680221280646, + -0.6650393792199791, + -0.5824203297744049, + -0.12892254522695357, + -0.767434730505811, + -0.34149631962322546, + -0.10571470870554822, + -0.4087179134419463, + -0.13677613936435873, + -0.5644814120856376, + -0.16903421401592822, + -0.6282705200384541, + -0.5280756842010228, + -0.7323546828070098, + -0.6109002566043935, + -0.47562595074826614, + -0.44161164028610156, + -0.6774101776443479, + -0.5881595101363171, + -0.44725564273029017, + -0.33361685380897843, + -0.6927513690408285, + -0.7472941058790271, + -0.2887009563038748, + -0.6445689118238047, + -0.18462404463996307, + -0.7118690491850058, + -0.028644436652831007, + -0.5682213006487901, + -0.6761455082238639, + -0.7003957845987544, + -0.30961203475365756, + -0.20623057177949677, + -0.3273935249206563, + -0.4032066598340096, + -0.3739556110157591, + -0.048505620904187974, + -0.6143557833771102, + -0.0034200841974143525, + -0.5446935886239564, + -0.24065317607590675, + -0.6181052453815119, + -0.45526548090616376, + -0.10945783990114921, + -0.28901501939481933, + -0.34033382267912793, + -0.1454832982009434, + 0.012897850363320473, + -0.6678582430210497, + -0.7850026998568009, + -0.7852278665419362, + -0.030556862254371375, + -0.6646340451448222, + -0.5726298468923214, + -0.4284284197961865, + -0.5436936367462497, + -0.4614212869037729, + -0.004799908953896148, + -0.7435909949194295, + -0.24612666817161566, + -0.6349580147073742, + -0.20004930889233274, + -0.6671581323153982, + -0.2845637584366414, + -0.033020424186114394, + -0.06968246509644904, + -0.3090867243991956, + -0.152423765587263, + -0.5652696296847189, + -0.568238228585626, + -0.1357651541524343, + -0.3543794614987937, + -0.14576374663857883, + -0.17984947437792098, + -0.022041597390107137, + -0.4123831774304446, + -0.6904124058368837, + -0.19707330349128083, + -0.32844467817671436, + -0.5255600177061701, + -0.2401551633468133, + -0.49730269014768974, + -0.5140029235684116, + -0.6427336183515416, + -0.583688828455233, + -0.7463995801345831, + -0.5314727403868991, + -0.7760832592575109, + -0.12106765545725462, + -0.6668961583831643, + -0.6918027771714741, + -0.7198097782297318, + -0.18619947760387257, + -0.5621390328431375, + -0.2731014847118969, + -0.21294833598853335, + -0.002661342332841099, + 0.0031716726548818297, + -0.3799537688383251, + -0.06830770149848542, + -0.5059256303047455, + -0.04857167339145774, + -0.4892303373727485, + 0.012225884826685185, + 0.0056307664183246064, + -0.332873174368265, + -0.209776962211084, + -0.08229534097028346, + -0.04048656746044199, + -0.7399131428242549, + -0.4388587387286096, + -0.6230182975078828, + -0.3003055968623449, + -0.6705299766690708, + -0.13802266641944783, + 0.002044381906342263, + 0.018918961055593875, + -0.27888213177451204, + -0.48463299877864546, + -0.3401154840910416, + -0.27710366368685035, + -0.6387493498620576, + -0.38551642806522507, + -0.17940987789800178, + -0.2524818971633992, + -0.48763190105543663, + -0.6222336471890448, + -0.17109825426774894, + -0.6835414124776183, + -0.772525301468476, + -0.6766934027237923, + -0.1076950317128833, + -0.2128081183234014, + -0.21791689372387402, + -0.5579305187666843, + -0.05135308827756613, + -0.023460168514662927, + -0.3149885289523897, + -0.5178573764843226, + -0.46634522056928124, + -0.34535650649826083, + -0.005577310243458644, + -0.05853409242996421, + -0.31739667962050716, + -0.023571032480717236, + -0.24547580189029894, + -0.23194484547769556, + -0.6557189324027477, + -0.006354114953748158, + 0.02857010456534237, + -0.1994003819967507, + -0.7141180236559873, + -0.31180971979843003, + -0.7427163700246756, + -0.08877440956658855, + -0.16605997092133673, + -0.15332693550905208, + -0.6296013609431108, + -0.37145316362603964, + -0.04388301730170052, + -0.36693004702360366, + -0.7433893912425946, + -0.16896388366056792, + -0.7316175215805563, + -0.5148972188223215, + -0.3959099441367876, + -0.0177045752340369, + -0.08594261758278987, + -0.23284462507091497, + -0.11679476762823493, + -0.01210191830476981, + -0.31951713949030813, + -0.7427116127736441, + -0.35071996154453466, + -0.06462277846440778, + -0.2955683319808774, + -0.36523402275562544, + -0.733385324703893, + -0.06310247150668546, + -0.6623004160714272, + -0.1939839253158271, + -0.028844364080795604, + -0.13654579718631066, + -0.35877482231772134, + -0.5626299015888594, + -0.08541630481228202, + -0.17881778727763797, + -0.015351181521610857, + -0.2010133316677445, + -0.1069770101891716, + -0.3726844039212457, + -0.4049397081170551, + -0.7417485823134328, + -0.6802794650798121, + -0.02130852272063022, + -0.6400836989009979, + -0.3678876623947573, + -0.7610433491098076, + -0.0694886312211308, + -0.252982224111188, + -0.2825075679647888, + -0.7927326588947858, + -0.26352733599070677, + -0.24422570823760736, + -0.32304360819023226, + -0.3390189540645605, + -0.32399021557821556, + -0.14469914673706485, + -0.2817646070207982, + -0.5103712701967662, + -0.4285893730046574, + -0.401203350166824, + -0.6771111804185244, + -0.7104216740149053, + -0.3192284316874434, + 0.017786541757378926, + -0.03201783529176372, + -0.2826019319558072, + -0.7764561334259938, + -0.7833816275309494, + -0.15264816282142157, + -0.6499788975909858, + -0.188629997834727, + -0.5433002672934204, + -0.03008504505782139, + -0.568786381614895, + -0.2440275158012516, + -0.009473770859637853, + -0.46947217102460737, + -0.24019826502769526, + -0.6372902904471724, + -0.5218485919158382, + -0.6842749684192738, + -0.2935006487647196, + -0.37483948961838537, + -0.38770625831187566, + -0.08768741132242885, + -0.3486766344442988, + -0.37456364415500965, + -0.2042292917660612, + -0.21920718851305454, + -0.057898135215270985, + -0.4380378113327816, + -0.26066875024215697, + -0.7473097849691618, + -0.5475786233099075, + -0.1574278769931493, + -0.6108684237310923, + -0.4349474357542298, + -0.5606028801472006, + -0.4964135483072312, + -0.43336374662003935, + -0.5652635542386734, + -0.3636620699801873, + -0.21871063766098764, + -0.020631759257782267, + -0.7160331741984897, + -0.031558931746257235, + -0.20614928192312865, + -0.1737798038093039, + -0.08751380883167503, + -0.3083121351305639, + -0.3877389966231362, + -0.5115295705663062, + -0.5827043388296944, + -0.7090319178181832, + -0.26073502478377586, + -0.5739663376550358, + -0.39496315886852373, + -0.6575210688138703, + -0.2692209183342398, + -0.664616955155737, + -0.6794305728761255, + -0.7137792938848052, + -0.22301432647531072, + -0.2567319358771605, + -0.26548471304625454, + -0.7246339843782515, + -0.4033902132682898, + -0.27656735708417135, + -0.6392732101891146, + -0.4954179835736905, + 0.002975274858330601, + 0.014477149180258109, + -0.6646730750130856, + -0.24591246816394197, + -0.6868564597886957, + -0.04334715687516977, + 0.020431097420084865, + -0.5374419578935599, + -0.07017306341050689, + -0.3139960152481467, + -0.3769172691233961, + -0.08247553124809515, + -0.4445322149533635, + -0.7497248661059652, + -0.29528361013229565, + -0.3587957494920995, + -0.552912238526478, + -0.09453094549574192, + -0.7661358241452023, + 0.014503487658766856, + -0.6485973623072108, + -0.4032302098645176, + -0.12891785646368026, + -0.35196480654687107, + -0.7386233981317014, + -0.2056061223731268, + -0.7368199169420901, + -0.4533385497429416, + -0.35466743904685366, + -0.6714945670218072, + -0.6687201938265028, + -0.5915987370350417, + -0.31273541856994325, + -0.5201962848083782, + -0.4994916047453349, + -0.7542317400100009, + 0.012349411146361011, + -0.7486225593437275, + -0.36950863795194155, + -0.5925850040948341, + -0.2792402504767182, + -0.6408625805503269, + -0.09388905995983732, + -0.6543473676900937, + -0.14477367930955898, + -0.5251651090526217, + -0.5466530391133149, + -0.15812657478318348, + -0.6161614455440395, + -0.4963654079458288, + -0.21033425101648384, + -0.05425923114475917, + -0.5657110359117172, + -0.5164183520541652, + -0.7733228926445131, + -0.7438621299718542, + -0.6725311075242977, + -0.7124447317689679, + -0.05544480394914453, + -0.6059856142726605, + -0.2396824048017303, + -0.40947247031252865, + 8.28653487226827E-4, + -0.09015678248253256, + -0.6121167451063412, + -0.31169492162324597, + -0.19521252303029002, + -0.11056480029494387, + -0.6727445013217316, + -0.23316131213334645, + -0.17022966947591, + -0.12757895818566622, + 0.022671854384848644, + -0.2694250592182065, + -0.7598085900285642, + -0.6454473747564246, + -0.02683876023419951, + -0.3439670622131043, + -0.47069235525497055, + -0.5819910368011265, + -0.23133573798427043, + 0.011458731832515001, + -0.57118784757535, + -0.0018145853919742105, + -0.35652211245349097, + -0.5530380729712387, + -0.6193999580966358, + -0.1893079786395705, + 0.024957218616917687, + -0.2173836769080001, + -0.17066547252886133, + -0.05060238982586773, + -0.7867706646779886, + -0.10168554721500855, + 0.0011147825232927788, + -0.19017701361940564, + -0.7181685143572314, + -0.1129451938753614, + -0.7146387669912889, + -0.0784207089556147, + -0.45591076452989, + -0.4172748427428094, + -0.6039295766652144, + -0.03185438324595691, + -0.17980909909657272, + -0.36944864614072875, + -0.38416933307491336, + -0.7706989493506609, + -0.0658501479802216, + -0.5764435940838147, + -0.14189907312740868, + -0.013422462719137385, + -0.6222453065970618, + -0.5259733607281458, + -0.2310878328693836, + -0.40291401742280114, + -0.07106973779853265, + -0.47043175124731434, + -0.7273444314211993, + -0.08087869990696672, + -0.3204767136982867, + -0.2585946646721726, + -0.6057498828989125, + -0.5905434508301268, + -0.7928344995379331, + -0.7248512606136377, + -0.34250218135957566, + -0.010363589996780553, + -0.27416628514225216, + -0.7651383433710999, + -0.6298385586469244, + -0.13582485423970347, + -0.18288015968938032, + -0.1732340130327007, + -0.2656632648902896, + -0.7697560015861669, + -0.7223572497125923, + -0.5822413284805388, + -0.22021654979663208, + -0.4730215008907269, + -0.2631864639552025, + -0.14052292274361888, + -0.563243279324239, + -0.47252000708722186, + -0.27982176036006123, + -0.25941358184032426, + -0.5029363225967856, + -0.4288107677190784, + -0.7835735943611504, + -0.4089508126522304, + -0.42676754675753203, + -0.46108953156007204, + -0.4248841356215185, + -0.11288109473906172, + -0.2211061003484276, + -0.4150572663536512, + 0.030656896715989812, + 0.009133695764402816, + -0.667006805809373, + -0.7557082419596406, + -0.3291178758199489, + -0.17805700026721483, + -0.0871829094003469, + -0.711765326594408, + -0.27685834607945614, + -0.18110053812623084, + -0.4690174878926864, + -0.45003982694885347, + -0.6113757205779646, + -0.26071468186049607, + -0.23438814623526794, + -0.4978693341836642, + -0.14653549139058653, + -0.4982195755520266, + -0.025575660730456473, + -0.454448022289329, + -0.12622311508218176, + -0.748848055905728, + -0.7476313187018037, + 0.0018038960917283742, + -0.7415838329702403, + -0.5677466171217503, + -0.25663908048026374, + -0.6800504639381837, + -0.47671137891350923, + -0.5610727418111003, + -0.7723747973828496, + -0.2537128833719168, + -0.7847893087788816, + -0.12957214951440366, + -0.10489070439695891, + -0.16113521780433837, + -0.30372131005173375, + -0.2384752396954145, + -0.4181247289117847, + 0.009703748589484973, + -0.022895333117143313, + -0.6128646059555032, + -0.14465444499403624, + -0.6853462301712031, + -0.0078026569664998435, + -0.10536741440162134, + -0.059307699191376906, + -0.17953429858312764, + -0.26786236900891824, + -0.4535908401193144, + -0.2538687709834475, + -0.7125516562196998, + -0.36660982163193545, + -0.2454898166514844, + -0.12254012214796639, + -0.7517480399835548, + -0.7295155466411832, + -0.05978689878887722, + -0.23097878529678972, + -0.6342399832496994, + 0.03217876691197008, + -0.5139233967284, + -0.3701739407086189, + -0.6674158735079075, + -0.7917770787569359, + -0.40161129732928263, + -0.6970068511778603, + -0.5050140308570752, + -0.7246925860571658, + -0.7200235268262727, + -0.07124378601780434, + -0.5494437995093958, + -0.20904149138621575, + -0.45452387220910323, + -0.6132484370059039, + -0.45724382078310144, + -0.5333297419443971, + -0.6491166444197426, + -0.1344794885671422, + 0.024308734580423597, + -0.51809124702873, + -0.6822588833174883, + -0.590516185062501, + -0.6868662610651999, + -0.5943128580154429, + -0.4767653875726424, + -0.22600813491235427, + -0.16472684741535004, + -0.17292294186209511, + -0.321454692424985, + -0.588731742014493, + -0.1066485381364537, + -0.5714593833056831, + -0.6653087025106876, + -0.3049450553218727, + -0.14503695017078788, + -0.11620517402539599, + -0.022408716013234464, + -0.5701076444217026, + -0.6112383983482428, + -0.4863692937265071, + -0.4502291455469535, + -0.19764294369954793, + -0.4299971124701484, + -0.1675036256007001, + -0.3488828793152377, + -0.1090276424175034, + -0.6846792195180742, + -0.12686881623383373, + -0.19724460530558052, + -0.4513643184078011, + -0.007808535971994046, + 0.03191818547447789, + -0.09563028865079037, + -0.7016096095466148, + 0.022473777632734615, + -0.462346845773728, + -0.30328995926547536, + -0.26007309937241285, + -0.09196557162667507, + -0.32802133947452966, + -0.7925413107287014, + -0.5008871340753411, + -0.008416861998349012, + 0.02606685745844728, + -0.054987839142220274, + -0.49588503022438785, + -0.03308022536048305, + -0.702756442516447, + -0.47107916583746207, + -0.6830205495795528, + -0.11328308749724636, + -0.3008272996219197, + -0.7503706656593389, + -0.7370198647241777, + -0.4069329281707632, + -0.3125007266682357, + -0.43570015190262434, + -0.11732726371044455, + -0.4339642046773194, + -0.5164417438608457, + -0.24467923591843044, + -0.11871571642590495, + -0.7080734369008009, + -0.13296392770583743, + -0.4292120905627611, + -0.5432359464556052, + -0.6423766534311552, + -0.036189056981117074, + -0.5157453051622938, + -0.5060239160700146, + -0.6362832052848465, + -0.715573937698591, + -0.04143410846770745, + -0.24322895835935443, + -0.6392634252532154, + -0.10894386845758308, + -0.16488187359178585, + -0.28943631390143854, + -0.2764858716395975, + -0.059676145046893, + -0.07378463732049878, + -0.1729525334272789, + -0.7858504776949403, + -0.6406401734105314, + -0.6515775422144823, + -0.6375900463451535, + 0.02511702588218323, + -0.653392679049351, + -0.3185126800958841, + -0.7584164385118924, + -0.518492079517992, + -0.1482650911624781, + -0.29991022887974683, + -0.6559018260653308, + -0.6870272550867548, + -0.43629500357611695, + -0.3765365936885969, + -0.5653873937152796, + -0.168956300130365, + -0.7336499008805688, + -0.12861170943410993, + -0.135730724080094, + -0.37187220714752695, + -0.38779318208542873, + -0.629635315763273, + 0.009704494820207743, + -0.23669629738712328, + -0.326227595971116, + -0.5031554893072568, + -0.2661685424917246, + -0.045897324659389005, + -0.6115561678510802, + -0.3419880151973794, + -0.44294460913539774, + -0.06863517244242356, + -0.4994614951158129, + -0.1477894358275781, + -0.41934105691046847, + -0.2206872436428179, + -0.03320131217989131, + -0.5723403986441075, + -0.027445480842139824, + -0.6418786473313005, + -0.476083376392335, + -0.5018593574710868, + -0.5663171600560113, + -0.2804869080806267, + -0.42536032175022054, + -0.6941794092924961, + -0.24453573132534234, + -0.1984690762195882, + -0.5064358389889363, + -0.01738635964380575, + -0.07546576824310114, + -0.6658307514069565, + -0.5523773053452022, + -0.25454402581871094, + -0.2624578501605319, + -0.06837127835728718, + -0.28932274534507263, + 0.01327586175050599, + -0.23938050611103112, + -0.2364658768109239, + -0.5762722034209132, + -0.15248134555732895, + -0.11622941219574101, + -0.7075884420902977, + -0.18826023293349048, + 0.01019056088285808, + -0.6847940087390453, + -0.4122153944663661, + -0.6937746549153775, + -0.06418901631993368, + -0.4509793467577941, + -0.7806309842238376, + -0.6013465070207337, + -0.16055697289709037, + -0.6661737911470489, + -0.42333742278009806, + 0.006247782506570543, + -0.49986828157360613, + -0.11442943928544036, + -0.6513957624077014, + -0.1774368600260361, + -0.4234205919468303, + -0.3703282073658169, + -0.7135778141064897, + -0.7495614875577817, + -0.36819022361301457, + -0.6711765037578539, + -0.49190609559545634, + -0.4536586479998692, + -0.23251036848860596, + -0.5391828550342428, + -0.13231009069676902, + -0.35776185320336745, + -0.16928211934050896, + -0.17433533833256487, + -0.24775968631069079, + -0.2989511406850551, + -0.25384400408191754, + -0.10713974094945355, + -0.7804718436429406, + -0.5682743258981755, + -0.29373307725895204, + -0.5340469496437472, + 0.032851467201501894, + -0.6174891648347074, + -0.4050249608096046, + -0.7711156790914869, + -0.1817552760790635, + -0.07448804152441257, + -0.7599178794709691, + -0.5995717080408052, + 0.02195675914346895, + -0.6308333927585608, + -0.14428816447122972, + -0.0797344199099016, + -0.7211739510414674, + -0.3937556877016114, + -0.033824734891451436, + -0.5354470394207049, + -0.1439634913668083, + -0.5972027926764891, + -0.5332527723867185, + -0.6800020303903413, + -0.23885445921266768, + -0.07745033155248848, + 0.005083267940292235, + -0.19443702839364652, + -0.49157957970164573, + -0.3573816051268854, + -0.27941842256498217, + -0.6284994269458148, + -0.3165700761289172, + -0.19813239793806203, + -0.1118939796717231, + -0.13274027020549473, + -0.09002628499522936, + -0.6901981995331077, + -0.22365941001963563, + -0.5614782045779492, + -0.13344635650108017, + -0.756273555825669, + -0.5930927594569813, + -0.6233102522317505, + -0.5954138152055675, + -0.1668798137263593, + -0.4788009200566102, + -0.12734941605905936, + -0.31448104003597543, + -0.05738440338888284, + -0.33084068445309867, + -0.4057543607382148, + -0.34855282732203585, + -0.6403024534345169, + -0.09433315500796535, + -0.7002402844477739, + -0.5044847860214987, + -0.6727906763659818, + -0.43802560828675324, + -0.5804536746272644, + -0.7347803862073712, + -0.6049945090274944, + -0.15990698597071318, + -0.633563377673354, + -0.33281024787536256, + -0.1230356661818417, + -0.7097071743969986, + -0.2558899352240095, + -0.10530123603714425, + -0.6710831818466573, + -0.3298602963595659, + -0.615003479923401, + -0.6723535635519909, + -0.16826753287717866, + -0.16491631875031965, + -0.47404256448074783, + -0.2992547750836425, + -0.6690893687190003, + -0.7759093448001242, + -0.34508746535289075, + -0.25324874213531434, + -0.7232722216664452, + -0.3147685355483583, + -0.6599358639101516, + -0.7917420033839161, + -0.6411380096627898, + -0.14975940791938191, + -0.11845984978836721, + -0.41889814608628945, + -0.5173352439397632, + -0.29752673030804205, + -0.6935028273248652, + -0.16399473745784043, + -0.47592842536818847, + -0.34837091226119066, + -0.32406730880304563, + 0.03061157584484775, + -0.09253230475111895, + -0.26230108761483517, + -0.5686043306638882, + -0.3962422024665556, + -0.53180526461415, + 0.012531154231611774, + -0.770795590733425, + -0.7264506855848256, + -0.6567552899617026, + -0.13235223291232412, + -0.6285306033326522, + -0.7445887978070114, + -0.6319617730308145, + -0.20505357190559093, + -0.2805857707060062, + -0.22093192391569905, + -0.0372319226370349, + -0.12467507583784088, + -0.30969653086279914, + -0.13151215013283413, + -0.4168785570360154, + -0.03951862316367849, + -0.7360886380008581, + -0.7032514696725986, + -0.11969263097826777, + -0.4226259961785681, + -0.5956260619885615, + -0.6710374705794984, + -0.10299303841211771, + -0.1736606745418282, + -0.07389847186391829, + -0.1382959642822601, + -0.299231907557821, + -0.04169891320977204, + -0.1791789614101229, + -0.49584832658918027, + 0.0020492784236193495, + -0.7373071629917763, + -0.13733636291991058, + -0.7000526267989857, + -0.06013413443224358, + -0.6535704528178649, + -0.7089010572948997, + -0.19937621079787649, + -0.7553625497544202, + -0.48918682041044614, + 0.029638310973938653, + -0.16492087908058595, + -0.5566226852830378, + -0.6551575971863272, + -0.25011257245761964, + -0.5261323089719867, + -0.2892777013783566, + -0.7878240528331778, + -0.7272720291810205, + -0.5482982427003854, + -0.13222952045641312, + -0.0838503158711057, + -0.043498968284120254, + -0.1147631170783785, + -0.20526718239017006, + -0.09351482732584149, + -0.049552647058247024, + -0.1732079080468003, + -0.5160700601045064, + -0.1439395185200446, + -0.06981173516433059, + -0.1386370192586318, + -0.5717515484508299, + -0.17181420625894306, + -0.473392191624673, + -0.25357836485194163, + -0.2921541187687975, + -0.05319825148229873, + -0.6208897655211428, + -0.0450901699223345, + -0.39030154815804846, + -0.055019525797222135, + -0.4261499232737379, + -0.32934690002443523, + -0.3501454241263356, + -0.5045088018683648, + -0.2881636413500156, + -0.7692402335612436, + -0.06510713029066173, + -0.41090394175677064, + -0.5053239860024024, + -0.7762770719975131, + -0.041718341550800564, + -0.5460507297404152, + -0.2939058052478915, + -0.4320077759050138, + -0.5073052337840216, + 0.03324105828674084, + -0.4953678759980301, + -0.5857807681761021, + -0.6704001358916081, + -0.4132135492932214, + -0.45441787702966424, + -0.21044514119714353, + -0.22007829013920444, + -0.3608291017080544, + -0.18671619419080254, + -0.41709494554843285, + -0.35341058807110415, + -0.3273201853607853, + -0.6897638167010467, + -0.5384939952426475, + -0.3958607776765772, + -0.23753570080058128, + -0.769871172912403, + -0.33082468045987684, + -0.7511379555946688, + -0.6766726445632939, + -0.6541435878544906, + -0.5266526105863001, + -0.10207483570508802, + -0.05080273929851675, + -0.24394861223335418, + -0.6723590854017463, + -0.5307764828291411, + -0.6319420732729679, + -0.6022875788769844, + -0.39677247115746217, + -0.1953344678928478, + -0.534534692581148, + -0.2943917754951315, + -0.27062619167118784, + -0.20824002209824688, + -0.15133988067648485, + -0.05219304486442333, + -0.4659042504344871, + 0.020327344736411734, + -0.19447650767111158, + -0.4323948824096013, + -0.5828601629452616, + -0.18646635172105586, + -0.34280642493418034, + -0.46091062247655673, + -0.2787870942049011, + -0.4579989932638007, + -0.78824303407088, + -0.1197835322207007, + -0.4175410412863832, + 0.0012088558675816818, + -0.2731890255492838, + -0.35535525742185037, + -0.7252128134135282, + -0.11633263527683357, + -0.27866621312609086, + -0.52382599880742, + -0.33391964411623093, + -0.6479053097890342, + -0.08975268924960889, + -0.6209052190911855, + 0.023083007768978536, + -0.5557851082969456, + -0.16157604469015796, + -0.0724372490209455, + -0.0495505886133254, + -0.3878311270118106, + -0.48949318075416254, + -0.09494326557947497, + -0.23335239048031764, + -0.48228391277761096, + -0.22631866218560925, + -0.5929139920573763, + -0.3430749156218318, + -0.33892174861708213, + -0.4688443744834029, + -0.5363649064759884, + -0.3107185459234752, + 0.007708516941042132, + -0.4730589663282211, + -0.6788548247135193, + -0.6200511717657662, + -0.288722645026553, + -0.700903493361996, + -0.40082943236509844, + -0.7489412824263818, + 0.03461416170656395, + -0.29825890808179956, + -0.39864720135976456, + -0.5930256034892631, + -0.263513301083934, + -0.6324474616555595, + -0.49242672385667846, + -0.48560990486872924, + 0.02362935827714996, + -0.6298072696596222, + -0.25147374867640615, + -0.07848359554520845, + -0.24674058077408578, + -0.012263158293670307, + -0.23229672978557558, + -0.7657972098089191, + -0.7352639502799808, + -0.6775460570805267, + -0.7487240066023368, + -0.05126552568252429, + 0.032464270018653485, + 0.017851133983904477, + -0.4198503582127633, + -0.6558810261424987, + -0.5271945871856112, + -0.14895827726115185, + -0.028454114764777105, + -0.2649289282068955, + -0.20592658188438895, + -0.35763150148647826, + 0.0013282018878705282, + -0.4531603371219599, + -0.07630574606987939, + -0.724139537693219, + -0.06412121603739185, + -0.7817453448229755, + -0.4286575837165389, + -0.6408899411994583, + -0.1313461322792463, + -0.6632360495403837, + -0.6730193767246124, + -0.40864217613118614, + -0.7749333290536907, + -0.5130815871761524, + -0.6418378939535541, + -0.3708966929106333, + -0.5749134250717003, + -0.010975663664617885, + -0.5164676982916647, + -0.7370143303618245, + -0.6695795014673463, + 0.031360834456165, + -0.49959664682233684, + -0.6859985675017239, + -0.009995526768192708, + -0.13943660582285533, + -0.4885171216093596, + -0.7705775480389246, + 0.022501846499317857, + -0.5078197589119802, + -0.40211302878096195, + -0.060063783729691345, + -0.029308956698123945, + -0.37841050771067564, + -0.5456342057207966, + -0.12686628542386047, + -0.6179546906371615, + -0.6790803793026624, + -0.28253835989204856, + -0.0015717097796272839, + -0.6077186275896374, + -0.049314444294704995, + -0.7860311475543592, + -0.5325774264564678, + -0.5703936079189501, + -0.5863316499804672, + -0.6454407730197068, + -0.5900448376631369, + 0.006848844370682672, + -0.7376895301996448, + -0.7097383075263907, + -0.6835983332762877, + -0.1276412712616175, + -0.4587664759227373, + -0.4392971776287275, + -0.3328834107129518, + -0.35977579514984, + -0.27043604477845296, + -0.2519278702362727, + -0.08218311029922998, + -0.7014912198706068, + -0.23195044319469282, + -0.4958431995451776, + -0.5544965015864766, + -0.4679780035553173, + -0.5132822749924224, + -0.7641568213420822, + -0.5321976135803256, + -0.5837004359953905, + -0.4798238904195544, + -0.5674297310202601, + -0.14483959211031439, + -0.2529227414690758, + -0.3443041507888581, + -0.6006372726855345, + -0.6589135185270847, + -0.44098291835490666, + -0.6205306467857522, + -0.016870528210274127, + -0.5177143975683843, + -0.14768830873200933, + -0.1992104309359234, + -0.12424087565482633, + -0.2035508485320957, + -0.4820014822260369, + -0.27534124184567077, + -0.6800447188063323, + -0.7755147492107645, + -0.5756176180234372, + -0.24207282902907168, + -0.72040582481972, + 0.004527871391003302, + -0.3322920328093088, + -0.18100592629454815, + -0.4184191339335987, + -0.32261597778520223, + -0.3545792698062639, + -0.006672792324399435, + -0.06835047566511554, + -0.6607644001787514, + -0.4786183667118361, + -0.03513521199400116, + -0.40876297307936993, + -0.14368112964412438, + -0.46282693545017284, + -0.16930222407871076, + -0.5812293118911955, + -0.4647539395974092, + -0.21773903836985276, + -0.693862109708601, + -0.05126696029797739, + -0.6688561518758832, + -0.7451329275053756, + -0.7802456545318212, + -0.283923273352121, + -0.4899849209506357, + -0.785732019694183, + -0.3481142760079432, + -0.5713732928793567, + -0.5000767483545112, + -0.3908693462836726, + -0.022462597925433703, + -0.7334478215199934, + 0.024689967452817152, + -0.18634674853911415, + -0.665961945769949, + -0.22000840070825267, + -0.45856532488638513, + -0.29625295650180355, + -0.09730318987146991, + -0.5778402095246735, + -0.7447787435755028, + -0.49180008313911794, + -0.5977440453875981, + -0.6003133173126101, + -0.7148131162429346, + -0.7349557896843418, + -0.24159760922192186, + -0.6954401226391085, + -0.19479291921335573, + -0.7815422393258987, + -0.4043197716632178, + -0.13991067136829438, + -0.1336454293909708, + -0.6720913458368037, + -0.18271668005339825, + -0.1162631769920972, + 0.005967038037478889, + -0.04102274848402199, + -0.5671162206575208, + -0.7239103515244917, + -0.5042719144152783, + -0.6230716563181128, + -0.12777398300806964, + -0.3968498941037569, + -0.6545673458609336, + -0.650645597869091, + -0.22196353189215112, + -0.24212689855855263, + 1.047971213463672E-5, + -0.36123327420627516, + -0.39018413029942006, + -0.2710562491274652, + -0.21187451053403217, + -0.43716305358115304, + -0.16013909592837805, + -0.25455842163805453, + -0.5360524988902435, + -0.7080782298925345, + -0.5824516856801322, + -0.6736469397318823, + -0.7209300913011292, + -0.33604010902358905, + -0.5313295674132731, + -0.16815340070274465, + -0.17356661866041345, + -0.4414964768146462, + -0.054174514239599625, + 0.005887372470019803, + -0.09730178545570489, + -0.5791500200865971, + -0.22312506599622517, + -0.7009483649079742, + -0.4064721687351931, + -0.6880695490767827, + -0.4689145779368606, + -0.6696618945511532, + -0.23169366666778135, + -0.007569278381555189, + -0.39497858973412164, + -0.7608867333063412, + -0.052752787894636666, + -0.2521360157443392, + -0.7677555119277779, + -0.7088390598829266, + -0.3104160421784301, + -0.04003191133160866, + -0.12207293583229817, + -0.2557707118904188, + -0.11129149100859548, + -0.7012500169206597, + -0.6521051494587826, + -0.461597004183464, + 0.03016072677321735, + -0.44848779640440317, + -0.08969026310028372, + -0.7309717292420966, + -0.10318408582471972, + -0.5599121663892537, + -0.42452872113947565, + -0.5599015655184201, + -0.5967250017634745, + -0.3538847557062413, + -0.6696418952226448, + -0.33418490143747953, + -0.4336558567165822, + -0.04636198824000004, + -0.11271875448859103, + 0.031119921384286764, + -0.1905954551556054, + -0.1407491865850049, + -0.4556528013247818, + -0.018140271470337366, + -0.3096806076771443, + -0.41373052426358037, + -0.6925155100797322, + 0.021188309158246765, + -0.2990608598945399, + -0.48274549654961213, + 0.007472395021256295, + 0.02672062995085045, + -0.5296690942174976, + -0.3782361662259277, + -0.033104729197459104, + -0.44026049713536075, + -0.5605687583168468, + -0.19833389541875124, + -0.5199461018365696, + -0.4475843490803444, + -0.36789631548032037, + -0.6724953999051304, + -0.13831409636539038, + -0.20068323667551347, + -0.6298187180300431, + -0.690383460781715, + -0.04951074565908864, + -0.1319807016604252, + -0.3590947802350185, + -0.11066575752023822, + -0.2810377419496828, + -0.7708462941796744, + -0.20878270542354027, + -0.7330902421485962, + -0.05341173456782988, + -0.6166532213736374, + -0.25680252134693493, + -0.35700061819269513, + 0.006046714115483409, + -0.7404232325878498, + -0.3697598891270426, + -0.5880911504560362, + -0.37422118825414524, + -0.2307171433420051, + -0.2282093218281931, + -0.20942001959356293, + -0.2523110425627427, + -0.68292474144442, + -0.037361598692412734, + -0.6447522446759045, + -0.4873021852174014, + -0.43048443237865675, + -0.5396959599179465, + -0.23069634477201661, + -0.2573879403154069, + -0.36249536900036716, + -0.4510409319738745, + -0.07724294726495295, + -0.28802105189408733, + -0.6330361788810356, + -0.16714932100800728, + -0.34534339199508096, + -0.0013499281240251237, + -0.716573748920715, + 0.016688447514834892, + -0.7700374673118641, + -0.3868346841521628, + -0.7439282421239203, + -0.7225364830778199, + -0.467472891805536, + -0.661099697740121, + -0.7535168255681416, + -0.6486368055368054, + -0.2929268934035172, + -0.5697512103987582, + -0.18232113482445755, + -0.2734826768490518, + -0.05579007557276172, + -0.548795993816951, + -0.016223258465786095, + -0.02148078128924069, + -0.2595444355585401, + -0.6190249693560921, + -0.10505363176553817, + -1.5679007702606995E-4, + -0.27915350711387177, + -0.5555887329042855, + -0.6588509013016333, + -0.3953638980075538, + -0.06301188393415624, + -0.23344535246867837, + -0.028875716007441654, + -0.05827578726058291, + -0.7895483906997106, + -0.20610947865808282, + -0.18094119346623005, + -0.6598192066294442, + -0.13942236297752797, + -0.36529200263803624, + -0.009176061001677338, + -0.5634344969342666, + -0.6876672360135442, + -0.014511012382622313, + -0.4854908913869333, + -0.2048359105042502, + -0.21434581996574187, + -0.5791219920420355, + -0.6780287504941361, + -0.7038769487642423, + -0.73899573722431, + -0.23040283066415668, + -0.37467977089347526, + -0.7550496501913383, + -0.6331192054037552, + -0.49866305336643935, + -0.781201082791045, + -0.7209453392218887, + -0.20021135174949622, + -0.5770606608165492, + -0.6433394584256065, + -0.5114345149450683, + -0.5745157326607716, + -0.2638769874148519, + -0.7876743118600503, + -0.48944018963662594, + -0.09943467699290343, + -0.6114368020134766, + -0.2966629079701761, + -0.7798856465653339, + -0.7159261310284725, + -0.3543849702770864, + -0.5015310113767302, + 0.03132329542969858, + -0.07525567904077757, + 6.752111767593938E-4, + -0.03641013028761175, + -0.5038261294089754, + -0.24021404054623297, + -0.43239254517716774, + -0.4608124415524506, + -0.26046611398175556, + -0.048639345028680614, + -0.24564618247513348, + -0.6816916196710536, + -0.7693318794137107, + -0.08151907913049616, + -0.30766187548280444, + -0.5033891252453877, + -0.09461227878388889, + -0.6464693052576798, + -0.7638492088752294, + 0.004797179154370279, + -0.1833806732785429, + -0.3985593461439495, + -0.19515577506074833, + -0.46128152421686014, + -0.03212520162538979, + -0.7396630004525394, + -0.6625254633169643, + -0.538267546975146, + -0.7849396114143096, + -0.05034377884670893, + -0.09609427397546721, + -0.7108682981075108, + -0.1815516064866065, + -0.7566815185112952, + -0.671501358001361, + -0.2543991863431265, + -0.7856521835388227, + -0.39871699078002915, + -0.30812763235417656, + -0.20426302631486914, + -0.3347136447176435, + -0.3640324352178688, + -0.2982642602804499, + -0.6154933626910952, + -0.711808140977203, + -0.18882096228612044, + -0.6142308234925228, + -0.5367969027988494, + -0.2734885702681732, + -0.2590439470836743, + -0.10631094467224023, + -0.015299417838801288, + -0.7207050227437684, + -0.3325661260626656, + -0.10019405486872401, + -0.6592776451415353, + -0.34236203391008624, + -0.5351430243213142, + -0.2849028388075697, + -0.4018786440437122, + -0.5749030156608457, + -0.7377769467045292, + -0.2697745523712054, + -0.6160189815672794, + -0.1787188194328564, + -0.024342677011031655, + -0.23853037315239112, + -0.30155936384684456, + -0.6331446449786193, + -0.4706423478051226, + -0.22528415025078985, + -0.2775397185523719, + -0.09041439029104648, + -0.6277903403193613, + -0.46997569028928715, + -0.7849048234629199, + -0.5863555670105787, + -0.10774981390483185, + -0.32983029743287473, + 0.018379660398119113, + -0.7338696537858592, + -7.59824959258526E-4, + -0.33879339106152395, + -0.10464274984744393, + -0.6164338152110451, + -0.7735187177726851, + -0.6541638793315199, + -0.3273368457443866, + -0.44407260906349405, + -0.15658370631532315, + -0.6613276094415184, + -0.1438837402515587, + -0.5576813839426419, + -0.7668589163395308, + -0.29763315370014914, + -0.28573154080607166, + -0.6037151274025617, + -0.1264286945964943, + -0.29818139376591785, + -0.7188429079178189, + -0.3884527169211098, + -0.4985607378012302, + -0.7044699501754836, + -0.30049996520450184, + -0.23542270680337474, + -0.6420296435093625, + -0.2957263382527379, + -0.1498276669936609, + -0.35308472102954774, + -0.15162553436103787, + -0.3750250300503019, + -0.2264994589135072, + -0.6205060859947452, + -0.1119505963354126, + -0.04102762787081149, + -0.02469382563772482, + -0.15529859590199657, + -0.6238214928874387, + -0.43508762229231207, + -0.5670375026769051, + -0.41499885698269673, + -0.36777294757537554, + -0.12604268563956456, + -0.6151136211449588, + -0.4839522439615772, + -0.26743837622242506, + -0.5698486678417666, + -0.16374665356839357, + -0.4070596964865238, + -0.15852580911630032, + -0.5223769480201474, + -0.5466021850575631, + -0.592795935563423, + -0.19210856882377958, + -0.6210764473413306, + -0.6410143314420444, + -0.43703018984818437, + -0.4709393579483418, + -0.12781031745495186, + -0.3223622464405789, + -0.7215272966143049, + -0.2042849872852024, + -0.160007557929563, + -0.03898928542451163, + -0.3266708011316816, + -0.06181466200794594, + -0.34448422726312716, + -0.6185098881365586, + -0.6922469362834338, + -0.7897487034892247, + -0.027495403778915684, + -0.08502542992558071, + -0.0174506952887874, + -0.3223909431908251, + -0.1462026421105178, + -0.6157342683771422, + -0.30601865356611635, + -0.1890958063447098, + -0.10102456695104234, + -0.6078419905411091, + -0.3486939763113935, + 0.030781007654438364, + -0.3715716671085146, + -0.4529244673698536, + -0.05850838928761504, + -0.1713692090756611, + -0.43112812287620966, + -0.2411702398741008, + -0.015752681838542837, + -0.07401715419280464, + -0.15199979099954808, + -0.14244648427433082, + -0.591810506075059, + -0.3771805606979448, + -0.39498540628369266, + -0.24248417762100072, + -0.2292126751750162, + -0.5962490218843289, + -0.6199007361181618, + -0.18180986268357602, + -0.1284741523517925, + -0.2558673772604999, + -0.5010815082085773, + -0.6628070902129439, + -0.05094706726682241, + -0.3383828515482358, + -0.2839747183029544, + -0.19588620497203046, + -0.21478544858648985, + -0.053773279241218996, + -0.3018992884717704, + -0.15726887295152858, + -0.036851232024717184, + -0.39922687518081135, + -0.7088015525076107, + -0.16854188888293242, + -0.6003053891148977, + -0.5278105662661734, + -0.03687426869393595, + -0.27627083380855355, + -0.2923950263581463, + -0.2820966545416772, + -0.5057872264477339, + -0.38572891651245705, + -0.48637743095270203, + -0.3087564579016277, + -0.04323214459695057, + -0.23566975151400604, + -0.24312415372667384, + -0.351974495920043, + -0.29004960941275937, + -0.44333470349889015, + -0.6240821236965928, + -0.31148642460932024, + -0.14872640805071546 + ], + "y": [ + -0.4096477562911808, + 0.18749260441031212, + 0.06829721654937981, + -0.3420770384581052, + -0.002400526314887297, + -0.05280192308722964, + -0.0992651736968383, + 0.1350288547749806, + 0.22223964534114926, + -0.4706655183556956, + -0.17309649352630002, + 0.23150911877578784, + -0.01681238732072965, + -0.03741269378568901, + -0.1357618925817779, + -0.30092878538489304, + -0.534378459885241, + -0.19578006790418684, + 0.2912924564325504, + -0.5042385029352286, + -0.4300259583824423, + -0.2843904054179383, + -0.36787548974181916, + -0.2815098363746651, + -0.5470363113358362, + -0.34183338847426625, + 0.10370262481784498, + -0.3303356043380446, + -0.4819041436045123, + 0.02413515722133497, + -0.21093833729345496, + -0.07189540845992548, + -0.3776257357436176, + -0.16607875787817772, + -0.4755955212029108, + -0.49937691563929976, + 0.17497179033984134, + -0.3008125483153798, + 0.22965872215767458, + -0.15241834880517663, + -0.43622307731856613, + 0.13107917178441653, + -0.10043417541075805, + 0.2809663127286971, + -0.16803302314056062, + 0.2167759088996507, + -0.4538862624938166, + -0.15790516285907408, + -0.4844709448122107, + -0.07471141390157993, + 0.23459579767799432, + -0.2177809651298453, + 0.288896347384631, + -0.09852973632948048, + -0.3691256816979681, + 0.15534627817949254, + -0.1567868675557162, + -0.1415032947417753, + -0.4287672296100807, + -0.18730172288779912, + 0.14786019783589144, + -0.4604451487561816, + -0.3811482078659205, + 0.30988643815922323, + -0.2018690807606835, + 0.009947937293745768, + -0.03722892312233361, + -0.3482463629119634, + -0.3776719436609959, + 0.11907682583117662, + -0.4543594626125251, + -0.4566799355197617, + -0.48007945622655745, + -0.5139412176639372, + -0.12412218054533158, + 0.12447079305069164, + -0.3540823887703475, + -0.47860294772907414, + -0.10065601479392805, + -0.06579725855633045, + -0.03449143386077347, + -0.522768469250392, + 0.04277082478599248, + -0.378580523965034, + -0.07323143034227658, + -0.043336743606666395, + -0.33099872312009976, + -0.06719310636716885, + 0.043939139859997534, + 0.03521474082317433, + -0.03128157786440522, + -0.29307288854455854, + -0.26420320912087125, + -0.3810574805260642, + 0.10723144115009675, + -0.4858761172648171, + -0.47631139545712226, + 0.04552026933345299, + -0.36674988939918873, + -0.019450623568658787, + -0.09284322458482419, + -0.06077347774939995, + -0.2720366953536244, + 0.01574960021650984, + -0.48398315201884723, + 0.06365061368764646, + 0.06968275583492789, + -0.21067748780044532, + 0.21437618658262791, + -0.18136823116214262, + 0.10343687839243332, + 0.2956970833389184, + -0.49811647263109743, + 0.27288833805709944, + -0.5298248949772498, + -0.4436123361250707, + 0.08428324525514297, + -0.07583795668622778, + 0.29652835507161235, + -0.2323767840246433, + 0.029623762462827274, + -0.2782061754764153, + -0.252948003578585, + 0.026303905632580893, + -0.21577424776700965, + -0.03569026950251819, + -0.3934251623883752, + 0.30491666221671776, + -0.22293765877228922, + -0.3724701911062412, + -0.4494030396391027, + -0.5464826242001161, + -0.2788584560349018, + -0.28679290724342066, + -0.4746578372595468, + -0.256510178752399, + 0.21917952208294877, + 0.1634220526861615, + -0.11983126387745563, + -0.26018342476324186, + 0.1820106017847264, + -0.023552911188141956, + 0.19053973989112105, + -0.45132358086662266, + 0.06057494915558459, + -0.13281248096027948, + -0.4058347975526494, + -0.41638979488482336, + -0.246323288181795, + -0.048016881982824944, + -0.3303848040036139, + -0.011305029394976684, + -0.19172571112105458, + -0.5371107805580042, + -0.21497445248041486, + 0.28197046475198606, + -0.3755380212720577, + 0.17895383386143715, + -0.19931777263875056, + -0.2736119508625021, + 0.20351225683758756, + -0.29811658912611044, + -0.015383153783681047, + 0.18960668964597227, + -0.23584114884816065, + -0.5291082965015353, + -0.08656319800975848, + -0.2981745945222676, + -0.1875046959248418, + -0.5455446415006664, + -0.14622960099223686, + -0.12713376378642277, + -0.5154318849832105, + 0.21287309844467595, + 0.12629053484440456, + -0.20546332277187807, + -0.33330258384891737, + -0.19726606799756652, + -0.4287557708661356, + -0.13213310689100777, + 0.30174874831122633, + -0.03393559635834398, + -0.4220681947027398, + -0.2304380990681562, + 0.20854895893169134, + -0.2740811139360852, + 0.05876329463192398, + 0.013104171264562536, + -0.49095868166957746, + -0.0808379625323774, + 0.005699473366230445, + 0.21267490869504924, + -0.3724056930901842, + -0.16525599158197096, + -0.316683435062162, + -0.5155331207288915, + 0.1691658432762685, + 0.21073270416511536, + 0.023823423880988126, + 0.051547603663334884, + -0.03411507765507915, + -0.18092827913417414, + 0.19188483180791327, + 0.1634412058536533, + -0.1902693765153199, + -0.30844501867108576, + -0.4219294497645971, + -0.1924043319509125, + 0.025941450969686697, + -0.1085583324763334, + -0.15765536529062296, + 0.09721951147183361, + 0.18311643662899446, + -0.3643491764410336, + -0.18357417291795797, + 0.021216659216295897, + 0.0725345364940061, + -0.05047025285839801, + -0.4086619793593543, + -0.02013073741302074, + -0.43324759023663667, + -0.40587833985199984, + 0.18024155642538653, + -0.519493876559641, + -0.1387111447796216, + -0.47704755004043786, + 0.08582702543122422, + -0.35584622026431123, + -0.019798673948430157, + 0.29304112105765023, + 0.24373260742879588, + -0.4263250672167551, + 0.20030949252025443, + -0.047068262086094714, + 0.2406359467365814, + 0.14769852468105837, + -0.10546554517557344, + -0.3678499095170185, + -0.06185531500055763, + -0.14159554005623065, + -0.4072577666899947, + 0.21127728614730779, + -0.47046047692040055, + 0.24291901037548025, + -0.48760854270152754, + -0.5515672349781173, + -0.2772567153785384, + -0.46847134217597647, + -0.12317757958612163, + -0.10207462903133202, + -0.05273414279414523, + -0.0944709322472903, + 0.25173090046763846, + -0.5515814591701362, + -0.36162589456332606, + -0.13146989407969217, + -0.4336283984269591, + 0.2896663276084872, + -0.30982376906639336, + 0.15933535680410615, + -0.2990450312121093, + -0.0011885257555734885, + 0.14009974858874497, + 0.0955374583336005, + 0.12308048214799472, + -0.19255692236465488, + 0.04176497767861187, + 0.3025108928655137, + -0.5508920363778388, + 0.12167884091247472, + -0.1057413214198118, + -0.45980875238857577, + -0.3873986201181665, + 0.15678971786856488, + -0.23623589133506023, + -0.49021686953945814, + -0.38526224316472474, + -0.3772081162910297, + -0.09265524706894557, + -0.4660649211869279, + 0.017622918888313688, + -0.022438942755905855, + -0.32594918517516736, + 0.0983662184772891, + -0.15280332751256037, + 0.009731097802525124, + 0.0035530359513963328, + -0.3850144040568292, + -0.49480498332730644, + -0.18608371863558448, + -0.44576299994494134, + -0.05455849003142432, + -0.0054815558146680265, + -0.45349625031911667, + -0.5063780664579527, + 0.19625200804653176, + 0.25277991250567944, + 0.005947382356229158, + -0.3381939092491292, + 0.19484569857135547, + -0.4353378899997517, + -0.0850732386086066, + -0.3123778896159747, + -0.5481334933918249, + 0.014403622371416458, + 0.26338003733112436, + 0.18520924957382523, + -0.2789866870771953, + 0.23075438978026697, + 0.016061717899407135, + -0.5399518764654597, + -0.10202806369968481, + -0.005720177376899671, + -0.4966143526716611, + 0.04558511720508274, + -0.055881112266447874, + 0.18070858379008947, + -0.243120740376576, + -0.46654758141543634, + -0.3809026892658526, + 0.2681128577143159, + 0.12971376387259692, + -0.22035497866395015, + 0.21628491645474435, + -0.3937140388602313, + 0.29340143854925116, + 0.13001545792038482, + -0.33415002786798087, + -0.3545271911374706, + -0.2208566641085732, + 0.09518341922383633, + -0.14430127827648742, + 0.2777870006677967, + 0.07614207580049792, + -0.009788980288426674, + -0.21925183786189512, + 0.16433288006393898, + -0.02505427552186623, + -0.5173642588734564, + -0.43804556303287623, + 0.27447220443936127, + 0.16579095741446803, + -0.14627345239694767, + 0.25966335121654716, + 0.31103217672015404, + -0.11562931269828464, + -0.17374225953323902, + 0.16017644163373057, + -0.29386012422462554, + -0.04700882942485274, + -0.475406045575919, + -0.0861991064731159, + 0.2127571850365203, + -0.385003096650097, + 0.07972027323172792, + -0.12871254249913427, + -0.0026398035897032823, + 0.26462737985230256, + 0.2004682106944684, + -0.027020926878708162, + -0.5411359490672385, + -0.042537380717559414, + -0.5442059869688534, + -0.11000561260979408, + -0.2939729597641183, + 0.03526598141500148, + 0.09203645473376776, + 0.062436560434793176, + 0.14340481948356543, + -0.3327265619839293, + 0.0746318301225698, + -0.505481323851333, + 0.13237508350789495, + -0.2460483070284767, + 0.20099637415894744, + -0.23386247365548868, + -0.5317693293725291, + -0.11205751879714593, + 0.11227759765243384, + -0.20218325600231363, + -0.4567042392100063, + -0.3585676598146613, + -0.4826928022929059, + -0.1360469443810038, + -0.3936112045852943, + 0.24824635736024936, + -0.35180182801363635, + -0.24194404513123396, + -0.5458986256924425, + 0.2821303415730876, + -0.03721938497299593, + -0.08193849334935055, + 0.25899508333447374, + -0.5400401428053989, + -0.4332625180349224, + -0.28176212600665046, + 0.15555560192592366, + 0.044945075597131456, + 0.16545822973992197, + -0.2172629097654708, + 0.12468062962878157, + 0.08981734231925986, + 0.28550414527712753, + -0.009592977511525103, + -0.08215520203768217, + -0.19839283128439217, + -0.03813441536829787, + 0.2174680922075497, + -0.08655061996891172, + 0.04542487674841866, + -0.42488847466329455, + 0.12890112402350506, + -0.5483009206496554, + -0.021141416250266443, + -0.007020842361695201, + -0.3212729978544658, + -0.22734750333906512, + -0.13618846644762983, + -0.19494629657903634, + -0.1823040985174465, + -0.4047021614930527, + -0.03401530168412459, + -0.00948769585115039, + 0.11374138675404344, + 0.044410175278078445, + -0.3738309926147075, + -0.23382525750421268, + 0.30507554595916775, + -0.28834271905485237, + -0.4857062000556884, + -0.4562432521537243, + 0.22479210234688507, + -0.4707214226617907, + -0.3283549301761604, + 0.20306216047996628, + -0.20792144180268174, + 0.30018503795933715, + -0.26808993583057444, + 0.22940142969472233, + 0.2624421684789373, + 0.19850414020886764, + 0.015060620364561683, + 0.11289653276404255, + 0.06100597027636345, + 0.3172093907888661, + -0.2745566800782283, + -0.03660710049742655, + -0.04303313515987106, + -0.004755992505385276, + -0.22470992810382268, + 0.21414279827248728, + -0.23549478598058005, + 0.11511885960775414, + -0.15549324354004668, + 0.11442399128462954, + -0.4091471069484407, + 0.2843532172002835, + 0.008519357599662492, + -0.41844628752710517, + 0.16762005174261707, + -0.011954661252641552, + 0.13780231971300672, + -0.29108703933355157, + -0.5406882005591049, + -0.46580207828460873, + -0.20188703006036762, + 0.14192529524586162, + -0.3354371968365327, + 0.008357788321777804, + -0.06826565247455235, + -0.557152758068432, + 0.14163430867836158, + -0.5514136140294529, + -0.430709151421826, + -0.27451347784487523, + -0.12658546103840423, + -0.06798722612198171, + -0.4124242778142451, + -0.36604567202236815, + -0.3242592425174513, + -0.12489686501251529, + -0.22148081567431882, + 0.04673149372828167, + 0.12922687154503332, + -0.2635798127599651, + -0.480184954429308, + 0.3193054079869049, + 0.0434145682328303, + -0.2626138494640247, + -0.47212362391415924, + -0.2951687597310474, + 0.18764404055377604, + -0.10673539918534075, + 0.11989622621213591, + -0.45686553990877155, + -0.2845638949208605, + -0.519516414760641, + 0.14411700385038673, + -0.5207154667758737, + -0.14021950773265507, + -0.21618502232016945, + -0.48932031225504213, + -0.14490535353911677, + -0.3035421158391066, + -0.3188792972821039, + 0.11785127038344123, + 0.22997368516284655, + -0.11672092936347384, + -0.25086765276884054, + -0.4667531985418675, + 0.16745573593747087, + -0.3968779912682585, + 0.20022562759132045, + -0.05591436964747465, + -0.42266822739705634, + -0.3109207941298007, + 0.06370911519146616, + -0.2897798896288354, + 0.013742416542256719, + -0.42695527699600894, + -0.26857667869798835, + -0.13883166676665154, + -0.22653344304557, + -0.3719974335972732, + -0.15268839736616074, + 0.2969615148129232, + -0.2682802351886277, + -0.26692260832646486, + -0.2647624266768782, + -0.5437371353025393, + 0.025021180727972103, + -0.5538839787670344, + -0.12353979037941559, + -0.5491801536006361, + 0.1475579983818076, + -0.004520415491028995, + -0.08822855704291627, + 0.044579700001466716, + -0.28692367702351457, + -0.15260058120800685, + 0.191765551964987, + -0.022541499169476564, + -0.0968180044650499, + -0.28781918866867284, + -0.01006085980521787, + 0.11393637925860722, + -0.4725685230043419, + 0.3009305877064792, + -0.15159544119370139, + -0.5438583484875015, + -0.492462795571676, + -0.4470274656553325, + -0.4864479707701822, + -0.2656698599189881, + 0.28973935751684277, + -0.26837804878742993, + -0.3689055802277702, + -0.09238808850329416, + 0.03291251343006085, + -0.11862348774038928, + -0.2473101403678052, + 0.19386110709602866, + 0.13578073667636636, + -0.15315254865201078, + -0.14513409931843835, + 0.29105775865502825, + -0.45767627138123046, + 0.05784643780644294, + -0.028587376897697303, + -0.3499831721532928, + -0.25770519444144946, + -0.2360765093180925, + 0.07072891298986017, + -0.19302053470504765, + 0.11177570778729629, + 0.2818378934274144, + 0.21719938824581897, + 0.19496652877177434, + -0.29135957443975496, + -0.27211385929491716, + 0.20579847252463956, + 0.014435383093822307, + -0.4915601122553409, + -0.20738695800919216, + 0.030356988760285475, + 0.3024541996169716, + 0.24747342598033117, + -0.516738753580773, + 0.20344079984388408, + 0.14043924722143397, + -0.20507031108672746, + -0.26290936961878764, + -0.43694786457582874, + 0.1771094532420261, + -0.1722170453949784, + -0.41288159137285496, + 0.1402239295073594, + -0.38489495872999857, + 0.20517822769999772, + -0.1899740581322551, + -0.3988279269139593, + -0.2750535145061923, + 0.20491538210823457, + -0.314944361731795, + -0.17912654632134983, + 0.09867849284714325, + 0.1026241313456483, + -0.25325623526996793, + 0.25146605198169103, + -0.35494075614055465, + -0.16370442022524995, + -0.5438875272713599, + -0.38769583469914937, + -0.33640240933116855, + 0.30331275858715334, + 0.08051971608895758, + 0.23950853388194615, + 0.2785242585836596, + -0.033996737717092995, + -0.4992048284995884, + -0.4771554590341583, + 0.05358164916147001, + -0.3725357622562069, + -0.29128183120885953, + 0.07769423128295239, + -0.5578757233621233, + -0.06664487453668566, + 0.08951406634768955, + 0.11846662772042738, + -0.3219189502741451, + -0.3533428174391513, + 0.2841598580843534, + 0.09454768928967272, + -0.07220086540353993, + 0.1840549903355172, + 0.23866100760983655, + -0.044854509413939425, + -0.24093519277414832, + -0.47806788911538445, + 0.05437397278302847, + 0.11014176755739169, + 0.06901952960548952, + -0.07172180278979445, + 0.3165863664855433, + -0.08385107971302852, + 0.19040201602574502, + 0.16958002744206147, + -0.20281321355038961, + 0.15961758492688516, + -0.2723300887092337, + -0.4185323893625071, + 0.11537952214553548, + 0.10483934048384758, + -0.47393461907250445, + -0.4830203080593717, + -0.017442373236849718, + -0.5416632237627897, + -0.20943462510591637, + -0.2972005916998788, + -0.3134014507329055, + -0.13780229166819674, + 0.27261178915039974, + -0.3422605139278926, + 0.02023370167520866, + -0.33457861290372126, + 0.23783689344515735, + 0.2283784762497213, + -0.2324929486587159, + 0.2880656010654161, + -0.44014504178420355, + -0.2354645202042932, + -0.14800159541875862, + 0.30437255311922917, + 0.2039398175047411, + -0.21820503180283213, + -0.2808497718941932, + -0.09513645797608827, + -0.5459315170894545, + 0.21511128064621998, + -0.28780680573487444, + -0.5329112085163217, + 0.073249464212081, + -0.04017634336050402, + 0.1128448612860633, + 0.1660210110698438, + -0.31195543000108583, + 0.23166304564985574, + -0.5470908109983984, + 0.28270734319574786, + -0.517657089676595, + -0.2024080402608811, + 0.09697199820985836, + -0.1474179876627803, + -0.417560054510556, + -0.13621152331401343, + -0.1841887353906877, + -0.26239821482412673, + -0.15147954745023007, + -0.12011521197568792, + -0.4348291816046552, + 0.29123330322662444, + -0.48394620719381654, + -0.2883380067455289, + 0.29255965848160803, + 0.15625855787969145, + 0.2631154248619264, + -0.35764878768177943, + 0.31697923052756627, + 0.15993747859423646, + -0.3866643185220987, + 0.17847064390552414, + -0.18899920192296032, + -0.5016911539032664, + -0.3521003389009735, + -0.15340830118974352, + 0.14254902705373862, + 0.14894459296567908, + 0.03127042399932789, + -0.3596824521325828, + -0.204013399031452, + -0.26507141720398464, + 0.25588026092716853, + -0.08101976563593627, + -0.3416435403550287, + -0.23937150083555553, + -0.18603595722157046, + 0.023728245470781784, + -0.3291717741875467, + 0.2761978879446485, + -0.1377958333536834, + -0.39979160979012973, + -0.34574324159565806, + -0.41634446704242295, + -0.4592943009017524, + -0.11616796617901343, + -0.21679832184434727, + -0.5496491697354352, + 0.28972961169608624, + -0.5006208336067144, + -0.10366597081712559, + -0.40077605156499574, + 0.10797176487172433, + 0.2477924306988193, + -0.1959128641173239, + -0.09493030501784472, + -0.060964648209367256, + -0.15164439338259872, + 0.2850900721769909, + 0.05480580097464882, + -0.1986870983077192, + 0.23847452751595066, + -0.08708210892849011, + -0.45371675830094804, + -0.317850943677945, + -0.20340273156194533, + 0.09293215937466093, + -0.21653557611129753, + -0.2928184306007654, + -0.12815953629627058, + -0.07877302899032396, + 0.0060151165036965715, + -0.42226179969174515, + 0.2722197678340541, + 0.23633157325846543, + -0.2230021283122558, + -0.28425854032954445, + 0.2991198580826564, + 0.3181038909485122, + -0.20032446954259098, + 0.0949724573466385, + -0.19624269935795324, + 0.2592835427762822, + -0.37871012001497373, + 0.10555516137109144, + 0.2827624037575446, + 0.2078504791381156, + 0.1606807148426389, + 0.05895967876665542, + -0.0031680945545921047, + -0.19534966135946225, + -0.33996046844257133, + -0.4967688160788958, + -0.48158769396821466, + -0.45977442048832173, + 0.2599887313737368, + -0.05307484254270234, + -0.07990703804237809, + -0.28806424453704543, + -0.43398397713990217, + -0.038538010703897396, + 0.10941025748696187, + -0.045524254403607634, + 0.10620521344238898, + 0.23888853782960673, + -0.26189942725702686, + -0.44369631246449137, + 0.04204427921226117, + 0.25828716533488316, + 0.02344180521782857, + 0.30232232971084927, + 0.2714657569873258, + 0.25885854738420155, + -0.4317746429647147, + -0.5214566197328206, + -0.18383759630899882, + -0.49811004451822266, + -0.1527194780179429, + -0.5453850010787856, + -0.5374280044067732, + 0.08943832773579075, + 0.17706977803253798, + 0.12078859084704507, + 0.18071825003297093, + 0.09336061678087182, + -0.5093260966743246, + 4.531129047635751E-5, + -0.30082556017034834, + 0.23418719000749033, + -0.18366293387879168, + 0.3049332045298332, + -0.1517564413048928, + 0.12089449019887755, + -0.25485032662401436, + -0.4815285451540234, + -0.005827436795668772, + -0.3601711868682415, + 0.15832536155635657, + -0.19225413849072254, + 0.11928379325021266, + -0.2557618288584662, + -0.47895226935054036, + 0.12079317874657869, + -0.5486077324279779, + 0.14911293723439978, + 0.18050375987201928, + -0.2585795237761485, + -0.2928372692377276, + -0.1949500360155476, + -0.2315845638658695, + 0.21966842734607572, + 0.3125415973214539, + -0.48918639273942965, + -0.2438605803194177, + -0.5373574557268785, + -0.42096304098113035, + -0.48162694584234883, + -0.06778580671970647, + -0.019339121269753012, + -0.07655596283892313, + -0.5570380149935515, + -0.5177431141409524, + 0.0032080101446406717, + -0.04013310585640906, + -0.3682997310632157, + -0.09766981254469137, + -0.04471968969214124, + -0.08017754019318457, + 0.27268598010471956, + -0.48243065168627774, + 0.29484705352378215, + -0.43988919913522234, + 6.000334468049262E-4, + -0.01026899230157341, + -0.2047681682644369, + -0.5054968467559465, + -0.13026673696357766, + -0.17680185192164832, + -0.5240299659979628, + 0.04534400970533692, + -0.48214841481854326, + 0.29203703933422465, + 0.19054157313386488, + -0.31384877766020824, + 0.2742522465071242, + -0.26072695615783087, + -0.3570199069972172, + -0.16403730868809296, + -0.15120345777078958, + -0.16577696586921964, + -0.12249185036402449, + -0.24332843375832164, + 0.19955754370163137, + 0.20565232230375696, + -0.09378626207452362, + 0.32006729585760296, + -0.02132624838770769, + 0.27705066565918424, + -0.27395915396186704, + -0.025470271261353372, + -0.10363813088123319, + -0.029749597639713632, + -0.4639491885005627, + 0.29245344364266024, + 0.05502318584006982, + -0.4858309044953764, + 0.0725679788734146, + -0.030704499681003194, + 0.176058268903865, + 0.18230468590068227, + -0.05514955695356405, + -0.1451112879600565, + -0.3817541871489202, + 0.09913955235277228, + -0.4997591409208556, + 0.11861076022680106, + -0.39693728233799974, + -0.08164227704695015, + -0.0036543187811445277, + 0.06136879626189129, + -0.04463237371661921, + 0.20343140840940555, + -0.13675960206733956, + -0.29314145550000975, + -0.2623547698301337, + 0.3158908323755706, + 0.29602808309240847, + -0.19106818168821044, + 0.11386680571344376, + -0.016712935165135168, + -0.48276504632907746, + -0.04902842232108273, + -0.5192936855397541, + -0.35618657208493176, + -0.3949613725753207, + 0.24594150820639749, + 0.11081724618045374, + -0.2666641337853787, + -0.030819038143866218, + 0.13047380994704005, + -0.2757307439738276, + 0.14732241345141694, + -0.048428228095589776, + -0.2666512434631738, + -0.503297087471769, + -0.02746680080545949, + 0.1211426505770562, + 0.14616458461612136, + -0.5302501677641891, + -0.043297025791848576, + 0.021351907140995885, + -0.4465624566695596, + -0.4910254359894402, + -0.33706632442310086, + -0.2388526663244398, + -0.4711238772657089, + -0.37821727066796174, + -0.5529759216494881, + -0.25762633698941495, + -0.23596645501141378, + 0.2173086411795977, + -0.34962594108310074, + 0.15747274388186294, + 0.10189250031026775, + -0.12020483368600082, + -0.16619691133207098, + -0.2563227051654043, + -0.44289179179441107, + -0.11359852735849774, + 0.283916825414509, + 0.2971010832003399, + -0.4930625768733345, + -0.2891350870644755, + 0.1355754532245943, + -0.20360307079791023, + -0.21896873890393692, + 0.24670516199440684, + -0.4976836696548668, + 0.07876630142935048, + -0.3459380639010389, + -0.25497656010829883, + 0.09508415009098792, + 0.2843311318057804, + -0.24350642065140293, + 0.14497348583284797, + -0.3063938846356634, + -0.029569094802013973, + 0.2580083224287718, + -0.5040161816255984, + -0.41505451629923784, + -0.35530817142738447, + -0.39247556231301606, + -0.2958626262681478, + 0.031490667092864744, + -0.18615757920389864, + 0.18054547971469725, + 0.15606903853915388, + -0.38613585489970403, + -0.23026702204172222, + 0.26793015361603323, + -0.45336757470079236, + 0.20975590512417486, + -0.5377727893523405, + -0.24994075430432366, + 0.11487021050625867, + -0.29196370582056075, + -0.537415452398828, + -0.09449970134288377, + -0.2468896570937661, + -0.05157105436127507, + -0.1552267591658752, + 0.23343770254661333, + -0.3009769976034521, + 0.23314580301254206, + 0.316943957816597, + -0.3677223555508472, + -0.41407666018693057, + 0.2510288347445676, + 0.2803553598345032, + 0.2981272817132997, + 0.04084744667433293, + -0.48267224986507196, + -0.0533843215088623, + 0.2627491752173198, + -0.422372762233439, + -0.27119261432626784, + -0.5432490513713819, + 0.15424408410523882, + -0.011694763832993949, + -0.13488499363868994, + 0.04500628939326745, + 0.1565143971674815, + 0.02234772992488876, + 0.2479493861414005, + -0.3952467151229049, + -0.050546682487293104, + -0.5391935061717593, + -0.35600965085032393, + -0.3391543977918434, + -0.18108390386891315, + -0.09138449311024932, + -0.08372562565227604, + -0.5033301094499862, + -0.4007512878706162, + -0.43275342333485284, + 0.13223923098993207, + -0.09012232594169095, + -0.469151398843462, + -0.1930620731063754, + 0.25734912100963425, + -0.11718500700836487, + -0.17056854996576715, + -0.39130689247268213, + -0.39440474782059076, + -0.48099945388667137, + -0.1770930582107058, + -0.2411583560490605, + 0.3104963956343929, + 0.047960504794115066, + -0.49885464052887263, + 0.18782467718291407, + 0.2294953160129528, + -0.4054042326724141, + 0.02289557040109169, + -0.21362843603214637, + -0.3157376644106723, + -0.028094683357883787, + -0.1742732092303661, + -0.386052678039825, + -0.11626050375370206, + -0.09078939299588568, + 0.2498752181863182, + -0.34714229620169107, + 0.2005998567865206, + 0.13800702252295594, + 0.14971877624161067, + -0.1191620429806532, + 0.016479993689645367, + 0.11507270356732147, + -0.1822450800698031, + -0.36030089453010883, + -0.057400304690092274, + 0.06351385433966139, + -0.41802460839968575, + -0.551346971750351, + -0.05212209706446369, + -0.19979234411016406, + 0.26542233831288264, + -0.4682894520847779, + 0.22516937216307653, + -0.18205529921892033, + -0.36055318924197416, + -0.3243549481376561, + -0.20066356524744638, + -0.337129648848759, + -0.35736135537167424, + 0.05206019690915242, + 0.1770801077563745, + 0.1989153091627026, + -0.10977803645863132, + -0.2904041206170612, + 0.14563451385305248, + -0.5232186339360484, + 0.02629344724257998, + 0.2356336869483845, + -0.49168177439946303, + 0.011895400303228776, + 0.2351965572225555, + -0.5179810126792017, + -0.3585953517629589, + 0.053320168301218995, + -0.4579543903254919, + 0.020455016743346488, + -0.07686016224171249, + 0.21446838325102213, + 0.07621736191710049, + 0.02903203706257651, + -0.39833768977737016, + -0.1002643552610587, + 0.07757562216824432, + 0.31094916590080235, + -0.18262162268238252, + -0.404193555470137, + 0.09977703716157638, + 0.07201525200407088, + -0.014943945912369916, + 0.20137669475929576, + -0.06787296437128298, + -0.05703231926132846, + -0.5355502902389487, + -0.47143938777897587, + -0.08122066803902989, + 0.2647576899589199, + 0.17574879722838876, + 0.08415742018133676, + -0.41576841116579233, + -0.439537861381035, + 0.18526994204414737, + -0.052557625646117434, + -0.12961739650612836, + 0.09278835820580056, + 0.31985331522515204, + -0.5281938208269424, + 0.061062032970773394, + -0.5113993789134934, + 0.28909857447004705, + -0.03197992852962461, + 0.15344817445286796, + -0.03293440189684582, + 0.18057177568208516, + -0.04902511978107382, + -0.37614308016567893, + -0.15003571268334404, + 0.15125068847156542, + -0.1570340239033765, + -0.037737195397582246, + -0.23842986364473845, + -0.430244584541121, + -0.46597344263940166, + -0.29688859352720676, + -0.31294384949129644, + 0.060128936108451936, + -0.2806557842849447, + -0.19052070170342772, + 0.17418504636329468, + -0.33533793819506785, + 0.1569961115427334, + -0.16061290427196562, + -0.4031953471906732, + -0.10241949013441604, + 0.11937672882351147, + 0.2833172889013511, + -0.3842790066611216, + 0.16213538321065668, + -0.17995356029696902, + -0.01889155165988321, + 0.13437374633512988, + -0.47996284418772006, + 0.05059056751871949, + 0.2819807250749362, + 0.14842825713891072, + -0.2535557660615947, + 0.2074881328572803, + -0.09936381704749314, + -0.4312148071439521, + -0.30692795975738946, + 0.12379833142427998, + -0.08495670428917473, + 0.04675831630645233, + -0.05785868387879922, + 0.20358276961875776, + -0.14128867773803833, + -0.36439807597330065, + 0.1446230022745243, + -0.26097947625214446, + 0.2097303716116491, + -0.29580461162628097, + 0.09736983788288234, + -0.2258167394888746, + -0.07952760233261114, + -0.13434059423899047, + 0.047610886685918063, + -0.2927322657310315, + 0.16466489522897576, + -0.19894414175956077, + -0.230286421800097, + 0.07864110057790397, + -0.1034423727257453, + -0.3749111308591566, + 0.11849986473313179, + -0.06686980665934239, + -0.24326866050193485, + 0.18304595636036503, + 0.26203261108481346, + -0.15286873171306026, + -0.45816915472097663, + -0.11852224352000734, + -0.5219819577000515, + 0.17379229761241466, + -0.31908554535176603, + -0.09928118570213612, + -0.009359403979378955, + -0.42141766594215607, + 0.15290528038509854, + -0.25618268062675137, + -0.513272429599717, + -0.1114732733895395, + -0.2759135670885761, + -0.10727939474369996, + -0.35429576106376737, + -0.42782410180161534, + -0.3705079014944683, + -0.480638555389997, + 0.017557041008003704, + -0.23171366141994043, + 0.20742763359165017, + -0.16616679251213906, + -0.30248687040301364, + -0.13606437796052206, + 0.11738949300988433, + -0.21174525358909613, + 0.04747006548605881, + 0.035948873169356355, + -0.017354461127040977, + 0.047497251446131594, + 0.06315915027957508, + 0.14785157426997864, + -0.501936730933181, + 0.1283599014620207, + 0.1157778198143401, + 0.1057547451267461, + -0.48781539360131576, + -0.14680745886161212, + -0.2835319061670345, + -0.43500704878922264, + -0.40003901531606767, + -0.2060987731425643, + -0.05635982195855138, + 0.31194232808568956, + -0.38892696350001177, + 0.17274228281819226, + 0.17291257836808038, + 0.2091961855910327, + -0.3803693474626942, + -0.32543397908313887, + 0.17355068195314716, + -0.42019386201154985, + -0.21423844680209897, + -0.18710650004580848, + -0.3029925118516206, + 0.07368415934503403, + -0.5498019492214257, + 0.13921248052882906, + -0.11457494805267687, + -0.336798479975004, + 0.09110349449626431, + -0.09201355678890272, + 0.2747450642515368, + -0.16576357010471676, + -0.036895911685465355, + -0.40159579310215404, + -0.42547800126126223, + -0.22652485957204543, + -0.03270053367809156, + -0.41379011088457074, + 0.08085498068587593, + -0.21654133632102163, + -0.3143823157632485, + -0.3891672884912538, + -0.015897135120746864, + -0.02725497500116736, + -0.4439764135033165, + -0.17214680854601921, + 0.06388450203426699, + 0.21490667584232115, + -0.09957370680854338, + -0.4066876483705281, + -0.5318945592914471, + 0.12978526956976666, + 0.09579970938203153, + 0.2815921384824841, + -0.11578421581061682, + -0.1111034105280741, + -0.02115080194449237, + 0.06276541632389188, + -0.4762688046364132, + -0.38552880103939213, + 0.14178963543620937, + -0.023919083220879767, + -0.3706757919132241, + -0.06879297614023394, + -0.411350589221101, + -0.4890681157511164, + -0.07096634168667981, + 0.1285372506779452, + -0.29256442455044074, + -0.23329122179282635, + -0.3533655240870843, + 0.15113461954371932, + 0.033566352792570586, + -0.28047023518270137, + -0.3837878847941978, + 0.18197858594142402, + -0.5298419442778023, + -0.45301760549897896, + 0.20685979536486032, + 0.03297519521833414, + 0.2689705725387449, + -0.3730605976273741, + -0.5196595916502829, + -0.26354608839254173, + -0.25663306449003437, + 0.018199634383289198, + -0.3730087240067243, + 0.18669701418488227, + -0.29732450723988285, + -0.05099635358665, + 0.06954224990364866, + -0.5556991882993212, + -0.17313956062245278, + -0.1272025915980805, + 0.025200007519529444, + 0.10771085869651875, + -0.3884694236594309, + -0.48871752622568804, + -0.1686166546321582, + 0.08493539859192856, + -0.5201525555637331, + 0.2544668794551499, + 0.3036784515058889, + 0.012495378768293763, + 0.23195558274961514, + -0.030704783871677965, + -0.39073612926298096, + 0.14594506633457638, + -0.058251099740406764, + 0.12840556761165967, + -0.03234804756391496, + 0.1812073597886663, + -0.37800629036521616, + 0.2027589274305024, + 0.16657263886899465, + -0.28506841368990504, + -0.1664428698109119, + 0.14051945011192324, + 0.19894256187728554, + -0.14617664831594918, + -0.23664079071336025, + 0.25943691956295356, + -0.318823119010449, + -0.008797070079808345, + -0.510049933206354, + -0.4479448139513439, + 0.19458261389063947, + 0.2284140754884456, + -0.45725717051589176, + 0.0606640695642352, + -0.4205377014006062, + 0.04063390732566485, + -0.04527291393313959, + -0.2736419939966379, + -0.2356419192807086, + -0.09296237797393109, + -0.07858954577371186, + -0.15703101899888544, + -0.33406335808285137, + -0.4242302236223642, + -0.04834099067028719, + 0.3023714103878723, + 0.11048217840549024, + 0.24095439057196832, + -0.33602201436790713, + -0.19592024289144128, + -0.34997502353468224, + -0.14726123111038653, + 0.31872388916844885, + 0.2733406274953356, + 0.11357598035529137, + -0.35843898454499157, + -0.40412624303531985, + -0.43956186465342806, + -0.35397528479247325, + -0.4955809891484949, + 0.23525361841504133, + -0.5336764143382922, + -0.32110433447626907, + 0.25463886847148876, + 0.21856591886781107, + -0.03864468979384894, + 0.2681936650844653, + 0.235704305010091, + 0.26714442079052614, + 0.0888933052371601, + -0.030642824494499843, + -0.34743491788583547, + -0.18902206315681458, + -0.5311441986931759, + 0.04042860212169541, + 0.11541541770529706, + -0.04382886137058839, + 0.054217494621499385, + -0.4554897988176617, + -0.18257785381736374, + 0.09318475730581344, + 0.016937232178351858, + 0.19778178538323032, + 0.14991477928531394, + 0.06810597379092787, + -0.3564148451495994, + 0.10254118749553331, + 0.05929319439614722, + 0.13049339576201613, + -0.39119135206213007, + -0.23553542259662769, + 0.2034172785268774, + -0.4655398507681707, + 0.20778459726852916, + 0.28893028532248777, + -0.10512237846112171, + -0.3952679783821944, + -0.45896628385974125, + 0.060094649583873894, + 0.16112523720967808, + -0.16707717751373186, + -0.2489914420694691, + -0.22877984491579623, + -0.10525949019295516, + -0.08952715744297307, + 0.03162017253628868, + -0.5340263350614788, + 0.008109163497973193, + 0.1845737387447839, + -0.4284131563114456, + 0.28899504314322777, + -0.15340794007941272, + -0.1549228744892896, + -0.48479188306761445, + 0.017515839494207652, + 0.18473372523414044, + -0.17817560180800113, + 0.06699524097045617, + -0.14942308452019692, + -0.1103261791297992, + 0.031990319690550995, + -0.5490529685875273, + -0.1117411461617479, + -0.49577578198696115, + -0.5268055516829402, + 0.21560429651336954, + -0.1096202339188781, + -0.1337320687603566, + -0.09710235324002259, + -0.29092193608874806, + -0.03601864222713658, + -0.34115258923073366, + 0.12380783514108151, + -0.4223029127622213, + 0.06746506985552458, + 0.10696516064398787, + -0.15058052885537582, + -0.3631992429910472, + 0.002908843876274325, + -0.5035298352347428, + -0.5318065555196861, + -0.3847458117389193, + -0.25073699064778593, + -0.07605950975058229, + 0.08305211571775384, + 0.29053082765730187, + -0.12423588311180411, + 0.2828816610546734, + -0.266817916070154, + -0.0070430781601512615, + 0.14933386886713929, + -0.4129944551273053, + -0.3079391257554661, + 0.3068417991662826, + -0.3991534959927291, + -0.03612655665383102, + -0.46075957260188966, + -0.29043516093527655, + -0.23545901325547736, + -0.030505536737911343, + -0.36477776401707906, + -0.4861019220220133, + 0.2186033324801383, + -0.5206847253666874, + -0.2729487345477392, + -0.4119210671976738, + 0.21812620545866712, + -0.018616275901243262, + -0.208232203697162, + 0.11778584237346645, + 0.3163121075535067, + 0.02108950448364877, + -0.4445132844262737, + 0.2381478647598424, + -0.10604013991524858, + -0.4099322188947626, + -0.11941791767135912, + -0.19685913552357837, + -0.4943092114359048, + -0.09958410749112778, + -0.11039944170985072, + -0.5058395738764752, + 0.09792311489011529, + -0.33064679388133367, + -0.045970200285772034, + 0.013761762268814537, + -0.40113778615837414, + -0.26916167648367983, + -0.2714356769804465, + 0.03315678092145913, + -0.46288007497961503, + 0.03307920615645754, + 0.19308757103288854, + -0.023721849149378027, + -0.181192695494379, + -0.5086460382019501, + 0.16798215705469566, + -0.08385912396355971, + 0.17958030426313065, + -0.20560929198982747, + 0.08163033880673098, + 0.02773473766518053, + -0.2199216246447374, + 0.11017193325523311, + 0.2522998984538556, + 0.0651373214386527, + -0.43437276550137216, + -0.005111266017855054, + -0.334448307737201, + -0.2308088300963615, + -0.6026924268590017, + -0.005190706138323953, + -0.3227036494401482, + 0.11580678299223923, + -0.4256699047746152, + -0.36249113340203415, + -0.4789682910855698, + -0.023360972273397507, + -0.4028887542163954, + -0.1664409052027368, + -0.44090256160067076, + -0.44412643785867995, + -0.12179709860599586, + 0.03003684741681234, + -0.5895901997857975, + -0.2881291089293445, + -0.5144229256800246, + -0.3447170557340809, + -0.4213171989080437, + -0.5424058278104219, + -0.585116059246504, + 0.08720577253477257, + -0.13196250613492033, + -0.5720761474503353, + 0.013615324566599862, + -0.3086947929251241, + 0.03245373668863216, + 0.07357258551379386, + -0.0023836450763556893, + -0.4441251901838268, + 0.0768129119465647, + -0.43170514206451926, + -0.6419466438543554, + -0.2812082389009253, + -0.04574898438435071, + 0.06793054617128391, + -0.178574681660931, + -0.1507011318478214, + -0.33938055930181527, + -0.17739377977190202, + -0.02101099019285635, + -0.3535531715694571, + -0.6453286299732565, + -0.20042696241894642, + -0.4556524040962303, + -0.40706202452023243, + -0.38430416975663767, + -0.6372269055838472, + -0.07599275815899875, + -0.08075411927746745, + -0.5743606631466995, + -0.6164319877108126, + -0.05560753633274684, + -0.2037742155046532, + -0.3130169853129591, + -0.08894235205385637, + -0.22189975594619898, + -0.6107627208151849, + -0.13130386639303604, + -0.49240200706428405, + -0.3213136545253284, + -0.6047536998214852, + -0.5287860869564337, + -0.31488365966611703, + -0.10958570268042822, + -0.37905494122538247, + -0.4291928344641174, + -0.16502871053085605, + -0.08854899022514162, + -0.19660867788489111, + -0.5808593039530027, + -0.5896625206317714, + -0.10590349944984456, + -0.5419989901020837, + -0.18368265911492088, + -0.40205661112748464, + -0.28466117827623083, + -0.29826142833269037, + -0.23197440254480806, + -0.10500168136223986, + -0.5902087278486788, + -0.015255124865682146, + -0.48263776127848856, + -0.32593021456969695, + 0.06318393533902422, + -0.038711863900311005, + -0.44080064194061214, + -0.14435008662447935, + -0.17188190420074534, + -0.5526408303589537, + -0.16375708740144196, + -0.09093103624959387, + 0.09830211114661436, + -0.6039250037437699, + 0.08937852654649314, + -0.3964794523940304, + -0.6542600383201331, + -0.6425572837139588, + 0.003628074046863383, + -0.30729117600188494, + -0.0730344972743463, + -0.5005461004155785, + -0.43202594830094954, + -0.46280367255028904, + -0.5556490103810665, + -0.4813752499946051, + -0.10373134087785219, + -0.2210490803018233, + -0.5473660096116677, + -0.12339470610810266, + -0.5780987206875765, + -0.32940392400001195, + -0.24744685303288216, + -0.6276279654335989, + -0.577546006149786, + -0.6311519808148525, + -0.37805667537286597, + -0.39915943203112386, + -0.40485284205237304, + -0.37534730317900494, + -0.46083512851964503, + -0.57997896445252, + -0.18811471379219058, + -0.2612036131845849, + -0.013308321577108151, + -0.5306075420297673, + -0.49003915543801013, + -0.33365334776615685, + -0.2479358782168442, + 0.07768803870697705, + -0.03172221171929235, + -0.44962579604670927, + -0.23604858668114542, + -0.06773885257760781, + -0.6042959417597175, + -0.009923611801429422, + 0.06658949348997434, + 0.10413715433919102, + -0.31674050033735435, + -0.3283028810007334, + -0.6525263779573796, + -0.27624703202258283, + -0.06049949979946978, + -0.32551134738445897, + -0.28407472156957725, + -0.11380456051415477, + -0.4024008148915694, + -0.24198876065972613, + 0.08265621705240223, + 0.1202676952415096, + -0.3216134023349307, + -0.6388364101119921, + -0.2700119827500489, + -0.645982765748083, + -0.04845845032389873, + -0.5859298028543722, + -0.3959645437197545, + -0.43914215731860917, + -0.5023541765706173, + -0.028800520316338063, + -0.024118144328933222, + -0.07064156766499918, + -0.00872092316414863, + -0.5585188405249814, + 0.11349893510914366, + -0.5411253119822217, + -0.23198940874220153, + -0.3556382789022766, + -0.14574650430598202, + -0.1222102752105867, + -0.1305604960556329, + 0.07220059599464212, + -0.45784743423361307, + -0.06668307995330913, + -0.16090623846858298, + -0.16777226040906934, + -0.05526002733437996, + -0.3974311111363549, + -0.036593548817030364, + 0.03099674676648878, + -0.3678308860052181, + 0.0816212381533874, + -0.41755825039968997, + -0.4551889521983238, + -0.015506065397983382, + -0.5686462178807695, + 0.046650487796379925, + -0.00841742918647781, + 0.012574528517236838, + -0.16527418615600808, + -0.2096262868786034, + -0.42532794084033865, + -0.32670060766309317, + -0.11889502136762142, + -0.05740353877564863, + -0.18919393896076725, + -0.38790950854079315, + 0.11681548150533538, + 0.015607440371495529, + -0.5496871411408674, + -0.43169128243446864, + -0.4935692073657829, + -0.3677128680108731, + 0.04431017404968185, + -0.3061609001543733, + 0.1045265506473394, + 0.08358534091025782, + -0.18602149500186688, + -0.43251056738798627, + -0.6538446967601559, + 0.11023904106862448, + -0.36328898205364896, + -0.26500777905509426, + -0.05826681463655925, + -0.060036719856821796, + 0.10474737934713474, + -0.3482676581060117, + -0.22940474934462457, + -0.15427899469698503, + -0.20065990328436778, + -0.24502387107263973, + -0.5650371026595785, + 0.04659879101791575, + -0.12512415549793032, + -0.17045944401341379, + -0.43776823511016105, + -0.6228399737232229, + -0.44460045145337657, + -0.1174455592195578, + -0.5778880247793677, + 0.07260197359892528, + -0.08781497288045437, + 0.008492115270013034, + -0.17386280038915308, + -0.004599999612647898, + 0.03395433039769491, + -0.37170611904400586, + -0.526140110520721, + 0.06166299039541778, + -0.3718382639470537, + 0.09197375237717909, + -0.42557210223187236, + -0.5401628329147738, + -0.6030359011541634, + -0.47829203280734844, + -0.051398958644517045, + -0.3070277489140675, + -0.37250099022813876, + 0.07954863269139356, + -0.6635402232342693, + 0.11791388796733049, + -0.5028237494472932, + -0.3957577829435543, + -0.10242874040106331, + -0.3115857809579027, + 0.11309380436295724, + -0.030266066231571465, + -0.5043894833641986, + 0.043480282033169115, + -0.11324368702784693, + -0.3332570677147316, + -0.5056059757288387, + 0.08947184127155239, + -0.12038276112989665, + -0.6230294638491665, + -0.548854047100455, + 0.0052170269333233765, + 0.08737854097499131, + -0.11398454467930819, + -0.2877610794041485, + -0.03044649744760597, + -0.5622495151055371, + -0.13047107606655495, + -0.07745806242377318, + -0.4200040147479942, + -0.3513464294669507, + -0.48671803179504125, + -0.1375983291639924, + -0.09393807599271586, + -0.45950080862427045, + -0.003456102053839283, + 0.036130708089688546, + -0.08248411084968088, + -0.5412144344279602, + -0.5549177950643048, + -0.4503858894575679, + -0.6305711920361324, + -0.2735109387462456, + -0.6325158648345245, + -0.435198641398885, + -0.3919917743173209, + -0.4061721365295673, + -0.6355618919642926, + -0.0919826829917415, + -0.5278118969987778, + 0.01953080691449971, + -0.5838972633298153, + -0.5682998046120153, + -0.25420661959784463, + 0.02869651256265926, + -0.3790921850731956, + -0.25009228797257455, + -0.5855443941834146, + -0.46658460655455425, + -0.4203608711353093, + 0.10992421913473804, + -0.033605635429112324, + -0.6220390017361134, + -0.22748486708092214, + -0.41307540574050927, + -0.11530463109807265, + -0.653417086946047, + -0.5838714971216767, + -0.26493823376526504, + -0.03875828977950824, + -0.19382899250736524, + -0.17219140975753583, + 0.029287380230502924, + -0.6231938555731376, + -0.5141329217853423, + 0.0944324805147223, + 0.002686705644079135, + -0.47712815142336285, + -0.5121857466140318, + -0.019670715449254694, + 0.06780357319090013, + -0.4222665617179844, + 0.09236389486385577, + -0.5175586804038251, + -0.5262652859930887, + -0.32867518215792446, + -0.003989472885745027, + 0.024918991181954175, + -0.5763586539933063, + -0.587381791177418, + -0.3514460101324938, + -0.2122386181222755, + -0.418992646736565, + -0.25932929939825583, + -0.24699223257530112, + -0.06581900719685341, + -0.533833415966115, + 0.04118491083370823, + 0.04302898940360178, + -0.2950028716327236, + -0.2974924073613618, + -0.5217752265774818, + -0.33004973222589185, + -0.13843511318399004, + -0.5351722697940035, + 0.10601961015691697, + -0.3104803422064739, + -0.054790599026402265, + -0.22572951916828027, + -0.5031318157616551, + -0.44591042539944675, + -0.1897806741932947, + -0.4787413945904758, + -0.27674983258149793, + 0.12259273310639662, + 0.12304559238074164, + -0.08962334849215092, + -0.6132947910745737, + -0.4729352276992446, + 0.02845396705327896, + -0.40377751488963076, + -0.5181220231216446, + -0.013388765320207163, + -0.05841283565117272, + -0.1490072319562522, + -0.6494934640192035, + -0.6611778302687067, + -0.3190637012708257, + -0.06345546605694052, + -0.41037810268842917, + -0.301200909576346, + -0.13231942808482755, + -0.25153255438813243, + -0.3717661237451892, + -0.1700610556190872, + 0.0772436701417738, + -0.6200947911801554, + -0.11317718732025728, + -0.19490007353319266, + 0.008849889901141439, + -0.6501990645384728, + -0.12565401647540309, + -0.5692328442805361, + -0.19029658601022154, + -0.6563809242964708, + 0.04964142783258996, + -0.17390745367806348, + -0.49390339927940113, + -0.35150558857838554, + -0.06425087638980875, + -0.3604508457339325, + 0.0345713673127902, + -0.3417688742164273, + -0.32242053609387805, + -0.606778988723203, + 0.07322102527435348, + -0.5653385209121856, + -0.6393375713260508, + -0.5397213519805313, + -0.18153824683813596, + 0.09609083080204806, + -0.5171147709988683, + -0.10798925815517968, + -0.6049801814709558, + -0.12023933533441855, + -0.4115797711919392, + -0.15058446877380371, + -0.4384036753707836, + -0.4111957524322663, + -0.4803009964308441, + 0.05703965395577193, + -0.47837261323007974, + 0.09139774312103488, + -0.49392476059331564, + -0.04814512701994533, + -0.2186582554089791, + -0.08051633833374217, + -0.29260777995376036, + -0.355330309014048, + -0.4073642602278019, + -0.2935319502992784, + -0.5163463282850402, + -6.347684058188863E-4, + -0.4779388335337378, + -0.2937483993755685, + -0.07529613993075257, + -0.008225859038789252, + 0.0851994445127735, + -0.5817592573434441, + -0.3158955150145574, + -0.47573467689769056, + -0.18699042335240823, + -0.027728875527376462, + -0.3277777687607794, + -0.07524461952665995, + -0.4304611032610103, + -0.42752396043962543, + -0.26485639845871567, + 0.0994721536927492, + -0.34015773577335584, + -0.08091388292698964, + -0.28661136313439206, + -0.521557584906658, + -0.11776615577957095, + -0.2668287625755933, + -0.550978208767457, + -0.3444415775533549, + 0.06090092067449793, + -0.4341489680869147, + -0.6399272080752502, + -0.3298607458204584, + -0.4070878552260922, + -0.5120136739820477, + -0.09892351433452629, + -0.13445335667036784, + -0.2984008256730031, + -0.011765429323949972, + 0.11002460483960641, + 0.11715323706485758, + -0.3717526768908503, + -0.39455820256468577, + 0.04847388427222765, + 0.030574774116081116, + -0.011574574035896346, + -0.34849619376152474, + -0.5466430372110778, + 0.015125746806854301, + -0.28038672102558093, + -0.2964512777786784, + -0.6514851525099812, + -0.37493679068175917, + -0.25174702442688873, + -0.045963995760482046, + -0.5811471010970634, + -0.20723000944991937, + -0.23872900683214066, + -0.28438583546893853, + -0.5647071417721508, + -0.21178632208604597, + -0.1649588007065083, + -0.22247331647105062, + 0.05124472054216578, + -0.07512400418049425, + -0.049538720914168555, + -0.03858177640127225, + -0.5090431732773413, + 0.02027072799636065, + -0.2379127318971424, + -0.020339211542424684, + -0.4499742960922577, + -0.59648991414312, + -0.3154195056128612, + -0.09304641736203267, + -0.4992376503583372, + 0.08874206126995432, + -0.34936612258188127, + -0.4295395333812841, + -0.4113831219790521, + -0.2350324497439707, + -0.3214161909276456, + -0.06320130443112004, + -0.172773917650273, + -0.34275168320515603, + -0.49422032105810554, + -0.5722927908084585, + -0.6161592002753478, + -0.6103033866732924, + -0.09868581535223997, + 0.011980501101184204, + -0.17025836420931445, + -0.4398785088443529, + -0.3730017140629263, + -0.5112413195510934, + -0.2948163173049173, + -0.5070189233109058, + -0.47983057823011493, + -0.4330076459172953, + 0.0885535098955097, + -0.07949767397498908, + -0.4185536267177018, + -0.5612178584668377, + 0.016107378395652683, + -0.6606458941171731, + -0.5296895494400857, + -0.419104508182506, + -0.14165101778606037, + -0.21592143314483397, + -0.06288655086610928, + -0.12521368942287303, + -0.49284945383922274, + -0.25092509464050394, + 0.045985218843428766, + 0.06447773054715233, + -0.37946368738547576, + -0.05900154930666379, + -0.5712161147069678, + -0.041265921657906435, + -0.586125839338726, + -0.3562194394854067, + -0.22173240343991735, + -0.22793966971405039, + 0.1039296849540795, + -0.6579452706094513, + -0.3653902160506153, + -0.6040761172519276, + -0.05404383779395616, + -0.21615081295239053, + -0.2668281454838181, + 0.11483590425312673, + -0.17131712595211818, + -0.14832413785633614, + -0.4798490057260549, + -0.6072654333566597, + -0.42922806620970155, + -0.0658440550122461, + -0.5854935244059444, + 0.06801119508326725, + -0.5147393424988125, + -0.4934293476207793, + -0.39840670395135674, + -0.07386681325843458, + -0.26462131908414965, + -0.2804281732692469, + -0.18801164723363678, + -0.6362643427238671, + -0.5003187308924786, + -0.06766063238103381, + -0.12641108988305916, + -0.08850900780886051, + -0.22897949121477468, + -0.5140253360277296, + -0.38379085492906123, + -0.359871813724288, + -0.005932981384510927, + -0.10363789774468635, + -0.29820798266289433, + 0.04096431735140016, + -0.6419323032258567, + -0.3829241540506495, + -0.5444438960423946, + -0.2018211212340344, + -0.1832920369573794, + -0.4461202941795809, + -0.5332953846222412, + -0.1827937439545747, + -0.1632522555850373, + -0.6210887876415142, + -0.0899078669672857, + -0.15834381429085687, + -0.6046966965884112, + 0.0013680688516549688, + 0.00790800729172969, + -0.3924053665572555, + 0.10093500957273771, + -0.6581914734472409, + -0.20149925252422368, + -0.57616814812929, + -0.31755189240377635, + -0.32188609085156034, + 0.058792258182023494, + -0.03413181842012436, + -0.2539017072607666, + -0.5015281203200768, + -0.45802762537717967, + -0.6423632327450515, + -0.42253422012498854, + 0.023239859304730603, + -0.3646905926634347, + -0.055981014228404735, + -0.5203379947081641, + -0.4249570411615905, + -0.5354344006004161, + -0.13211412633844655, + -0.6449135964023847, + -0.15976369665379742, + 0.034245138844137046, + 0.04887723830484236, + -0.32008167713303143, + -0.15498092026893362, + -0.2578189715785877, + -0.5096070700716336, + -0.4014084056622924, + 0.055772246808155734, + -0.1137996265282053, + 0.026499084349639213, + -0.019727763928103048, + -0.5098829282929986, + -0.45777137824662023, + -0.1297724754829529, + -0.37682133701117293, + -0.26650305245567835, + -0.18770145743493782, + -0.2780731300808312, + -0.46546264461456643, + -0.16823369918570136, + -0.542923525995912, + -0.5374295042472396, + -0.24847192562571085, + -0.304023599311949, + -0.08734092578926633, + -0.05785684361512011, + -0.4460193763666154, + -0.4909769507269582, + -0.2444638209109477, + -0.5985335243000066, + -0.18096123889930688, + -0.3998026212421945, + -0.011965910819965342, + 0.01037105105149061, + -0.49030679951907463, + -0.2219052561950675, + -0.5955234046961184, + -0.2814237708251885, + -0.13948023615087757, + -0.5650289838374871, + -0.22957794872233667, + -0.36531314963617767, + -0.3317403826110018, + -0.2106256332317094, + -0.6312697198529951, + 0.006087754752979846, + 0.10762608933170026, + -0.07428344174824109, + -0.5164027520059801, + -0.655627860160379, + -0.3457087858428038, + -0.21030886499190438, + -0.5567264702162619, + -0.2556714518986484, + -0.6572695118165539, + -0.1490067814850209, + -0.1317584952078954, + -0.6552054084844315, + -0.21382213207436201, + -0.0626567936350525, + 0.09795311845232357, + -0.6413166918768083, + 0.01353832146461098, + -0.4730729941694356, + -0.014491009785799425, + -0.10174557017003016, + -0.5977710744236798, + -0.24606992465398642, + -0.4959481433114717, + -0.1617939513216664, + -0.06387194919659855, + 0.05669976094996987, + -0.050569547506729484, + 0.040549538731731616, + -0.6219804434016012, + -0.422349346537021, + -0.018107764704617724, + -0.030500577833464604, + -0.1644901063746667, + 0.016790109719513002, + -0.019366616915446166, + -0.14164691453066913, + -0.5497043082700489, + -0.16177488136050788, + -0.2796584287288173, + -0.3974608856289077, + 0.09186668405664866, + -0.09140646088916804, + -0.5620779085953825, + -0.5621013550200016, + -0.6263589792231218, + -0.45505832433428883, + -0.12229885678282437, + -0.35849009985639096, + -0.6115929969178476, + -0.3926743972225823, + -0.11325773794774874, + -0.6506961929990973, + -0.053587578372211286, + -0.6017127219916331, + -0.4555891420102256, + -0.06966246735550863, + -0.6120985202396859, + -0.17419317661392503, + -0.5646192895569155, + -0.3114235244823394, + -0.6132793214901164, + -0.02071879594962589, + 0.014232684191238243, + -0.3101435502812297, + -0.4662066971499118, + -0.5399621659708281, + -0.10274143862379115, + -0.3779544016671251, + -0.33082644827941576, + -0.18209456886903613, + 0.0663347546942008, + -0.250581035299323, + -0.08285730388539181, + -0.06951805271491296, + -0.06539732223207506, + -0.07450236513356723, + 0.01783456703473818, + 0.014403921098616435, + -0.5103375185406054, + -0.5588746988672425, + -0.42079625732678405, + -0.5948513285666672, + -0.4403837757815643, + -0.5602909412421521, + -0.06173939912360815, + -0.2436730226569997, + -0.6343823915160721, + -0.11128298022688021, + -0.21173509805254687, + -0.3880621294731675, + -0.5309859104389341, + -0.49925298797025575, + 0.016918959393016464, + -0.13353755350622087, + -0.029624905530200696, + -0.06121206126159251, + -0.17304205279078222, + -0.49778184912270285, + -0.37645476172062353, + -0.4229050412508276, + -0.24396957253266355, + -0.5303625395583881, + -0.23699401681169963, + -0.37042491965810737, + -0.4302979528518579, + -0.08066449227819861, + -0.6422413418368339, + -0.49288594767938093, + -0.39659678477561233, + 0.10397574361102213, + -0.01890066092237952, + -0.2736601617509152, + 0.009981163574357743, + -0.006614085013993742, + -0.008333870346970418, + -0.3020551729373681, + -0.6262043128776626, + 5.529068080585287E-4, + -0.26337471542348095, + -0.1922115099982506, + -0.37583810794100125, + -0.39719526443957814, + -0.08485357422713014, + -0.32092664013386724, + 0.027373551059699408, + 0.08054814433179958, + 0.08794694026009242, + -0.503420990794242, + -0.16506396673047524, + -0.2828741332809417, + -0.04368390041399883, + -0.5192830162217834, + 0.051430885262990333, + -0.3316763195744895, + -0.4917725735768884, + -0.08054217172973699, + -0.19625054709272083, + -0.21428371794084627, + -0.26482772767126694, + -0.5121235994538579, + -0.09682097071413953, + 0.05271713469020678, + -0.5553699988143344, + -0.09958957597391427, + -0.662478087061184, + -0.049843655710134604, + -0.6119501570473083, + -0.40916379857648233, + -0.2795490099131226, + 0.022270479742259486, + -0.27290713048554754, + -0.55212186982849, + -0.4121701257033197, + -0.030383529129365483, + 0.06709879024343923, + -0.1796025504153933, + -0.3503505137501676, + -0.3557706347802966, + -0.49023906280753926, + -0.17076151501058534, + -0.08395813874234626, + -0.6070312108903572, + -0.20878857285625113, + -0.3328739676937222, + -0.5049810543442916, + -0.5993945711438959, + 0.02474635253043278, + 0.04182145907221668, + 0.059049969643502065, + -0.45959461844741445, + -0.5807870000678932, + -0.5742757191498007, + -0.6318438436390036, + -0.5279720174229002, + -0.412908843404131, + -0.12550950599222255, + 0.009680503964538234, + -0.6100459464582989, + -0.5462855185640872, + -0.5045146801273843, + -0.5902727796531666, + -0.16761672279564405, + -0.23823776111539818, + -0.6242112601158604, + -0.18161595873502123, + 0.08366672149560084, + 0.07985504742649652, + -0.223965127917227, + -0.5151130289856722, + -0.5389344194557396, + -0.5418937669317027, + -0.36158347020483245, + 0.032916187912065964, + -0.3070450469336947, + -0.6486086816421309, + -0.4429172876854535, + 0.043934441883277886, + -0.3748228046723809, + 0.09633293908963514, + -0.2939831254351411, + -0.26846526144061394, + -0.5720809100774873, + -0.4221353460636512, + -0.5398456210613081, + 0.12188793720557767, + -0.27509170118483556, + -0.047791080939383335, + -0.23426480851715725, + -0.6562564399055177, + -0.5235390685089448, + -0.15649899200978135, + -0.33662448890428676, + -0.38006367753434817, + -0.5475766146245189, + -0.5182797580749596, + -0.5054597592070355, + -0.48049840223223383, + -0.40509714848353945, + -0.4162374038492503, + -0.02391980253571513, + 0.07842314516960969, + -0.443908223114204, + -0.08793391341788404, + 0.023692666526597517, + -0.4532562463741113, + -0.45707818134799344, + -0.6083240874118391, + -0.1158228680514567, + -0.5171425153578442, + -0.5756172368060803, + -0.62184982731546, + -0.1917624534553496, + 0.09394360688625958, + -0.07783028313770857, + -0.6588918215521283, + -0.0920602277070316, + -0.3313642112118209, + -0.14361651974805945, + -0.523787200333174, + -0.22614283476348068, + -0.19527291487636744, + -0.47312567243292636, + 0.04657460074937736, + -0.09518601590221076, + 0.018124735159303462, + -0.08147520025892419, + 0.04398788033773149, + -0.584950021403083, + -0.27150937996371066, + 0.05174968635695498, + -0.3187867122867031, + -0.0785580282911893, + -0.0489625691960599, + -0.09719912594278779, + -0.5155828756480468, + -0.3438405779431836, + -0.5859694697213778, + -0.06733449774121825, + -0.07768181841332822, + -0.18541188151994437, + -0.5180616857637939, + -0.1541990534885933, + -0.051684205226173674, + -0.5326729104330111, + -0.2560209839228974, + 0.025222751210753014, + -0.568277827351196, + 0.05242744983009151, + -0.14133730084115315, + -0.4231244326305314, + 0.08228753675293077, + 0.0846063194827944, + 0.060012550924950614, + 0.04379353542002895, + -0.0937070401529565, + -0.3173470356768724, + -0.2553976474683689, + -0.5692821420563671, + -0.43133865534337623, + 0.04911971638185575, + -0.18325708507110666, + -0.3260031344349327, + -0.6165076348717022, + -0.49031432684763865, + -0.549538502096134, + -0.1658724334398593, + -0.5846236306266338, + -0.35573392115733327, + 0.11516918627897033, + -0.30838629158349723, + 0.0012554170255358876, + -0.07303994316176854, + -0.3856043498912215, + 0.11807510123191123, + -0.5382238125796088, + -0.5325241142838845, + -0.23111326222854622, + -0.1024467700748879, + -0.5202804896854378, + 0.0517342855497438, + -0.542354803984798, + -0.202859591694798, + -0.37709616135343355, + -0.5334502159716791, + -0.08342843272921463, + -0.5369691045244872, + -0.583094504417943, + -0.45809578060022904, + -0.013423543685320838, + 0.08003686418055955, + -0.24671402604054032, + -0.09167587470614147, + -0.054899967202777455, + -0.19864932624248366, + -0.5744192434962017, + -0.4129522900739349, + -0.1636432863750822, + -0.21779449616528657, + -0.015158659508415662, + -0.18136184042036435, + -0.22683408130131327, + 0.09337847207438255, + 0.11612919559247059, + -0.5572562822706498, + -0.5546296199418937, + -0.11074318743942124, + 0.11709846284300385, + -0.16681362867334515, + -0.6562961515758348, + -0.2157708991406106, + -0.34798552512022846, + -0.5397171843562776, + -0.4369073908427054, + -0.4141155378699115, + 0.04812500249507157, + -0.244617303264963, + -0.08714306122428339, + -0.21500775714724502, + -0.36685430343084663, + 0.11381122248703113, + -0.39897803259575215, + -0.09721590124792157, + -0.3582447997635564, + -0.44488077651213764, + -0.5961555922957461, + -0.19635560522722145, + -0.41406512195055445, + -0.06723926306218131, + -0.5137026141220156, + -0.6591902990137452, + -0.06537904820438678, + 0.0563962922843948, + -0.16596169879202544, + 0.045161852546847014, + -0.3534319215688039, + -0.26784653749314624, + -0.17382712750380663, + -0.3949396137851457, + -0.3460597678103207, + -0.2801761961118509, + -0.02358690787197626, + -0.2146064169877791, + -0.41999252017020916, + -0.1715860907361092, + 0.09214801624158897, + -0.09256177138963884, + -0.19765936244474885, + -0.25508797525149574, + -0.42769562627050967, + -0.22118683126965277, + -0.14881738047876403, + -0.2758922828205246, + -0.18401264269562956, + -0.1713596363394545, + -0.553842350054202, + 0.1133045525351627, + -0.6176719170705497, + -0.29840880821558646, + -0.6555839167942203, + -0.6632299349997535, + 0.10572258752233055, + 0.024223791064977407, + -0.23928865632554008, + -0.6201447434940283, + -0.6047480711449512, + -0.5594137552363283, + -0.009172207496212836, + 0.10222526260570508, + -0.21733852676447096, + -0.41339960262600645, + -0.06218116250400385, + -0.5431720997338626, + 0.07398678885228371, + -0.11886119640519732, + -0.5793131762339951, + -0.09359363339739857, + -0.5559779073761963, + -0.3928744289380371, + -0.43368857648582476, + -0.2825955246440472, + 0.0012394109276073761, + -0.051895222396665885, + -0.09374613601305137, + -0.3789589250575414, + -0.5938351696525842, + -0.10234728187102093, + -0.24030729271186652, + -0.39371958203811136, + -0.2596297443472637, + -0.6026032553018241, + -0.34491965543987846, + -0.1750316622541619, + 0.013396168832035649, + -0.6141353974402423, + -0.006442577369114244, + -0.5851001189090259, + -0.2642581453905816, + -0.5238281108570972, + -0.17287416903225455, + -0.5392458998088342, + 0.06096301734654097, + -0.06367287287917434, + -0.017195514575379933, + -0.12406895079415436, + 0.06124805159723412, + -0.3997024172586843, + -0.2137821913391103, + -0.25221212339731836, + -0.36664004155005964, + -0.11597774677384609, + 0.03087026128906234, + -0.5896600194673713, + -0.2975161652007332, + -0.6400980194289727, + -0.08255231209108427, + -0.5183621599395829, + 0.006796386033526836, + -0.6292455012568736, + -0.33071759433451436, + -0.013082337883412176, + -0.6121864826365204, + -0.4048124156156295, + -0.38880836228451165, + 0.047139154240625536, + -0.5856040703651437, + -0.14634560043958522, + -0.0670066916792793, + -0.1536888907974937, + -0.5885432094599437, + 0.03648058640985008, + -0.6248274287156736, + -0.587188316285138, + 0.03346743527972951, + -0.27525339995379505, + -0.030823842788662903, + -0.1356233474084949, + -0.5697774915167662, + 0.08518896068455872, + 0.07292739717148367, + 0.05255430768157909, + -0.22513538956117662, + -0.29186444680821794, + -0.522960131674751, + -0.2744550558070439, + -0.4502434383075854, + -0.03134448214657615, + 0.06499233222215439, + -0.07492817615843728, + -0.3213213095946824, + -0.09838842916554114, + -0.5015185195426304, + -0.6344872465393983, + -0.3026461476419576, + -0.00957164349365669, + -0.3183120607062177, + 0.12093372814576742, + -0.38192120438340715, + -0.3818486041360611, + -0.12380018046884267, + 0.11895875896329344, + -0.3809974530193942, + 0.04353872008109305, + -0.18291462609860826, + -0.18899690464353025, + -0.3066958197296358, + 0.09782208817515281, + 0.08791178023760182, + 0.024310122406844825, + -0.07079747778493539, + 0.01289776925303976, + -0.6501634436133861, + -0.4781128691620101, + -0.052664143646765416, + -0.09683682605290322, + -0.5372040047013915, + -0.29278333370676285, + -0.5916539563163037, + -0.024333605345920217, + -0.4192719405164074, + -0.2745499366717887, + -0.018795337948350643, + -0.24503273905441175, + 0.09273635373038824, + -0.6448863224220476, + -0.10312730021879646, + -0.537997496127006, + -0.019689923256508868, + -0.39264024575484197, + -0.09655723570804875, + -0.4540403340458628, + -0.17817485045017678, + -0.16510013750419034, + -0.6511118979924133, + -0.03283878373734905, + -0.20422490505404534, + 0.1232101268524165, + -0.21284293651921898, + -0.6231559715449029, + -0.28867133306084003, + -0.6027823442961048, + -0.5635912687867909, + -0.27812253063116005, + -0.49367768173258264, + -0.07147016777731952, + -0.6578849495536687, + 0.11523420551357533, + -0.5144015619804357, + -0.3386094865493366, + 0.03235568038227621, + -0.29112727819344003, + -0.23112074307560548, + 0.09303766869360386, + 0.019705093932306128, + -0.49897491235692437, + -0.5612651868355122, + -0.04495593536866904, + -0.143574878326567, + -0.3758874430240887, + -0.11140300944018444, + 0.09153010539232143, + -0.28123286585074464, + -0.04467047010271008, + -0.26571701675099474, + -0.05636309658678529, + 0.11137404833271769, + -0.41626059949184213, + -0.12056244296840846, + -0.5157140420059181, + -0.38025190263352643, + -0.1741872534622319, + -0.30838849695104353, + -0.31896148743635694, + -0.4353340481837553, + -0.3355353609540804, + -0.2761890190017331, + -0.01664798633177489, + -0.16327472024065426, + -0.08838608459288133, + -0.06431536542227012, + -0.44883297101622266, + -0.5862049057944347, + -0.22061355600598215, + -0.30401610632287757, + -0.3210508676464538, + -0.5220182540919434, + 0.0580268346293048, + -0.08549853009099717, + -0.43908825975352606, + -0.09224099898302784, + -0.1779028757415831, + -0.48992158268433195, + -0.10277927938530385, + 0.06668696671176677, + -0.3620900279637737, + 0.11950864018498941, + 0.027768874892183493, + 0.10954001043665929, + -0.37820101894366137, + 0.0876085993580179, + -7.458331863736678E-4, + -0.5925155515691419, + -0.018785351961791097, + -0.6278853335710044, + -0.39753081356312847, + -0.07872739945699703, + -0.06380587459571685, + -0.44537875823656115, + -0.5118732216409877, + -0.14045180441063898, + -0.34947714602786806, + -0.22690014328791847, + -0.5610918030753708, + -0.30779601843540977, + -0.07145234800454581, + -0.43022786716585215, + -0.21629589318364673, + -0.5323666849703846, + -0.607361003829701, + -0.1271612880470241, + -0.2618043938346083, + -0.3668994356932944, + 0.0613912438970079, + -0.3572140595639046, + -0.10740518134408095, + -0.4314841642095753, + -0.16371215082759727, + -0.12776125659410498, + -0.5107008969566385, + -0.4622367272815209, + 0.038646182529229134, + -0.2022264545469638, + 0.062345589507734944, + -0.4261736620111004, + 0.028158901135519998, + 0.01786448241002725, + -0.5634987086779424, + -0.5083901625150262, + -0.45213926966831963, + -0.2746208037255501, + -0.4015330335530501, + -0.5000788841424625, + -0.26205535620306303, + 0.1007956053561494, + -0.2529087448956385, + -0.27929078187469236, + -0.5624755639456632, + -0.030468539556392726, + -0.24339503428990739, + -0.6067405748138299, + -0.03755921408182061, + -0.22516502441934472, + 0.04030282019818632, + -0.06487766028047959, + -0.429846404172212, + -0.5786985160030369, + -0.3457386545691886, + -0.6285049192720523, + -0.20709863129057726, + -0.024426519871644015, + -0.2851171290283011, + -0.45254142539457987, + -0.012530117670200513, + -0.2841367617859053, + -0.4693439905423327, + 0.015305081874493087, + -0.35523296840970453, + -0.5085416789625526, + -0.0064758245011959925, + -0.004349760388276058, + 0.01797285220956535, + -0.2924706885136865, + -0.4847947705764931, + -0.22882436534766154, + -0.24593746378782577, + -0.5229588310490391, + -0.2786761266937521, + 0.11936676771213528, + -0.2089197052298663, + -0.6175056923078791, + -0.28666386071049715, + -0.23766571617240045, + -0.26339779549448583, + -0.2516267568754319, + -0.5027804325714372, + -0.2418230939358113, + -0.006442122221642865, + 0.09186523533341329, + -0.08143660665036234, + -0.3161028309624339, + -0.6194620497504814, + -0.10060028266286647, + 0.01954816046796637, + -0.21144624834324016, + -0.3354933685646855, + -0.334584375965864, + 0.028689927293330753, + -0.192836754181612, + -0.1473820414916326, + -0.043938323587332295, + -0.11779764163214368, + -0.15971238004270272, + -0.47090910351216775, + -0.47139481205773054, + -0.05769463589209389, + -0.5809725004920057, + -0.5800083770270811, + -0.4384080785505737, + 0.10578787249813015, + -0.4249958829032364, + -0.6462024319479812, + -0.29178999063743594, + -0.5221918992426733, + -0.4736361312071549, + 0.11097844596949047, + -0.6198548296108559, + -0.5998847676112332, + -0.41582246457656746, + -0.41162422834670986, + -0.49614423223356185, + -0.4359060313359252, + -0.1314728419085851, + -0.37782771471859683, + -0.18884874135675572, + -0.36704472268352045, + 3.0235109829102047E-4, + -0.32750878539368844, + -0.44668472571337, + -0.15155264647914402, + -0.4471486272220477, + -0.17127283740520993, + -0.4872365313575783, + -0.021938329961947223, + -0.636255599075701, + -0.022894219280747752, + -0.28289229259730825, + -0.5225692847343094, + -0.05535406234792983, + -0.0669291241990736, + -0.2824689205168542, + -0.21982759993094703, + -0.25181788698486673, + -0.26511901521921083, + -0.27074570141417975, + -0.6085975612048535, + 0.07118219538475123, + -0.4559685883274619, + 0.08782994655804388, + -0.5412743511084777, + -0.5748615207349569, + -0.11479467726241233, + -0.2565044749344109, + -0.46538016199367593, + -0.6346634347601607, + -0.6580181074632967, + -0.370816541264146, + -0.27798270289262855, + -0.25350275240604636, + -0.5477234145763783, + -0.5290766340208954, + -0.5740133130087097, + -0.1963874667148397, + -0.09495523625756319, + -0.14751318739286923, + 0.10259983377890436, + -0.2567299388129232, + -0.48061611688024275, + -0.027986190172149983, + -0.5968275289672508, + -0.5982249049944516, + -0.6137900843888887, + -0.1129116342401425, + -0.5928353455853991, + -0.4402113535073221, + -0.2983834151634731, + -0.23467193913500417, + 0.11453606230016955, + -0.06713877255034006, + 0.03731625429807928, + -0.6517717225751103, + 0.03764805046908648, + -0.6321866330009795, + -0.2237943571710761, + -0.06728009906636911, + -0.5711733077516443, + 0.0886888541483748, + -0.27501100885354113, + -0.05009061268696113, + -0.17076210890806248, + 0.09975090722157609, + -0.3424858241365391, + -0.4397021658657938, + -0.465854442000682, + -0.010418038123404139, + -0.31178878782461195, + -0.3900866661341618, + 0.11771074938905857, + -0.551239415431287, + -0.49652174274316696, + -0.4069518647951775, + -0.05326697963218108, + -0.33733340538142165, + -0.09687357311872924, + -0.41930542576874363, + -0.007283678632348911, + -0.5257906984619907, + -0.254106871207474, + -0.6164683559959054, + -0.43121116109658, + -0.14022114553885467, + -0.3322698167843209, + -0.12052368636275546, + -0.6163522104378711, + -0.662259370193255, + -0.42572436768948196, + -0.18310992800775783, + -0.24962998319651636, + -0.4147911300087809, + -0.17454064223001675, + -0.2964083755015769, + -0.3219490455513164, + -0.46455596053830417, + -0.4004329227774915, + -0.5294660845480303, + -0.19801802204168578, + -0.49154913682335466, + -0.23343795270046247, + -0.6186147934019817, + -0.1987593876289077, + 0.058617615092627084, + 0.09212679122075562, + -0.6431880765505441, + -0.271455489200602, + -0.31502660970515006, + -0.3770268502501811, + -0.15059519612381556, + -0.5761698292709392, + -0.17582511337160384, + -0.15154644888773683, + -0.36543571749429066, + -0.5462913933077521, + -0.06039819794440504, + -0.03467223303774536, + -0.1565609065441287, + -0.002491214614607995, + -0.4628840844261768, + -0.5819941649627517, + -0.08689447886002866, + -0.5023971800935499, + 0.03146551396971797, + -0.42845956065721486, + -0.24818130633560354, + -0.2537163216883941, + -0.3228563259459471, + -0.12417264868655908, + -0.5497380712115811, + 0.007691655105973694, + -0.4463116666216302, + -0.004500883219858753, + -0.0643795314017318, + -0.6231128639904202, + -0.12460791199129084, + 0.02165430315793171, + -0.020013753906362175, + -0.2593128936477818, + -0.31504405796618, + -0.21229083906872925, + -0.2860456398835091, + -0.3663432969291664, + -0.5145453005913578, + -0.30476031900933287, + -0.22684289641398558, + -0.6337419721133869, + -0.43117340561378387, + -0.08428261468734854, + -0.6341721191402532, + 0.058795268217632146, + -0.10639858304236438, + -0.06667243967602188, + 0.09188935672413023, + -0.6185760901793517, + -0.5048471872848357, + 0.013558573710715005, + -0.14790798038755992, + -0.21958239095810683, + -0.6462767785126978, + -0.6349534047996558, + -0.34596411380808334, + -0.198172619310229, + -0.18172757374084803, + -0.021632308337575457, + -0.5849497291818845, + -0.3105942053633193, + -0.2830225527676646, + 0.02695763602386203, + -0.10034478656295909, + -0.5343934620888696, + -0.11388938238172863, + -0.03143721032989644, + 0.08999445806108008, + -0.008474769527996528, + -0.4844470819051664, + -0.4133496580682603, + -0.17056941917252705, + 0.10281470204070475, + -0.5031112706282501, + -0.015587070324590502, + -0.615016526982309, + -0.4996234513534382, + -0.4461984208437293, + -0.1066650785605241, + -0.2387112234228731, + -0.2954804014299495, + -0.3432685583232783, + -0.34227374412579437, + -0.39756233868787205, + -0.6490230916165001, + 0.104215404445824, + -0.5194473682342925, + -0.4442332853849323, + -0.44934710555762725, + -0.22011996642029563, + -0.09488266375737175, + -0.5581567519817332, + -0.15872687029396526, + -0.3063153931660701, + 0.01829032555530663, + -0.6563146198630527, + -0.03521951286913649, + -0.4350412141448641, + -0.21563134385485894, + -0.5749731084023814, + -0.3397623922696005, + -0.10997892870349668, + 0.06694909850904773, + 0.12158917635786848, + -0.3731602482341501, + -0.19503460036239428, + -0.2613690106396068, + -0.3270765437132397, + -0.5618960021678603, + 0.0460266797441925, + 0.04495815899246691, + -0.6462611601084568, + -0.6148114407810965, + -0.05511767135774126, + 0.046336272427827674, + -0.1959495174913855, + 0.10779539310391928, + -0.37752650523123016, + -0.46151971510114875, + 0.10740673333397699, + -0.599965090161083, + -0.601874754863776, + 0.029507451317301037, + -0.1945314175259169, + -0.5380010874520791, + -0.49950409731915724, + -0.0026155353168186846, + -0.07988821949887037, + -0.02027967321015578, + 0.07896058994232569, + -0.37925152013239727, + -0.178588387518742, + -0.13403256252665674, + -0.041258711836585804, + -0.34346063020445516, + -0.3789745942473397, + -6.888600569053827E-4, + 0.029986058359810608, + 0.024595406528878927, + -0.2641508830557723, + -0.3886754648341483, + -0.3790337687029644, + -0.44456554983452634, + -0.5209584959026475, + 0.03161597887293621, + -0.17122175792926425, + -0.6362655633638808, + -0.19630006399106648, + -0.29127705451640534, + -0.21330412853750846, + 0.11741072842295741, + -0.580501784062994, + 0.09164738922227122, + 0.046161551249742305, + 0.07223673976748657, + -0.4624322109156769, + -0.5719888079286112, + -0.16784609590480165, + -0.32364248000022033, + -0.06933650830255567, + -0.27447712542357977, + -0.4039020869638734, + -0.3756217400946692, + -0.24132635930145352, + 0.028299088013270635, + 0.004500570008229343, + -0.06892334555056201, + -0.4807399413742192, + 0.060919246634603574, + -0.6619774013245708, + 0.06569608426290585, + -0.21156565962985857, + -0.40688326343409875, + -0.40607555471456636, + -0.4065760920998656, + -0.1346322820988367, + -0.1092007596655391, + -0.5522548888954668, + 0.04337681484071876, + 0.0140501287280822, + -0.38001533112718555, + -0.5622909171922638, + 0.03324993695745493, + -0.3862006305570465, + -0.21732042034971621, + -0.11116709513737943, + 0.12200379952884433, + -0.3671444950990447, + -0.4310593481614429, + -0.0938793559537805, + -0.545121824251775, + -0.6380914770055068, + 0.04112536231448638, + -0.4376143660216644, + -0.3713825281840973, + -0.6207041869338135, + -0.47909384276891237, + -0.639517423181518, + -0.5424597178255947, + 0.11211936275521539, + -0.364971046250355, + -0.24082909112228246, + 0.11176795147523932, + -0.5244350287855417, + 0.04581199029802585, + -0.3458012030337137, + 0.03465052283832504, + -0.41322688273769903, + -0.46991839712611483, + -0.394641365772213, + -0.5354712202510138, + 0.027547687159113154, + -0.13748714794282757, + -0.15581983516755105, + -0.5161903793381838, + 0.002115494445974253, + 0.020437471415968633, + -0.612386789620686, + -0.5541852041851024, + -0.3090779585527016, + 9.492300362017314E-4, + -0.6388538926837849, + -0.6349374062913299, + -0.13367790286513603, + -0.16793262643655305, + -0.2521830084664088, + -0.6469747766983551, + 0.09855914082402084, + -0.2508988150180683, + -0.23616947391465254, + -0.5001814774990637, + -0.44958060432464325, + -0.25965055259455494, + -0.4005290517717102, + 0.056917035815984396, + -0.02345712505252795, + -0.011742279315313353, + -0.038164814296972605, + -0.6153833169013415, + -0.42577027284698393, + -0.527382860767112, + -0.1461367616557655, + -0.19624186879417177, + -0.17401885362721287, + 0.006152202983281452, + -0.351841104469754, + -0.6606654861061064, + -0.19223669088203987, + 0.10567642381004105, + -0.5636581049635263, + -0.33872427445048525, + -0.020608040468789945, + 0.014176889212460075, + -0.5684945867206573, + -0.42814660485040457, + -0.07766505382963074, + -0.6082409495100694, + -0.3412235932958068, + -0.2005885694068188, + -0.6394300364413814, + -0.23799920010747566, + -0.03634948757800882, + -0.608994203162142, + -0.5820870869012144, + -0.21776796661853898, + -0.467007310060391, + -0.10592233444138388, + -0.11536302142155885, + -0.3689108498190854, + -0.11614364787635578, + -0.26334860329993576, + -0.30092138118837775, + -0.2793920654935309, + -0.028661357805577548, + -0.38498628007820235, + 0.11975170195528184, + -0.37430992834441035, + -0.11488684810197591, + -0.21723227537502432, + -0.3919447110592767, + -0.15216821127997837, + 0.011320223214482672, + -0.601333623932484, + -0.3394484281233205, + -0.4145084211999318, + -0.2865810014822423, + -0.2715312088665171, + 0.0114711275033762, + -0.22312319483986537, + 0.07436298754185044, + 0.07400369677071095, + -0.5524971592773422, + -0.3539942840507853, + -0.5577867056624599, + 0.09051369492293371, + -0.6413961974657268, + -0.03165887868524431, + -0.008097870879171909, + -0.5766748796749827, + -0.12626227982901217, + -0.5865712242787091, + -0.09733553933048045, + -0.33378709767660836, + -0.5799344412348315, + -0.14914711020880067, + -0.03639322472485129, + 0.03834182463417335, + 0.07252394970155951, + -0.6148562281089835, + -0.3410895475451359, + -0.5338734427794856, + 0.04590191146238931, + -0.28807480736237373, + -0.3765501099702159, + -0.23053751608611533, + -0.5546070444257925, + -0.3605439938061713, + 0.025562646791980725, + -0.6325541490290886, + -0.4635070082461099, + -0.5598043295484585, + -0.3518052051823184, + 0.05729932716959585, + 0.0891894225683677, + -0.24922905237912402, + -0.6385535038995371, + -0.35489399915660164, + -0.48177983658877827, + 0.08176667256553893, + -0.4515979604878557, + -0.48730857912328596, + -0.11136588527256852, + -0.5048033221611847, + 0.037083055627707195, + -0.5702189392379439, + -0.6025386505287853, + -0.41194549112796724, + -0.14974733719202005, + 0.022819763813334615, + -0.21419224655261465, + -0.05860069017491765, + -0.3957092148260762, + -0.553502013183348, + -0.01566275476867396, + -0.4418472531838091, + -0.41264163204142634, + -0.6461620575851804, + -0.5607076060355387, + 0.11674449857507607, + -0.6323848198816009, + -0.5990714716777139, + -0.07974402869758779, + -0.5178139013796892, + -0.537192629268611, + 0.022054121287609973, + -0.35687245766259895, + -0.47451483592446625, + -0.20925752989814145, + -0.2964817702267198, + 0.025863310161788444, + -0.28987129125594197, + -0.09088191487333941, + -0.6395602849389854, + -0.22810258191097554, + -0.12515718802502585, + 0.06854178991344018, + -0.12963165327275872, + -0.5247048677203482, + -0.6209019888408362, + -0.3276629051703454, + -0.0630519278126862, + -0.06717840179289358, + -0.5608658997090481, + -0.6247459303873204, + 0.11783981870586502, + -0.5181984200028398, + 0.075041843258287, + -0.37517207466951535, + -0.4061192642306237, + -0.45630037560299597, + -0.029876150748952224, + -0.5616966579468801, + -0.34919912650218626, + -0.17117998870539153, + -0.02303761991221409, + -0.4268124873274204, + -0.08104303745116004, + -0.030998503795020005, + -0.21434912520998062, + -0.3055866413316932, + -0.17541386880526677, + -0.5611556094800558, + -0.5198937522826326, + -0.1979053573568706, + -0.3874479319915266, + -0.24013917045383498, + -0.37344897484688033, + -0.42162269268213903, + -0.060538814182852896, + -0.46874387697759506, + -0.5491022449766956, + -0.6481655689407051, + -0.30696055857120796, + -0.13540984467293404, + -0.5573770680396211, + -0.5819852136484545, + -0.03662691122307138, + -0.4461487345188624, + 0.030845809210627628, + -0.23988077238350541, + -0.563495648052324, + -0.39091336284023626, + -0.4103578792636485, + -0.4254752948245242, + -0.34593649005977795, + -0.6244696534989882, + -0.27488739827709097, + -0.21599530331440575, + 0.07918987583394366, + -0.06181279680637031, + -0.17737007730916, + 0.0358573743423638, + -0.09310336895492732, + -0.5939045231584211, + -0.08128918544549768, + -0.18401960801926637, + -0.28474653939589506, + -0.14429599548195515, + 0.04894708426569616, + -0.1941762808557112, + 0.4412557934211129, + 0.6076791724376981, + 0.3196325437917351, + 0.3848542671821632, + 0.686803606866169, + 0.26268859605568506, + 0.5620526202028758, + 0.6228391974966495, + 0.543158941175012, + 0.4711371535582488, + 0.6155290233932542, + 0.2631141609708186, + 0.3145422680611038, + 0.33209427182850815, + 0.5779906212279058, + 0.6149978779285521, + 0.5903906451467167, + 0.4426823580683257, + 0.4443267189851793, + 0.5954260527292152, + 0.6174476128053246, + 0.5576856572097837, + 0.37685220645710854, + 0.4275802753187365, + 0.5714619293221119, + 0.522203688662542, + 0.4178734493710443, + 0.5499394559945827, + 0.4158848257673885, + 0.3919516584865136, + 0.3917465916004387, + 0.36959567321198794, + 0.593112818394279, + 0.6038498308800824, + 0.46232555076092885, + 0.29323369688238676, + 0.6106143818768024, + 0.30818192498975205, + 0.30226842635702544, + 0.633369582181152, + 0.28580001399968874, + 0.46802518323643016, + 0.37449566175030913, + 0.6280247224852956, + 0.4171417036139696, + 0.4658496050738725, + 0.279931226670965, + 0.3855753131145133, + 0.2900863184806591, + 0.6749116776115691, + 0.44941282977514146, + 0.5721232218351788, + 0.6560162376448397, + 0.39231255573810353, + 0.4312604038371106, + 0.6618814539329555, + 0.6241961875740134, + 0.5967947795258683, + 0.43786107063359986, + 0.49175115436911765, + 0.4476193728790612, + 0.42858296967632303, + 0.36218895857993, + 0.6101177724317333, + 0.5287611772431299, + 0.28238844236857863, + 0.5199531889758582, + 0.4310597417535991, + 0.5904717633431771, + 0.3797487570427296, + 0.3880668656007549, + 0.6277657438049067, + 0.32056749211074403, + 0.557220011530204, + 0.5419969098318138, + 0.671787004145632, + 0.37924149217955583, + 0.5612749456102006, + 0.5270021192297201, + 0.618560887932918, + 0.6664637394675312, + 0.35754000549133913, + 0.5006773377825107, + 0.6614152253623478, + 0.5402804066290516, + 0.34942279269217524, + 0.4045631092973148, + 0.6359746952908315, + 0.6375321602814534, + 0.31293531440749917, + 0.6311569186942152, + 0.508064985069143, + 0.570457624188873, + 0.3666608409801894, + 0.275216341828745, + 0.5405683287745572, + 0.46571625817795737, + 0.5787291342530748, + 0.5653621022385666, + 0.27923170687125, + 0.458554751306941, + 0.5398875759694628, + 0.5402459422787207, + 0.26853784096488054, + 0.53831089854944, + 0.5998963618817315, + 0.37167511865400393, + 0.5515060455309763, + 0.4418959971652162, + 0.6813585296613065, + 0.49296472412668185, + 0.28057873665317756, + 0.32826500184570934, + 0.3269272399987023, + 0.34617300831510456, + 0.5739841189869979, + 0.44007068772489255, + 0.5260293989058187, + 0.3760184590732316, + 0.4207923825997507, + 0.4761733609211084, + 0.49385389064191854, + 0.25900190037754334, + 0.37262754973169165, + 0.42832492502950165, + 0.585572844886839, + 0.5007080998700323, + 0.31772589233540227, + 0.32732192435260643, + 0.5040840062550641, + 0.29199813936300617, + 0.6608699131818027, + 0.35938192594860985, + 0.508823116228821, + 0.2620183210743941, + 0.6441512221037332, + 0.53292867014837, + 0.29559460964949347, + 0.4516100587046335, + 0.27167722490346924, + 0.29464117573603205, + 0.5400188589400812, + 0.4020876084072147, + 0.6206877487416201, + 0.42606271670233253, + 0.4278554191317402, + 0.6058070412959387, + 0.5344781401264824, + 0.5091191759846183, + 0.6143370498400365, + 0.6063559228386779, + 0.494067503951485, + 0.49383536442472653, + 0.3669975753835741, + 0.593087466243627, + 0.2610715475407516, + 0.40591849903386945, + 0.6380431974777302, + 0.43856755411972237, + 0.41779821433787534, + 0.5821716702367342, + 0.41111119120984274, + 0.4721866895453408, + 0.42049952246730793, + 0.5382359596333581, + 0.2597514639980245, + 0.4143472098378704, + 0.4612437594039025, + 0.5378740138037388, + 0.46818730485135895, + 0.5501374502329048, + 0.5609286466750836, + 0.3800060048399104, + 0.5127726102513166, + 0.6707255777432606, + 0.6864982271321756, + 0.4693853140024795, + 0.3633467310977988, + 0.6740610922522337, + 0.663213478742939, + 0.3173074692959844, + 0.626158979915989, + 0.5795193522190775, + 0.6829690510939201, + 0.43204268455678874, + 0.44457260396919124, + 0.6246149832557595, + 0.3317429206843514, + 0.2959540367024699, + 0.4667079117138374, + 0.4217303364806784, + 0.34189937215705873, + 0.33342133358772474, + 0.38208256804190416, + 0.2622138342131183, + 0.2794818746148367, + 0.5347928581319898, + 0.473205263217447, + 0.4984645870516333, + 0.47220247655760794, + 0.5439837402611304, + 0.2971689766271177, + 0.4014623642370324, + 0.5247217372862552, + 0.3444672332557865, + 0.5476508046657173, + 0.6444987663901236, + 0.3663186576532055, + 0.3982308605194874, + 0.49649010644640035, + 0.523537692037314, + 0.3393899461287336, + 0.26801751618211206, + 0.575123749097767, + 0.49410544043680293, + 0.6106078326321431, + 0.28255742806596873, + 0.6641913263676609, + 0.5484421243038183, + 0.6858031806869447, + 0.30175088013278206, + 0.5561993819487925, + 0.4509785800384798, + 0.4826000093366867, + 0.616629649308218, + 0.4680136000951961, + 0.45251383806858014, + 0.26306963004762457, + 0.6805064669315666, + 0.28887228047060226, + 0.5912479331989416, + 0.6588807568353134, + 0.5745760596008371, + 0.4957374388586483, + 0.4750196401766801, + 0.646773799162887, + 0.5355152002994514, + 0.5535600926432008, + 0.37367764907299095, + 0.31928690810348764, + 0.6862129255170679, + 0.3335158449431725, + 0.5733007533817067, + 0.6248276758194693, + 0.6882457617800326, + 0.44494348852218824, + 0.440016513694776, + 0.32112782649648364, + 0.4383350581836718, + 0.4137269208426076, + 0.4696431702324213, + 0.3478882450243278, + 0.3065619217956552, + 0.3437453211701062, + 0.5570707893328468, + 0.29830928738762874, + 0.6805363350432214, + 0.42756954735379415, + 0.42796083312179134, + 0.547823007278197, + 0.4278655224685074, + 0.5065193734848119, + 0.5122080282042973, + 0.6247148021808189, + 0.29061314540483413, + 0.31833196954861176, + 0.5962141885759102, + 0.40720364553819927, + 0.6418376497080275, + 0.5817392980945052, + 0.41576456710652726, + 0.5967871475756867, + 0.2812688451018811, + 0.5974469213405178, + 0.5498553360460605, + 0.6154722915453223, + 0.3149914579001188, + 0.4610177550532399, + 0.6562582597382629, + 0.42888255364180405, + 0.505634344864546, + 0.6083616846246186, + 0.28472330174032334, + 0.26875751162511957, + 0.40023489042558935, + 0.644374572247119, + 0.3669875141415676, + 0.4225670590780123, + 0.49641454734408524, + 0.5672732105147476, + 0.5556012790141087, + 0.3762147287099188, + 0.6103566447845112, + 0.30596589217622305, + 0.3303487353521295, + 0.38374580806077047, + 0.39086665153561406, + 0.2607789847776372, + 0.38741406535487977, + 0.49410400985124225, + 0.405657383035217, + 0.5974198881000099, + 0.511754625817281, + 0.5946651211640346, + 0.33960116192513495, + 0.29420469656270987, + 0.5447350090629581, + 0.3156287325547687, + 0.45789839070758975, + 0.3617217480482949, + 0.48930245456317234, + 0.4135799157014506, + 0.284327700523165, + 0.5366473675459736, + 0.5332440046717635, + 0.6642740693525084, + 0.5198320784233595, + 0.681681006355915, + 0.5047599175102203, + 0.3282171741036567, + 0.4738103699784994, + 0.2627771535660702, + 0.6727633561484578, + 0.44279463331344104, + 0.26263022941847713, + 0.6793183462117267, + 0.5166184336859088, + 0.5608241595465306, + 0.5884186354300747, + 0.5044238171585077, + 0.6055128466169977, + 0.3935727254900293, + 0.5334922464442742, + 0.5259187902404642, + 0.3123522461585642, + 0.47503802869067047, + 0.36138650984977627, + 0.37994076275653466, + 0.5209896152887574, + 0.6539917409948376, + 0.43796548175506567, + 0.6026410081668181, + 0.3164879849981402, + 0.2946053621713773, + 0.619627127194602, + 0.4987005382606634, + 0.4901065788954133, + 0.5295802931194737, + 0.3863448939102243, + 0.3596005950912585, + 0.3931733936285132, + 0.4015303338184131, + 0.5091698287644271, + 0.5840538170199707, + 0.6345739776756099, + 0.33851094384010905, + 0.4913352987209578, + 0.3439029317230093, + 0.37749769480810114, + 0.27841009228262936, + 0.4858913539119284, + 0.4927492157486583, + 0.4730919103803145, + 0.6167023615195971, + 0.5685120766687501, + 0.6504420919598591, + 0.3617628643204034, + 0.276077867705118, + 0.6613293078151102, + 0.42820747745601007, + 0.47496561872544224, + 0.305569552347696, + 0.2751983334100789, + 0.4300781137050883, + 0.4788519014917283, + 0.35998710674263545, + 0.37647649212051254, + 0.6327146076165082, + 0.32156820076066045, + 0.6178241634264419, + 0.28693175114963254, + 0.6883944898207606, + 0.5620510108470091, + 0.5382499645502513, + 0.5787503046392068, + 0.4274063369928399, + 0.32069616173086685, + 0.29025747768189136, + 0.420070517995624, + 0.6798826081813502, + 0.33258088751510456, + 0.6722944927059491, + 0.6058227343498315, + 0.41559080245129054, + 0.6822025097074678, + 0.6188446939549721, + 0.3818681302825281, + 0.48871359333848124, + 0.3460147956721147, + 0.46169880752065073, + 0.575288104547756, + 0.35976084182057694, + 0.4591209580673378, + 0.5134112344267849, + 0.5871225278826726, + 0.385851788745901, + 0.6383951642047445, + 0.4827950441159964, + 0.5918198977286357, + 0.6199523514043549, + 0.49500999385727096, + 0.5619014607053312, + 0.6754019108442599, + 0.6228388891788561, + 0.642681011002209, + 0.3291034274424331, + 0.646201965666502, + 0.27294551235692116, + 0.4388884684448804, + 0.6266056511765096, + 0.5357453265196721, + 0.5246791176014765, + 0.453871834627855, + 0.6483641200906931, + 0.42216202708579775, + 0.5527488836179563, + 0.29444600160168455, + 0.4488145379829538, + 0.6788800848086302, + 0.3358266677335331, + 0.3443117513648346, + 0.5677417996913672, + 0.4914287260364618, + 0.4786680292461859, + 0.32612810299017025, + 0.4948946207316568, + 0.583873733481619, + 0.4424921253056038, + 0.3915427662456793, + 0.386916905984501, + 0.6246325657165533, + 0.5196335545805617, + 0.39434874483220445, + 0.5835649270967926, + 0.3097951751992769, + 0.4157929508882802, + 0.5066539015243399, + 0.3791823297459132, + 0.5695741664204765, + 0.5377628262511591, + 0.6530089819722091, + 0.6574670566910521, + 0.35024302871051954, + 0.32802353009751045, + 0.6792257153475166, + 0.6618556019933914, + 0.6300867095451417, + 0.40480469292631993, + 0.5568124054266779, + 0.535972831841771, + 0.43553918321354357, + 0.6528574775158318, + 0.5920831802414896, + 0.6600602375249893, + 0.5614391322543182, + 0.364282770580937, + 0.5602961688228287, + 0.6031222273815506, + 0.5306828317565012, + 0.6152213868787166, + 0.36338057812806224, + 0.5662634251147523, + 0.5146368671570305, + 0.42332066285442155, + 0.48597310237507946, + 0.5895767911569908, + 0.4185868233562259, + 0.4386658678903729, + 0.6284130416794333, + 0.5052778446725235, + 0.45040152540516437, + 0.5353597955193887, + 0.36644788273533874, + 0.28998440082184984, + 0.37512146024948917, + 0.4469782523420971, + 0.39069457432711985, + 0.2709145950131206, + 0.6186182494312352, + 0.5119902193070611, + 0.3398129215663967, + 0.3716608696473306, + 0.3001942897936771, + 0.46070949264085004, + 0.6556107599941249, + 0.6800227527495073, + 0.28876786164405704, + 0.27226913710638584, + 0.3266938148708885, + 0.3128575199117717, + 0.3316801010544702, + 0.6417469118493102, + 0.3722155032082669, + 0.3232674311206458, + 0.5700349707188266, + 0.2877568988359563, + 0.6784076964102574, + 0.47036114041191845, + 0.31878383911918545, + 0.28913854242725817, + 0.41532597175198127, + 0.5519051429322472, + 0.4825207259741713, + 0.5007073681739557, + 0.2716570652125821, + 0.6765885144613226, + 0.6771676976603451, + 0.26262070617704947, + 0.4635166407943678, + 0.5313272744412265, + 0.5065581722220653, + 0.6325348179656692, + 0.5233163356648948, + 0.49460866412706417, + 0.37967729264362404, + 0.3233665807294194, + 0.5696653876249451, + 0.5924590325305001, + 0.450533096918673, + 0.5143428859020488, + 0.3103534543994366, + 0.3000028042022838, + 0.27545989956380723, + 0.5594158976427511, + 0.6041211515347085, + 0.5804162395834115, + 0.6142220657390784, + 0.5534166158926412, + 0.6721692929901131, + 0.6681416717823887, + 0.42795254718843867, + 0.6698717243786281, + 0.45595514718821495, + 0.6041324301441153, + 0.31723531235026287, + 0.6517722277668051, + 0.5273001882485833, + 0.6647744335857897, + 0.6460511784853857, + 0.47123960462172026, + 0.6041102686468701, + 0.621555954429273, + 0.40049719108887016, + 0.403511306488724, + 0.6853309889117792, + 0.36844607344415586, + 0.5705715891175319, + 0.6572182276388121, + 0.4599309200636594, + 0.6056762909872031, + 0.5842124857964125, + 0.3725798262808887, + 0.6699457333192558, + 0.46633903266647814, + 0.3082051744234116, + 0.535668002672415, + 0.3179215057786139, + 0.4388257336048629, + 0.46066295339562857, + 0.37846704318328517, + 0.4895225833554695, + 0.32300177049672274, + 0.31321049687800595, + 0.47729541489165117, + 0.6749203439501912, + 0.5454110435301542, + 0.4201665043292512, + 0.25857284622756543, + 0.4430239155466055, + 0.53955603251604, + 0.3046402631366938, + 0.2822017893880635, + 0.38300953814233163, + 0.5815603809479195, + 0.3388444419971641, + 0.4768385278517363, + 0.3792845221569469, + 0.5283683978554705, + 0.5468697974357335, + 0.49598804464265045, + 0.348170002299228, + 0.3435766776375754, + 0.3167917078921251, + 0.47819602474261313, + 0.2864199088567233, + 0.35353866254382726, + 0.5335954356036212, + 0.31825355691841595, + 0.2784496666686802, + 0.6131263835373457, + 0.43757046602492056, + 0.5778397414857677, + 0.43388875336897464, + 0.5838873211171494, + 0.5048405500535925, + 0.5809572372200491, + 0.4333570760294009, + 0.43245127769147684, + 0.4315146950038773, + 0.6082561021698647, + 0.5010964296536904, + 0.33174808532606437, + 0.2814113989844661, + 0.44469242936406544, + 0.31856057490209366, + 0.4859876037580576, + 0.5984190217116411, + 0.44831369552475453, + 0.34755992320234946, + 0.38870447847117606, + 0.3992223531649903, + 0.5036969069500942, + 0.6027439289489661, + 0.38086834224576355, + 0.43037034930950235, + 0.47264223167434327, + 0.476686935381876, + 0.5316666387656793, + 0.6681920101054319, + 0.5960118526192586, + 0.2737429856132531, + 0.3133981994201455, + 0.6246308619333563, + 0.343558660751669, + 0.44420869830055215, + 0.5409784460271942, + 0.6400373436044895, + 0.34652801756389223, + 0.6130156077123684, + 0.36357104209828806, + 0.3222953312895265, + 0.567609055166441, + 0.25898262249564985, + 0.677669517831349, + 0.4788302568352417, + 0.3398884888043384, + 0.5721804385292891, + 0.3274814881912181, + 0.5686207689218794, + 0.39688336351086445, + 0.4510530379757879, + 0.44699453531274347, + 0.6699958544857187, + 0.48037548640424854, + 0.38667588261389607, + 0.2818140052023526, + 0.3271745567656534, + 0.6710426387373141, + 0.3381494699742953, + 0.6657027383503706, + 0.3280070109334297, + 0.3238976659659, + 0.4605697688417285, + 0.41296827223054666, + 0.5824041319969055, + 0.5545792455005644, + 0.6585911275452261, + 0.5036349357500434, + 0.2952031626121732, + 0.30342899790269146, + 0.4152174509080363, + 0.3727748742486074, + 0.6603051542154482, + 0.3333364290600196, + 0.4161354118210021, + 0.3644250386910771, + 0.44450644706554987, + 0.6442572280872756, + 0.6838341458000768, + 0.38984841201647225, + 0.6648199467665054, + 0.4131182095392879, + 0.5568969968538903, + 0.5166353106018682, + 0.4814484538182708, + 0.25892308835341216, + 0.28910624035201, + 0.31794276470409805, + 0.5504750941863568, + 0.5178858973486883, + 0.6741893700059515, + 0.26452700290041103, + 0.6029866316780178, + 0.2690709462680292, + 0.267936339012365, + 0.49850808288630166, + 0.5558153166668282, + 0.2619608379674846, + 0.4774648144134327, + 0.3984288523587519, + 0.6457375488629415, + 0.3425650234373958, + 0.3316231096440103, + 0.453686841485488, + 0.5017736139691, + 0.488370262494633, + 0.3924130359980466, + 0.4511256415803995, + 0.50861351033161, + 0.37246992106931426, + 0.6249448167228597, + 0.558011857254978, + 0.3963188095243917, + 0.5455183300240025, + 0.5160369868696102, + 0.2743805940850622, + 0.586266574899208, + 0.5770923504810783, + 0.30498317687043264, + 0.6454684559435849, + 0.3124209026123289, + 0.6145282426726963, + 0.30495054010069156, + 0.44062041848423183, + 0.675764386205443, + 0.5067001708098149, + 0.6859099978592823, + 0.6596381762250837, + 0.26460503515387424, + 0.38471719816355243, + 0.3634309344604761, + 0.32131918386539116, + 0.5253663407448417, + 0.598058891061749, + 0.4870449888361872, + 0.49581476917517064, + 0.600570474508879, + 0.5539897354999143, + 0.39646724841889336, + 0.35945911566070193, + 0.6761524200195768, + 0.31552285426519044, + 0.49516565713178795, + 0.2587013984674797, + 0.5940629634953442, + 0.5863180913244999, + 0.5077559657466867, + 0.4471797901528519, + 0.5446183433192192, + 0.5135522615250143, + 0.6774279185005583, + 0.31401828006701094, + 0.45126813445300684, + 0.40176188102331567, + 0.5584951075914185, + 0.27325880439563477, + 0.4229964535763632, + 0.5357305602761295, + 0.3227114741503407, + 0.298667445675278, + 0.5813842436019576, + 0.6051511921665271, + 0.34053213287400486, + 0.5252342393946727, + 0.31758879645377613, + 0.29046942797090514, + 0.4763159548914474, + 0.41555801740389764, + 0.64495116175089, + 0.5215036848578166, + 0.6286687652839231, + 0.5127779993002008, + 0.29435817310717977, + 0.32411729662017436, + 0.5182321650103352, + 0.5873557357657695, + 0.6349812149249975, + 0.2821749055931272, + 0.49236438104383873, + 0.2631342550611555, + 0.3477314768445843, + 0.5120186566829577, + 0.2670475275088453, + 0.2971490104086185, + 0.3918391368950725, + 0.4296344279361314, + 0.45061608543787524, + 0.5331949483040599, + 0.535624047628765, + 0.4378576186154001, + 0.3017409535461379, + 0.26848078829372357, + 0.6741555737234788, + 0.5259170409184155, + 0.4277210558722281, + 0.4290130915644105, + 0.6447831869767533, + 0.28557232302607466, + 0.508331159278361, + 0.2638735026837855, + 0.34242617590715385, + 0.2580138103286811, + 0.4275531805662753, + 0.4649016855611409, + 0.5544992960420605, + 0.6532252003896699, + 0.46665860246823865, + 0.29956692201425356, + 0.4153514670025406, + 0.5971018231076364, + 0.5094974440027646, + 0.3140166073335455, + 0.3761954991022899, + 0.5804937982775338, + 0.6780589752879915, + 0.5563202063894336, + 0.5017521641572636, + 0.3196026618670636, + 0.5748010293196613, + 0.521776111175847, + 0.687052997564888, + 0.6021388669520122, + 0.6302293962016047, + 0.6189045305303582, + 0.4947815612443337, + 0.4421426316589417, + 0.46765366912004014, + 0.5394295501334541, + 0.31415115675349925, + 0.39603499587898705, + 0.2733828058936504, + 0.5681309913608699, + 0.6766396686297502, + 0.5482468486525818, + 0.3844854406504876, + 0.56078403667883, + 0.3830305368138624, + 0.6476650978975559, + 0.515537842966787, + 0.44195315879585373, + 0.3229502156763555, + 0.2927957246497578, + 0.3504290965849224, + 0.5956029674657051, + 0.3222430441646889, + 0.5403291120555179, + 0.6413320356056076, + 0.3762831810377131, + 0.2748792977959603, + 0.43299932900652344, + 0.5334924119560922, + 0.6587499906404973, + 0.5428858776218524, + 0.5213789744812467, + 0.5258481801000177, + 0.5496060994258012, + 0.6553536685114891, + 0.6711830329001371, + 0.2702275858382071, + 0.3297281843583564, + 0.6197858787451009, + 0.5493322491545243, + 0.4081705777191116, + 0.34887203916193094, + 0.4738178553540441, + 0.46385874816454825, + 0.4580664023025629, + 0.6861286351668151, + 0.5268639501226011, + 0.38579480382159764, + 0.5728336485689818, + 0.2779669403884202, + 0.5521881320238176, + 0.3988748278612636, + 0.6331688272199483, + 0.5104224505687516, + 0.45063647771496973, + 0.3657570404830399, + 0.44113228571768437, + 0.26339415717857245, + 0.4582054408332477, + 0.5719000400510951, + 0.4828915145498862, + 0.6134091750566822, + 0.6384501025001439, + 0.6516671044591595, + 0.4125263378041994, + 0.506642839667785, + 0.6755492826171126, + 0.29502069371739736, + 0.40797808631426924, + 0.6843654362234752, + 0.513448787172166, + 0.33280621290027784, + 0.5666992153351557, + 0.3679288821314015, + 0.5757936547676692, + 0.5448029460049215, + 0.44004519582320645, + 0.2590054680538968, + 0.47872976314100446, + 0.5341538634353157, + 0.44321489455180857, + 0.3591266939618958, + 0.5950771560742374, + 0.6703354748780981, + 0.27673234804866287, + 0.44205340699243584, + 0.4989880499284637, + 0.6376658381181466, + 0.6259332246553027, + 0.32546322645673376, + 0.5557642929054101, + 0.47493450762767386, + 0.49722648375388945, + 0.5581065355242258, + 0.590381585429649, + 0.27818728061637443, + 0.40137462023003667, + 0.5990246294978676, + 0.560756481577828, + 0.5532851887138277, + 0.4381457204010708, + 0.3559312263066019, + 0.5738150087974274, + 0.43422266339518084, + 0.6011433835403421, + 0.36176731252585503, + 0.4157979834038017, + 0.28290436376536254, + 0.4179681065670878, + 0.5371365764569532, + 0.4802070287992143, + 0.4549784678743799, + 0.4484461056003459, + 0.5348149677990826, + 0.5646631117196232, + 0.32418400295750077, + 0.6867048902152235, + 0.3315222083314135, + 0.4207386018509919, + 0.5974128870013611, + 0.43953831593779735, + 0.6645296680498609, + 0.4362322755437703, + 0.5595086784169209, + 0.4881948975498111, + 0.5785748155212342, + 0.40040056432667714, + 0.47880920977496905, + 0.4731310006402993, + 0.3561231297570195, + 0.5569646616039297, + 0.33149313464072444, + 0.3042590660332501, + 0.39101658500345493, + 0.269765807707365, + 0.32972694599832403, + 0.4707361949363158, + 0.6437987429726004, + 0.6269178665770581, + 0.31385617521814085, + 0.495281205480843, + 0.6659648671712111, + 0.4862097740043255, + 0.2880176759325232, + 0.44170275206094844, + 0.6396543289597246, + 0.6376862341389435, + 0.29510792762547167, + 0.6632378003539612, + 0.542888039457133, + 0.31383523194305585, + 0.5375551197125954, + 0.6696183028856202, + 0.4379997669092528, + 0.6566307322041796, + 0.4717670082952401, + 0.2891228703217233, + 0.6038243729938252, + 0.6472492714872857, + 0.6610875928323892, + 0.4821677546051608, + 0.5834312881152088, + 0.4653725066702039, + 0.43677586270938695, + 0.5510086428663638, + 0.4726033049876702, + 0.29902849748636334, + 0.475844491959444, + 0.36201205169616796, + 0.47435296793415793, + 0.44722307686754775, + 0.683799530194309, + 0.3220343163568915, + 0.5754901374766402, + 0.6787316122661466, + 0.4464474076131656, + 0.4454617057525052, + 0.3133381981414262, + 0.36172027632785037, + 0.3377375003311525, + 0.2642650097880276, + 0.5083186107233841, + 0.4505874291771056, + 0.43820692531389493, + 0.47816153729315236, + 0.4652175938728206, + 0.41907684095661746, + 0.5592059994410475, + 0.5676345108635188, + 0.3608773723374407, + 0.6754861259861231, + 0.30612341050620506, + 0.28456534112172177, + 0.35551408102688176, + 0.45397667031736283, + 0.4973830877099363, + 0.49910555524203837, + 0.558926848310755, + 0.36014804475058904, + 0.5613887408198093, + 0.3710647737668133, + 0.3002808929842424, + 0.4119762175763676, + 0.4535934365736824, + 0.6593874724993627, + 0.330574506780158, + 0.5156731456550242, + 0.5234747798792999, + 0.6857908894209161, + 0.6127628698424765, + 0.26092067685011144, + 0.6703282148411802, + 0.4904071554717895, + 0.29577383019608433, + 0.6186644833854604, + 0.3639588432205131, + 0.6570588022546622, + 0.2656300269587552, + 0.385958086283343, + 0.5722419833562551, + 0.6517257008417315, + 0.6439784136810771, + 0.4020008313870882, + 0.5783364849837634, + 0.5147576369721312, + 0.4844722466698178, + 0.44096223012799757, + 0.6247751994256765, + 0.5997258911513463, + 0.35968931386323133, + 0.5198690305983465, + 0.49261484653154236, + 0.6525633773542082, + 0.5483509583677426, + 0.4475358832683013, + 0.454580081855012, + 0.5010716790461229, + 0.4385797650402926, + 0.5744119067003126, + 0.39160193435198065, + 0.5570916564459456, + 0.45126540902243883, + 0.40078357495308287, + 0.5610895350521358, + 0.46584574937922996, + 0.365587243379629, + 0.44111661042186023, + 0.531926561042909, + 0.30369579820474246, + 0.6085253853064643, + 0.5551403880064587, + 0.4778438267311629, + 0.58072151375817, + 0.3604379731108611, + 0.3176929394840586, + 0.4604681509889803, + 0.38518635265320833, + 0.5917824513718186, + 0.3788965005198706, + 0.5335752699466927, + 0.527537331999327, + 0.6294075137420846, + 0.31960900801519004, + 0.5729294659747055, + 0.42329944644342077, + 0.5682809599399814, + 0.42989023964719264, + 0.2736553301806667, + 0.3834754511443856, + 0.5739255790565191, + 0.5003314625414197, + 0.5195317286869041, + 0.4239505320681496, + 0.42370196840346064, + 0.4284060446893735, + 0.2669208612644959, + 0.5732773762207333, + 0.3191264863664642, + 0.5813385190464095, + 0.27525692418491504, + 0.39856151318457145, + 0.35994987441537074, + 0.38597936561865775, + 0.6255700191006854, + 0.5016176843837128, + 0.44523282130086317, + 0.5926881249720457, + 0.5859744485129526, + 0.5082951319638351, + 0.6881757056924054, + 0.608502519688203, + 0.46781757384831996, + 0.6156647928653807, + 0.4368842284281099, + 0.6128805458654099, + 0.5958224110967811, + 0.5448637998470857, + 0.32827013498386787, + 0.2883584263754633, + 0.5123356520020195, + 0.46221370028464576, + 0.5268687362987547, + 0.370051763555595, + 0.3484481966107676, + 0.343733005036355, + 0.5958444701300251, + 0.5891738430079865, + 0.3831489893017619, + 0.6305592379520999, + 0.47151509088492677, + 0.4301730602901068, + 0.29278332890834935, + 0.6146754450482494, + 0.48566021044918145, + 0.4617489650756078, + 0.620345381461479, + 0.6286236338680766, + 0.5989407570878755, + 0.6262827289900761, + 0.6544708602553655, + 0.5594403990163976, + 0.6502143382508964, + 0.4175808197045212, + 0.2581576277932008, + 0.5182254102589375, + 0.45643349252907145, + 0.6138478151841604, + 0.3801748359081182, + 0.3561334448072149, + 0.3619039426392992, + 0.6619265979839035, + 0.3855003485143629, + 0.5151187778666022, + 0.5268419628012062, + 0.5677752076954691, + 0.48046312075459685, + 0.38787831327402766, + 0.35348776245635594, + 0.36131233128353174, + 0.276382116086622, + 0.3482201985206621, + 0.5416426576917779, + 0.261928255497856, + 0.4439123474757566, + 0.47779883014153146, + 0.5698673702765022, + 0.5830990289563185, + 0.4093717031606803, + 0.6537738565810853, + 0.3357940219628789, + 0.6076140298977959, + 0.5115875851875286, + 0.6276582521910818, + 0.29539403738576736, + 0.2947977275516671, + 0.3375559348177604, + 0.3631967478091847, + 0.5437146492302023, + 0.44951397260641335, + 0.34668592719092584, + 0.37238432777283925, + 0.27451201791689395, + 0.37955123940957447, + 0.5308475826732588, + 0.28825284504726717, + 0.6618698925164043, + 0.44608122747534706, + 0.4814771993511112, + 0.48866051397488586, + 0.5259493894428549, + 0.6614281632224221, + 0.6814871189876128, + 0.36288627084524694, + 0.3045871771472343, + 0.25953299063212787, + 0.6802470388707997, + 0.5707429025579815, + 0.38888579140370366, + 0.31510533678979863, + 0.5213519892233192, + 0.40054879609967836, + 0.33845555823403284, + 0.2797070680723771, + 0.5242916082995774, + 0.6600391322275022, + 0.29550132920131317, + 0.5984225307705432, + 0.5166077938594169, + 0.3085696072628129, + 0.6006702541274862, + 0.5454611786675467, + 0.6139738694848983, + 0.4232003126159694, + 0.5794651651787586, + 0.2585700983683443, + 0.3836607633323727, + 0.33831707146877826, + 0.3224964950008745, + 0.4023575185124983, + 0.4002393909574408, + 0.4701364813002831, + 0.5337939200559432, + 0.3107618703614187, + 0.3360487307747292, + 0.4480581214201504, + 0.3449452576853525, + 0.5485446728338002, + 0.3078475168207656, + 0.621899511700619, + 0.6216213874485618, + 0.4921025126747549, + 0.6513368119934437, + 0.2802287986098698, + 0.2877876433889881, + 0.3204808459955374, + 0.27968845822229965, + 0.5662013981353253, + 0.5855216239064027, + 0.624630632028627, + 0.45477365367342554, + 0.5135077178918617, + 0.2881035390025014, + 0.5658737651643947, + 0.5014997332547804, + 0.42579642069038426, + 0.31186200471529535, + 0.6883851493079062, + 0.392368738453189, + 0.6326742384250439, + 0.6727310124705161, + 0.4588794973076643, + 0.42623643957259627, + 0.277460196265971, + 0.6759778590380803, + 0.4645376931977081, + 0.5385889540194366, + 0.5802250791033892, + 0.5550729140646316, + 0.5559982429758179, + 0.429034981588131, + 0.3711792732167427, + 0.27373199538143794, + 0.6803864745278876, + 0.47836004777579433, + 0.3022288432457384, + 0.47004992161974135, + 0.29600607345815405, + 0.35530219711302735, + 0.6043068016008537, + 0.33181247773666833, + 0.6482554426958659, + 0.4995463387771272, + 0.27046284994811715, + 0.6795070291087177, + 0.47571372859928496, + 0.4233790661156298, + 0.3295551695933479, + 0.5271231953052419, + 0.5396833140557201, + 0.29460973048861083, + 0.6420718076898387, + 0.26223836141297363, + 0.6704585727669732, + 0.639393145676793, + 0.3857607531626185, + 0.41974091225674326, + 0.33498693917684763, + 0.6281833072591254, + 0.5889821848914597, + 0.6458408428445995, + 0.5648309761350553, + 0.3671366111328529, + 0.61424787192832, + 0.46589237105728587, + 0.6461728921841342, + 0.6563931560220047, + 0.521975772186903, + 0.39688885150628894, + 0.3135177439811329, + 0.6118605734678069, + 0.46321669479401384, + 0.28728310134813073, + 0.4757540235329034, + 0.37321498103644835, + 0.595198746836877, + 0.6087936766100606, + 0.5168692634663021, + 0.5499074031546239, + 0.3376233736929713, + 0.6578356323564164, + 0.6262978028621077, + 0.6668897639968219, + 0.47822080152251023, + 0.4373919347784486, + 0.47394810649030533, + 0.3863776048459557, + 0.4514833388462082, + 0.609828159742134, + 0.34087034967594676, + 0.5523372306371404, + 0.40766895728345176, + 0.6793639271807532, + 0.44249330297028927, + 0.33868201780561624, + 0.6835844278947094, + 0.518602932601607, + 0.390260262084753, + 0.4613964179385368, + 0.4029305719692376, + 0.3615602305594142, + 0.5559392999066728, + 0.4925088210354912, + 0.6314709342043274, + 0.4595196541780016, + 0.28557286533532633, + 0.6097943482347998, + 0.34819745408953684, + 0.35426811274951264, + 0.35662197923001615, + 0.4168059884046505, + 0.33942964364702216, + 0.5966493400682762, + 0.5014912253687083, + 0.38017745230971955, + 0.5512159010520157, + 0.6378217139223303, + 0.523567448787666, + 0.6079328969637623, + 0.6295521364881762, + 0.5163974720269553, + 0.3055881014665295, + 0.6340933362135412, + 0.42294116968629675, + 0.6591255939583553, + 0.4019620756553858, + 0.6121988688356186, + 0.3047646875648005, + 0.46791249148797154, + 0.4463400418029184, + 0.3815645967924712, + 0.2712597809822125, + 0.2935530328738317, + 0.35791568489922204, + 0.458033369843709, + 0.5319644020270562, + 0.267576109553462, + 0.34053669254712093, + 0.521043919235417, + 0.6486268175255514, + 0.3170645577141654, + 0.509322524905395, + 0.41091405407712434, + 0.5216242551119729, + 0.4568000433839086, + 0.49966708413568117, + 0.5231468349065632, + 0.5120946979100099, + 0.6484174335332975, + 0.4421668412329299, + 0.5436207630811818, + 0.4667059974466009, + 0.3241459029619823, + 0.4389784126705142, + 0.6300293471610461, + 0.5913878949624306, + 0.33119766441187715, + 0.5700127852268063, + 0.5273760555001501, + 0.5346403816945903, + 0.5101379224873777, + 0.37142831159700546, + 0.28790125307417336, + 0.6346927891517933, + 0.3738284666543952, + 0.6142699124806856, + 0.5550136786499895, + 0.662524395526429, + 0.34414212441886116, + 0.30246626272335914, + 0.3337546382714726, + 0.6025758833868569, + 0.5280817194657493, + 0.6485887545148139, + 0.6375905463835195, + 0.4650735134283992, + 0.43098672136228744, + 0.36525698563116393, + 0.6544405529765371, + 0.493990896706368, + 0.4478457119299778, + 0.4417189226776948, + 0.5491564191385496, + 0.686547686829613, + 0.44035081743672944, + 0.5240469557696863, + 0.5238929519828255, + 0.46589227854254434, + 0.44264823051989566, + 0.2807635061138326, + 0.4737114519927067, + 0.4883622326114825, + 0.366972082757374, + 0.2711273001644959, + 0.38866685788838506, + 0.5116966654627066, + 0.6789057597418828, + 0.2697095250822023, + 0.2974307494657082, + 0.5724848676570342, + 0.4170741122406463, + 0.29870490118209203, + 0.6178592679191954, + 0.5805140876603485, + 0.5109393959843263, + 0.5384081623961177, + 0.4945712339444112, + 0.6197754178377588, + 0.5914830868314249, + 0.28098233827577196, + 0.36235442202579693, + 0.39347178788634285, + 0.41425081370159045, + 0.25942565529230144, + 0.27985080609353685, + 0.5722010216127551, + 0.48419916683593356, + 0.36731004885792, + 0.4144283491141647, + 0.26282644761469187, + 0.4466789972809822, + 0.3286939609975305, + 0.5770847807623417, + 0.6079286489122975, + 0.5984339588956105, + 0.3321146957416688, + 0.411019084917425, + 0.2609753814256973, + 0.48478388477670253, + 0.5250468472402965, + 0.4720893465791175, + 0.5362611095027515, + 0.3610662751310053, + 0.28135660351378844, + 0.4622785341320055, + 0.6510300840488461, + 0.5282965206468891, + 0.6460485703924763, + 0.5590103840593009, + 0.6691840512411031, + 0.640311625925339, + 0.3528474730922876, + 0.5329505809334174, + 0.6175482092506228, + 0.5646799122746446, + 0.4223058888574203, + 0.5364526631886358, + 0.5791072685625218, + 0.6241260603587961, + 0.2993799908825392, + 0.29185363829696265, + 0.6247414867127703, + 0.6810840239353912, + 0.29296411500761244, + 0.4866557040801222, + 0.35460418091412155, + 0.3499078284466723, + 0.5616845876356948, + 0.662282571253316, + 0.43192361014333813, + 0.5128386189028203, + 0.5769419648278917, + 0.5745462607940514, + 0.4783891157658402, + 0.4924886486208975, + 0.4682024160452488, + 0.687346166740074, + 0.3209755858506522, + 0.3122924392018366, + 0.4631850383750512, + 0.6221005924518832, + 0.6497270967619146, + 0.6780921580360617, + 0.38810413768788743, + 0.4103419575571295, + 0.6884354521557886, + 0.4733603961723658, + 0.6694269060585327, + 0.6575585479489978, + 0.6737496033227487, + 0.5197355992677284, + 0.3883296451059304, + 0.46967793406778713, + 0.5776617502041199, + 0.3503838909618889, + 0.32406599350758064, + 0.3732906072763198, + 0.3273299449693953, + 0.41721882287743095, + 0.587599157272616, + 0.5997058242049161, + 0.6225644322510124, + 0.6244002495531477, + 0.28306434657330365, + 0.3546303217242826, + 0.5080376491722345, + 0.6230080105581726, + 0.6443686020163225, + 0.601197487333781, + 0.661717301312138, + 0.4125258803160047, + 0.3357678482431624, + 0.2957950164996377, + 0.33178636065326106, + 0.36857129446472126, + 0.30276903787585735, + 0.5975177440438915, + 0.6642650124041718, + 0.297353391916138, + 0.29321150536836876, + 0.5466452866755925, + 0.5344489548978931, + 0.57496099826086, + 0.4828688209893075, + 0.5980327826874761, + 0.4651100546852648, + 0.6633115605311777, + 0.6122216299011807, + 0.6132501923469659, + 0.40322281356132117 + ], + "type": "scatter" + }, + { + "mode": "markers", + "name": "Expectation", + "x": [ + -0.20638117589512645 + ], + "y": [ + 0.003724452792381816 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines+markers", + "name": "Mode", + "x": [ + 0.09867441654205322, + 0.4300057888031006, + 0.4300057888031006, + 0.09867441654205322, + 0.09867441654205322, + null, + 0.09867441654205322, + 0.4300057888031006, + 0.4300057888031006, + 0.09867441654205322, + 0.09867441654205322, + null + ], + "y": [ + -0.558321088552475, + -0.558321088552475, + 0.3203643560409546, + 0.3203643560409546, + -0.558321088552475, + null, + -0.558321088552475, + -0.558321088552475, + 0.3203643560409546, + 0.3203643560409546, + -0.558321088552475, + null + ], + "type": "scatter" + } + ], + "layout": { + "title": { + "text": "JPT" + }, + "xaxis": { + "title": { + "text": "relative_x" + } + }, + "yaxis": { + "title": { + "text": "relative_y" + } + }, + "template": { + "data": { + "histogram2dcontour": [ + { + "type": "histogram2dcontour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "choropleth": [ + { + "type": "choropleth", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "histogram2d": [ + { + "type": "histogram2d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmap": [ + { + "type": "heatmap", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmapgl": [ + { + "type": "heatmapgl", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "contourcarpet": [ + { + "type": "contourcarpet", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "contour": [ + { + "type": "contour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "surface": [ + { + "type": "surface", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "mesh3d": [ + { + "type": "mesh3d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "scatter": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scatter" + } + ], + "parcoords": [ + { + "type": "parcoords", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolargl": [ + { + "type": "scatterpolargl", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "bar": [ + { + "error_x": { + "color": "#f2f5fa" + }, + "error_y": { + "color": "#f2f5fa" + }, + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "scattergeo": [ + { + "type": "scattergeo", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolar": [ + { + "type": "scatterpolar", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "scattergl": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scattergl" + } + ], + "scatter3d": [ + { + "type": "scatter3d", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattermapbox": [ + { + "type": "scattermapbox", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterternary": [ + { + "type": "scatterternary", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattercarpet": [ + { + "type": "scattercarpet", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "baxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "type": "carpet" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#506784" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "header": { + "fill": { + "color": "#2a3f5f" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "type": "table" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ] + }, + "layout": { + "autotypenumbers": "strict", + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#f2f5fa" + }, + "hovermode": "closest", + "hoverlabel": { + "align": "left" + }, + "paper_bgcolor": "rgb(17,17,17)", + "plot_bgcolor": "rgb(17,17,17)", + "polar": { + "bgcolor": "rgb(17,17,17)", + "angularaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "radialaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "ternary": { + "bgcolor": "rgb(17,17,17)", + "aaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "baxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "caxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "sequential": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ] + }, + "xaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "yaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "scene": { + "xaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "yaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "zaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + } + }, + "shapedefaults": { + "line": { + "color": "#f2f5fa" + } + }, + "annotationdefaults": { + "arrowcolor": "#f2f5fa", + "arrowhead": 0, + "arrowwidth": 1 + }, + "geo": { + "bgcolor": "rgb(17,17,17)", + "landcolor": "rgb(17,17,17)", + "subunitcolor": "#506784", + "showland": true, + "showlakes": true, + "lakecolor": "rgb(17,17,17)" + }, + "title": { + "x": 0.05 + }, + "updatemenudefaults": { + "bgcolor": "#506784", + "borderwidth": 0 + }, + "sliderdefaults": { + "bgcolor": "#C8D4E3", + "borderwidth": 1, + "bordercolor": "rgb(17,17,17)", + "tickwidth": 0 + }, + "mapbox": { + "style": "dark" + } + } + } + }, + "config": { + "plotlyServerURL": "https://plot.ly" + } + }, + "text/html": "
" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "p_xy = conditional_model.marginal([relative_x, relative_y])\n", + "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", + "fig.show()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:43.321629Z", + "start_time": "2024-03-12T16:15:42.344156Z" + } + }, + "id": "1811b5e17a88ebdd", + "execution_count": 6 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "# fpa.policy = model\n", + "# fpa.sample_amount = 500\n", + "# with simulated_robot:\n", + "# fpa.try_out_policy()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:43.323571Z", + "start_time": "2024-03-12T16:15:43.322300Z" + } + }, + "id": "6bfc00e5d93a19af", + "execution_count": 7 + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "data": [ + { + "hovertext": [ + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457", + "Likelihood: 25.972408031624457" + ], + "marker": { + "color": [ + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457, + 25.972408031624457 + ] + }, + "mode": "markers", + "name": "Samples", + "x": [ + 0.3418050044209915, + 0.42046289382091045, + 0.48810300202734136, + 0.4187827740915557, + 0.4705772942227926, + 0.4781452289763214, + 0.48309168342402675, + 0.5442943845121979, + 0.5315863645867595, + 0.3435085802309865, + 0.603781343783121, + 0.5504520379475959, + 0.37158248149876005, + 0.39456619996327447, + 0.5703835615125314, + 0.3671055066828624, + 0.5618150201032995, + 0.42832116488254884, + 0.3794676095448985, + 0.42995694698024683, + 0.5992332680182701, + 0.538438320162445, + 0.5075291077971777, + 0.3757486538815614, + 0.38094265823621554, + 0.5575078503610276, + 0.5659602164563106, + 0.4323932672621166, + 0.5936343869124514, + 0.49536724032059054, + 0.4469609865678917, + 0.6066118256417401, + 0.5138906602935309, + 0.4345392092766999, + 0.37401643042715393, + 0.5195647442239216, + 0.5493208962851699, + 0.5207675187022458, + 0.5262119471285246, + 0.5579526886429735, + 0.36070389114107854, + 0.3459472051400382, + 0.4337613620258962, + 0.5919431586772768, + 0.5273699503304089, + 0.42043620622279815, + 0.5446058973748606, + 0.5270447090663273, + 0.39840371170449096, + 0.4460208729991434, + 0.34669152072630643, + 0.42104060702535784, + 0.5522872550567137, + 0.3837377161213302, + 0.5780286914010967, + 0.5575899916239728, + 0.553296258476877, + 0.5477753187960491, + 0.3820731081849196, + 0.5452762441745149, + 0.4105534416608081, + 0.5681290010949585, + 0.5467012231047081, + 0.35428445939475456, + 0.5857895383189562, + 0.5626551258797161, + 0.47551643619236594, + 0.5862828572736039, + 0.50483555862688, + 0.42422059932831807, + 0.6057381220491029, + 0.4233448892949359, + 0.5486517705273007, + 0.4521250090813296, + 0.47686613797257527, + 0.4027652004853193, + 0.5353004553063754, + 0.5961425881536002, + 0.35898628456861864, + 0.45961054950877933, + 0.5829007560360822, + 0.37491379018207294, + 0.5190360861308956, + 0.43190498111437503, + 0.4165759516165968, + 0.4344813534692188, + 0.4735758359947455, + 0.546745518943785, + 0.45122964304486995, + 0.445119677506937, + 0.397395847187173, + 0.4134347480886363, + 0.5593323564705878, + 0.49055725824742424, + 0.4811105641877005, + 0.5211846126435176, + 0.4855909942145834, + 0.48363320141500826, + 0.45957552755767606, + 0.37838391780639846, + 0.5311797269372021, + 0.4268431058955042, + 0.5853497029631878, + 0.5211101644967847, + 0.37880642954208865, + 0.3607564188282458, + 0.4796413392359218, + 0.4247603008690887, + 0.4220248713078427, + 0.3594771701746183, + 0.58796828134802, + 0.5240799509003502, + 0.5512682330300651, + 0.4523673283844806, + 0.4255733109218371, + 0.38441205766836173, + 0.44217577081246684, + 0.4599894811627133, + 0.4109615190357875, + 0.5937880529884361, + 0.4944378751031075, + 0.3520844122797129, + 0.5190914496368122, + 0.4374819681643781, + 0.5591500621116273, + 0.5412963139073228, + 0.37603819641104536, + 0.38847396349388397, + 0.4032250024516821, + 0.4924560426283685, + 0.42086937066789404, + 0.4377345821230907, + 0.5122981954640152, + 0.4615735595265509, + 0.5541615701910219, + 0.5910663794297686, + 0.3837607812198708, + 0.4130275081138012, + 0.4165348041313972, + 0.35894869511526184, + 0.5145242367943522, + 0.5361395729533764, + 0.5039829582625056, + 0.47443433435163485, + 0.4831235378191445, + 0.549973061612568, + 0.4080920528076598, + 0.5100989489052936, + 0.3699179851507403, + 0.4155715476537355, + 0.5693689999424961, + 0.4705469761038527, + 0.4801240143554987, + 0.38748116623545326, + 0.48562037498672805, + 0.4722297271679715, + 0.557274899602064, + 0.38828791391059786, + 0.34724720685448135, + 0.5294519261029174, + 0.5536338065513148, + 0.4524898698433684, + 0.37063524426673955, + 0.4776500695926752, + 0.37196290028519025, + 0.5888293502998804, + 0.598369123636812, + 0.4946860527859774, + 0.451312616919999, + 0.5386536815414474, + 0.42137599250273033, + 0.4047268712312119, + 0.4363656762114295, + 0.3708796072993625, + 0.5637979612148067, + 0.3753290421171312, + 0.5357246981946138, + 0.49227880803839263, + 0.5483333215307123, + 0.5786464200447774, + 0.38977478581252745, + 0.4803259289169385, + 0.5391310372584164, + 0.4721955210526435, + 0.5575439611242762, + 0.42765923669174366, + 0.4873031733600067, + 0.3947155080501368, + 0.5373224198890412, + 0.47958640195826285, + 0.4148924713202303, + 0.6048835649587367, + 0.4118773291379324, + 0.5692551639564323, + 0.38084193240986425, + 0.5458891345421714, + 0.39726126307120335, + 0.43628092811580865, + 0.42182168439114637, + 0.4079438937048501, + 0.5990363636897748, + 0.4283853209746475, + 0.455401028400296, + 0.5090943311669857, + 0.45828691822825723, + 0.3870017874529029, + 0.4825897183751542, + 0.5740055369285366, + 0.3491943689753291, + 0.5727940002645229, + 0.527382677048351, + 0.45288711124681785, + 0.35090038529314405, + 0.5979905376584136, + 0.4369820154882582, + 0.347301844360368, + 0.39823102448812764, + 0.5343952740480163, + 0.42462646033846, + 0.42806138988553294, + 0.3548538692940955, + 0.34434641491759554, + 0.3742213383693845, + 0.4259450562242172, + 0.4714730095132724, + 0.44131543821839003, + 0.4273601630333004, + 0.5150302704931038, + 0.47039763891435604, + 0.4262175908469459, + 0.4843730426565765, + 0.4953798061486048, + 0.47349958800865344, + 0.606016705445918, + 0.5703363407871588, + 0.5253468259409346, + 0.4593281894255417, + 0.5731230280609131, + 0.3550769748293646, + 0.3448133977639368, + 0.39928619819974126, + 0.3602313712495848, + 0.509923338306495, + 0.4381816896798335, + 0.6048458046435725, + 0.35380625483404027, + 0.4976721565519823, + 0.4394503088497847, + 0.4564761397354343, + 0.5481786455718839, + 0.35136243638525727, + 0.4668248774194044, + 0.48101827984721834, + 0.5203163771652594, + 0.5353866093241932, + 0.5304272763249565, + 0.5575014598338159, + 0.4180265012754054, + 0.41635215748632515, + 0.572786289297615, + 0.4138492779168663, + 0.4912302783001208, + 0.37300226755993215, + 0.5532154068039915, + 0.345469132188884, + 0.4563700531850752, + 0.555105555836032, + 0.4724852623703465, + 0.5547359292054037, + 0.4691213566209098, + 0.430646120311847, + 0.5321907977577964, + 0.4051326028575885, + 0.37922302373874617, + 0.5642873332242331, + 0.39522261868056924, + 0.4199920828604664, + 0.4546367566417414, + 0.3664239825399167, + 0.5070956223113164, + 0.5907621012909742, + 0.38380415132416223, + 0.45700890039294384, + 0.5672300657643817, + 0.49952544574048674, + 0.502742834785098, + 0.37542615459366224, + 0.5610482393554925, + 0.35324051900281495, + 0.38683591055208866, + 0.5187059517016726, + 0.6069826431766234, + 0.4746358790858021, + 0.37947460855274545, + 0.5950988773371437, + 0.43394270441128424, + 0.42470052888732357, + 0.601506290589547, + 0.4836574368265671, + 0.5357119285119457, + 0.40105364976484953, + 0.3933365642506542, + 0.5065042908275231, + 0.4630004708632466, + 0.5384975641466532, + 0.42614875438690925, + 0.47793499970453157, + 0.500047440585773, + 0.5230421788531616, + 0.34591109922841434, + 0.4702380726339741, + 0.511851950832901, + 0.3453731029303581, + 0.500344915606301, + 0.48643341147651475, + 0.5825380574841507, + 0.39346628195932926, + 0.4551245741849041, + 0.45506291357056117, + 0.5458306785287304, + 0.5649031547786072, + 0.44385068633177677, + 0.357375583121979, + 0.5931094326752944, + 0.5912218357537184, + 0.4366874156434475, + 0.5028370875301964, + 0.5183589245573642, + 0.5204314796589822, + 0.555717165484436, + 0.542489579485379, + 0.4004308658690381, + 0.4468073136283036, + 0.5472724683772513, + 0.5515889572914914, + 0.4903176414681521, + 0.4950075288891008, + 0.3676160759447097, + 0.559582433055563, + 0.4742595980219382, + 0.34311552895437103, + 0.5672136922943017, + 0.48968039947007164, + 0.5877250901375654, + 0.35683204505023985, + 0.470464260723502, + 0.49932212721642977, + 0.34606829265864353, + 0.5741082630683694, + 0.45996334786767373, + 0.37706058127455805, + 0.42048596370067204, + 0.36433469493265047, + 0.4870593427974892, + 0.41509557110579565, + 0.5616749958263956, + 0.4183791363442587, + 0.44115838504540894, + 0.4305499673133141, + 0.45064179870048787, + 0.4824053436375251, + 0.49047880565681656, + 0.40680569938488687, + 0.43027096382095253, + 0.5445271830946932, + 0.48352870458515307, + 0.3562593519870652, + 0.4340151394465868, + 0.4220339644208058, + 0.5576622854086145, + 0.42849349641651435, + 0.35514014616730527, + 0.46453057978869167, + 0.4556737999473217, + 0.5145912265164778, + 0.4232598937763039, + 0.5827168642500915, + 0.6042270539665575, + 0.4196009148311382, + 0.4162381950889067, + 0.5522686887519869, + 0.47098512361658473, + 0.4497211300770748, + 0.571291844662733, + 0.5220114509744439, + 0.34198721369407653, + 0.5492845731107243, + 0.47310042557922294, + 0.3697430501474994, + 0.5831464575810755, + 0.4991417275437521, + 0.3879106589555589, + 0.39290901491987085, + 0.4070194843148901, + 0.567360447699915, + 0.5853373224690831, + 0.39130022549666976, + 0.6073516939931729, + 0.3515124474407596, + 0.46397531869876296, + 0.5331086738808357, + 0.5605502885656051, + 0.4232159949419967, + 0.5881475923021946, + 0.38244472114858563, + 0.3895715158309093, + 0.5541518802765582, + 0.5540350252719712, + 0.386325232345691, + 0.37702272918079827, + 0.5666105689396475, + 0.41962014725654556, + 0.4883526168229082, + 0.5017176425169911, + 0.4184204438049325, + 0.5684073485670914, + 0.5668555891446393, + 0.44979722461756494, + 0.500787484165339, + 0.47495501152657393, + 0.5255501977942031, + 0.5055073985545164, + 0.46816320894378816, + 0.3548002033278716, + 0.4554460962858839, + 0.49970934277717305, + 0.5056835799878427, + 0.5538339093188502, + 0.5406653280088244, + 0.5776933652323823, + 0.3944791130182638, + 0.4536000151426348, + 0.38892969661281074, + 0.3994798483797707, + 0.3909518671782786, + 0.4046262202245543, + 0.5693420798827523, + 0.4085714184385464, + 0.5559829586390747, + 0.5693660243753869, + 0.5112609472276227, + 0.49414100978993714, + 0.4158907804423544, + 0.48946438517834845, + 0.5609260730068716, + 0.41908655049793975, + 0.36263897925145283, + 0.49136555980786434, + 0.43135030741708724, + 0.37130440365499867, + 0.578345047796383, + 0.3654310628809949, + 0.5278785708494265, + 0.36935206409020915, + 0.49376595070440066, + 0.3661952703176776, + 0.46188924766777734, + 0.3971579032590189, + 0.5323992785517696, + 0.3600624234057818, + 0.5873045518940048, + 0.5326456121932067, + 0.44446782071962593, + 0.4047184789231033, + 0.37097260388287184, + 0.47184085655186686, + 0.5122539587661926, + 0.3653866138452558, + 0.5332906210426898, + 0.5923468052544637, + 0.6032595107955263, + 0.41427218240248836, + 0.48496742055429287, + 0.5655480870300347, + 0.5182318258182519, + 0.4210299596914131, + 0.37448626452496103, + 0.4713133374240237, + 0.45515307143982964, + 0.36629048281125864, + 0.3535669945896626, + 0.4786371418070452, + 0.4231123330379258, + 0.5835767798472082, + 0.5288241485351058, + 0.40745991473549986, + 0.5736699955266886, + 0.4120339301429695, + 0.46020292469017826, + 0.5819833899575882, + 0.39274248337114387, + 0.6053181748211147, + 0.6034615450010086, + 0.5027138442610434, + 0.5645048929873853, + 0.6009975955220158, + 0.3464112411657779, + 0.42583700911134437, + 0.3969341878594123, + 0.5865688262254342, + 0.5939059784094451, + 0.46450094965295496, + 0.43543591169009005, + 0.42703208431351314, + 0.3927218843706935, + 0.47282248410249783, + 0.3962767871486313, + 0.3719207829212973, + 0.48578754331603013, + 0.4110370346123026, + 0.526008565051441, + 0.5507179506021536, + 0.4713630217185355, + 0.5468796831448549, + 0.3902831947579364, + 0.49036271369844986, + 0.5591194914825147, + 0.3932708382209499, + 0.5053775259235191, + 0.5159363025463032, + 0.5159875843333668, + 0.3920553750603311, + 0.35388573532117334, + 0.6073671470752882, + 0.4681643922234685, + 0.5696438707300826, + 0.5030281072046372, + 0.5400524491621141, + 0.5505805988083616, + 0.5637201046160271, + 0.4494011986326907, + 0.34312189733108256, + 0.5873153594611857, + 0.511911159930812, + 0.5207533655709462, + 0.38925849424828723, + 0.5535177512537484, + 0.3691933930650747, + 0.599940326861013, + 0.5970922797916359, + 0.5919562426489086, + 0.4670148345538072, + 0.5771390253783447, + 0.4351681235647079, + 0.5710250868233444, + 0.3737855709496639, + 0.6063094677954497, + 0.36895582480369266, + 0.38138896603828126, + 0.4794679932365303, + 0.4427800685100388, + 0.4450047476015143, + 0.3546693878039054, + 0.4544569841168816, + 0.4104276562579435, + 0.39132258827374466, + 0.5265312098601524, + 0.4516579553962491, + 0.45009214973859885, + 0.353082941705289, + 0.40472712087553686, + 0.47632093155821287, + 0.4491809011576849, + 0.5037554821831255, + 0.48453605716532083, + 0.4448319333697399, + 0.41012964213380443, + 0.41158228744711034, + 0.5900780604899777, + 0.5319852807846981, + 0.42352140874872235, + 0.5965660560048065, + 0.5757669622895147, + 0.4945030394866377, + 0.5520046815720451, + 0.5725019362210265, + 0.5601029804593164, + 0.3757874035008278, + 0.47655280365422514, + 0.4193357071425664, + 0.5153804327906357, + 0.35035514047775507, + 0.5820094230420183, + 0.4434608142308336, + 0.4653979904342358, + 0.342434415673505, + 0.4690135169177803, + 0.5341312652383704, + 0.42195983235722956, + 0.3982024160275346, + 0.5969828927969294, + 0.5591079725721156, + 0.4484826058028812, + 0.3623391518905481, + 0.34367175981323766, + 0.4706192289986152, + 0.45085538412410775, + 0.4752468067674138, + 0.589494358107242, + 0.3850828094194676, + 0.5551175353082214, + 0.5128646363014648, + 0.37965180440672075, + 0.3590572551444592, + 0.38747536239478736, + 0.5340772553702514, + 0.3549693338727901, + 0.5639140336289648, + 0.3551788907962904, + 0.5159173083109188, + 0.5788219684475677, + 0.39845053923211426, + 0.5665400239854612, + 0.504045450980162, + 0.40121600461562795, + 0.5563984134110226, + 0.5507541158608086, + 0.5010631455482744, + 0.4742473686132547, + 0.5960954687771511, + 0.44598803369623924, + 0.5102804234128492, + 0.3518714890462425, + 0.4762818839156858, + 0.4775758296779308, + 0.5454199279067482, + 0.4629751687190453, + 0.5242696648974423, + 0.5437565282143462, + 0.5086850346491032, + 0.49863518502355547, + 0.3813376788322677, + 0.5476877445150633, + 0.5031559684268758, + 0.4072566101567615, + 0.5063796367720175, + 0.3537351061928446, + 0.4116514033756369, + 0.5334929473637947, + 0.35857401950170525, + 0.5739937704326459, + 0.5449637557473108, + 0.36724268390950804, + 0.41309275125647577, + 0.36128042193358084, + 0.5304325096229855, + 0.5629321531326743, + 0.46777188864137836, + 0.5906491304581328, + 0.3632956698619843, + 0.5928748927326136, + 0.4455638048902415, + 0.4843314914298229, + 0.5195833052312449, + 0.38869536848953895, + 0.5169128147980115, + 0.5606579840396742, + 0.5606872788825054, + 0.3852819916055446, + 0.42137722573907754, + 0.47668852031141185, + 0.4649500455121294, + 0.5707089649462989, + 0.5902086168034774, + 0.5007230954938793, + 0.4902206502954126, + 0.46574224275793435, + 0.5979178718054408, + 0.42321927621987554, + 0.37998064753963545, + 0.3522797306230855, + 0.5977124642955361, + 0.5220948489466776, + 0.4609279012289877, + 0.3786426774361397, + 0.43121920495978916, + 0.5289272725729629, + 0.46964224170069246, + 0.5159758986949573, + 0.38373138475105656, + 0.5937522616557724, + 0.4329531861823541, + 0.48325978960862703, + 0.3848690323735415, + 0.48031671160734934, + 0.5972293505723218, + 0.3456306546768843, + 0.46818900821656506, + 0.5630358354110924, + 0.36678641861952715, + 0.3875294442248968, + 0.40024465315002433, + 0.5897001775534649, + 0.5940801121013141, + 0.5892354875948655, + 0.3477475591544767, + 0.5836560777460615, + 0.3994047024058845, + 0.4947635393534486, + 0.4407473774753668, + 0.43021965578967075, + 0.4727862918979651, + 0.40823214497503413, + 0.4323653275463216, + 0.5328707000800581, + 0.4186444341389905, + 0.3674355384436607, + 0.4560689360281785, + 0.5014736053867173, + 0.544413041226391, + 0.36799876845183643, + 0.3554170565475439, + 0.5467570826523778, + 0.44842925793121297, + 0.49551718914524556, + 0.5051619034229737, + 0.5295046804560828, + 0.5167885878367219, + 0.5893443546291093, + 0.43290995123445536, + 0.5064648317976532, + 0.4476360324752185, + 0.5241053432280334, + 0.3971216966470027, + 0.4609846382458378, + 0.35192229391114666, + 0.4326082956274897, + 0.3733907671070571, + 0.462965494143488, + 0.4372046596977981, + 0.5894289379142832, + 0.3831392915296863, + 0.393640556560316, + 0.49113923906297385, + 0.375085773312048, + 0.49918853089601745, + 0.49049442686396766, + 0.558470366620296, + 0.3735446928366424, + 0.4384849816973547, + 0.482510389974109, + 0.46726557888811915, + 0.39879614805306984, + 0.4540794470335071, + 0.3615471549788125, + 0.5498705000979084, + 0.5591087896516915, + 0.5076995853616341, + 0.4140633448885778, + 0.6058704953701393, + 0.48858740637947673, + 0.4680799659814403, + 0.3790819517633766, + 0.3452060115089, + 0.5597743236075825, + 0.4161178995374226, + 0.47745495553068507, + 0.42216656824107746, + 0.4683760597292973, + 0.4851843288862344, + 0.4814246482178729, + 0.537943992438922, + 0.4664276136421387, + 0.34751961450677993, + 0.40458598304356896, + 0.41086318350288786, + 0.45333571718614396, + 0.5688438247331922, + 0.5710919225013837, + 0.44935871653999876, + 0.520234266803157, + 0.4773498877855949, + 0.479657920017467, + 0.49425894591864794, + 0.40195869060845946, + 0.5211366198368661, + 0.34612194950464575, + 0.3685194451441486, + 0.38099707493856155, + 0.5755613601109767, + 0.4267467073262868, + 0.4934533475353434, + 0.34209164401081243, + 0.540695411135333, + 0.5571691834808344, + 0.3814166237877245, + 0.5233641140068109, + 0.3681660045353565, + 0.566768506188571, + 0.4560396107959273, + 0.43267814331803406, + 0.566925802477404, + 0.44358095264039366, + 0.4149614237351253, + 0.5832913910880755, + 0.37290581229974096, + 0.3759174244220248, + 0.5146667765882483, + 0.44787174995184037, + 0.4338513719440353, + 0.3693395018368529, + 0.4653276128837221, + 0.5628953802660652, + 0.45773076606647944, + 0.4762781061903889, + 0.4502459764823845, + 0.3558523170454293, + 0.408528408199931, + 0.44403350259185204, + 0.5692069650609863, + 0.5598268936202506, + 0.430977686011557, + 0.5219150791309493, + 0.5969408278978459, + 0.42397770995408307, + 0.5778444778315747, + 0.5333912877553382, + 0.4618029853398552, + 0.5497536324500718, + 0.5022381853290987, + 0.5597920466234443, + 0.3413211166304529, + 0.39285722438042225, + 0.4457643467460786, + 0.38310894695805336, + 0.3480125421885832, + 0.5952086679792236, + 0.432343210813199, + 0.422360079373964, + 0.40531298508617625, + 0.4321160679577169, + 0.41900427628870185, + 0.5009038443394201, + 0.4538630406645209, + 0.5553022310986414, + 0.5715160880044118, + 0.5290995955449675, + 0.6037303639998648, + 0.3610488951537596, + 0.477067582855881, + 0.5912330290777326, + 0.5724350033757576, + 0.588703580944484, + 0.35167382665782015, + 0.45406475706780186, + 0.45750251078897297, + 0.5461754369850642, + 0.5430806331230144, + 0.4753058758596046, + 0.5647063927824121, + 0.4993185739791919, + 0.5790976317157648, + 0.38832487367103324, + 0.36454661788011755, + 0.47700852696980034, + 0.4882683618568661, + 0.41153800703049376, + 0.600879915001096, + 0.3501774832247708, + 0.518304479505953, + 0.561922484708129, + 0.5812714582973075, + 0.4729152000738767, + 0.48855397806849304, + 0.39469568297150903, + 0.363247819524434, + 0.42512051887844937, + 0.47030567163502046, + 0.46017949358134574, + 0.4980376977288078, + 0.5103147362751859, + 0.37696089437818797, + 0.601600742922141, + 0.39603504048794813, + 0.39604902130991465, + 0.3902842588142154, + 0.5944569241886681, + 0.42230313910991124, + 0.5971612223348683, + 0.5505069059361313, + 0.5276941769208399, + 0.5841868204127173, + 0.38450140084918183, + 0.36857784948114575, + 0.46649179627252735, + 0.3811651262988, + 0.38089413387726534, + 0.5127142949690029, + 0.47763586579957906, + 0.5085876667582309, + 0.5508238215692671, + 0.42617152900249505, + 0.4762923131576057, + 0.4512576762969043, + 0.3488693950335889, + 0.48333976945188306, + 0.34776322982406255, + 0.49839377716243344, + 0.5175239481662307, + 0.5661281048651898, + 0.5085188888400605, + 0.4569557703776227, + 0.5400339212272878, + 0.4657553139450715, + 0.3430054963135999, + 0.40030879874997743, + 0.5461444328153299, + 0.4964816225736033, + 0.39175239181123417, + 0.4994808663191305, + 0.5554144503690076, + 0.5336284094662216, + 0.5507766668300478, + 0.4341518882866944, + 0.408857608762657, + 0.5361948636672714, + 0.5946391822356529, + 0.3565568594010011, + 0.34924007471018687, + 0.5675554582834661, + 0.35919749993473526, + 0.5124724563606644, + 0.48692452233994865, + 0.6064765710501503, + 0.36062096968556034, + 0.38675478362991444, + 0.42536214975996456, + 0.41514468269768723, + 0.4542930657418876, + 0.5130408334421371, + 0.511104718154213, + 0.5545527730518054, + 0.5195340897665097, + 0.4820076288849965, + 0.47843227646982917, + 0.4494341418377483, + 0.460997892727249, + 0.5878754204485115, + 0.5188707133686966, + 0.39141637034879284, + 0.3900819612045877, + 0.5525439287676416, + 0.3772965574566514, + 0.5605430778671425, + 0.5488067119787274, + 0.3472505778110037, + 0.48300163535721763, + 0.5435862071905465, + 0.4500575464999361, + 0.601444870945393, + 0.3795018398077262, + 0.45188404214486244, + 0.3827733807902073, + 0.5565507670026301, + 0.5493387971532355, + 0.5075475394375325, + 0.4617855080453377, + 0.5834482739572837, + 0.3958186492976678, + 0.3585776820688415, + 0.5596010188906496, + 0.5487266329353938, + 0.5419630476274999, + 0.5341062204172816, + 0.4360177576039962, + 0.4150147194164592, + 0.4173071722496712, + 0.4531013642950532, + 0.3713644083885882, + 0.46973108966098753, + 0.38218255884171454, + 0.4681956244454821, + 0.519040650959924, + 0.5371869519812372, + 0.5609755059373175, + 0.3493912698697034, + 0.3546371561265873, + 0.5173657676620915, + 0.5991255033422764, + 0.3475695106983017, + 0.3596917043353417, + 0.4791165413357966, + 0.5860832180480118, + 0.494794721452843, + 0.494285312412303, + 0.5105520810366437, + 0.4084825550856339, + 0.49616493686480445, + 0.5106647062688094, + 0.42116090096085046, + 0.5767676340975374, + 0.5288022184997668, + 0.42405534108263016, + 0.3675406494678646, + 0.4121943653793813, + 0.40641199994799976, + 0.4795675279071252, + 0.4217346589919411, + 0.5485296742062635, + 0.5529474340161399, + 0.4802389408906298, + 0.5501090166600342, + 0.4373055571544473, + 0.5159137021014512, + 0.5433131737694117, + 0.46900399409539173, + 0.47664578289523696, + 0.524598931222689, + 0.39858549011306765, + 0.4005741961953101, + 0.5204368279325485, + 0.4102762871777138, + 0.36593026203504786, + 0.5997429520850301, + 0.37752042937663444, + 0.409228979139513, + 0.5317902459865063, + 0.4452558606895077, + 0.5841478320394538, + 0.5976979318940462, + 0.49850232571895275, + 0.3806390546667547, + 0.49789181015025924, + 0.3921425655336298, + 0.5204784539833935, + 0.4158971063370702, + 0.5390035176921297, + 0.3717686243329384, + 0.4513218000482286, + 0.5145778934985099, + 0.3599685549105291, + 0.37977414698556966, + 0.5755118353842792, + 0.34567092400399957, + 0.43207441168593125, + 0.5379236798948418, + 0.5497947549097533, + 0.5861495988526599, + 0.4870248892642786, + 0.46608196173995226, + 0.35267816246117323, + 0.36177201992153785, + 0.4401486734633157, + 0.4876304816012202, + 0.4207044421692101, + 0.5549279150443177, + 0.4212713664130435, + 0.5011931191855039, + 0.5499644397152684, + 0.3494226740657319, + 0.4040587294105462, + 0.44494596480131027, + 0.3985971736300473, + 0.3923178663674774, + 0.5984118300255239, + 0.43289408651228506, + 0.36157076283281786, + 0.44763881155715035, + 0.40671220557116883, + 0.42687196432000524, + 0.38729463914446133, + 0.37620747639506, + 0.5117155765752572, + 0.3893791779154112, + 0.4262078610041713, + 0.5453043407243159, + 0.5181580784422574, + 0.3494224323542498, + 0.5821328974676583, + 0.5760442603398617, + 0.5749077736789385, + 0.3509548907424325, + 0.36806066371790136, + 0.47932854805590264, + 0.5635375648551246, + 0.5012271699073241, + 0.37775590665989756, + 0.404688831056476, + 0.4692621879829995, + 0.42081861067281806, + 0.3985597516564739, + 0.3652351077009996, + 0.5685994451794981, + 0.5917394607970419, + 0.44363037585051107, + 0.48437179907875005, + 0.5938076894361478, + 0.5245994141066175, + 0.3551634877493606, + 0.4447755926451189, + 0.524791112897769, + 0.5390764048854781, + 0.5848022697394551, + 0.5377318199547328, + 0.5280184417838356, + 0.5562396140574288, + 0.5822791074201548, + 0.4139022346476278, + 0.4440258673687219, + 0.41780729816955664, + 0.5096313360146618, + 0.43914686489989024, + 0.4169913831977342, + 0.38395539747936686, + 0.34673936655866966, + 0.6032165091988764, + 0.5569336958503369, + 0.5347727068885018, + 0.40004200842992904, + 0.5538516672488639, + 0.4638023065487117, + 0.5924296471839444, + 0.5708624696982371, + 0.5566577012389169, + 0.46975087232348534, + 0.5278700291165634, + 0.35426532349050016, + 0.4426965839164455, + 0.5392766191140718, + 0.5822796645862357, + 0.5135094965303912, + 0.40908851207997754, + 0.49040256612337696, + 0.5099730330773409, + 0.3984912268318044, + 0.4779933861330685, + 0.4151416237449075, + 0.38574086932520346, + 0.4329378683081606, + 0.4903466763727349, + 0.5043349054907943, + 0.42376427936074085, + 0.42913929512246324, + 0.5545876739355654, + 0.4873924644880851, + 0.4102639477412568, + 0.4705378735419574, + 0.4602598546369153, + 0.4722992627977438, + 0.4602289180684951, + 0.5542645659297213, + 0.4277181994850236, + 0.5131392772238891, + 0.5258411627079675, + 0.48256855981863533, + 0.551679788292831, + 0.40449635219275804, + 0.4093439869156161, + 0.5791091649804749, + 0.4867964070761205, + 0.5741482080300446, + 0.49612168732630907, + 0.5001771923231492, + 0.4989848182571631, + 0.46529754890204017, + 0.4639342636323957, + 0.6043388655620308, + 0.3452031223821156, + 0.4377079598971051, + 0.4264831637235553, + 0.47773630315051163, + 0.5683746406343471, + 0.4095659154778148, + 0.43700489345671684, + 0.4808462831827053, + 0.48084349469725846, + 0.3727546599432704, + 0.5141152315456583, + 0.44580589273511656, + 0.5229878666211187, + 0.42166254414194865, + 0.46359478618961314, + 0.5448697829129506, + 0.3807814022803044, + 0.4710590894760348, + 0.4906746172597636, + 0.34383596274425354, + 0.35142325144067976, + 0.485649891906331, + 0.5919593366279876, + 0.4330496118976616, + 0.3551411942564184, + 0.5578136789726261, + 0.5488170525455053, + 0.4432562010958158, + 0.5108785495466552, + 0.3443965511710134, + 0.6054912384857585, + 0.5512042519658078, + 0.387627570340434, + 0.5890032302168721, + 0.40206621711334395, + 0.4752476439113572, + 0.5779191430636944, + 0.47246865854179865, + 0.450733380650573, + 0.49065455520353735, + 0.47141975312452983, + 0.5457300046736495, + 0.5945213751828275, + 0.4025227542053948, + 0.46293163955958433, + 0.5439932435601947, + 0.3531446136862463, + 0.406174907097594, + 0.6035329279755755, + 0.35820464800526164, + 0.41592354858649805, + 0.5067401222862093, + 0.46007431270828497, + 0.5166541796672329, + 0.606660543372301, + 0.5270967616313977, + 0.5384087476115993, + 0.34370147443890486, + 0.5661129158806429, + 0.42931277059027706, + 0.4979980047977233, + 0.4650722969488757, + 0.5758942106560527, + 0.5734857874929075, + 0.5509739658362858, + 0.35776981328632246, + 0.5586920655674166, + 0.40120937937731016, + 0.3417393295567787, + 0.42069209310361083, + 0.36841641300892974, + 0.5112848638920253, + 0.4695631923835515, + 0.3944100363641463, + 0.4976200953268122, + 0.5694108509855249, + 0.5853371494159534, + 0.5344733144475069, + 0.36301907461119565, + 0.6053925053987789, + 0.578097126094147, + 0.5578179474403271, + 0.5717838467049554, + 0.5847874916852009, + 0.397871624190293, + 0.4912126658170014, + 0.4019151982292043, + 0.6052452159370221, + 0.5828515197753213, + 0.5378979810222226, + 0.44747484208303767, + 0.49429297369969705, + 0.4884186995970845, + 0.4787866955057921, + 0.3427118594444619, + 0.5411194997107612, + 0.4061653882778526, + 0.42140110903370115, + 0.3652821251927276, + 0.39892571035596625, + 0.36443776468180744, + 0.5021766232479261, + 0.5493581366831808, + 0.47936849348665056, + 0.48313144968849187, + 0.5089359691340426, + 0.47827345596436155, + 0.45809709834995693, + 0.406961680691158, + 0.5401388859888177, + 0.5405289049609743, + 0.45421706303546977, + 0.43884938922451705, + 0.3866559499030143, + 0.5598501072917277, + 0.5965474235682422, + 0.3677329250794242, + 0.47962325799555355, + 0.5651506605940745, + 0.5470317233006022, + 0.5540817346064688, + 0.5941257357992997, + 0.5675150513676889, + 0.5618269025213701, + 0.5528250352793151, + 0.5285035563524196, + 0.4057948136778905, + 0.35825667469766365, + 0.43706226936383824, + 0.5376444498369544, + 0.3967112037900809, + 0.4251881580540937, + 0.35352090657965846, + 0.49075486444327476, + 0.5277915797382433, + 0.5494753310446482, + 0.3656473775965038, + 0.48169864003889, + 0.3747822603789379, + 0.42092838173496583, + 0.5865037581904856, + 0.5092179317145871, + 0.4532303905983471, + 0.36804419646419473, + 0.5907101230843081, + 0.41599566493357515, + 0.5661356005784269, + 0.5346400172610124, + 0.4605869890643859, + 0.46120459171452055, + 0.4924294044571569, + 0.49668740039052056, + 0.49590707540851064, + 0.6054443314637221, + 0.44057492673362086, + 0.3927729595262504, + 0.5704993400711761, + 0.3520725272808028, + 0.539198466905225, + 0.39487362249921965, + 0.5413949331225973, + 0.3670117601856999, + 0.501958985728708, + 0.5273175289118641, + 0.5484868371903794, + 0.5062465486149542, + 0.4665669844792709, + 0.5671535351853063, + 0.45855821464053004, + 0.36058412411277124, + 0.43062928321663013, + 0.405001632753064, + 0.5337485494264602, + 0.5133967472084515, + 0.44310639444811134, + 0.48334612100127855, + 0.4552567648260003, + 0.5427375663754783, + 0.3418045649162545, + 0.3551398296115273, + 0.48326114042567936, + 0.4932084584290826, + 0.3642590181935925, + 0.44396201617357184, + 0.597358418218051, + 0.5536693614389065, + 0.4020207489260304, + 0.5952207556998241, + 0.3660961407027712, + 0.3785491622581903, + 0.4242627679404203, + 0.606695763753605, + 0.392461173710016, + 0.41885786885559406, + 0.539784309246004, + 0.4090084569644603, + 0.44042604795964874, + 0.5730081789344831, + 0.46577256518341387, + 0.3675912931302057, + 0.42619890681929967, + 0.5708482929502462, + 0.511296106097015, + 0.5133682067666803, + 0.3536055064486195, + 0.45197936225170265, + 0.35349651026365303, + 0.34641495784255383, + 0.5467879379178933, + 0.4575673907874381, + 0.40037120080808997, + 0.5403972273840868, + 0.34283755809663113, + 0.3652610449498642, + 0.37305869542444264, + 0.5955174873404755, + 0.3516078721277744, + 0.4831651576349084, + 0.3783084665323867, + 0.42259266751213687, + 0.48324112363286786, + 0.577526186389424, + 0.5923123775795511, + 0.538016400979911, + 0.4671252251498206, + 0.3610849201295662, + 0.40176300707374646, + 0.525447858158189, + 0.3578576990299993, + 0.4687082973515295, + 0.5238135873319546, + 0.4065742911278351, + 0.4977709253748299, + 0.5207403029582378, + 0.5771624131905057, + 0.43342985790604144, + 0.5969294889070169, + 0.5793050669716379, + 0.4787464520812086, + 0.47258453523838606, + 0.5197913899908064, + 0.44232320739945036, + 0.44216555232432736, + 0.4080231217559076, + 0.5003194464656302, + 0.5762335339481615, + 0.44226009187476456, + 0.4212149417877318, + 0.3443636552215967, + 0.4062108402268042, + 0.606326787007728, + 0.5056925322121428, + 0.37109575729067146, + 0.46800129726912076, + 0.45104349414376793, + 0.4292873547941039, + 0.5627432140844206, + 0.5451734099122009, + 0.5373691614494499, + 0.3887973006643662, + 0.4510710050706381, + 0.4004052483347408, + 0.43515287027600696, + 0.4976603863827777, + 0.4314414681730773, + 0.5070565444570232, + 0.3616193100519047, + 0.5006617045828884, + 0.3449995705840502, + 0.4818353381291514, + 0.4556686405562417, + 0.5978572542279198, + 0.34897114025882314, + 0.3409822274894937, + 0.5415914668947654, + 0.5176308694711975, + 0.3763088829380787, + 0.473755923337486, + 0.4526280059247925, + 0.36012705079526675, + 0.4260984998972496, + 0.5226166210850928, + 0.5891235604473557, + 0.3479133059552282, + 0.5016689510466745, + 0.3447043183950339, + 0.4700949197329335, + 0.43623223697363783, + 0.3505050161618999, + 0.5861478628999355, + 0.3780899107226463, + 0.5965781823060655, + 0.5959367427314861, + 0.3779940956576678, + 0.46340736138897937, + 0.5818669526198004, + 0.5613940052643753, + 0.3696078423562674, + 0.34970690793943515, + 0.4456167247707, + 0.47026306459450046, + 0.5489119139892007, + 0.4587471176687994, + 0.39781795925203706, + 0.4199147676768043, + 0.3415684181387399, + 0.5631757333036549, + 0.5210242341668159, + 0.589444974119202, + 0.39202685482927535, + 0.5786953745437059, + 0.4424620343925433, + 0.5857535998972173, + 0.3831702528856662, + 0.603404614094308, + 0.4864843822226469, + 0.5098100668593947, + 0.5484185599539609, + 0.3609724246593813, + 0.4302904772798027, + 0.41831359967031806, + 0.44241129785445177, + 0.5296957392290019, + 0.4493594120407865, + 0.5758531447548155, + 0.49371803702158823, + 0.49883740141594846, + 0.5179544163701408, + 0.399097146895844, + 0.3790416591666389, + 0.468161040731337, + 0.3593834988126361, + 0.4696885172783928, + 0.4903528002807924, + 0.47888945584544146, + 0.3941243172410985, + 0.5949751532910679, + 0.5792030585272847, + 0.516260113265514, + 0.592639896417546, + 0.5108246650003956, + 0.4621711375940228, + 0.3549921782881267, + 0.34419042844772707, + 0.35592151329234717, + 0.5366962390025276, + 0.380996249350582, + 0.5390645749831615, + 0.4815888441435784, + 0.4137922919188369, + 0.5642540067912105, + 0.4472557744419753, + 0.4816715402349563, + 0.5584985960992093, + 0.5123938021877864, + 0.3614155234170871, + 0.4092593716631853, + 0.4003015821420569, + 0.4561079914526023, + 0.5532737605549063, + 0.5507594548125366, + 0.4601950285571985, + 0.56423751736139, + 0.4830252538623965, + 0.4979114833595524, + 0.42958506741739944, + 0.565437858396905, + 0.4180710650143092, + 0.5117342457791612, + 0.45922459560038653, + 0.37567715383453715, + 0.593049920500933, + 0.49651641403614377, + 0.5475541550580917, + 0.4374183549772779, + 0.5688798097644869, + 0.39737852423029557, + 0.42805323896908526, + 0.42935982631376324, + 0.35729542253336816, + 0.5915915867502046, + 0.49974439159439143, + 0.5364984904350721, + 0.3763109213030394, + 0.543790487333214, + 0.5472909749440531, + 0.4017165218891652, + 0.46836141303809786, + 0.4296626770451416, + 0.4552329385539034, + 0.431504662907053, + 0.4357318458951015, + 0.4906276997106476, + 0.5739848189584823, + 0.47643815249411137, + 0.35943210068620807, + 0.49908593227073306, + 0.582510008898103, + 0.4785465768901364, + 0.5525311387060066, + 0.47364719908757924, + 0.5900961364769591, + 0.4989347455329335, + 0.5374627152765787, + 0.4388284469175143, + 0.49656496078448287, + 0.5722171120099486, + 0.5344004097437738, + 0.44761203782931736, + 0.4959797440940694, + 0.5928494439529697, + 0.6018383463952373, + 0.37047954886205947, + 0.5241524042501857, + 0.46999761043232113, + 0.5688667714533728, + 0.4808262896437844, + 0.5218902150646384, + 0.4268504771707149, + 0.5637630311820285, + 0.36255079749969393, + 0.38434342162691504, + 0.47754310889422075, + 0.35221939416819675, + 0.590774303162905, + 0.39710962499107594, + 0.5208095864858034, + 0.38488131014046695, + 0.36657874081817193, + 0.5797554715469266, + 0.35202209156267744, + 0.42862559663343186, + 0.5436237138225644, + 0.361694919099174, + 0.37123440841445204, + 0.5989587145286132, + 0.48347856687466284, + 0.3622709707812483, + 0.4184696753687244, + 0.40918016041480854, + 0.5135210549708782, + 0.43104402053884705, + 0.35134999803656375, + 0.5100477942387148, + 0.39859536921978916, + 0.5299805251002494, + 0.546190026818351, + 0.4956723017107683, + 0.38141256458959044, + 0.4199818201363078, + 0.5984475814408099, + 0.5487399277534105, + 0.4842771226870802, + 0.38586242710097507, + 0.5424567071799237, + 0.4474693419998597, + 0.5435982195838254, + 0.40355403389597616, + 0.46091025074890035, + 0.513291270281824, + 0.5828382207881566, + 0.4629646286829769, + 0.4458819293065666, + 0.43630804022546626, + 0.4853797245015391, + 0.44722416173211904, + 0.5246940485467683, + 0.5645903050587975, + 0.5966971746473727, + 0.46294552666447697, + 0.5132953656220485, + 0.5095213715006454, + 0.4765886280760146, + 0.40409511496883754, + 0.47670217013125155, + 0.36498720848992344, + 0.5845940374728326, + 0.4130792660627183, + 0.37356265169504843, + 0.4399114197402956, + 0.5036059197835155, + 0.500082142453562, + 0.36311832006305156, + 0.3890316668314808, + 0.4488864946009695, + 0.4243462499807549, + 0.44665308394986575, + 0.3793758396033923, + 0.5958784453708247, + 0.5559226637617731, + 0.540310350736598, + 0.3849038340289976, + 0.43371715544760514, + 0.48780177165088, + 0.536637871763491, + 0.5447438693536855, + 0.39475437510706285, + 0.37820052524232817, + 0.3972292567458137, + 0.5878197672505225, + 0.3738287382375631, + 0.45831577060727, + 0.5447679302022996, + 0.37047096601347257, + 0.6034015704511099, + 0.4414872774322497, + 0.3581792790311684, + 0.48268683757612635, + 0.4351224851182274, + 0.5126286197532355, + 0.5660686655002676, + 0.4522209186469125, + 0.4297563423378059, + 0.48176575710218456, + 0.5568075552939239, + 0.5122737192992761, + 0.3897719561528098, + 0.5303139603526139, + 0.3890735944662835, + 0.5156910254651415, + 0.492265389645744, + 0.4543400116809689, + 0.4315192204057235, + 0.3517682755416012, + 0.4458799725307709, + 0.48348261260610204, + 0.5361232202682916, + 0.41741332709021106, + 0.3598244905762465, + 0.42308651755084087, + 0.5443162756989902, + 0.4692497890006355, + 0.5493292845388383, + 0.4823487616656143, + 0.5927394826218776, + 0.45291898008964787, + 0.5647822221789737, + 0.4222863973893678, + 0.572437485070457, + 0.6072671509795817, + 0.378493550054688, + 0.3618665149594862, + 0.4982309972816673, + 0.5356049797282111, + 0.39092952343652043, + 0.4751317058727445, + 0.5447436272406033, + 0.481135246889857, + 0.4790468770082716, + 0.5738145645332279, + 0.40514715854339295, + 0.5730767010911577, + 0.5637371839504364, + 0.5779303967577918, + 0.5803651489945478, + 0.5251813936646836, + 0.39157773178963695, + 0.5147832589206653, + 0.587081956536606, + 0.5925045850481256, + 0.4708974309105739, + 0.47743333070548905, + 0.3494952619487619, + 0.5406174012589257, + 0.47208730160054113, + 0.5325605722115214, + 0.5856971282646489, + 0.4287317918905761, + 0.4594243619267505, + 0.491826809873512, + 0.47226564135738924, + 0.5382753559203767, + 0.4585170894853853, + 0.39175127980288205, + 0.39084045304016474, + 0.5724782917701027, + 0.412821166133059, + 0.5250816769630482, + 0.46378122513385617, + 0.4642306132137287, + 0.39635907376612906, + 0.5710115086071117, + 0.362069688157322, + 0.5511502987910317, + 0.52858616508491, + 0.5561599961867905, + 0.5383692844219772, + 0.45599045085718215, + 0.4348805315801754, + 0.4580328383220731, + 0.5490123780806453, + 0.579378881507812, + 0.4624101759760124, + 0.5656358083069314, + 0.4482145729272018, + 0.3984893041671749, + 0.38808574339373403, + 0.5859427078396667, + 0.5021175538645386, + 0.5937790372235039, + 0.6000843283112475, + 0.3727275144592678, + 0.4893443149651098, + 0.477915779298977, + 0.48047670229103845, + 0.5591144327995468, + 0.4642371933965854, + 0.5224901144551484, + 0.38096228461726084, + 0.4134934889234984, + 0.5458326470269318, + 0.5470773190847519, + 0.5262718169740518, + 0.5977991604872139, + 0.5881744882881204, + 0.3858866199562464, + 0.43871752564816385, + 0.5307343881858637, + 0.4639455868091231, + 0.3759985005301699, + 0.504282550038908, + 0.5688263543348893, + 0.536388011552948, + 0.5559997467100166, + 0.3441022128290943, + 0.49006327399236077, + 0.35005151870369816, + 0.5005544166318121, + 0.48153638929069026, + 0.42914614834059217, + 0.4913255829409019, + 0.3756202993726586, + 0.3704749206471512, + 0.40107975828391446, + 0.46514651338668256, + 0.4835215323344906, + 0.46349410842704597, + 0.4363624629148393, + 0.604617583193086, + 0.4940654660671455, + 0.41023122516756366, + 0.3946376612725568, + 0.43209728328794733, + 0.5049950297279239, + 0.6054037498711096, + 0.5074431682817182, + 0.538832603853358, + 0.44695991137230606, + 0.45154354365483795, + 0.46070498600617615, + 0.5429191875456703, + 0.5334693264539616, + 0.3681650929949051, + 0.38087821821721624, + 0.41887579338151437, + 0.41348527097894294, + 0.5424270563759517, + 0.5897118559496941, + 0.48818471035237576, + 0.39784320707796833, + 0.3475927922349093, + 0.4010968842099402, + 0.4164637025131879, + 0.5813192315501314, + 0.5565592378430699, + 0.5732294958091141, + 0.38470904275546264, + 0.35666385731839556, + 0.49835103127225533, + 0.39764500224053884, + 0.35832996477324186, + 0.5041522249823469, + 0.4540196224982539, + 0.49542443367269284, + 0.41172333353430157, + 0.5655527717624992, + 0.35091940962711166, + 0.41040375770404025, + 0.36996424612362355, + 0.5620274690102021, + 0.46381486597565447, + 0.4246272592011066, + 0.4526916826329957, + 0.34439248096933495, + 0.43750099781222834, + 0.36758406126375104, + 0.45176748547064927, + 0.4822453973812701, + 0.36704579921416397, + 0.3465623331408789, + 0.4020401306508859, + 0.5209421000833968, + 0.4988270327275549, + 0.43810339174486645, + 0.5292477574055329, + 0.34381783039692204, + 0.4180089464233579, + 0.43543082629526, + 0.5840615198611738, + 0.4143304315487832, + 0.48707260870602465, + 0.5224169061061676, + 0.4914426770721485, + 0.47443819130651455, + 0.5059929060336875, + 0.41848194299583463, + 0.5416917751709962, + 0.6052600806803394, + 0.47397518543088857, + 0.4550221214810435, + 0.6007174144976646, + 0.45567305098776084, + 0.41543441629082006, + 0.5238956991835527, + 0.4579849326936323, + 0.557291601566468, + 0.5157644580697222, + 0.574486685995402, + 0.5235643984204038, + 0.5784757518325264, + 0.3771143180121184, + 0.5002793155811469, + 0.34371736722743523, + 0.5789218736715671, + 0.6031944717190088, + 0.4363314010678456, + 0.5400483259258544, + 0.546546034568991, + 0.36361558996215515, + 0.6047473676331951, + 0.4980419147893706, + 0.5686990224778705, + 0.5111650295491694, + 0.5677807439290499, + 0.5626251826156322, + 0.3692570359810935, + 0.4996160457293035, + 0.5993861226588986, + 0.3781336397090818, + 0.4796287500021098, + 0.41764636730704024, + 0.558457873530459, + 0.4336952337979916, + 0.36354081139064137, + 0.49577635830334876, + 0.5997234436182977, + 0.3833419758697108, + 0.35561128677037196, + 0.4595680432230874, + 0.46720292006924424, + 0.3608082940693741, + 0.48487006160398416, + 0.42110333203818895, + 0.5998259165935435, + 0.5770972028447763, + 0.37494788261952544, + 0.5660755327808039, + 0.45072271186855345, + 0.5569975939959351, + 0.5041257351341618, + 0.5402113941375282, + 0.4727194533216551, + 0.46117540710941907, + 0.49827888954305893, + 0.42684577829670395, + 0.5333083765592986, + 0.450629158285831, + 0.5385174774911126, + 0.5172283499706463, + 0.35829604400709725, + 0.4313168986634953, + 0.3647069651057848, + 0.41872348517273295, + 0.5541903570512077, + 0.4287421566382332, + 0.6066725398616125, + 0.48535929324288285, + 0.5044759227653379, + 0.5055803226242288, + 0.5940182450467646, + 0.5670321958466793, + 0.5843877152250271, + 0.5737302316867929, + 0.359460088370601, + 0.5750074927545036, + 0.5229223728348661, + 0.525623867329186, + 0.6040554795602362, + 0.3680555433511406, + 0.44309251089218693, + 0.49747153399776733, + 0.45223254007034897, + 0.4813330286071019, + 0.34769222207182743, + 0.43858346589417385, + 0.5462125600304433, + 0.3921608872345419, + 0.4252736727044042, + 0.48735035843839725, + 0.3919319875073238, + 0.4229385013730056, + 0.48923468898649775, + 0.5402259272232729, + 0.5880193197805855, + 0.3600559089058265, + 0.48415914104379704, + 0.34390882754128327, + 0.6020519347530171, + 0.4285075639376177, + 0.3733675752221049, + 0.40806757100349667, + 0.5600835276416463, + 0.4270187187628765, + 0.5561200081008018, + 0.49142282125712977, + 0.5205932278849679, + 0.5650620368971974, + 0.383138710273459, + 0.4008507333781728, + 0.6028197490899224, + 0.42895530474869714, + 0.3455640269514752, + 0.4624088890599434, + 0.5290348755870589, + 0.45173578784678936, + 0.5588767124120043, + 0.3700130358864547, + 0.4782073667698169, + 0.4200445703396176, + 0.4581896604709206, + 0.4427967544265796, + 0.5639366895262188, + 0.4928958248049241, + 0.4329847610061154, + 0.5367941504284734, + 0.40228817729076105, + 0.5369659580439285, + 0.5655691832654881, + 0.4881916405947886, + 0.5806028833843923, + 0.5239377008660213, + 0.40116096688369923, + 0.47020322822442695, + 0.5596187213443222, + 0.4858937015844428, + 0.365019502906801, + 0.39594394669596816, + 0.4629861989697638, + 0.4958554263705953, + 0.3648921494875471, + 0.48876063160793304, + 0.34960799191057845, + 0.566552390695838, + 0.4393016987762499, + 0.49784216718705, + 0.4724076711140998, + 0.5175845031088082, + 0.5673779869307186, + 0.34806867423039684, + 0.43664750887595183, + 0.5106061876771942, + 0.44758317148271987, + 0.5406325306481734, + 0.3458526180567025, + 0.52558942848519, + 0.3674678114050265, + 0.5895592042634485, + 0.5343730556540154, + 0.34241522376939365, + 0.6031524836911649, + 0.539488326702104, + 0.5976321727786149, + 0.43764683588953746, + 0.4457562392906118, + 0.3762688888752953, + 0.48433791270700943, + 0.37472883085236997, + 0.5127848846512508, + 0.36570113422386424, + 0.5435933980770954, + 0.4656150582366835, + 0.5533021824679818, + 0.5075451259884742, + 0.5382769478523386, + 0.4520249020213211, + 0.372360401958235, + 0.5718517062205781, + 0.56212588297668, + 0.524101147742825, + 0.36565966488040685, + 0.39790661343766043, + 0.45238730300529595, + 0.4215557840958121, + 0.4325427708147481, + 0.49989503391839735, + 0.5461496456582927, + 0.3513849223987647, + 0.5920244137098933, + 0.4491056571111683, + 0.5694116345689199, + 0.562649323268183, + 0.5577054727513088, + 0.5172941976937043, + 0.4095836564399813, + 0.47175239211708675, + 0.5520720570796005, + 0.5637401473073307, + 0.5704998554569636, + 0.5463175841589537, + 0.553410900995879, + 0.342826102887559, + 0.4255966133698375, + 0.5195661229166846, + 0.6041520709927526, + 0.5334347758900477, + 0.3982809324813973, + 0.45656108486365854, + 0.5048319172463278, + 0.3471281060371162, + 0.5573155572364891, + 0.5878211371113131, + 0.5632622163543164, + 0.47102101058494644, + 0.5304900710721557, + 0.3943490983760981, + 0.6026584540976604, + 0.5027188209571614, + 0.38669932777478516, + 0.5098948370341785, + 0.5955773368924072, + 0.47366901174210485, + 0.4984146443474535, + 0.43388579675386507, + 0.5725548574964232, + 0.4814306491024427, + 0.38088407951730496, + 0.5284153682387986, + 0.4868438330754675, + 0.5159301975718916, + 0.3409034339487584, + 0.4560692175084253, + 0.5378727680804956, + 0.4616437563550293, + 0.41880877994646243, + 0.4712516632079647, + 0.5551301940454775, + 0.40558349684862394, + 0.43451035483935835, + 0.43677970771060837, + 0.39848359912597353, + 0.3655010333607104, + 0.5211479780547938, + 0.36593816784253397, + 0.4200227996482171, + 0.5586375421430192, + 0.3811451623076212, + 0.455671873836934, + 0.5379643385873132, + 0.3851014377092196, + 0.4513906341588465, + 0.4947886416224355, + 0.4099451136431704, + 0.5717642037331849, + 0.5446692987385748, + 0.5147355806201437, + 0.52461770171248, + 0.5038610426983585, + 0.42499711174396415, + 0.5835852220380184, + 0.37138976612348956, + 0.49971169729386716, + 0.536588472706207, + 0.5967979804195329, + 0.35863147573086396, + 0.36565371490260484, + 0.5873672243629264, + 0.3690016482192036, + 0.38082632780464437, + 0.45740005881091916, + 0.3755906879636911, + 0.47992634818451474, + 0.36344064319502944, + 0.4154486612861844, + 0.4612961295521035, + 0.4303868674515872, + 0.4356531256192087, + 0.6023095930929667, + 0.4941947501228827, + 0.4852175293499573, + 0.48939974004316644, + 0.4683801830556315, + 0.6017693888901976, + 0.42471361561447835, + 0.4389681923840648, + 0.5840023348865531, + 0.5984206236845462, + 0.4262435913996844, + 0.4297562809081923, + 0.38392223550469956, + 0.3477721778336985, + 0.5361326773915226, + 0.5022498445678856, + 0.4362531519411411, + 0.3999986129061441, + 0.5429349159337243, + 0.3458400573355226, + 0.585710067345121, + 0.42136472398450303, + 0.39554260702791433, + 0.5906177326724089, + 0.43455383343691933, + 0.42001725653099703, + 0.5860014725854814, + 0.3455577414795612, + 0.38717372224781776, + 0.5924424788660981, + 0.4993672504784784, + 0.5050506992888779, + 0.6031179940300071, + 0.570140133446224, + 0.4572558286251834, + 0.5318683005310849, + 0.4109621658358643, + 0.5905781262479999, + 0.58077252668856, + 0.5767278372824144, + 0.3842403746807115, + 0.601242812755018, + 0.40055683907139944, + 0.36021311711170195, + 0.34350822439067447, + 0.40426421415919567, + 0.51466232179607, + 0.39250581060215567, + 0.38187348620284683, + 0.5174849658788863, + 0.5180765129420417, + 0.5853854364410551, + 0.527402031111851, + 0.5877559275113711, + 0.5767727872850834, + 0.5818896816600602, + 0.5969519658012206, + 0.4803385161120309, + 0.584207945429351, + 0.5937387338960768, + 0.43114666240668237, + 0.4173854441837846, + 0.43525139667319046, + 0.4026618567735406, + 0.482243217207434, + 0.5150571057136888, + 0.5636333381914264, + 0.47181902556097377, + 0.5266145015840384, + 0.3656633235432021, + 0.3816279303351911, + 0.5924915637636213, + 0.5077142557855513, + 0.5242538692837724, + 0.5582099140189751, + 0.5390990145427298, + 0.5699443460401585, + 0.43545541795029663, + 0.517886888070764, + 0.5103985672893961, + 0.4553408916462779, + 0.36674023513969195, + 0.5542372958090295, + 0.38694112095324995, + 0.4394978465896851, + 0.5141891988411978, + 0.49689943849386853, + 0.4804903388262922, + 0.5551343230424937, + 0.35192853779223837, + 0.4001626720759709, + 0.37069077739587314, + 0.5867694482361421, + 0.49765564858833566, + 0.5700707484206068, + 0.39664341074338394, + 0.45242336978221964, + 0.41143949808597274, + 0.548210563084936, + 0.531583712603067, + 0.4957087669462903, + 0.5444753544340261, + 0.4407876884547026, + 0.5362198582711942, + 0.3995295587248442, + 0.34854244840153303, + 0.3714284828416545, + 0.37128704193864936, + 0.5150938887977593, + 0.3679680799645099, + 0.4727455710272873, + 0.440895853136057, + 0.43573937907781796, + 0.5690186593413963, + 0.5683022081837414, + 0.5711851431735742, + 0.561889379993446, + 0.4382381353641992, + 0.357175846820834, + 0.48184732007769177, + 0.48959741823454006, + 0.3976964143536792, + 0.5413700775630486, + 0.44603669298668147, + 0.5575093466539597, + 0.5759501843300838, + 0.47089703885608536, + 0.4576481516225741, + 0.44649076996060016, + 0.5880840745162972, + 0.5762730322910441, + 0.5065214547646866, + 0.43339409755090114, + 0.5975890437096028, + 0.37129697382075844, + 0.43055161821694843, + 0.5905503858744674, + 0.388854593693407, + 0.5668736610733817, + 0.5515749981388804, + 0.40706471995567556, + 0.3502994417283673, + 0.4508369655300074, + 0.4506269194521547, + 0.5194815464266922, + 0.5695055032868659, + 0.3930679862345533, + 0.40052819933087125, + 0.6047863916946136, + 0.35569004672340504, + 0.4433654625988125, + 0.5181739757852903, + 0.35694959152255323, + 0.4142641867597158, + 0.45083266277075773, + 0.34620199442476235, + 0.43499649585099437, + 0.5480474644732848, + 0.35269147557840363, + 0.5481515657522653, + 0.5389910370012247, + 0.4822044154136622, + 0.468151991414449, + 0.35933451853204235, + 0.5293301321840558, + 0.4918205273176812, + 0.5525423992205885, + 0.3445728307874536, + 0.4600437703664185, + 0.4531674009316183, + 0.5244210942776948, + 0.4429456859254012, + 0.47494113906087865, + 0.43614472578259905, + 0.47497018069638786, + 0.3815841010711111, + 0.3836194076478524, + 0.36513381839740205, + 0.47095072903990665, + 0.4406932220600682, + 0.44705133732263597, + 0.434485134308049, + 0.3905251669072398, + 0.5963936231540962, + 0.5774346604026814, + 0.3697529337010669, + 0.3979327316297813, + 0.5836098009393933, + 0.4329320991345441, + 0.36959571961303234, + 0.3675015679422302, + 0.3938217962774474, + 0.5300071892116893, + 0.5138783614097975, + 0.47154607780997126, + 0.4463348542341557, + 0.4965455177958962, + 0.5772358861063113, + 0.4432138698142227, + 0.35227460650078624, + 0.3533142638430749, + 0.5464167343709512, + 0.44928888430556263, + 0.5126934806894776, + 0.589993442505031, + 0.5081571705809269, + 0.5433456316360263, + 0.49043538133217407, + 0.38017202006235884, + 0.43654149911389006, + 0.3793651681897868, + 0.38151228093507655, + 0.5332002179974936, + 0.5089177654644226, + 0.5700581381281749, + 0.46703956947001485, + 0.5214227017731614, + 0.3472858082360989, + 0.40117351082777963, + 0.3630934365929554, + 0.5645231798164867, + 0.5744940120643287, + 0.6066662376181085, + 0.4127692014038956, + 0.4785979860638449, + 0.5871894278605647, + 0.4029527364817791, + 0.3780905004869681, + 0.44219801807717, + 0.5974364773569296, + 0.469457899358338, + 0.5955015639393018, + 0.5901560842834087, + 0.5642393447272207, + 0.3499933857863502, + 0.6030229136683062, + 0.34185699589264434, + 0.389499708592053, + 0.42704361003387065, + 0.5381973769710526, + 0.563367342750058, + 0.4475014364143385, + 0.4690846572296624, + 0.3568869397905371, + 0.5075145053452167, + 0.3728177124197881, + 0.4113246222168306, + 0.5085539903464926, + 0.3525915309708196, + 0.5380302498920292, + 0.41291089844232204, + 0.3577458690828222, + 0.4377909249580116, + 0.34955937432682305, + 0.5166671524056243, + 0.5883804906409171, + 0.5027459519767858, + 0.4457200531120105, + 0.44549725746013347, + 0.34979952807115056, + 0.46863153085403575, + 0.49903095618170845, + 0.36606014990888647, + 0.5903941265627326, + 0.548117931968185, + 0.43396967142961324, + 0.3641551166131207, + 0.5688856782718663, + 0.38910355504639277, + 0.45998889965437734, + 0.34139331944112483, + 0.5683517703892648, + 0.5874492933185416, + 0.5470498563043013, + 0.35986508461983047, + 0.5137192607248188, + 0.3901621191655087, + 0.3692500726123208, + 0.4036059557279845, + 0.47162556139481027, + 0.5982376791508018, + 0.4716336119866198, + 0.574337095809456, + 0.40207124670766786, + 0.4601119308621689, + 0.381015174876138, + 0.4574311717413131, + 0.4188863710707065, + 0.4521973692795802, + 0.44508251075240113, + 0.5983626761901739, + 0.398624392527328, + 0.3957109344590092, + 0.3821304914705967, + 0.5476669365147218, + 0.4121818398587784, + 0.5881618525073584, + 0.4194602619024192, + 0.5374228876403213, + 0.5677951681126381, + 0.5277292794422975, + 0.5145737830205208, + 0.42800106522486525, + 0.5255608407999002, + 0.4273271994528143, + 0.40749624570427445, + 0.3998876750953001, + 0.4714843689694087, + 0.354121638891267, + 0.42384069316731704, + 0.5714953026658576, + 0.5575541456172901, + 0.37145020552999664, + 0.43504187662142874, + 0.4407236929707368, + 0.45842328772325397, + 0.5211857192663406, + 0.5324902035307142, + 0.5414192247121028, + 0.5774103195542553, + 0.5733414024202672, + 0.4038472743174902, + 0.3812371511033552, + 0.4425202940384548, + 0.5964265254590978, + 0.5840680838022165, + 0.5991792019266406, + 0.5156430406820665, + 0.47939831958903206, + 0.3887283628090319, + 0.5790277110575255, + 0.57801725751734, + 0.4433228199419039, + 0.4713900596088169, + 0.6043557031977409, + 0.3502814209274927, + 0.5566321855954661, + 0.3835650242384078, + 0.36566350196533576, + 0.474989559921265, + 0.4529110958193883, + 0.6062372260507487, + 0.46083736495472816, + 0.6062127015813248, + 0.4377688898584898, + 0.5551403250673934, + 0.3995512312300459, + 0.4604005180761992, + 0.4273295328599033, + 0.3631495960769759, + 0.5162970209701361, + 0.521325568162219, + 0.411529185936083, + 0.5330699093913727, + 0.42676211702059164, + 0.4619149753539925, + 0.5784511330591268, + 0.5407101080507138, + 0.5253272989604495, + 0.5369198054541772, + 0.4013412648674857, + 0.39107887671715724, + 0.4054912895521653, + 0.42703288498803416, + 0.4958308912252307, + 0.5965458080578074, + 0.4839946699986284, + 0.5364755138070304, + 0.5560537224176804, + 0.4210829548956295, + 0.38944307840944725, + 0.4748973088116586, + 0.5180758435461542, + 0.4723194295437103, + 0.42414170256388384, + 0.40082337890387676, + 0.466430972604146, + 0.5211067513464067, + 0.571760619451934, + 0.5868770845276051, + 0.5976977604869778, + 0.41870515793495444, + 0.47157242479704864, + 0.42048573119433685, + 0.47129767082589125, + 0.45050175174797935, + 0.4578374490780328, + 0.5704646368619033, + 0.43397166522973546, + 0.5668399175770066, + 0.36563803737028966, + 0.5624490378382778, + 0.3831607600926631, + 0.38377805820981387, + 0.6069129661939516, + 0.4204855186366302, + 0.4725872560948969, + 0.5942599101750501, + 0.5964913571391558, + 0.552153607447438, + 0.5345768710123384, + 0.5509380132145133, + 0.4478094125742072, + 0.47992685502273236, + 0.4918387520564884, + 0.40655296574534344, + 0.6032892859373337, + 0.40170494552588026, + 0.35393576320652564, + 0.5941840476244853, + 0.4668984292308642, + 0.4359776468353096, + 0.5697811618600199, + 0.3432293215950925, + 0.4206352370467111, + 0.355214362164549, + 0.3872671515077638, + 0.48439397922880795, + 0.42229664518451493, + 0.34291235768405176, + 0.6000929221858134, + 0.5396789270573518, + 0.3779068474109781, + 0.38587871048232236, + 0.4279876678646749, + 0.5416679695366442, + 0.3601083011053589, + 0.44005386599393204, + 0.4910213271885211, + 0.4636678724614484, + 0.5845740483743382, + 0.474230263010182, + 0.47364289338845733, + 0.4002599702424151, + 0.3982839851334967, + 0.4407340638654539, + 0.40415959225706616, + 0.5952155668475108, + 0.5096063098008807, + 0.3836381108006843, + 0.4370080011538227, + 0.4046069136065773, + 0.3810701509709522, + 0.41709308939612677, + 0.582652272165155, + 0.35597351162161806, + 0.5103572653387155, + 0.4686358136251968, + 0.37573524634998307, + 0.41173245824528387, + 0.47535681365027516, + 0.4467799291116489, + 0.543105421599735, + 0.5031893369128076, + 0.5015801193796757, + 0.4413124840412973, + 0.5404332219747517, + 0.49843528559711636, + 0.35853161455181504, + 0.4286966138533015, + 0.5109215734884437, + 0.3755380029169503, + 0.48768232797104694, + 0.36729109943254645, + 0.3858414582431581, + 0.605841659887945, + 0.40128511846321163, + 0.5461065028361636, + 0.5401197283074233, + 0.5002079725243912, + 0.5681896095256078, + 0.5896894395784137, + 0.5455403900758713, + 0.5224744447392173, + 0.5003262418875674, + 0.4639850764903982, + 0.47538704022230105, + 0.4204326527833532, + 0.4359724784297591, + 0.5690844163317792, + 0.3877210718302619, + 0.3886932072336763, + 0.5669233017571499, + 0.581882439836231, + 0.37306801926872946, + 0.5213067842721167, + 0.3788056534354651, + 0.5258205088957082, + 0.5887920388062594, + 0.4287802738985794, + 0.5207521292111031, + 0.40002288801776437, + 0.36445535376609345, + 0.5487790624052529, + 0.47840887659460946, + 0.5779748039330346, + 0.4181900668535201, + 0.5897117342421704, + 0.5947784789180255, + 0.4111880888177135, + 0.533290204713131, + 0.5243048954583456, + 0.41758470452940655, + 0.49729672695167937, + 0.3794110405103833, + 0.6026404460188377, + 0.4646859782490979, + 0.47850143895117325, + 0.4346691909622664, + 0.5160374010799846, + 0.4160922425802653, + 0.37629639770629547, + 0.5210144246771757, + 0.5805594963423566, + 0.3465032819848858, + 0.3467111778626129, + 0.5606132528715901, + 0.5898612182041103, + 0.48954384482125723, + 0.5498191779346736, + 0.4602197980647327, + 0.4495642330630609, + 0.3678680716556008, + 0.36622785828181653, + 0.45803917338777284, + 0.5691407748152236, + 0.5663513036573249, + 0.5175707224199956, + 0.573143108941977, + 0.5360058469741674, + 0.4143760581596253, + 0.5083069936631057, + 0.5208780699994776, + 0.585888960739959, + 0.48230585601314396, + 0.476327830239332, + 0.34602968501691844, + 0.3693312791539548, + 0.5114317826309651, + 0.5284399369064399, + 0.6073883480412614, + 0.5424380511999232, + 0.4773155449660213, + 0.5647220260128138, + 0.44810391701323254, + 0.4125477552730398, + 0.5693496340278668, + 0.49217467854028374, + 0.6009529922026036, + 0.5245060854009949, + 0.43217751465723486, + 0.40117173395518047, + 0.46817516801214143, + 0.40843432404281094, + 0.49576950164331934, + 0.5232494570070706, + 0.48640912038487427, + 0.4407309712084316, + 0.5935512375286917, + 0.6024286205839332, + 0.4383746007715627, + 0.35377591492877997, + 0.5429421601181543, + 0.5545601379995072, + 0.41355463277432275, + 0.3427438928789937, + 0.5529839083804439, + 0.47753975660995635, + 0.5182356401373046, + 0.44984379736644137, + 0.38158050444554753, + 0.35089126511001734, + 0.43670773737018415, + 0.5144892868730309, + 0.4796643107759119, + 0.37675697483409093, + 0.5185126930837999, + 0.4404928288973715, + 0.5543321331263863, + 0.549049524633487, + 0.39917770001123576, + 0.4191751935004053, + 0.36505527260429954, + 0.5118052433877915, + 0.39183837394041177, + 0.5062444317542475, + 0.587701452812981, + 0.6030429503483237, + 0.46263875389781445, + 0.37672882232936167, + 0.503650953953524, + 0.3425711395249922, + 0.5081825000715521, + 0.4175024580726619, + 0.584463329400742, + 0.43038328103323825, + 0.46016524881188287, + 0.38158492466439614, + 0.371849368096073, + 0.5356287973253003, + 0.37841142063715727, + 0.3907784183564876, + 0.42841232785362554, + 0.41630902215859805, + 0.3606987524405799, + 0.45378203671036704, + 0.407117955734074, + 0.5706907618669468, + 0.48333574165558085, + 0.40059323878244524, + 0.4404208948834411, + 0.5751270515308207, + 0.5891131236689426, + 0.4218469856569072, + 0.41527848115622407, + 0.5585607772341628, + 0.4910677643379465, + 0.4606655373564502, + 0.3874241649166903, + 0.5361418979673104, + 0.5541114987178543, + 0.5519753767815289, + 0.4960662563391007, + 0.5994383995595594, + 0.5748209067914986, + 0.47345266621037, + 0.4666972181531208, + 0.4204484336728031, + 0.5997394004434058, + 0.4305944683983949, + 0.5273135288434979, + 0.5620858740896157, + 0.5257199490998822, + 0.3776345073250535, + 0.558225235787473, + 0.46723283550841876, + 0.4325607363784433, + 0.3723276709066616, + 0.404605294649374, + 0.5834366988449935, + 0.42457033178019615, + 0.553031869162783, + 0.5729033552503078, + 0.49167368691694624, + 0.4511260148124397, + 0.3532290512025263, + 0.558711293281765, + 0.5785771941912105, + 0.45893701272541837, + 0.44580654079920917, + 0.3941468529623248, + 0.4174119400836544, + 0.5227834167372666, + 0.5467960885767733, + 0.5612900524320981, + 0.5612399453320689, + 0.5532867850256648, + 0.3862881564007677, + 0.5362950077233517, + 0.5844258607490441, + 0.3885821758413086, + 0.5484825671317772, + 0.3866782070720891, + 0.3893912560503786, + 0.4419469979178036, + 0.5264998938548889, + 0.5662070165423535, + 0.42473948006847995, + 0.5688812791317233, + 0.40200618805945393, + 0.3836022866938881, + 0.39741425139103265, + 0.5671975871222379, + 0.5454008794503439, + 0.35408775083511607, + 0.3593925268086878, + 0.6071152824147541, + 0.3494843397801426, + 0.5083096297156754, + 0.3650195868390244, + 0.36715665889095506, + 0.3590501595051067, + 0.5590917342228394, + 0.5224384488456307, + 0.450734119810024, + 0.5571365391002817, + 0.5331296102050722, + 0.43599747274555334, + 0.45620696584466, + 0.4038502434300028, + 0.4540866261299499, + 0.3514656632103268, + 0.35676845245647526, + 0.459989935978494, + 0.488829062886094, + 0.4342691962254997, + 0.588240456663972, + 0.5481865817103585, + 0.5186891097129764, + 0.34090810719554143, + 0.4023528455617401, + 0.44847995895697784, + 0.37073725211438474, + 0.5132161897157604, + 0.5220094455007769, + 0.5131175489600297, + 0.44907216136827854, + 0.4714329237465483, + 0.5177235019346635, + 0.5939385759077853, + 0.5534036659446222, + 0.5383987708601117, + 0.49627327311124614, + 0.40363457611947545, + 0.4524393673914104, + 0.3754049436495784, + 0.5632522491275106, + 0.3525310608627026, + 0.3636537531160835, + 0.4339491433989592, + 0.46380312294220405, + 0.5233192313668771, + 0.41557374369200023, + 0.6017510639672878, + 0.5624086592935513, + 0.5486718541717376, + 0.554384807000126, + 0.34530876575406794, + 0.5566658218906735, + 0.40992440521803086, + 0.3420295095936165, + 0.4272591072683827, + 0.4379236152997013, + 0.5735181466728441, + 0.5540274383455197, + 0.5950063944469508, + 0.5508139750390755, + 0.5571909264198418, + 0.5103801232568488, + 0.43199907652290054, + 0.6064174194892114, + 0.39983366988841457, + 0.42740671801269225, + 0.5603295064586449, + 0.45116374041482643, + 0.4220991580032228, + 0.5815112310261376, + 0.3935500583393764, + 0.3637450042715051, + 0.4004253109645629, + 0.5488808288569419, + 0.5069151822931237, + 0.46405300047841747, + 0.5988968297932331, + 0.5780611781059347, + 0.4689664033663137, + 0.5304900448113623, + 0.39655055999039873, + 0.5101546834723075, + 0.3736721700132078, + 0.448941712498251, + 0.4621207803887918, + 0.5830368264032357, + 0.5492617445654724, + 0.3898079794098416, + 0.5936588664409554, + 0.4712876686345207, + 0.5792779087788412, + 0.4433789946388818, + 0.47726034496035996, + 0.5598440957405566, + 0.5741240350225446, + 0.49432427309369287, + 0.5354588792698488, + 0.37781732732953244, + 0.4069340987756215, + 0.5108348365105546, + 0.5290715875982267, + 0.49430291009409544, + 0.5446506948650276, + 0.576644721594663, + 0.4135877867232166, + 0.39712622137208925, + 0.5027435052680292, + 0.43143970092347034, + 0.4052982561729646, + 0.4352938128921654, + 0.5521213674947341, + 0.5497034279113481, + 0.503552169437041, + 0.44221681964933446, + 0.5806079041716172, + 0.4932912573115048, + 0.4179250226693302, + 0.6074712677406384, + 0.3713451266081315, + 0.5420948958744889, + 0.5343785186325769, + 0.5605371042843921, + 0.5326010017155108, + 0.5504934960158249, + 0.5595582339089981, + 0.5814011323600579, + 0.5087620016345406, + 0.5586422012570111, + 0.4138948188581598, + 0.43814987254907656, + 0.5830826043736005, + 0.4547230010899324, + 0.5833631491219198, + 0.39275540949721094, + 0.3773016582023501, + 0.37266213310624685, + 0.430808403358036, + 0.42381145482254495, + 0.4580162963035302, + 0.4547745716303093, + 0.34534295103486934, + 0.37860558139247596, + 0.4692119219935719, + 0.5125162922241411, + 0.522342334213131, + 0.4987162252533879, + 0.5766515985328261, + 0.46164843214726525, + 0.4684073312065953, + 0.4556593378075725, + 0.543024696363872, + 0.39801617597583117, + 0.5763189837823455, + 0.4298212958312958, + 0.40327787932447795, + 0.5370990791196664, + 0.585534910093353, + 0.5185304328086593, + 0.45593923429914124, + 0.3806944350646748, + 0.3685764421023524, + 0.3772735377180935, + 0.42593836600757934, + 0.47135220517077314, + 0.37325369365516947, + 0.37436717587975493, + 0.5863053316417584, + 0.35661734801324113, + 0.5089293274789144, + 0.5829615809622218, + 0.38106238748627863, + 0.5857853506667445, + 0.5401125291007263, + 0.5136479941510288, + 0.5529609228766391, + 0.5430907058200701, + 0.6060734135981808, + 0.5723121154362468, + 0.35359871084715994, + 0.4334117558922804, + 0.38428711336038895, + 0.3717780339154314, + 0.49471636205615077, + 0.4024902047380177, + 0.5811671013327211, + 0.3797670452441879, + 0.47109852489709547, + 0.3461616202579337, + 0.5350342011138994, + 0.43791075754662856, + 0.5460511369323462, + 0.565216562209372, + 0.5094399963926688, + 0.48578590233197616, + 0.5872539139141981, + 0.4008270023886836, + 0.47117734922044624, + 0.4191038584462795, + 0.6056977200396751, + 0.45184791262116636, + 0.3590284770162765, + 0.5977352616069678, + 0.48525292206730575, + 0.6074516453584541, + 0.46554436039050795, + 0.42369881497364087, + 0.47067559085924426, + 0.45267008942262676, + 0.3919739301044632, + 0.4871073723684186, + 0.5384676120684293, + 0.5590342551189883, + 0.5686301309942984, + 0.52629685784497, + 0.5658232903990247, + 0.3778350610321216, + 0.5520011665434325, + 0.386404602767803, + 0.4234732241639996, + 0.4778664520850671, + 0.4544024307184627, + 0.3818238910374095, + 0.39730468286160614, + 0.5668049535935197, + 0.5226206358163625, + 0.45572419171845385, + 0.4813346071728015, + 0.469579768355647, + 0.41993797391417165, + 0.5783733047584265, + 0.5668971346845088, + 0.43070561150833053, + 0.36450953585223383, + 0.43443043658134256, + 0.4712016693200071, + 0.4840456501348993, + 0.5248998190113422, + 0.44949494709967536, + 0.3956778449278586, + 0.5121829942018588, + 0.4618384048227203, + 0.5267347925107942, + 0.44462289243993464, + 0.4526550525279818, + 0.49890116975383214, + 0.5107045371927033, + 0.5253897366076823, + 0.5620774551655525, + 0.4883129203781044, + 0.38709467686968724, + 0.6005200160970801, + 0.3542266094508042, + 0.5751492107194056, + 0.48441701434601725, + 0.43265617648849264, + 0.3544674523618376, + 0.5943533675804176, + 0.5267761342415445, + 0.5763894858341427, + 0.5271241213380121, + 0.3592191830760683, + 0.4178738302486784, + 0.40709670748947496, + 0.35125863735653623, + 0.3788183429582538, + 0.4898196525053947, + 0.3555337909207506, + 0.44470936859570864, + 0.5432514537749391, + 0.3741496066243864, + 0.45725800067355526, + 0.34547925435923665, + 0.487788376849713, + 0.4613572977521411, + 0.4826442900497505, + 0.5628003781792423, + 0.35619022713522575, + 0.3812124910163937, + 0.38505352256221265, + 0.605790217577272, + 0.349416815866856, + 0.5187615460499315, + 0.46146866555680205, + 0.40135402735078757, + 0.460207478636744, + 0.34261312354624274, + 0.3799903297236374, + 0.47726941625831876, + 0.5913398998146797, + 0.4045854185359133, + 0.5891278346959188, + 0.4374151514890701, + 0.35738763295966813, + 0.3525248351055207, + 0.5533867500116006, + 0.49969417896642854, + 0.4643648810054173, + 0.36174877833335933, + 0.5019653880239938, + 0.4339811812168522, + 0.37480910014627, + 0.44597264843567563, + 0.48693957904059054, + 0.5306593140284617, + 0.4380831865954437, + 0.39336447645837225, + 0.6015675148200721, + 0.3468939079020783, + 0.5369352234992394, + 0.39331857395573333, + 0.49856014567735996, + 0.44201321908269364, + 0.36424416828636896, + 0.37125342597053046, + 0.5119284690721071, + 0.3623307521667819, + 0.5417042633164135, + 0.3475571179231943, + 0.47455316314966767, + 0.3711803989478287, + 0.42144550198528236, + 0.3756043102315688, + 0.4702163707253253, + 0.5642207492291764, + 0.5564988198473257, + 0.5260612615880274, + 0.3880994434140918, + 0.535422547236674, + 0.37233737245658316, + 0.4373204698554875, + 0.6054412931823943, + 0.3987251168783118, + 0.5432847947572155, + 0.3731927250900135, + 0.36603854193552193, + 0.5370123072651758, + 0.3856768385267346, + 0.5495487397370384, + 0.5043403628210006, + 0.4581377671788185, + 0.5413836213428785, + 0.602963603814641, + 0.5309843474396683, + 0.5658246692115715, + 0.48736395427555856, + 0.42581962364287657, + 0.487307793214388, + 0.564999668877728, + 0.4586417566840275, + 0.4094908126341903, + 0.3615113589044683, + 0.3635721585045815, + 0.6038223124850606, + 0.39906667677603597, + 0.4868372785937547, + 0.5123389097053194, + 0.45724730132817104, + 0.4955397216362575, + 0.5186824150125873, + 0.4845731459853546, + 0.34536041129603506, + 0.3823797116496993, + 0.44284952862601934, + 0.36979732736235105, + 0.5633155759258658, + 0.4174525925399927, + 0.5860325774541582, + 0.48252953419758404, + 0.4340454697873471, + 0.5664889913720148, + 0.47043422500997956, + 0.5720377897081493, + 0.5575912027978682, + 0.4041122207792169, + 0.5480704318276348, + 0.5993143392110265, + 0.5140063492175228, + 0.3440658798309921, + 0.3766118331037919, + 0.5420509234717317, + 0.3965165047105589, + 0.3749204164081752, + 0.3767200061304764, + 0.42861525502901593, + 0.568995282406549, + 0.4220049137054084, + 0.37252167363623795, + 0.49156356885332636, + 0.47256357663975285, + 0.46439726772536516, + 0.4569302661208675, + 0.477315497920905, + 0.6011464110433786, + 0.4744513124074101, + 0.36697619133648485, + 0.5243914562739552, + 0.4587408969051862, + 0.4152054181292112, + 0.5688709169958153, + 0.5100609250880032, + 0.5423260458282435, + 0.34870370541565143, + 0.49521777455155036, + 0.5192797796028793, + 0.345825474050742, + 0.4845598745831817, + 0.6056972958128469, + 0.38222051289887793, + 0.45850212267175217, + 0.5728764779368047, + 0.3432042206460658, + 0.3946362717965675, + 0.5964822397974529, + 0.5205247012053839, + 0.5222913233314215, + 0.4858988814106598, + 0.41293500764055424, + 0.5597007901531723, + 0.42387325384242514, + 0.5707503916172328, + 0.34774035829739136, + 0.4961642287657727, + 0.4523986539056766, + 0.37848478059649704, + 0.5914172433078867, + 0.5185779384656706, + 0.3417239523881096, + 0.45933736525567714, + 0.598044549514267, + 0.5492443365516928, + 0.49950748379851073, + 0.44052048749180595, + 0.42578074689108575, + 0.5950107951993762, + 0.46565915059333834, + 0.38461608738700637, + 0.4742198602502873, + 0.5643380004927909, + 0.562810286934021, + 0.5871233662879286, + 0.4260410132317157, + 0.5622333803404066, + 0.43805177066293227, + 0.44733077860638537, + 0.3553112781436645, + 0.4629947471165362, + 0.3952475805898368, + 0.4490863361349348, + 0.5023014456892471, + 0.46096292477794654, + 0.37366891254694107, + 0.5354559005676247, + 0.4160530304845248, + 0.5402906947487107, + 0.5862305176955951, + 0.3438938743729029, + 0.5633559367745218, + 0.40594160444474786, + 0.463197916087352, + 0.373099243965012, + 0.5833678416147268, + 0.48940699474056604, + 0.48545005838357946, + 0.4700870141287482, + 0.4010501391416275, + 0.41597629367627376, + 0.490828661028552, + 0.3910772634614243, + 0.54473099713442, + 0.4410369789821863, + 0.411621192453115, + 0.4624060786925399, + 0.4458801651470508, + 0.5118697435249231, + 0.5673378636377864, + 0.4203150015749538, + 0.48537321685543144, + 0.4801750821476951, + 0.38080442938105796, + 0.3588777772135786, + 0.36841217785384917, + 0.5591745186287411, + 0.3472744728242063, + 0.36143774429260433, + 0.5259306376906994, + 0.39945433141380504, + 0.4387440245318839, + 0.5321107941197453, + 0.41972986722602307, + 0.43624407088624795, + 0.5685755134068498, + 0.46780538233041075, + 0.5465036246783694, + 0.5630948922159955, + 0.5624489779020856, + 0.5836333159500753, + 0.4895182263306348, + 0.5004190392670085, + 0.5645945443282065, + 0.4397684504985465, + 0.4327061591036255, + 0.35526256602173817, + 0.3567453289330194, + 0.3870239327049966, + 0.4714327190300249, + 0.40793212599875783, + 0.4994242961596933, + 0.41721716827917155, + 0.5304972725934265, + 0.36611298709491263, + 0.3900569408204053, + 0.5779215888303988, + 0.3631598540778635, + 0.5858011115453455, + 0.4156309626226138, + 0.4421940303825647, + 0.5902637115669084, + 0.4581720060192019, + 0.48960709204416875, + 0.49380047965089235, + 0.47349646675537005, + 0.4156223997113885, + 0.5512015787134226, + 0.46345612526310626, + 0.45420131688038157, + 0.38141296035800953, + 0.3453387383049242, + 0.5502050387866538, + 0.4168427098575536, + 0.5114204717791284, + 0.4216996498857426, + 0.37618708303066256, + 0.39587223349160444, + 0.605178727200705, + 0.5103136253606742, + 0.47853255003690853, + 0.393270189752326, + 0.4495474067028054, + 0.41455517453612883, + 0.5076256399232619, + 0.5826167187109501, + 0.45808567946618556, + 0.47295216542000545, + 0.4358469669028647, + 0.3437843154743614, + 0.595704334358534, + 0.5266303594222764, + 0.4276912208830249, + 0.35376671968723306, + 0.3554343983578698, + 0.5090485371041243, + 0.4507220779131251, + 0.4582943396209131, + 0.5727921932241615, + 0.4184557386960739, + 0.38038264027941904, + 0.5581536417772492, + 0.5736292603198803, + 0.40764186869040614, + 0.4795777600197143, + 0.46057219979427866, + 0.45980780651274744, + 0.34125017957687426, + 0.5557572441087544, + 0.3863343629226124, + 0.5822267562765219, + 0.45036503862155597, + 0.3572207792805657, + 0.4207195745812701, + 0.5311566928713617, + 0.5771569069121293, + 0.5766503165681591, + 0.5937105908978431, + 0.6062578265968763, + 0.4300495119556589, + 0.5718327131212645, + 0.49797809825207573, + 0.5931617335206425, + 0.4824855506923792, + 0.38905472348848547, + 0.39779810457366466, + 0.4118616379657478, + 0.40282731184572607, + 0.3690801718713093, + 0.3645229178623783, + 0.5943183582779802, + 0.5601506661992932, + 0.3576523297314117, + 0.39339095793506484, + 0.52361379843068, + 0.4809908615442905, + 0.430380422271326, + 0.38750512193317715, + 0.4513720856185813, + 0.3891027141387473, + 0.48051386032249543, + 0.4328898885406558, + 0.6073883956200621, + 0.4911960243160319, + 0.4182481668815258, + 0.3996570381056072, + 0.3629742392178112, + 0.35407228699226706, + 0.526257153123645, + 0.49727549839638163, + 0.3505884404194626, + 0.5464131423059072, + 0.401578968126833, + 0.4460925795234328, + 0.5430197564409367, + 0.5868127631694509, + 0.5467089222005685, + 0.4695355884362545, + 0.5778747580844565, + 0.47755739665333274, + 0.5091305484255901, + 0.48178006378560767, + 0.5037550360444328, + 0.5325835217792009, + 0.36865123226193114, + 0.5987902895503201, + 0.5363448868577034, + 0.5841345722697826, + 0.38927862631418986, + 0.50638699124064, + 0.4092866617748159, + 0.4149012017203894, + 0.42436868008612333, + 0.42850269749068204, + 0.602894826576039, + 0.44385424335993046, + 0.5087026894452966, + 0.4638233875796688, + 0.5520345715239271, + 0.4840530702083258, + 0.5201212543308893, + 0.460932243243816, + 0.5396020502973393, + 0.6014794494157422, + 0.5651745250152241, + 0.5226558398972037, + 0.5084704805565091, + 0.5833440726604656, + 0.34527702259951165, + 0.5075207810611682, + 0.3716485419846491, + 0.41360092780997165, + 0.5861284742657106, + 0.4824402906830467, + 0.46176870178965923, + 0.39301447225806735, + 0.5976338737534614, + 0.4608178651477017, + 0.49779619214539705, + 0.48410869872485257, + 0.4670482180379872, + 0.39104057548519827, + 0.5979735803433226, + 0.5854476759211044, + 0.5995866442152274, + 0.46991352159076116, + 0.5788644426285883, + 0.3793654251586627, + 0.584690037396948, + 0.39188825254003357, + 0.3815436693719645, + 0.5651610131753612, + 0.3640011107124968, + 0.43962302814442733, + 0.4548295958177012, + 0.5743829115783157, + 0.5528261771213715, + 0.3680644427274761, + 0.4949813650808912, + 0.3820539433693031, + 0.4979357139668468, + 0.5301466948678694, + 0.4826985315880906, + 0.5509636012481239, + 0.37412627669716964, + 0.3950661656212815, + 0.3487811024652465, + 0.5654534607901051, + 0.5542352428636733, + 0.38344560480173295, + 0.37845944475808024, + 0.40994787070756056, + 0.4098042600279297, + 0.5824528062740094, + 0.3677819042513511, + 0.5667421903982117, + 0.5823098350362161, + 0.4997354606595198, + 0.5577228717543639, + 0.37599816309134687, + 0.36460166186300336, + 0.39776649894842664, + 0.5029836657076963, + 0.5446670584974052, + 0.41635432137191997, + 0.3747724066364892, + 0.5648710418041084, + 0.5229557425354546, + 0.43470589357894773, + 0.5096539890440522, + 0.5493011015673386, + 0.364659006530313, + 0.40595928088074873, + 0.5635193226305706, + 0.48844950906225715, + 0.35559809356832767, + 0.600011817130077, + 0.37656692691979204, + 0.4688931014175079, + 0.4191055274303525, + 0.5917983156040607, + 0.5629791462873793, + 0.4765892715933069, + 0.3489056856214575, + 0.42298416013668316, + 0.4134646286376371, + 0.49036157657622015, + 0.4369761052483312, + 0.5000002109697097, + 0.5311212855627583, + 0.4889066007161451, + 0.38370646646169804, + 0.496763177838493, + 0.34223873459542287, + 0.5633076355260674, + 0.5057857517364384, + 0.3695563858708719, + 0.3468905455666179, + 0.4695972605854418, + 0.4141619667332289, + 0.6012511424376816, + 0.41861742848578715, + 0.40219784676180925, + 0.3508856963239504, + 0.6009730955018464, + 0.5303029268710294, + 0.552270055309989, + 0.3870509336687766, + 0.5084792862736575, + 0.40008537260432153, + 0.48246843532826944, + 0.5121266519517882, + 0.5219039388856647, + 0.5306620891326109, + 0.3679562141849163, + 0.4061084800135673, + 0.3939881887592522, + 0.5464277673350729, + 0.5515407851580473, + 0.5737073040556503, + 0.5319421741875525, + 0.5610022481238619, + 0.4444769927395537, + 0.5468531780208243, + 0.5413089145754962, + 0.4490399287067752, + 0.5310804860651113, + 0.43132031736826215, + 0.425031809249402, + 0.35627977700852836, + 0.391828662156411, + 0.5585938822476366, + 0.5751730360215569, + 0.5460971387714127, + 0.3505415328756662, + 0.35610536257132896, + 0.44287292011606155, + 0.43866971803312277, + 0.6002496439391074, + 0.5173499312431159, + 0.5433434657710117, + 0.4858784378616148, + 0.4186920525554594, + 0.4703120902841126, + 0.42505275108860374, + 0.6024320863957435, + 0.524019716493683, + 0.5518777838819348, + 0.45529456413244535, + 0.5334458534487957, + 0.425198712729584, + 0.441115805578113, + 0.4793604623757344, + 0.5972366894718695, + 0.6062324108620794, + 0.5078091049400574, + 0.45421249985553264, + 0.5766961113418808, + 0.39894580986409156, + 0.39050101407425203, + 0.6013233462563512, + 0.48161778465440014, + 0.44154388594326244, + 0.3464969345224911, + 0.41141568887747293, + 0.6030161355558906, + 0.4371641000633485, + 0.5113923612089871, + 0.5328532752398514, + 0.4170688111212659, + 0.47593253962851867, + 0.603681414298519, + 0.4732769529455384, + 0.49340642519296174, + 0.3554451847761289, + 0.5291490255275522, + 0.4207853285950746, + 0.5011501624702486, + 0.4624766412862178, + 0.5885238569599306, + 0.3724478127845692, + 0.44306831446701844, + 0.37856609230532184, + 0.44057869815649786, + 0.4224483171886429, + 0.3652100480270075, + 0.44210861170660554, + 0.3844104595299572, + 0.39152426694676035, + 0.47587595917086367, + 0.570914664812442, + 0.570242137245777, + 0.5157957516372845, + 0.37464287404659474, + 0.5860840211028387, + 0.38421703526859385, + 0.5002348004547492, + 0.5109270577674532, + 0.5860969529316052, + 0.42933086298940115, + 0.41486111758568067, + 0.5153304777814366, + 0.4182411393011742, + 0.5018162240633419, + 0.43279307284180857, + 0.44579531203820816, + 0.5322029361603091, + 0.5871961565802967, + 0.5802632709945637, + 0.5655812710769048, + 0.5477996499392461, + 0.44060246166685, + 0.5259692464438083, + 0.46844954816988876, + 0.4699842809428605, + 0.5710934768186695, + 0.4642517574591238, + 0.41356934532671863, + 0.46941610197982, + 0.5841602491824366, + 0.5567929810414571, + 0.3513665173974507, + 0.39613104328474463, + 0.5284655633546714, + 0.509506370648284, + 0.35977187236664676, + 0.3648047519307317, + 0.5020882886217386, + 0.5191022325269707, + 0.39328240442584006, + 0.4820738325056765, + 0.45329101346962647, + 0.4793175452988537, + 0.40762876965469486, + 0.361131070320503, + 0.5287169478541102, + 0.5481594819326585, + 0.36719948540243247, + 0.4358641644472253, + 0.5371549727900025, + 0.49362440912066863, + 0.43269426023543056, + 0.41718744143355874, + 0.3837807765687033, + 0.5991559200467184, + 0.47624389040456394, + 0.3947819531136556, + 0.41235829959266024, + 0.5161763569255718, + 0.4932545633005001, + 0.39522137351942177, + 0.5064785973626273, + 0.5922611265887539, + 0.5459657004133738, + 0.4787210564800114, + 0.5534952313329465, + 0.5753993692109349, + 0.4502262334296868, + 0.39779936409766264, + 0.45598457184313684, + 0.5404345164140907, + 0.5358526207842351, + 0.437509209155544, + 0.6068864176435489, + 0.5473513412968533, + 0.40397623272386546, + 0.35742068705397567, + 0.559318633167904, + 0.34626248127803916, + 0.39085976371184633, + 0.38066367245698735, + 0.37703446583989497, + 0.5922138801754192, + 0.5324428994503232, + 0.564334557452713, + 0.5833797361457658, + 0.3471380050002642, + 0.5257455116357597, + 0.6004202824696133, + 0.5973272470410753, + 0.4281849829419391, + 0.3473922168431479, + 0.5679608007020709, + 0.38581286523108327, + 0.4643001921490008, + 0.567446977130964, + 0.5774026614078034, + 0.4122499401133527, + 0.46859659296365413, + 0.3470092896285691, + 0.5676266603884793, + 0.5072991944314883, + 0.47115530361089136, + 0.4699731878548561, + 0.5171983601413559, + 0.41700090704844595, + 0.474030917644699, + 0.4624737739782429, + 0.34201327187107117, + 0.45019533022510555, + 0.5263796044088731, + 0.38480505286385164, + 0.3434692593986602, + 0.5569124348203793, + 0.3945365683990615, + 0.3638436962932965, + 0.44145831408401454, + 0.43482092070023004, + 0.5859426769984667, + 0.5903842742844772, + 0.4302163962513328, + 0.5675014898466846, + 0.46783722320299015, + 0.5405388483068034, + 0.451772431140587, + 0.4900106800891879, + 0.4198275748512944, + 0.5008977080159845, + 0.372062843714078, + 0.5825601485729913, + 0.5624136641957483, + 0.5662513751375922, + 0.43640768356295917, + 0.417360119968949, + 0.37159748499135004, + 0.3663368459618999, + 0.4848374015024614, + 0.5405118482746795, + 0.6061034238201766, + 0.6032756774681289, + 0.5379328704964061, + 0.3439958456498413, + 0.5641359573270452, + 0.3948906107922503, + 0.46494403243446686, + 0.5328090962883387, + 0.5078623834831664, + 0.5701814163583913, + 0.34749601917302886, + 0.5901485441221049, + 0.5092394551857343, + 0.3959609331107027, + 0.5437687545546162, + 0.3790994159399483, + 0.5274211266541007, + 0.46941104913848763, + 0.493645564224092, + 0.5140882173719808, + 0.3607377608420632, + 0.5307025734064756, + 0.5865318472958503, + 0.578674015374796, + 0.3840989082506972, + 0.3572174197084665, + 0.5345465646148913, + 0.5573905285180834, + 0.3997596835393332, + 0.3934350497539687, + 0.3608918460695084, + 0.4432696215756754, + 0.5872731913329365, + 0.49111586604328694, + 0.373667943710018, + 0.45668820840474433, + 0.5247495297137788, + 0.37304070535325323, + 0.5655014458510781, + 0.4880975354956855, + 0.4728743440775973, + 0.4852589543887331, + 0.5211382244829801, + 0.3681153028192835, + 0.5883853568846613, + 0.4849228161139142, + 0.41468918686369954, + 0.40965754059041254, + 0.343393320193682, + 0.6066472892570084, + 0.4465169537818027, + 0.559836873395669, + 0.4511430045355601, + 0.5222701301094441, + 0.3495216635636515, + 0.41940700601411646, + 0.4088154557328828, + 0.39478295348538983, + 0.5282867810843822, + 0.3743979046656387, + 0.5535542252153165, + 0.5135138535629309, + 0.3442700601487605, + 0.4214374290607636, + 0.5149767872479609, + 0.5478982956722004, + 0.40369816650991264, + 0.3959137294123751, + 0.582295441642607, + 0.3703035596211211, + 0.3639299244363224, + 0.43949922529567576, + 0.5967422058144787, + 0.42761486243568747, + 0.5835623043890609, + 0.3765502698104801, + 0.5710841111232354, + 0.35004748583744133, + 0.3648000797120282, + 0.3976322036051092, + 0.4744623389810701, + 0.4322185745604355, + 0.4611441895398234, + 0.4470469417982491, + 0.5113507043137422, + 0.5733724104323815, + 0.4472487185854437, + 0.6048111615737413, + 0.3460304535630738, + 0.48105121477850843, + 0.5313306397034293, + 0.3645444342090415, + 0.598852993644403, + 0.5550215926381291, + 0.39585895754998174, + 0.5820101336331552, + 0.39530797658424105, + 0.4757668916140924, + 0.5804823315308345, + 0.5137485457996178, + 0.5884756911588035, + 0.4754113752325224, + 0.49076370478525766, + 0.4693439056690016, + 0.5139036073899077, + 0.4842753744263778, + 0.559074695576061, + 0.5308432188371117, + 0.5191753153261178, + 0.5960788200220881, + 0.3522458282581329, + 0.4539574221008101, + 0.5482479854062349, + 0.3558507313454642, + 0.5305720207051022, + 0.5935521937922867, + 0.6019875834898445, + 0.3677686410280343, + 0.4561128845309906, + 0.5677233641940589, + 0.6008488177326224, + 0.5709346760542268, + 0.6065195805492309, + 0.42921489183596206, + 0.3907517048959432, + 0.5202765116302817, + 0.4869480928569118, + 0.5804592674687689, + 0.3555954457207898, + 0.3737826263572326, + 0.4918013155645874, + 0.4789075261457857, + 0.5569292160026967, + 0.5918986609931349, + 0.4774049416812103, + 0.5251309927171721, + 0.37622893213511743, + 0.5367649149810325, + 0.5200556787822774, + 0.48585684380685745, + 0.36746941118793014, + 0.3504144909631903, + 0.3546429891811521, + 0.5660053152046313, + 0.5721780503065808, + 0.5682009546254901, + 0.4530636507320803, + 0.44429489920583154, + 0.5694766869478887, + 0.43915435347020954, + 0.35465900912768644, + 0.41024635885887756, + 0.40448817757323313, + 0.5261038431042016, + 0.4570117667405817, + 0.46562678417122577, + 0.39971027684784805, + 0.4981824629293409, + 0.5759615515096852, + 0.3724624940372981, + 0.5770631236900441, + 0.36990061544106634, + 0.4341166775822083, + 0.46148252740269097, + 0.4171712689290905, + 0.34602200295925845, + 0.3517899585054631, + 0.5987405697049963, + 0.4713507543161679, + 0.5689535653298192, + 0.6031863668566751, + 0.51088811349767, + 0.47976329772664206, + 0.5946489557784276, + 0.34243786376367924, + 0.47816156323227, + 0.4946104589166014, + 0.5594041130815413, + 0.4143872636016822, + 0.4198877071634649, + 0.3532714534580506, + 0.37651955214480914, + 0.47624143065079516, + 0.5135648746053688, + 0.5404308774183231, + 0.389500512906384, + 0.48675976770616874, + 0.46214400519591947, + 0.34789040966450213, + 0.3544543480584944, + 0.5281427836513264, + 0.4834667608380754, + 0.4664120249091887, + 0.44002047438692576, + 0.5065050997131403, + 0.5179882969949285, + 0.5554751528313422, + 0.356026965533862, + 0.4483228951414117, + 0.5393320055967439, + 0.4329543892111828, + 0.5497121219164326, + 0.5134689540483622, + 0.4884442862457684, + 0.5698882919124081, + 0.5993856859230287, + 0.6058209144144544, + 0.45951765458461713, + 0.5821240414709833, + 0.518957014552565, + 0.34150460952778805, + 0.4858431587887959, + 0.43595318798496363, + 0.4395244862971496, + 0.36574765579195034, + 0.49134564432101024, + 0.4683710634392918, + 0.4219523061092252, + 0.44814764802209517, + 0.34528163299237574, + 0.5823911196981766, + 0.34149086541454515, + 0.48819098983151027, + 0.5701729694009546, + 0.47092364277394183, + 0.4226641997127095, + 0.5837118949782591, + 0.49746863910139494, + 0.4657360309983918, + 0.4905029621970316, + 0.5376121699481634, + 0.47397373353035904, + 0.4830536446076111, + 0.5767464617534703, + 0.470691342717877, + 0.5644633121820126, + 0.5863199526913101, + 0.40420047891907196, + 0.39755345641695994, + 0.5538966815026581, + 0.5008824123424567, + 0.3737221531096048, + 0.5149637772698328, + 0.3834133155008275, + 0.4249427989267169, + 0.47579532239346956, + 0.4660155924053905, + 0.5707858448562337, + 0.5699252726463766, + 0.5532737227095872, + 0.5522154463895019, + 0.47429694164093505, + 0.4544489050031495, + 0.5731731389111667, + 0.5322910605048028, + 0.4839729798732396, + 0.36467990216799184, + 0.38432563967231836, + 0.35957443127297456, + 0.5906800017389878, + 0.34645397245125703, + 0.39091988997719923, + 0.3848332019082021, + 0.4715693855009661, + 0.5266316042716914, + 0.34684054782187773, + 0.34855266133987595, + 0.5994990199566795, + 0.5029368671219209, + 0.5695850316694051, + 0.458076530365192, + 0.4956063557413368, + 0.5067296376475224, + 0.4763475896242703, + 0.5829473364548814, + 0.39075815811805004, + 0.5450002593763409, + 0.38869035499641447, + 0.5743012747548941, + 0.5774946365903953, + 0.5024150771701814, + 0.5495888312897252, + 0.3657862237389591, + 0.4843248281163902, + 0.370096743260127, + 0.5362987040119, + 0.5173002014741588, + 0.4951406353323875, + 0.4237568936837267, + 0.3712469477529068, + 0.549147071062476, + 0.5230235825142091, + 0.5250253074799901, + 0.4920321190784082, + 0.43921442443358794, + 0.47122593403692314, + 0.4583082347517169, + 0.4643907097798591, + 0.3647914109364705, + 0.44375725062944255, + 0.5155370485521075, + 0.5575363822075549, + 0.5984778144125309, + 0.3886879106230864, + 0.5474294528123468, + 0.4743804617805184, + 0.4761327737603044, + 0.565857067100405, + 0.49650733450444096, + 0.4601512993183491, + 0.4917651113935273, + 0.44501725294122174, + 0.43903745481763407, + 0.4016396117973403, + 0.3577730973540187, + 0.505403227571768, + 0.47456627889745784, + 0.547198055179868, + 0.42335695190131184, + 0.503695219392275, + 0.6033187350517535, + 0.4477076329642996, + 0.4842381915613864, + 0.3449953675627985, + 0.471835833748945, + 0.5472353469599572, + 0.4434390663485666, + 0.44753283457625037, + 0.4335882513416939, + 0.5824167239850992, + 0.47894887839193545, + 0.5272095632268465, + 0.5078053706833223, + 0.5726813351055593, + 0.4225344695252811, + 0.38589849452461666, + 0.3750515583215873, + 0.5024321017490514, + 0.5204654123975265, + 0.3702976989869829, + 0.3792972052300271, + 0.5234878758663732, + 0.5588953031988377, + 0.593614094337761, + 0.3586762243593869, + 0.5618298216852471, + 0.41738068203148576, + 0.46036901227969995, + 0.3836721623758067, + 0.45060741290574213, + 0.45761345284610594, + 0.5090778733717967, + 0.5657991318680067, + 0.5071182588143011, + 0.5451202840160405, + 0.47897244912445935, + 0.5958904795183888, + 0.49102470192837355, + 0.6067936320656305, + 0.3780071033093939, + 0.5825276687411751, + 0.45443528755822954, + 0.5209601700631128, + 0.3781906112578498, + 0.4532466846082218, + 0.5280294548249118, + 0.5935696816911536, + 0.5323728617608161, + 0.5904641290861875, + 0.44906107451856697, + 0.3905929174669371, + 0.5086470163509907, + 0.36238713750838814, + 0.3961575664876973, + 0.5057007807764886, + 0.4813679743078634, + 0.604412417286877, + 0.5522107377789962, + 0.40106349952596987, + 0.5562927740636022, + 0.5647262485652431, + 0.3895753588271701, + 0.5046162266358994, + 0.4087592949589765, + 0.5536254368227302, + 0.5926355257940781, + 0.5920934788219747, + 0.5261319483250526, + 0.4957319166232663, + 0.5190132187478506, + 0.43734455915692727, + 0.35812077730890635, + 0.5623079492988083, + 0.4878677424349044, + 0.5098346902573396, + 0.494664482895344, + 0.5672837590807926, + 0.3607635929182386, + 0.45795487808838886, + 0.5675155129864495, + 0.40339477951946356, + 0.5983797114417004, + 0.597385668970684, + 0.5227130284111274, + 0.5165561759316293, + 0.4799873403317158, + 0.3976284942638267, + 0.5031673120388171, + 0.3978030174459169, + 0.522106706914395, + 0.590653206035138, + 0.44278948245742744, + 0.4386303672880802, + 0.5604897241496405, + 0.34653638322198016, + 0.504261242629784, + 0.5797301098940912, + 0.41134131873804936, + 0.5046560135571326, + 0.4833439805419989, + 0.3758263664536135, + 0.44978199927716733, + 0.5001788430756449, + 0.5907321051800793, + 0.4222995914660374, + 0.5590305923250589, + 0.6029767852600068, + 0.5340033965423121, + 0.5034935183670421, + 0.5131650410007257, + 0.581755355364706, + 0.46011556639662876, + 0.5385781047238366, + 0.5663183705722679, + 0.5576963075635891, + 0.46960242184052425, + 0.400478776041546, + 0.39921052395909346, + 0.6035974104398611, + 0.43077981315705627, + 0.5395370643138631, + 0.46291669080702663, + 0.3516941552442199, + 0.5822351994694762, + 0.3735975791899136, + 0.5716624663590919, + 0.46879475462080955, + 0.48816922856378875, + 0.4348107883843224, + 0.5527210158686148, + 0.3462129475783856, + 0.437668813225119, + 0.45398361266931764, + 0.45252915779414904, + 0.44082766067008256, + 0.571693984421884, + 0.3974536784799768, + 0.4203774209064467, + 0.37004100725958616, + 0.6023415544134177, + 0.5607789947674344, + 0.34214072491560066, + 0.40474447338640385, + 0.42091444359644614, + 0.4735040418746259, + 0.4370139922059038, + 0.42710397829133867, + 0.4813719951863104, + 0.4129671175881058, + 0.5044804374508585, + 0.5016479619431254, + 0.5941994195498617, + 0.5823968323521261, + 0.4701113363802019, + 0.4802095254835834, + 0.5012998232480464, + 0.541992343498247, + 0.5121212012819445, + 0.5591365320624495, + 0.40247189303756353, + 0.5210939488482902, + 0.45101805788071825, + 0.5043138926474448, + 0.5772985986066969, + 0.4716641735381307, + 0.3459072202373014, + 0.5954124019932168, + 0.3873075873960608, + 0.43097655837316384, + 0.4151877122248693, + 0.5713744577807444, + 0.45715808683145037, + 0.38326756628546005, + 0.5319350111535439, + 0.519806867156658, + 0.4008698554323408, + 0.5399730071742894, + 0.34910975232956304, + 0.5343339985736141, + 0.5936681080734139, + 0.5974876287056963, + 0.49703431371897056, + 0.5217598513243877, + 0.43749613139740046, + 0.4991513301229619, + 0.4732297030987782, + 0.5915849840441882, + 0.3934490717325936, + 0.5092012639206055, + 0.37223464733700995, + 0.4035982291530634, + 0.5852440269673262, + 0.6071191407576472, + 0.5997719720131358, + 0.3521013171715909, + 0.601724913434594, + 0.3733029341598839, + 0.4449180553499292, + 0.44670758269238975, + 0.5485365387393195, + 0.40615791871476625, + 0.5108702656952671, + 0.44589286973325926, + 0.4884132849545837, + 0.5992836344578305, + 0.48205373502240867, + 0.34564099166510776, + 0.4328075589338448, + 0.47892340830025504, + 0.37481696642389223, + 0.5212899919293463, + 0.37842480328219474, + 0.4923977338141691, + 0.4364907593165683, + 0.47587484554020604, + 0.42019841736010893, + 0.3698744302763331, + 0.5880647889451256, + 0.4040544699014921, + 0.595027371365836, + 0.46459440123666046, + 0.42602632911939115, + 0.3475582972398608, + 0.5764929316615062, + 0.5424990140841538, + 0.5311635603461717, + 0.3722118726551341, + 0.5242338250695099, + 0.4335675949280007, + 0.39250497045910215, + 0.512532929952984, + 0.5145646433344467, + 0.5529553000787272, + 0.49387560451724755, + 0.346536989651044, + 0.417907951271126, + 0.44731248683336067, + 0.5271414419244951, + 0.39912782531530133, + 0.5400391209910202, + 0.5596542436906078, + 0.4125788900763856, + 0.4206073351908389, + 0.3788635873731357, + 0.5596414977137669, + 0.3522436544324449, + 0.5677690983420309, + 0.540354132488851, + 0.5488643714710834, + 0.5810043073480815, + 0.4279494245954359, + 0.45571630372698, + 0.37506181156147456, + 0.5894363670106264, + 0.4930742807416797, + 0.5841310497886043, + 0.5998932493776483, + 0.5947239190736979, + 0.36679464481645147, + 0.5982747587160111, + 0.45992683438857496, + 0.38537851659094635, + 0.4615025463949791, + 0.5971143173467043, + 0.5277364344547224, + 0.39114049240478144, + 0.6008324982668809, + 0.3961105902281261, + 0.5915360171793451, + 0.5831168646409269, + 0.36098739147600867, + 0.3419362570292779, + 0.5572174527453038, + 0.457923771629149, + 0.43129614950135714, + 0.5178825180505575, + 0.46466835838982495, + 0.36544629716169635, + 0.43266785961139265, + 0.4021908479370423, + 0.5744105715621559, + 0.5686870973596833, + 0.3680529416898909, + 0.4903914992933715, + 0.5453064846945199, + 0.47442137559913256, + 0.591503958423782, + 0.380728466654642, + 0.5689459633978493, + 0.5508907698930872, + 0.4224918561359484, + 0.5936325579714719, + 0.39215183895125205, + 0.4529734171729353, + 0.3469129238902181, + 0.4314419249816683, + 0.38334697433608056, + 0.5436899263148411, + 0.3641271171845005, + 0.4241119213507395, + 0.48155639713355364, + 0.449139046774904, + 0.3706756462326638, + 0.4798353566427822, + 0.3700891914970429, + 0.34235714436599224, + 0.5500710890729612, + 0.44821888404261917, + 0.3903444878597054, + 0.43709871365488234, + 0.4510532979454064, + 0.4594557014881545, + 0.5135886634695406, + 0.5633922471625707, + 0.4383884087025855, + 0.3552130183224168, + 0.5184019191747087, + 0.4276127961477535, + 0.5162974805899209, + 0.34332630362375666, + 0.35676309319277555, + 0.5913361742253135, + 0.44610818852244316, + 0.3935449140459696, + 0.4920029864995243, + 0.3882269998825654, + 0.36649023767574124, + 0.4890105870390613, + 0.39335827469356055, + 0.4688768887978604, + 0.4997540310859362, + 0.3418400476985648, + 0.43626926262450183, + 0.41267208098648683, + 0.36629738712429255, + 0.6074664344180866, + 0.48929641232407667, + 0.46391553464193536, + 0.3740877047011589, + 0.48115527067829134, + 0.37966477514112545, + 0.34250105807292286, + 0.4912859977711309, + 0.34379043780102886, + 0.5838124794649393, + 0.35360041567600875, + 0.37429217713928914, + 0.3724630215753679, + 0.40326531763365586, + 0.41629852309486703, + 0.6016944351680409, + 0.39913490000006124, + 0.4278913101230549, + 0.40272050258015907, + 0.3903072384416554, + 0.559903397118928, + 0.49727754120318046, + 0.5187675969852753, + 0.4975295957161495, + 0.585554168684486, + 0.5084001990955314, + 0.391701969234127, + 0.39944264994412926, + 0.6051774718704273, + 0.34511613268827973, + 0.35078965367531956, + 0.5057073935346219, + 0.5923236640836789, + 0.5453576095783862, + 0.36085344941020625, + 0.4133714887847928, + 0.40854910753881635, + 0.4347092379364686, + 0.4126268611580694, + 0.3997037220203131, + 0.4913830597225295, + 0.4582023432222499, + 0.5072154780633854, + 0.3572205104303414, + 0.5136833559838432, + 0.4295656537352782, + 0.5476209704089816, + 0.3552848552124917, + 0.46746622705855534, + 0.3647275912385317, + 0.4874197562913253, + 0.5000377438703938, + 0.45975051326899746, + 0.38580663499312023, + 0.3918695994902058, + 0.5608777722515441, + 0.5400018136188159, + 0.5533310770302281, + 0.4772632785498062, + 0.5332677345736225, + 0.5204048138390205, + 0.5520297504253833, + 0.3679866466694846, + 0.5884779855904613, + 0.42769001087389047, + 0.46401649102419307, + 0.34918739263106574, + 0.5187020689567168, + 0.5425677072157232, + 0.5681116622271386, + 0.5443208331118151, + 0.4160927999884095, + 0.5268745081254159, + 0.5398006250847165, + 0.3849742095053288, + 0.3727442846320017, + 0.47337020760573184, + 0.48347322942303367, + 0.3907315482748321, + 0.4244851048370886, + 0.44001619412291937, + 0.5893045045324475, + 0.46465444543165013, + 0.3634207626365035, + 0.3950765065986035, + 0.6047077876204787, + 0.4098654225965914, + 0.551204142417468, + 0.49688938937664606, + 0.47076213599869465, + 0.5068539131646489, + 0.3807246829262258, + 0.38067800940673213, + 0.4538419103453752, + 0.4600826430033671, + 0.5340216522864689, + 0.36509890927320576, + 0.4214738916362818, + 0.569871284589341, + 0.5543740013382217, + 0.5167120262927474, + 0.3968792955996972, + 0.3778601032327837, + 0.37153465769039196, + 0.5745846720245934, + 0.38865087211598337, + 0.4895991416081877, + 0.383197498629208, + 0.5255986057282869, + 0.34790345654789684, + 0.5099653918602463, + 0.5095168839500009, + 0.4207702693166155, + 0.42954089120450073, + 0.39254026609205944, + 0.4007114321392893, + 0.45529865357396176, + 0.5240445669041448, + 0.5771929969808298, + 0.4204596203180939, + 0.3500870949167038, + 0.381135899139763, + 0.5818442691918664, + 0.38945379988614404, + 0.3423098804219534, + 0.47717959776044494, + 0.36457841980673766, + 0.393385446899411, + 0.3984245585464987, + 0.5883908423063522, + 0.4041872077675681, + 0.36939965405345315, + 0.5615059873314738, + 0.40992605078222777, + 0.4918106335476047, + 0.3928376603825265, + 0.5267379926754716, + 0.4614809616411724, + 0.38827682411310493, + 0.40594598536619564, + 0.4002433077273559, + 0.3497913830687303, + 0.4781696104635077, + 0.3414788999182605, + 0.5703053390935924, + 0.5097854729057353, + 0.4529116283362318, + 0.5083335464525203, + 0.5987837162464902, + 0.3884784154060667, + 0.5385308401025692, + 0.39708311571965665, + 0.5167347867414727, + 0.4242661530047943, + 0.3411885852533423, + 0.5445958413574707, + 0.5663409284192276, + 0.48480820343110353, + 0.3713793218614828, + 0.38020699303039407, + 0.5294822870589435, + 0.5750736137767595, + 0.3642299163669337, + 0.41270311844065366, + 0.5833371957133184, + 0.4813444427566243, + 0.3627744644587118, + 0.47251915975372194, + 0.34137481158666644, + 0.39343826698311946, + 0.5114240009276504, + 0.43709432697066214, + 0.41667524496223945, + 0.3758381450641613, + 0.42752412715835414, + 0.4573916287015163, + 0.48645247842772754, + 0.4272193254903053, + 0.5400170416382577, + 0.4956599616460471, + 0.544271497624742, + 0.4970515047509537, + 0.6058227734098991, + 0.4305034321937202, + 0.4309935507290957, + 0.46205229967209344, + 0.34970632651195793, + 0.5737867371802711, + 0.5009394699197431, + 0.4826382759841752, + 0.4787146566527033, + 0.4597996058691921, + 0.5230942687437785, + 0.48475854808454544, + 0.3966273427427452, + 0.586364655625246, + 0.5923224685951092, + 0.34892795120330283, + 0.5887917830686717, + 0.351521254036404, + 0.597290809048604, + 0.5174872642400983, + 0.4137998031215848, + 0.372240027544362, + 0.5237118369485276, + 0.5338577886242866, + 0.5492853051651385, + 0.3825044442963137, + 0.383285002551392, + 0.43417547326286515, + 0.4062538574734079, + 0.3935902412161791, + 0.5213598441781024, + 0.47367235895290616, + 0.5248862593214834, + 0.46743733895717426, + 0.4830331352031305, + 0.5371735997507262, + 0.5043286114024138, + 0.5831024760055453, + 0.5846215387690342, + 0.3626002138831306, + 0.43510405088476717, + 0.3721655667180501, + 0.5552185664992114, + 0.36338583981280154, + 0.38674404341355223, + 0.5055639079402703, + 0.4211923143897498, + 0.48064686668167256, + 0.39710529287933544, + 0.5295440771714732, + 0.4998455389007025, + 0.4156717115150133, + 0.397267273770501, + 0.4996795757797521, + 0.4480929406439922, + 0.4449212211481069, + 0.3578000593232174, + 0.5553667164218544, + 0.4678283872543554, + 0.5183257739474413, + 0.5288359935927611, + 0.5519967648094677, + 0.5517873233699306, + 0.4773242067858652, + 0.39575454402181764, + 0.4799154380164413, + 0.41686156787527845, + 0.5008112254901099, + 0.4058004100692964, + 0.41158155433580484, + 0.34475975583327134, + 0.3442510880504321, + 0.40401566002428135, + 0.5714549301323948, + 0.4402087340725136, + 0.4947345041333346, + 0.5412025500120745, + 0.5241689051654169, + 0.34222214824981273, + 0.3735759715225314, + 0.55826319366802, + 0.5585894044863704, + 0.5302291462403189, + 0.46102173890706677, + 0.5159008295550984, + 0.4370887457483057, + 0.5548028540916912, + 0.5548333118679825, + 0.351406317878043, + 0.4534911415584578, + 0.5841200356782686, + 0.4580904856382134, + 0.5620763661316551, + 0.3557330268074045, + 0.36819051992942353, + 0.5240540220873334, + 0.5315099911858809, + 0.5137267161849198, + 0.430763695374527, + 0.3595220371261201, + 0.4540242895139506, + 0.40333042059344265, + 0.4535363434495942, + 0.4630769882972854, + 0.4853290677213228, + 0.3448909568947941, + 0.40685767032005593, + 0.38337008957040536, + 0.49229940615302953, + 0.5129651360114913, + 0.49141613525500905, + 0.5255727253790384, + 0.38004825128709147, + 0.4329659904115168, + 0.5500235148228885, + 0.5912333105760745, + 0.5746835172603368, + 0.5543641333784942, + 0.5536975944359347, + 0.46468959138921073, + 0.5564452621367266, + 0.5991182494296027, + 0.5721753214470617, + 0.4150348159555953, + 0.36850232592127663, + 0.567241210216017, + 0.44662733448926534, + 0.46301093825639406, + 0.564965508580315, + 0.4160400088918695, + 0.4510916165724716, + 0.389761043203716, + 0.5239818441059906, + 0.4950709141508422, + 0.5768673801820388, + 0.437809405298741, + 0.4948668919813999, + 0.4025063832900456, + 0.5867752147147857, + 0.5874999222180233, + 0.5576597116872626, + 0.5291178095767435, + 0.4580411176820145, + 0.4583705615744973, + 0.554604973292439, + 0.5577044130435422, + 0.5387560254945231, + 0.5613873157057301, + 0.575421484151117, + 0.44261561211221057, + 0.4450586608612164, + 0.3645856135427268, + 0.37695051429643844, + 0.41798698305826754, + 0.4183488578877683, + 0.5480086205513909, + 0.40763245237979095, + 0.4707049135735989, + 0.5079415805523493, + 0.451372851429892, + 0.34927030294909645, + 0.43683363125392527, + 0.37916923742005376, + 0.5289833365825204, + 0.5601416129859287, + 0.4111902095231964, + 0.524589947194502, + 0.40815028486489224, + 0.4283270661428335, + 0.3615722453926818, + 0.6034060126314916, + 0.37859348951440813, + 0.4717420863729158, + 0.4635673595352632, + 0.4985916648114221, + 0.5416300222264527, + 0.54883804682161, + 0.5530708091635006, + 0.44651362468378325, + 0.3672239263068148, + 0.35842150056125766, + 0.41968597491730786, + 0.5014301141346466, + 0.4782744789362869, + 0.4354337968334267, + 0.446263083789423, + 0.4776611200055896, + 0.40707014709005607, + 0.5793909048013394, + 0.5929466064379292, + 0.40823173090963216, + 0.589355957862494, + 0.5223563928941342, + 0.415519337991591, + 0.5680415547422528, + 0.539633688774512, + 0.5319034481124587, + 0.35622423345998483, + 0.4054859181407606, + 0.5091489567860088, + 0.4774141773261595, + 0.41944229735658556, + 0.54092184775684, + 0.44691065903840665, + 0.46920751659240834, + 0.6017623629313197, + 0.4991337311351475, + 0.5977526729559919, + 0.4006779571688617, + 0.48381281841195134, + 0.5119331907423459, + 0.48270256565146175, + 0.4975244408113628, + 0.3675105655794304, + 0.47301817791355805, + 0.4122024433957162, + 0.5241380214222524, + 0.4670801937286404, + 0.4728537784356728, + 0.5590319908074751, + 0.378466258539071, + 0.5747264235501557, + 0.34645381332576297, + 0.42960485017231137, + 0.4881331906380566, + 0.38140210476046527, + 0.39607154710216397, + 0.6053485232672091, + 0.4285824300000046, + 0.4318358220386066, + 0.5285443035198489, + 0.500566148427715, + 0.4480597135722135, + 0.4499564316862005, + 0.5549101769795989, + 0.47620771388879896, + 0.3691688263728796, + 0.5859970470841185, + 0.3676223814695163, + 0.4841121757047685, + 0.3690730973051444, + 0.513196622034859, + 0.36408234604989187, + 0.49096087275831174, + 0.6060400769100164, + 0.539728149909178, + 0.49516462487182245, + 0.592791822527154, + 0.5509611897495419, + 0.39270275378863634, + 0.5474711420761857, + 0.4200106439609876, + 0.44787324661189, + 0.5151962792014102, + 0.45753591889491013, + 0.3464547802296827, + 0.586370419678967, + 0.3998134711705603, + 0.5607621957094835, + 0.47076905764088783, + 0.3601098410939672, + 0.4987166046783881, + 0.4363547217619918, + 0.46782380841604265, + 0.4163549086597488, + 0.48469665591761624, + 0.5824142160115512, + 0.441184814096548, + 0.4578671050919416, + 0.4230268230986026, + 0.5387602042919764, + 0.46501641388326675, + 0.43859268530553713, + 0.4375734246699945, + 0.34253304911026916, + 0.476698314384301, + 0.4296640313408992, + 0.49661564441789074, + 0.5297974539693031, + 0.5762243720327239, + 0.3561106409989898, + 0.4689415981683758, + 0.46361058174055303, + 0.37142021566183414, + 0.4698112299188447, + 0.5615547067809443, + 0.5472472615475871, + 0.5179319666066513, + 0.512822187479498, + 0.4178557637079845, + 0.4740227323028231, + 0.5318912244564038, + 0.542626881127761, + 0.5700183959477447, + 0.5247567401902204, + 0.34573598548861334, + 0.5979566894613755, + 0.49735860610456395, + 0.39801069366411995, + 0.4918062104483265, + 0.5330773555821162, + 0.5382031726994014, + 0.3628490469013822, + 0.5779800650155372, + 0.43646865480474173, + 0.4339106955338005, + 0.348419953680698, + 0.35268365317094275, + 0.5616270400385045, + 0.5512456962144441, + 0.35752837967505097, + 0.4954440322444712, + 0.5023033244843494, + 0.47160346945548415, + 0.40606730537272306, + 0.48374442501841053, + 0.3500597911621852, + 0.49238336525407245, + 0.6055041287717009, + 0.4117080963886307, + 0.3558826281489457, + 0.3543922696932283, + 0.5055606283167466, + 0.39874755174750576, + 0.3408594237640574, + 0.5451509246422763, + 0.5773693402742773, + 0.517014845383349, + 0.47191770841892544, + 0.5578997936308838, + 0.4856564239558189, + 0.5444237501367024, + 0.5255593829621887, + 0.3777746915252527, + 0.36078294797582156, + 0.3902434036499134, + 0.412617181274476, + 0.3644918752091448, + 0.5445875453431477, + 0.5758737525129956, + 0.4629527447239072, + 0.3971536916239647, + 0.5213562308909236, + 0.42857942085452466, + 0.35349703765073914, + 0.4067896653619118, + 0.5559190750562196, + 0.42062792438274543, + 0.5227512322031312, + 0.4491767086096571, + 0.5479535347567401, + 0.3731828850590343, + 0.5955665274196172, + 0.5665146035684071, + 0.5389758329341348, + 0.5602975527741487, + 0.4423687494335502, + 0.46527386293054385, + 0.5338313110560828, + 0.3953867057376289, + 0.5936726984395257, + 0.37484077223969575, + 0.49133352717758544, + 0.5671971118682897, + 0.35186113820271275, + 0.41589487825669835, + 0.3539477546610759, + 0.6051933242646395, + 0.531005373289706, + 0.5953481803061773, + 0.4178666902979937, + 0.5606855343401739, + 0.34940007180050425, + 0.46547736221437563, + 0.601957536955557, + 0.5884186323915922, + 0.5580939776988318, + 0.4465817458393127, + 0.5479061154664016, + 0.3784427375447932 + ], + "y": [ + -0.22160811627060384, + -0.20396133366088043, + -0.24800461689923653, + -0.2785571646911139, + -0.2010014478668365, + -0.16469850968357752, + -0.17572536189386284, + -0.19206239392557084, + -0.2946710998038715, + -0.18758298681189406, + -0.2605674934827026, + -0.2550368735422324, + -0.18044557357425708, + -0.2796317849260713, + -0.18523610963529377, + -0.2613129035832916, + -0.1666240202347511, + -0.1976282579812477, + -0.24018135426306264, + -0.21051611084785232, + -0.21702236028515587, + -0.2934520892644191, + -0.24742899191852377, + -0.22647339256854707, + -0.27548454098797287, + -0.17399093776167357, + -0.26497429316268245, + -0.15771709344990298, + -0.2787566886198316, + -0.21893407913922147, + -0.2524524943001722, + -0.1770787369734375, + -0.2668477547674016, + -0.23829022335991568, + -0.2696624230287358, + -0.195825877586688, + -0.20878158302562197, + -0.23107717848309942, + -0.29744499548522313, + -0.23747176982885956, + -0.16611682235286793, + -0.20608707010299865, + -0.2330184906521059, + -0.18972097155028234, + -0.17718848412187801, + -0.2742825927852023, + -0.23400928518633524, + -0.262008381787691, + -0.23014766748924298, + -0.2586982441178777, + -0.19112173221406717, + -0.21561300407760703, + -0.2695362394027705, + -0.2436506169405447, + -0.220773771400821, + -0.17979698508588285, + -0.15454634340692205, + -0.20297697992526126, + -0.19493129807461784, + -0.17865526791544428, + -0.22343165727121875, + -0.1743981185176352, + -0.21087365367927385, + -0.205635625379986, + -0.2843852834030462, + -0.24189934594152204, + -0.25969120353238534, + -0.27813462962957375, + -0.18186472651609886, + -0.2728753316157477, + -0.23818899011102576, + -0.2775434634542214, + -0.2516708355851365, + -0.20065961986288747, + -0.2768479108313611, + -0.25721217819947656, + -0.26693501393236985, + -0.19923270836116425, + -0.2919462540663527, + -0.23528099306756178, + -0.23198726733286226, + -0.22563575222149543, + -0.2155422044150262, + -0.2978119468332068, + -0.15939761007347042, + -0.19591349250641069, + -0.1982718803694354, + -0.22021849468374133, + -0.23749946524299068, + -0.15583809223023135, + -0.21794784804651704, + -0.2746879085945761, + -0.22425377188298004, + -0.24233334477459684, + -0.2861478166650862, + -0.25190588925469504, + -0.28951394436736877, + -0.27575828393413104, + -0.2636000245305068, + -0.22288815273555376, + -0.1937108680682587, + -0.28172430786460234, + -0.22679016394596457, + -0.18574458381894454, + -0.2532079095590062, + -0.2495942620956211, + -0.2541274194571035, + -0.26642661742891827, + -0.1643800985845383, + -0.25835302762906864, + -0.2565080697176225, + -0.23691326755166747, + -0.26379248941307015, + -0.2263839442557593, + -0.15526489109625996, + -0.1842048721122234, + -0.2663134681655525, + -0.21937852853185105, + -0.25309171849773293, + -0.29461151505376665, + -0.29552426276169, + -0.29193009259425856, + -0.2853548774344806, + -0.26259750904135004, + -0.25546125867565456, + -0.16786799268746494, + -0.16738389495870307, + -0.16762166364423872, + -0.25483248763720573, + -0.24442797826258866, + -0.24960099647691014, + -0.2349182651029945, + -0.2492950743110808, + -0.1635332857260371, + -0.27052309888871556, + -0.2819586670139416, + -0.2654168664166021, + -0.20417944511844283, + -0.24549874938745037, + -0.20488562197792964, + -0.2611157865937863, + -0.2596200952538608, + -0.2845680546608331, + -0.20853724315602873, + -0.27932121091721296, + -0.2837427898077954, + -0.20279712101187933, + -0.24033865237519186, + -0.2725835880645367, + -0.1636572914396454, + -0.21157134940414993, + -0.22440114667217037, + -0.2512138393405343, + -0.17935162021050483, + -0.1990408251406594, + -0.20285097357167947, + -0.256439379283971, + -0.2646049751814286, + -0.23454668717900867, + -0.21574232135359728, + -0.1848669930994554, + -0.24186788036457085, + -0.2660166589077526, + -0.2793787651739304, + -0.2786809157760641, + -0.20616623997424885, + -0.2674391895065514, + -0.23240190892281193, + -0.23583576375749082, + -0.2687992763050407, + -0.22955828353688562, + -0.2798036012004468, + -0.28595330382615125, + -0.16869394799926368, + -0.20541897528978575, + -0.15769606204812175, + -0.28603883845445593, + -0.16590650918994942, + -0.15928571494102808, + -0.2365466702273016, + -0.19677337986462995, + -0.2015795052678937, + -0.17997830270759496, + -0.17870749643236777, + -0.24864480554111032, + -0.2669696712864314, + -0.17264105168228014, + -0.17129618063308572, + -0.23299620162814003, + -0.25368153532277204, + -0.2579839403399419, + -0.18557182026637653, + -0.29617897052903086, + -0.16851193336355244, + -0.24874952192975758, + -0.2873397124483686, + -0.1770241035588819, + -0.26563290735578515, + -0.2181397943243435, + -0.18397335826384115, + -0.2641887778641382, + -0.18254225811938238, + -0.1797218358662131, + -0.28669593320999254, + -0.19861719026989352, + -0.1840225219682311, + -0.18807603246927873, + -0.281008974561277, + -0.2343194575472608, + -0.2554996649016901, + -0.16736155861425955, + -0.23104938675704867, + -0.21591783148588534, + -0.28998841626543476, + -0.27624477711452955, + -0.2500036612310293, + -0.1622274136984239, + -0.251932355352656, + -0.28778692791231836, + -0.2280731633976531, + -0.26670292098456294, + -0.2464209651839712, + -0.2604347072482591, + -0.2847860646359536, + -0.18356288968807938, + -0.2647057630125449, + -0.1922005582328803, + -0.16616123880967018, + -0.26808074375626795, + -0.1891204087223447, + -0.195385268901201, + -0.2530034528210566, + -0.20651490880888035, + -0.270704866718222, + -0.2456538052141114, + -0.24051720407816457, + -0.20155871018964017, + -0.15904544962606065, + -0.19110944757799017, + -0.20482662040561286, + -0.2518634861572583, + -0.2411073026116492, + -0.22391046442698043, + -0.21201928951298732, + -0.21505402329917123, + -0.17682358442147633, + -0.19994454760839975, + -0.15646639159979325, + -0.1829055735245813, + -0.16388120919342078, + -0.2613399594043352, + -0.18610550385176017, + -0.20807037964492964, + -0.17141645686081844, + -0.2677262285265698, + -0.2679543032730256, + -0.204076763674651, + -0.23346292886199183, + -0.29166313411481926, + -0.22864156723228463, + -0.21242785163750333, + -0.16013117724123152, + -0.17081098028444547, + -0.1812352599097345, + -0.25257434018356034, + -0.2439434162682617, + -0.2846613234007872, + -0.2937828092453605, + -0.1639071886776602, + -0.2021544013250393, + -0.17146837865499698, + -0.28469591508375963, + -0.2955206690175275, + -0.2620750467559404, + -0.2915582077309616, + -0.2718480659352325, + -0.23739519263577347, + -0.2476637662561863, + -0.19700472231342409, + -0.18391115962759072, + -0.26916794449226966, + -0.1650504165063395, + -0.22806341380370743, + -0.2863447308376166, + -0.22941498552123424, + -0.16150822781374288, + -0.2370218975333469, + -0.20374415408215452, + -0.17533863157200008, + -0.1625986846005882, + -0.27856185389082366, + -0.1753641189719727, + -0.23526101144670597, + -0.17331529975771937, + -0.16805614334006969, + -0.29169971190096305, + -0.2479226869453789, + -0.2586125802023047, + -0.2749429698799857, + -0.2901797548174578, + -0.1791059820231929, + -0.22354202830227538, + -0.15892566100071823, + -0.19358757890079076, + -0.18008742343530268, + -0.16282355568335424, + -0.28364957889916265, + -0.2145989441975631, + -0.2413519771565246, + -0.27676389785767486, + -0.26819261242201425, + -0.27558463308569997, + -0.2626723036594105, + -0.28775950101316017, + -0.183267162284736, + -0.2845782217097617, + -0.17151186021469753, + -0.1762036517534181, + -0.20705276775758213, + -0.18773065950690188, + -0.25904417646517164, + -0.2340620318673532, + -0.1884169410960087, + -0.19216583242007185, + -0.22911020830913167, + -0.1932465479535294, + -0.29755685701541834, + -0.2256331031665449, + -0.15852939134285585, + -0.1754156176324358, + -0.2683402540023179, + -0.20386371288755292, + -0.22212017477818713, + -0.19160055494603734, + -0.2117670354849313, + -0.2787411816999199, + -0.2539149151943866, + -0.19496274151554283, + -0.21822792081824055, + -0.21034732403342254, + -0.2652358900313419, + -0.2956339838188836, + -0.2652591279796069, + -0.18499004147540865, + -0.254564274225162, + -0.2385318426140473, + -0.19651796212881834, + -0.16941952397025023, + -0.1689685654646083, + -0.22553241123682435, + -0.2254308792013373, + -0.20634966461387533, + -0.28821755940526833, + -0.1851667916921975, + -0.19587331680264491, + -0.23733859406856345, + -0.16009498329334476, + -0.17402391275626689, + -0.2197902817511581, + -0.2880510930420782, + -0.2494420223806581, + -0.2399133399826054, + -0.24105151856509127, + -0.1850167227642927, + -0.22369040848565258, + -0.27704525327955126, + -0.15681061313724304, + -0.20772932561248394, + -0.16738444458157314, + -0.26081328910249413, + -0.25581887259699787, + -0.16444036398576553, + -0.18634282457637913, + -0.23771204750117414, + -0.23067914994312916, + -0.22857706721093046, + -0.2841046488045218, + -0.2199569680227676, + -0.22138325312754858, + -0.2781123773434677, + -0.26541926176022024, + -0.20191759726123948, + -0.19108092739886456, + -0.2443626253904356, + -0.25105861440474864, + -0.2888132662431997, + -0.2676373543318611, + -0.25237979634613705, + -0.2618521711489758, + -0.2022918858361647, + -0.26755470798665915, + -0.24864648507936715, + -0.2204697088505041, + -0.29447939452900074, + -0.2896615584695347, + -0.15925559066839753, + -0.2511602138811019, + -0.22754873533134579, + -0.2901994178788573, + -0.2803818362389028, + -0.19448113713075357, + -0.16938675637410108, + -0.18286571050948483, + -0.1876126055494136, + -0.20954950550683032, + -0.21095283733380787, + -0.15766453073573714, + -0.16213918890512902, + -0.22356179316276326, + -0.1976655861959395, + -0.15661533430742822, + -0.1792118296926307, + -0.2986799631530271, + -0.2748086894999963, + -0.18275832738420017, + -0.1557637203771567, + -0.18914884565877566, + -0.2916579580242493, + -0.1862389660272002, + -0.2859155790416171, + -0.1937986059653467, + -0.2826087840157017, + -0.1660540960720017, + -0.22614360118363225, + -0.1583382293370175, + -0.27666782921537963, + -0.29065371953547986, + -0.21201258011391405, + -0.22735505265886993, + -0.1868058690415183, + -0.15767675581015406, + -0.15971633011207062, + -0.19383538060170352, + -0.19205898148496975, + -0.192981949443053, + -0.18376959397374748, + -0.19038643421267704, + -0.167373443086927, + -0.24657755444471263, + -0.2954925115485918, + -0.17284599134398845, + -0.2198347258276105, + -0.16233069088940733, + -0.27122366586107854, + -0.27982613096198483, + -0.2120377572879043, + -0.2958708902872357, + -0.2744914761368636, + -0.20284460683203132, + -0.1642522202396043, + -0.1972720110928522, + -0.1901469745318904, + -0.19052231507999404, + -0.28032071770626116, + -0.2494008298945832, + -0.19782117645927025, + -0.2530701920340634, + -0.18883042642438824, + -0.15942790155863953, + -0.1805843645870029, + -0.2140460351310921, + -0.29541783013302086, + -0.1888523426728364, + -0.16734080000748994, + -0.27369232205907823, + -0.20547703821858926, + -0.21439524273064103, + -0.2206461778722264, + -0.2317659153333395, + -0.22048599400260505, + -0.17606963380029056, + -0.21035444453881003, + -0.28501610279654227, + -0.1604730484349601, + -0.1997486746778252, + -0.259432880936164, + -0.2189717309319348, + -0.15893277276312862, + -0.262689036579682, + -0.22830481481581116, + -0.23201373096857683, + -0.15838406838897062, + -0.2964856485081622, + -0.2531639216858122, + -0.280760103284727, + -0.18899092178681182, + -0.27757238689780417, + -0.1639633354769148, + -0.29593911657038185, + -0.29874741344563416, + -0.2561314869980799, + -0.19842874072473748, + -0.1935506530179034, + -0.23411545926952626, + -0.18684777681064305, + -0.2585911902013475, + -0.2355477485064399, + -0.1871816384400159, + -0.2921040051026406, + -0.2341006509246591, + -0.2800113720815368, + -0.1831585224522435, + -0.1853750398232072, + -0.16027584464304162, + -0.2635429846156068, + -0.16637599340203985, + -0.17122996562110468, + -0.16301731068532424, + -0.18881398051100517, + -0.2585266068393618, + -0.19600943745161797, + -0.24891923294049328, + -0.2766880695588587, + -0.27553794817221766, + -0.2893021619882542, + -0.20808196241483934, + -0.23600068687573067, + -0.1746433015762783, + -0.2193734788383026, + -0.16374037814902578, + -0.18927064474017416, + -0.17382074864633534, + -0.15591380020824155, + -0.1685680382279765, + -0.28668034602201414, + -0.2707787868143984, + -0.24421869900794338, + -0.22461978645143357, + -0.18956135279181138, + -0.17111779509078967, + -0.29868325136455076, + -0.250228116482467, + -0.28345363013941915, + -0.23588094771545548, + -0.15971680936817734, + -0.2698671428063414, + -0.2793645132043731, + -0.2854920629418811, + -0.2230308538098569, + -0.22520793194457206, + -0.2825467840583292, + -0.21560700112589806, + -0.2068374621826793, + -0.2803296600579356, + -0.1960185236109028, + -0.21353956178340133, + -0.23995410920022153, + -0.19481102563238314, + -0.23994377847721018, + -0.2610246775216167, + -0.20280467529743557, + -0.2840712391959363, + -0.2574550534699691, + -0.15720978016386744, + -0.19669979709031904, + -0.19021105765727028, + -0.1685331229205439, + -0.1851128687710038, + -0.15580787281655092, + -0.2190567149788818, + -0.2653103186025117, + -0.2057150862189806, + -0.2654755737745282, + -0.2494248246943091, + -0.26742130923509555, + -0.2558913450518523, + -0.2512993495173208, + -0.19572545288522122, + -0.18442763538456863, + -0.24685092315260165, + -0.2578982389612003, + -0.20051462118628066, + -0.1549560468935557, + -0.21609645179063405, + -0.2525140911635431, + -0.2962465312240354, + -0.176646536513261, + -0.17401039151692804, + -0.21005981519867623, + -0.23842822722981222, + -0.16942626026130456, + -0.1771085153130442, + -0.18581374786500388, + -0.2118657060685725, + -0.18178632864800603, + -0.2702611109815558, + -0.23421481427870228, + -0.16637788207971535, + -0.25025492390467075, + -0.22281903829179012, + -0.23517244468714732, + -0.15894903720818349, + -0.27854675657416456, + -0.2110898085052576, + -0.22237360456221433, + -0.2607755117421269, + -0.21459308502204577, + -0.21376496817502405, + -0.2770159068128744, + -0.16181816569348376, + -0.16313043333413801, + -0.15605255254056732, + -0.2767921125535408, + -0.19497594929987072, + -0.2426899954782576, + -0.1702528295184088, + -0.2607915202134281, + -0.2645501069233995, + -0.18980904444219315, + -0.2283333739059787, + -0.25248958986229697, + -0.289728351472599, + -0.2781804618026803, + -0.22160611324573615, + -0.19373666003753298, + -0.19838870897255906, + -0.2169832302417192, + -0.2550316184502576, + -0.25702821740665716, + -0.17681774551314836, + -0.23546190342439272, + -0.16972072126244975, + -0.2886042790378306, + -0.16721341746097354, + -0.2598340130676424, + -0.22374376886969632, + -0.1604957263668808, + -0.20689864875416103, + -0.2330116287299622, + -0.15935933051901857, + -0.2963711075708382, + -0.29578696602382604, + -0.16160990912606552, + -0.2550364196749895, + -0.24497701555713913, + -0.2588838331142244, + -0.2855314076706687, + -0.20936361954988786, + -0.1989736537218746, + -0.19585498687742153, + -0.27176186496234533, + -0.2087665513192142, + -0.25833473865718953, + -0.1560608160142971, + -0.2041125872337457, + -0.22654989472040393, + -0.17443073573334777, + -0.24652224838874448, + -0.17486184586441283, + -0.25424908070784064, + -0.15955767712335817, + -0.15563623023784773, + -0.2257496273217922, + -0.1753092331826997, + -0.2943844901226865, + -0.2638205130606731, + -0.24772684970262768, + -0.20795946454281905, + -0.15719079763808036, + -0.17345903563134632, + -0.29206051397383437, + -0.1683705772763208, + -0.1626826463186901, + -0.24417141026460537, + -0.17891784438512182, + -0.19452249644802405, + -0.2544702450489521, + -0.26533508078566415, + -0.18061390639251346, + -0.2590224366174638, + -0.24588091608495047, + -0.2000159090361825, + -0.29383561042808676, + -0.20691677189945362, + -0.15961521936782697, + -0.23210899902954873, + -0.2985706168784768, + -0.23323341446456541, + -0.20587386546040565, + -0.2219446345502734, + -0.25210046030790134, + -0.2858357518942137, + -0.24828799796359935, + -0.23759231579493703, + -0.22478322050339128, + -0.17749183152113263, + -0.2361365104656357, + -0.1910225561117497, + -0.28055523680190003, + -0.19459084612272615, + -0.2942322894519158, + -0.2660677335112149, + -0.255762641080788, + -0.24844982826559983, + -0.1826856026286381, + -0.21191829330499684, + -0.17967986218758442, + -0.24997745895729534, + -0.2407785800054686, + -0.26971263011845453, + -0.2635403797527595, + -0.19106456575398217, + -0.19028406479304055, + -0.18487996368695564, + -0.21597055932221332, + -0.1910243021216615, + -0.21662696225478034, + -0.17631240521145958, + -0.2842195184345411, + -0.28131016943118126, + -0.2575084618801715, + -0.24479174579765353, + -0.25290710507270214, + -0.20944277378284454, + -0.242917428932306, + -0.17405304781784725, + -0.21993448461695386, + -0.24931981187919722, + -0.18137911096177137, + -0.2795478448654952, + -0.24721735133089418, + -0.28274633917082126, + -0.2039894245397724, + -0.23977604992195914, + -0.26273511249135656, + -0.23428024627862298, + -0.23109798924853733, + -0.16246444345022926, + -0.19210518800618437, + -0.21580687018504416, + -0.17340135166884382, + -0.29592073924302525, + -0.23570025872181188, + -0.2032261960136021, + -0.27151104662236203, + -0.18003543084908616, + -0.22623516199536178, + -0.2233805215248978, + -0.15709792743504658, + -0.22265911164263275, + -0.18642679218399089, + -0.16737888663073944, + -0.22492476230143646, + -0.23232237231552766, + -0.23971793024771246, + -0.25120477807295766, + -0.2844618835773707, + -0.2976267232982882, + -0.22985313809447352, + -0.23396270653843537, + -0.2846166376529963, + -0.1903570915854811, + -0.19403953658764864, + -0.16444669806961706, + -0.19793202552603195, + -0.2952395471870622, + -0.24477925123897643, + -0.2329603300638003, + -0.21391105453650952, + -0.2910338105118854, + -0.2865104723992927, + -0.1840263585035849, + -0.28589857640470984, + -0.19994455881929635, + -0.21137147423641722, + -0.24901043500475534, + -0.2668168567146942, + -0.22108627682618676, + -0.27996746534877504, + -0.19135617736470847, + -0.18449875603544094, + -0.25988035812847693, + -0.20794735457061936, + -0.2689876314632867, + -0.25949982387081477, + -0.24325187581959518, + -0.2862951379394128, + -0.25927949499921216, + -0.29677068784229294, + -0.20812904671964622, + -0.2788418810619412, + -0.23264075487502214, + -0.19461902548071208, + -0.28483299400678674, + -0.18065915266110494, + -0.1685850354666685, + -0.15518928411768598, + -0.2608745751028097, + -0.2280137509480966, + -0.21998484801816282, + -0.21832931575972586, + -0.22758635476600406, + -0.24833129894071312, + -0.255830742906508, + -0.18535555009210603, + -0.16909963792686797, + -0.198454998617013, + -0.1792716172785875, + -0.19963034686845446, + -0.29537746411331584, + -0.28543463330580676, + -0.25093789019990903, + -0.22870419572184747, + -0.20464996802018953, + -0.1826492866847973, + -0.24449754640125645, + -0.2734200188483607, + -0.17621269194925754, + -0.16318348677568212, + -0.2937681114733244, + -0.22384717460736983, + -0.15565875894824835, + -0.15727000345574474, + -0.23174328741608785, + -0.24860916899237429, + -0.15906967162717345, + -0.2417645695162036, + -0.2812472061104348, + -0.24954241553266077, + -0.2493606613771724, + -0.2725891395860234, + -0.2786311376676288, + -0.17539751273878873, + -0.24145676998890236, + -0.27122387321353253, + -0.21610032957279068, + -0.2595751034208605, + -0.28008710051694247, + -0.2683476707097988, + -0.27618839526573324, + -0.21774856688627794, + -0.19337011777612975, + -0.24516506154843504, + -0.24810520233564962, + -0.19820154204426277, + -0.1989369645646879, + -0.2856127110946626, + -0.17478337570553998, + -0.28159941934197114, + -0.21942390844329812, + -0.241353453503342, + -0.26169080832973285, + -0.26536750152254207, + -0.23152643248002786, + -0.25434101923046026, + -0.19664161594948995, + -0.22962927195403693, + -0.2695772973508224, + -0.22552467535411164, + -0.250224907637835, + -0.19384409301274072, + -0.1558407394839137, + -0.28803026871443155, + -0.16657505494784827, + -0.23404118356568485, + -0.16874425726599998, + -0.2424622497728519, + -0.23801640946391517, + -0.21551731004601943, + -0.16706074323951392, + -0.22388447783434684, + -0.2979233834292279, + -0.2483672670949115, + -0.23119071054029125, + -0.17343297879128913, + -0.17690638949181642, + -0.27898050059833673, + -0.2278476907811059, + -0.23977750455377408, + -0.2513902765685849, + -0.276988993564827, + -0.18012259587244675, + -0.15663203403278492, + -0.24418001318864951, + -0.24438293937080446, + -0.1595648869787379, + -0.2910048024613481, + -0.28165946849840195, + -0.18451584113416364, + -0.20890033480006331, + -0.29574190895426244, + -0.2841338666698158, + -0.28899811700616235, + -0.18040013427898888, + -0.2375579979480809, + -0.2420742728752484, + -0.26235406111312837, + -0.23934003908020413, + -0.24886318137344177, + -0.198445388922752, + -0.15867644767709807, + -0.23163154684490264, + -0.2707275126788202, + -0.2860660966644758, + -0.24332067453711934, + -0.23719238873503393, + -0.17459805817268584, + -0.29355209923933867, + -0.21245287997347795, + -0.15800037394181923, + -0.26754955551895887, + -0.2916085688284379, + -0.22456811641585928, + -0.18422095513544168, + -0.2795259424154374, + -0.2566331591089511, + -0.19788073359245661, + -0.16584998149156743, + -0.22620035105344186, + -0.1930919696421594, + -0.18773001706832176, + -0.2952536681409196, + -0.2069836262311996, + -0.18420709540015168, + -0.28625164737072833, + -0.19599314494057402, + -0.2347405601600579, + -0.25582192737826404, + -0.2042656141910491, + -0.1802100954910813, + -0.25372929327018634, + -0.23279725660031975, + -0.2336680032551317, + -0.19105580245455206, + -0.28414212021517843, + -0.2696394725398971, + -0.26582830254876183, + -0.21620422179729873, + -0.18704075559462624, + -0.19969879161218473, + -0.1855828458848549, + -0.2276041446538421, + -0.21367205147644175, + -0.2510065337511376, + -0.21510474828103984, + -0.2063373337703015, + -0.22047458610457898, + -0.2520424392736561, + -0.275592452596733, + -0.2724831426069585, + -0.24421279648508648, + -0.245521148796207, + -0.29771417831657754, + -0.29610438199819106, + -0.17585907375969384, + -0.1763836119042237, + -0.28797668274345345, + -0.1933241840581664, + -0.1754652572596997, + -0.2013818505744103, + -0.2725058967534035, + -0.19316212441475333, + -0.20559181435590934, + -0.1950849550882635, + -0.21218119829198215, + -0.27608133862967027, + -0.27454108465209776, + -0.16187918456636563, + -0.27545700468171086, + -0.27663239582199095, + -0.2867805440560359, + -0.21376853196292567, + -0.255800784248003, + -0.1550421892348865, + -0.2525061892780387, + -0.27361803466998746, + -0.2908136388978073, + -0.2068083471538017, + -0.29043925216921795, + -0.24386804273561816, + -0.1982202584425829, + -0.16264497186467203, + -0.22426584406018077, + -0.24252392043467172, + -0.2303742619490328, + -0.15709116977793325, + -0.15827137895129495, + -0.16381875520713082, + -0.2890399698582178, + -0.20079584017132013, + -0.2810696898836195, + -0.28621299208811396, + -0.2745283549479036, + -0.19856315072907166, + -0.2095379411925002, + -0.1623996423496077, + -0.16510735360475787, + -0.1835756146196395, + -0.21511401239519784, + -0.29394974087465287, + -0.16829237082908305, + -0.16136839167350253, + -0.22227165316518177, + -0.19819743530520068, + -0.2444242210242495, + -0.2372006701357196, + -0.21616930930328718, + -0.20111490290036638, + -0.2478843043024613, + -0.2908437272982311, + -0.29683661647562903, + -0.2793134764579664, + -0.22466075755078319, + -0.293331259292317, + -0.28401949945693944, + -0.2690069253194499, + -0.20227457902061238, + -0.2587583322176276, + -0.22012066662650387, + -0.17805806838096708, + -0.298560530363381, + -0.2512547984897224, + -0.22478729463773428, + -0.24439790571304973, + -0.23565573563148604, + -0.263034357115182, + -0.2921634993731733, + -0.17949544527284414, + -0.17559209895900488, + -0.16283709981810118, + -0.2783200127323097, + -0.15964752465433676, + -0.22069610301660697, + -0.207035355088666, + -0.24619528935993745, + -0.21417377828887665, + -0.18365156766196097, + -0.23914187590400904, + -0.22923135320841745, + -0.1581679513896314, + -0.24191430204153458, + -0.2021097061797727, + -0.25423450819775056, + -0.21354518256138, + -0.229589180909478, + -0.1988687121302734, + -0.2984177254965442, + -0.17580588166827782, + -0.28115335719535184, + -0.1702284592786391, + -0.16976349800954793, + -0.24881630983708644, + -0.23668059965966567, + -0.1912828475552104, + -0.2530581341583995, + -0.277435293924346, + -0.17167078045136255, + -0.244857169803819, + -0.2312027069459569, + -0.29019498113213016, + -0.2521571675556203, + -0.16204712592578477, + -0.24267700576183843, + -0.16719926562778858, + -0.27219232127978993, + -0.28551639423890074, + -0.2825989731920497, + -0.20652127707922946, + -0.2960960648161283, + -0.19669579476609345, + -0.23592645054685168, + -0.16097985702366827, + -0.21536290763021904, + -0.18082002866070002, + -0.2688813716761823, + -0.2011806787949204, + -0.19076242227792578, + -0.2265237955429995, + -0.25663801772212314, + -0.20980680042185615, + -0.2081424363676763, + -0.1785326056015366, + -0.2111507378970007, + -0.2751421587525989, + -0.18144353210453557, + -0.2194045512872025, + -0.21849232473748098, + -0.22861389601298818, + -0.22464068684869015, + -0.28447920841342206, + -0.255064357580336, + -0.25661338718829846, + -0.25906668080344475, + -0.19726102703060827, + -0.16653095466923365, + -0.1582285367452612, + -0.17272999881138568, + -0.19924589386397734, + -0.1925848641164637, + -0.23731792021401746, + -0.20743500908828771, + -0.22489912810926072, + -0.17110160718583547, + -0.2051744596555738, + -0.1877622132515197, + -0.18450123861578482, + -0.2969114083619441, + -0.17389506522577022, + -0.2037801570789807, + -0.21495495560449682, + -0.16046484993312826, + -0.2163874475280489, + -0.21325875746954256, + -0.20354575965367122, + -0.20371931285136224, + -0.2665182870858924, + -0.17667665308396463, + -0.17515430807655774, + -0.21870574555865918, + -0.26062588544676407, + -0.16049009547524368, + -0.21636193499801104, + -0.1763121749395311, + -0.15542402306627892, + -0.1701713990544425, + -0.2555971078893739, + -0.2146756774173251, + -0.2956406062247066, + -0.15467813525563354, + -0.2845599343808933, + -0.20673916956302318, + -0.2647615487052413, + -0.1607759503950977, + -0.2648213485441305, + -0.2432278254648077, + -0.2070048428375036, + -0.28623786996410056, + -0.2444842594959351, + -0.1927197493061839, + -0.16049174920855688, + -0.25290755739379267, + -0.2250280537871422, + -0.24740533079167712, + -0.2578517487309576, + -0.18482371255232596, + -0.29127547499875095, + -0.24763958930625413, + -0.19237490352426712, + -0.21099639672178022, + -0.15474327835281879, + -0.16349273176941997, + -0.2832405118333811, + -0.23076007434504944, + -0.23739175600139895, + -0.23138171249633532, + -0.29774968881508584, + -0.23631773916569476, + -0.1961105552875336, + -0.1707991766101992, + -0.18332333901239967, + -0.26167016078431093, + -0.21730934514862477, + -0.2533219586314155, + -0.21652362448071574, + -0.24948694642937821, + -0.20857953784812255, + -0.19479013515159826, + -0.2260823398429041, + -0.1881439436041617, + -0.2607833963682765, + -0.20095363655608678, + -0.17396970292012742, + -0.23136831880627245, + -0.22975352567751867, + -0.19206770417518704, + -0.1635200891289396, + -0.2231391073931359, + -0.21568929808624737, + -0.23271810136786378, + -0.29221832850930163, + -0.22606025785475448, + -0.2931047334687098, + -0.18050925482405927, + -0.19250429633469823, + -0.24200648031879124, + -0.2801550966845365, + -0.24209045473458146, + -0.1950857664653354, + -0.17756850625383075, + -0.20092180133301507, + -0.2598783571273595, + -0.17122835404845196, + -0.1875815814266345, + -0.20314220124516275, + -0.20652066850524178, + -0.2440958637208267, + -0.18499886634150747, + -0.2958556817263826, + -0.21267780247727736, + -0.2645184379938195, + -0.25469438261930244, + -0.2541687695964797, + -0.19842985960868764, + -0.17983554283417336, + -0.19592381667205902, + -0.23725883721278107, + -0.16544326575885626, + -0.1661120704335101, + -0.2029243389361008, + -0.2702545664556363, + -0.2913771636387334, + -0.21502504783323287, + -0.17382266481126918, + -0.20146910944630378, + -0.24678091091876744, + -0.2766110889679373, + -0.2473976611178914, + -0.24686548335385408, + -0.16642913444542118, + -0.23250330823262755, + -0.2865183825073381, + -0.25697979858488573, + -0.25343138065846654, + -0.15933834077554537, + -0.20623082032176826, + -0.24208309696800542, + -0.27917034291934584, + -0.22811804081750162, + -0.22805108435854765, + -0.22082378258751617, + -0.253600803196119, + -0.2802834995770681, + -0.21557349544904147, + -0.2622301525462879, + -0.20057929318660417, + -0.17877778723862542, + -0.28920959027423765, + -0.19486765289978328, + -0.18900689893048456, + -0.22641972514907632, + -0.19494558265384598, + -0.23722209440422, + -0.16308529788282328, + -0.24997364806087474, + -0.2355668514507484, + -0.19819167930690354, + -0.2936567578395754, + -0.18873610257101892, + -0.2688387489962838, + -0.16979998860505793, + -0.2510176744117002, + -0.18852555080125588, + -0.1907720319290602, + -0.1958423657418738, + -0.2537990721461713, + -0.2507706769800539, + -0.2748532228762707, + -0.18555811406488174, + -0.21820286800059596, + -0.27271956380768286, + -0.2151920196342082, + -0.1598877711229105, + -0.27594215447784814, + -0.24599254835061685, + -0.2686636525257214, + -0.1845616720621251, + -0.2368474216458597, + -0.24666310249930823, + -0.2590390871600753, + -0.29230481830992416, + -0.226093087095583, + -0.1764757161385102, + -0.2533068777059564, + -0.2116025987930088, + -0.2818422854958231, + -0.2127380381475799, + -0.17564589689026844, + -0.23150633656221817, + -0.18849021601296784, + -0.25635523175441205, + -0.2723690535140038, + -0.27993134236422107, + -0.23534678345180093, + -0.18694353137590555, + -0.28988926740232307, + -0.21933488085807956, + -0.2777466823425524, + -0.2651130934292225, + -0.2895061956612312, + -0.256400827829076, + -0.28831362011516976, + -0.2815915458895187, + -0.1997875009423217, + -0.22325112204921368, + -0.2071976923930741, + -0.20432330187909414, + -0.29365805337492196, + -0.19146285862428303, + -0.17346547615458519, + -0.2574178771353096, + -0.21820080201106434, + -0.1824641980064981, + -0.1939772368952432, + -0.2627659272671784, + -0.21820827975067691, + -0.25864055864143226, + -0.16627668199388523, + -0.29163361093629314, + -0.22292026212143246, + -0.156716730256965, + -0.16779640156006626, + -0.26248506355250595, + -0.2755320731051857, + -0.2771862995193589, + -0.24751337919582556, + -0.23454506924223695, + -0.20481628004835928, + -0.18575118558724604, + -0.27131496650867903, + -0.2449766632883624, + -0.23297314962616628, + -0.17480956850180432, + -0.21269628646995617, + -0.24241161585961055, + -0.2240060269069806, + -0.22647349612965123, + -0.21304918738070394, + -0.22234927957229855, + -0.19748967885022842, + -0.20901135807233479, + -0.18426552235938215, + -0.22724639911609684, + -0.15910404053588817, + -0.22290448171659372, + -0.23850281697856163, + -0.254347813146387, + -0.25168412573761545, + -0.20957148160713132, + -0.2308237216335551, + -0.28907095024620955, + -0.18522215453780494, + -0.26185721822244856, + -0.28125026829318056, + -0.2408064075799767, + -0.2633634232800175, + -0.2367331402687562, + -0.23688775818989866, + -0.20754611416155355, + -0.24544764475412845, + -0.1721419882294708, + -0.2338429503580401, + -0.28235564147028414, + -0.16148856672253814, + -0.16221266707805138, + -0.241771022969841, + -0.18205458714606151, + -0.1878978504647889, + -0.2027916049180597, + -0.2513980890912902, + -0.2408987565801033, + -0.22105815602819617, + -0.19359326660337953, + -0.1610814397082065, + -0.21111688362002967, + -0.23786314680620277, + -0.21257650518116591, + -0.18292622857686344, + -0.22666872137563016, + -0.2569330601659605, + -0.23934737869058412, + -0.26696541867644824, + -0.2841203789667926, + -0.21034899462559664, + -0.28032068159632334, + -0.21556111627179014, + -0.18958528591461465, + -0.2333591425275566, + -0.1832021546341266, + -0.23166637447009603, + -0.23886786678947736, + -0.17735828661273978, + -0.18479737942696745, + -0.27356632884918924, + -0.2454106705763343, + -0.16575504745098113, + -0.1955792332938458, + -0.19333297722613124, + -0.2729433575264106, + -0.2939246285381669, + -0.2501535459352161, + -0.2582243828304896, + -0.21187076633086108, + -0.1577342840557121, + -0.19807273202446007, + -0.21344013556164831, + -0.24515885769752854, + -0.22165381074361315, + -0.1724311338000965, + -0.19356598707721157, + -0.17779565086228488, + -0.15870899185636397, + -0.16703062889103343, + -0.1578371618681679, + -0.18943932933257257, + -0.22915070544550048, + -0.25259195560396325, + -0.2789400944822567, + -0.25404286187758046, + -0.27316917381366684, + -0.28151742328695606, + -0.28532647069518535, + -0.27914637265641495, + -0.27856375840916603, + -0.26854174285962484, + -0.27945237962683384, + -0.27898280728287755, + -0.1665898765491227, + -0.2579493005135958, + -0.24722247988415846, + -0.2964123313764723, + -0.18676794012993247, + -0.26499469453280483, + -0.17375263163492366, + -0.21649487399428788, + -0.23928670689901377, + -0.1605134178306489, + -0.2378958814644771, + -0.2968997848931132, + -0.2777313978308892, + -0.22830734139993392, + -0.2947780589170834, + -0.166581643186107, + -0.17273187471009277, + -0.2731831864417645, + -0.1786905460919844, + -0.17265039844915364, + -0.27711553615139795, + -0.17437085528648982, + -0.27985491651276156, + -0.24355066210475032, + -0.25505485097876557, + -0.261805545873871, + -0.26765796124071656, + -0.2763429947479614, + -0.27347467833220046, + -0.193241659824826, + -0.23892948086408317, + -0.2650660427843298, + -0.19845190002134913, + -0.26400551042272136, + -0.26736130081319365, + -0.17465072556109532, + -0.29592972070948254, + -0.2363519916182759, + -0.16012805675936492, + -0.25197729070285546, + -0.23237080912205105, + -0.28460953610430434, + -0.2363843051408607, + -0.1793368699566245, + -0.17671595735202994, + -0.28295669596104833, + -0.29195578050792864, + -0.23827613240098586, + -0.18275881522914048, + -0.24196963851811867, + -0.28469726993398037, + -0.2534581960880323, + -0.20199866036876207, + -0.23187813787008793, + -0.1987931366941093, + -0.20827348410444466, + -0.20160398774994795, + -0.2120257563907174, + -0.253193521262969, + -0.162684627490784, + -0.25253187023154133, + -0.2982556848344328, + -0.17499301510072932, + -0.1579471870058362, + -0.26678019001788583, + -0.1724101672826353, + -0.21434188354007677, + -0.1993507877428777, + -0.23478060175805854, + -0.23559259704399121, + -0.25015138509114704, + -0.2930825796822048, + -0.17960275977523765, + -0.211345364368152, + -0.17657551841836427, + -0.2877023055125895, + -0.19937614711416413, + -0.25170141416177727, + -0.23209127199372964, + -0.23926193418160938, + -0.2502972583904214, + -0.16124610673510034, + -0.24661449157413545, + -0.28442704790093626, + -0.17775824942720508, + -0.15800444695963195, + -0.21574246675770317, + -0.182683161040636, + -0.26578561322240446, + -0.2674201281242001, + -0.25709324887659357, + -0.27814830023124565, + -0.18014424387429157, + -0.2382609898131816, + -0.21241218604544476, + -0.16222672892585643, + -0.23746537786559357, + -0.24327914290790936, + -0.28651061619006823, + -0.1562049534138234, + -0.19642933710446306, + -0.19991488539966323, + -0.20858017318109853, + -0.2210392554958917, + -0.2650455164784736, + -0.2857540895619538, + -0.2611046004137951, + -0.20777992080883323, + -0.19700168003241536, + -0.22304928556055703, + -0.2817244625792822, + -0.16577450276415193, + -0.20524790091778522, + -0.18319791931008528, + -0.20435435052431575, + -0.16484224293793753, + -0.28472848311908466, + -0.16121433281736783, + -0.28092279758839866, + -0.2605657803639215, + -0.21178752423847513, + -0.2289553384541101, + -0.21769183758415106, + -0.2443664413900288, + -0.18125334534358198, + -0.2342976911286791, + -0.21482435172014136, + -0.2729557948853808, + -0.1685753398531657, + -0.28341963480500976, + -0.25594806209778365, + -0.24874727426369822, + -0.27768491364644726, + -0.28227321542918493, + -0.2555866616372137, + -0.15627778414945415, + -0.2824933703981514, + -0.27061919775824467, + -0.19653760884085783, + -0.28470656416869145, + -0.27615782458926075, + -0.2801720501677333, + -0.18730739795282653, + -0.2061967426577481, + -0.17477503495089652, + -0.18128317878585276, + -0.20568868844952096, + -0.298532227124465, + -0.27354471113086914, + -0.2758991184438265, + -0.20542985639837363, + -0.22401888605487214, + -0.1764793128959386, + -0.24007949037420856, + -0.2853136548582389, + -0.21828568468456944, + -0.2015477745051686, + -0.1687685958203118, + -0.19725253449817554, + -0.19727443508428416, + -0.1807144971906592, + -0.19542807277131935, + -0.282800021013917, + -0.22324342053698104, + -0.19987013604794443, + -0.19034946228716412, + -0.2634881618647184, + -0.25635730939668966, + -0.24823235403301194, + -0.2496552127746631, + -0.15765529702696024, + -0.28617215817662206, + -0.18860241928975996, + -0.28550483652854486, + -0.23298134727604952, + -0.2880168130177248, + -0.20295116649528777, + -0.2175883273143776, + -0.2212305029219869, + -0.18540975571903384, + -0.2139612808339677, + -0.2931129020819199, + -0.23824913780640355, + -0.166260961258371, + -0.17084855758952167, + -0.23354756154965026, + -0.17903549098290228, + -0.29637509050095734, + -0.15635791043976102, + -0.19612143137105403, + -0.2378287341430949, + -0.2776576993156972, + -0.1901270529375125, + -0.24316980447728626, + -0.19307478971954162, + -0.1709230205629746, + -0.17944561312644014, + -0.17149852592789996, + -0.23085457866268289, + -0.22602423627653376, + -0.1797460061354233, + -0.20891280481442492, + -0.2248400840758969, + -0.24341242961237233, + -0.21323598687997763, + -0.2224832385216494, + -0.2594740422462156, + -0.18937154854847693, + -0.2701494859002583, + -0.27145432460023655, + -0.24654249011314033, + -0.2509230395968229, + -0.2768539966905871, + -0.18815122917843619, + -0.20681819553398756, + -0.25280237084623947, + -0.18871488059669017, + -0.19366028061069052, + -0.28163096382828473, + -0.2717279029987593, + -0.21919728112838036, + -0.18201656191152693, + -0.23648695744688442, + -0.21353208614803074, + -0.2907804421537365, + -0.2363227920496125, + -0.2256699480625991, + -0.27153654829362345, + -0.28303559499243236, + -0.1814648380916036, + -0.22989382341738068, + -0.2870480622092615, + -0.29174200619372864, + -0.2846539956251041, + -0.24990738455557193, + -0.27895316581894775, + -0.2684345223868372, + -0.2735166104922693, + -0.24847269894828083, + -0.23336031755477182, + -0.20038487300935415, + -0.23350514624642682, + -0.23197757423042364, + -0.1691767334293418, + -0.21786095873592923, + -0.16892742997405844, + -0.27557893955938295, + -0.27620206211130444, + -0.24514791044035963, + -0.16575232153081917, + -0.2688640197411254, + -0.1741229078370824, + -0.2712441264846264, + -0.2314178501100193, + -0.17761813427443274, + -0.20240484137017634, + -0.23594865359983422, + -0.1721712014941937, + -0.2477277059025543, + -0.18331985928372632, + -0.24941407646890387, + -0.21274668494395477, + -0.26677648789742564, + -0.2774454304487285, + -0.2577847026738529, + -0.17268506847148707, + -0.2774511959807017, + -0.22106601231747003, + -0.19214855994053043, + -0.26441532316655464, + -0.2564682521192658, + -0.1655461868712191, + -0.2674252461804113, + -0.15623133984865012, + -0.17315107506865032, + -0.2335679861586748, + -0.17617261871323173, + -0.1779547713986382, + -0.19295950969278428, + -0.20752081208318998, + -0.2114659622552718, + -0.2741587693118505, + -0.24081950921085862, + -0.27028981497767, + -0.20524738592284542, + -0.29479559443260683, + -0.2519588975747065, + -0.19519534348111645, + -0.24983894913880916, + -0.21562163310417237, + -0.2765679511018976, + -0.2729392928076577, + -0.2028441571968892, + -0.16668980306770634, + -0.19249023348837624, + -0.293911768681869, + -0.2216563149357233, + -0.18788559563955448, + -0.18102231827959336, + -0.27156359525003987, + -0.19062301690211825, + -0.26637809523078043, + -0.23400947131740027, + -0.26261872559909033, + -0.24851634935582897, + -0.2331210925197257, + -0.2755941218472654, + -0.17044194169040344, + -0.20879182128920268, + -0.2703166607928549, + -0.21845777435284025, + -0.26345923069671984, + -0.18542100248124477, + -0.2258850233970784, + -0.20801557673650878, + -0.23428891803306606, + -0.18550964507879653, + -0.2557860275326834, + -0.2812851287530719, + -0.26906096984371486, + -0.17610261580775943, + -0.25161913785396783, + -0.22689359756232783, + -0.2953818073724636, + -0.26397563625362847, + -0.24066638912185187, + -0.1817068508534887, + -0.15550555331682236, + -0.19044218312901978, + -0.29730726878474945, + -0.22714056463845272, + -0.26578576815537247, + -0.2392392222898208, + -0.22565057898167545, + -0.16044342035458303, + -0.16948659842525654, + -0.25334642852681327, + -0.29436759102687987, + -0.2481903887595758, + -0.24844711148018017, + -0.2259338463296609, + -0.2138212548550695, + -0.21265430257418122, + -0.172821891356335, + -0.1568999868909966, + -0.25118679139940414, + -0.2431972315606672, + -0.1555133311560963, + -0.23778557248278206, + -0.26570747125334093, + -0.2855606538101744, + -0.27674339150200755, + -0.2474991447666769, + -0.2731523490799625, + -0.24484499195601664, + -0.29053209910008965, + -0.1930749239265442, + -0.16867075465152337, + -0.26977228598153125, + -0.24791304208921272, + -0.17741522652022712, + -0.2764414461783437, + -0.2393201530565466, + -0.2377433568569574, + -0.18999239484299063, + -0.2013194645566891, + -0.1624731431688929, + -0.2597725639079552, + -0.25753297125031466, + -0.24496890537845714, + -0.25805982022089197, + -0.2898502070924052, + -0.1707100449612092, + -0.21156099141343546, + -0.2600720455601629, + -0.17547909471863782, + -0.2890310734641859, + -0.27312861581658154, + -0.22330436689538646, + -0.28753146883700237, + -0.291227603751941, + -0.21049298250998794, + -0.29542583059013683, + -0.21405399440957237, + -0.2985101231974064, + -0.23243186336611837, + -0.26575945704043563, + -0.16121581769589927, + -0.19201527884157116, + -0.1753921096978599, + -0.26842710748955534, + -0.22293560819914468, + -0.15923763538307872, + -0.2817148715590365, + -0.2365148020443637, + -0.29301840702286575, + -0.27916525912082296, + -0.2691659121535141, + -0.26159556422528585, + -0.26694901470601584, + -0.282119633383547, + -0.29687889923592825, + -0.2376756542085307, + -0.25615983759012595, + -0.21566819810828827, + -0.22701247497138632, + -0.2770909164687673, + -0.17088868335017204, + -0.1680201957915767, + -0.27530489536311775, + -0.16941281865554753, + -0.17843840651201792, + -0.21737021027799655, + -0.25852391507831846, + -0.21346488901028984, + -0.27367613427379817, + -0.17287986966956212, + -0.2921530060979388, + -0.28971295284956494, + -0.2502005124569125, + -0.24123720816729596, + -0.20236263505300597, + -0.22349422513183556, + -0.2641118425279603, + -0.2825203507628241, + -0.27346903221827157, + -0.16241455065135063, + -0.27797246382465923, + -0.28614873979933564, + -0.25895263249637546, + -0.19090004371050906, + -0.26784963182544325, + -0.24931778665838022, + -0.19999247746509557, + -0.2793598855858929, + -0.23905077588304352, + -0.2665991137982808, + -0.16710390932075325, + -0.286699075328447, + -0.255337230618967, + -0.22828573495936272, + -0.21211177536505837, + -0.29764502669891124, + -0.1987840384803214, + -0.2447489663735714, + -0.27673208204379923, + -0.19476620373666373, + -0.18133643401044058, + -0.2938622796572171, + -0.21982271770885292, + -0.22403179104475882, + -0.19062472442673206, + -0.21931306137245163, + -0.27239662966279593, + -0.2115087521892412, + -0.17966396451148178, + -0.27608051155142127, + -0.24014196973446567, + -0.2301147370517329, + -0.17894635703575057, + -0.23289418591852906, + -0.24974278762639657, + -0.23445444658945913, + -0.22810991387777035, + -0.16485990845329695, + -0.1803918030092428, + -0.2560018602847043, + -0.2775947357939713, + -0.2269390041738522, + -0.2931997728560894, + -0.17114951895821942, + -0.27018062354356454, + -0.1663437355167024, + -0.24136408760607758, + -0.2772171547172126, + -0.159848890773304, + -0.1638547267032229, + -0.26389446584389065, + -0.2744089390802424, + -0.1824111500535116, + -0.1934702112607668, + -0.24633816950565707, + -0.19547860722585259, + -0.2821103986660084, + -0.28629253635893465, + -0.20906230300757586, + -0.2531602163332487, + -0.275294019573299, + -0.2038374389364725, + -0.23078398926340993, + -0.2173516639426891, + -0.23455134577077505, + -0.2214716359352235, + -0.26795469097504326, + -0.23254160299885882, + -0.2694627348119418, + -0.29116329029532756, + -0.1679081644337697, + -0.20703321778776093, + -0.17775810973870898, + -0.28398947033007826, + -0.21595934080584653, + -0.2203886813533668, + -0.21513164065307494, + -0.1770799855560225, + -0.17280946599736394, + -0.17632798001325756, + -0.22197264542778317, + -0.17472899617016716, + -0.28574096389187814, + -0.15632685290370896, + -0.22364994377654396, + -0.16899623066799058, + -0.23741423845469092, + -0.22276639239392293, + -0.20310413959409895, + -0.1843256625744619, + -0.21238588937368125, + -0.2827823807172241, + -0.2682789864535664, + -0.282381388633539, + -0.17238178634280635, + -0.18637749377184568, + -0.2818473910224497, + -0.2811264556400659, + -0.2892267453216237, + -0.21229391491278904, + -0.255910070250455, + -0.16211586725831062, + -0.2507844650501776, + -0.19106535344809664, + -0.26319582648771256, + -0.1723995040748813, + -0.17056897805538979, + -0.24328534884466724, + -0.2055432389732073, + -0.27883942951424917, + -0.16784184351308548, + -0.28361635079923253, + -0.18074946598171243, + -0.16676161816784704, + -0.2077623545023429, + -0.23130917520387223, + -0.174460272462858, + -0.2754036405932848, + -0.22473317208793503, + -0.2821317227983766, + -0.20268300764830682, + -0.2803985124078378, + -0.290351895262486, + -0.2330112765376981, + -0.25589725862069823, + -0.1901573772226877, + -0.20422240906737482, + -0.22178115956542804, + -0.24653173863584976, + -0.276499569541854, + -0.16309095905298307, + -0.21716866086440412, + -0.16651810844725473, + -0.1546348481803859, + -0.23831285937870253, + -0.27260439675766934, + -0.2434808965804809, + -0.19107442345714337, + -0.254502453466823, + -0.22284289783213446, + -0.2287906576385347, + -0.21401078814672825, + -0.2555169216802665, + -0.19193867447747678, + -0.21297909410500576, + -0.1865197822306711, + -0.28014939758919016, + -0.18200609157583614, + -0.15576862798004376, + -0.22757360513956212, + -0.1550830594757684, + -0.1893105253397453, + -0.21722040348787675, + -0.18038031898337206, + -0.2646590351309917, + -0.1608925933081407, + -0.2850362235633672, + -0.23596295964986796, + -0.17991929502891563, + -0.26607267958345154, + -0.19588562539082643, + -0.22027993364239065, + -0.1993292792133023, + -0.22330731543823729, + -0.16036458991408684, + -0.2889540036350388, + -0.29612817575300304, + -0.26931840254492917, + -0.19293865079465788, + -0.18523441497358545, + -0.17271141748300692, + -0.18024810406108902, + -0.29376763760475827, + -0.2490734468650882, + -0.23398840023957462, + -0.18591406637589797, + -0.2190581640714021, + -0.2161706710938432, + -0.26718959847504137, + -0.26414357259355564, + -0.205140694617168, + -0.19031731101846372, + -0.17626779406848914, + -0.2696665798354657, + -0.2670130584702524, + -0.22425273177206909, + -0.18316913504033738, + -0.23971321413351582, + -0.19140912376119504, + -0.20435351149870734, + -0.24089619810102825, + -0.2786008631453943, + -0.24608785638160802, + -0.2514472371929018, + -0.17590882152010467, + -0.2129620612555993, + -0.2155917470348733, + -0.2684989306656945, + -0.2840750582314362, + -0.22510426704207637, + -0.22615845669080914, + -0.18798052041408864, + -0.27355296958541997, + -0.24938687567079684, + -0.26418867752637837, + -0.23571276035826355, + -0.2766886062564294, + -0.18886715406921548, + -0.2968475943894624, + -0.2897877455972622, + -0.18192580049247073, + -0.19472142882565904, + -0.2538390943197133, + -0.1894086152588312, + -0.15939271601049462, + -0.28594965619958856, + -0.24509299808094454, + -0.24337108238886979, + -0.28158138097529833, + -0.1809536389666238, + -0.2937102306971206, + -0.27652014344793774, + -0.23303518838286058, + -0.2717309956239828, + -0.2559733070781941, + -0.1615270107484701, + -0.1881122722323938, + -0.2607398690472073, + -0.17913612020026193, + -0.2882669534409732, + -0.2309562415739692, + -0.2913619044055153, + -0.2962511452498487, + -0.1771514837069556, + -0.27302489822405795, + -0.22562400397229912, + -0.20844921097208458, + -0.16175446318064082, + -0.28402533651780604, + -0.2361469636980904, + -0.24739768857681765, + -0.26694688690225366, + -0.23387962612541224, + -0.2338676285552711, + -0.2619381900051078, + -0.27503963282601085, + -0.2642716658508544, + -0.28388479271369893, + -0.24331622243068043, + -0.27287352744828514, + -0.283799043192353, + -0.1549105410656849, + -0.2524263772211466, + -0.2721889384872949, + -0.2459164772531565, + -0.2673415038674908, + -0.16995790611948278, + -0.15896020518993365, + -0.22452005099117878, + -0.18201775181519514, + -0.2082070626583784, + -0.24149142685584782, + -0.22907716278687848, + -0.16818089698015454, + -0.18086722502332472, + -0.1588881908698404, + -0.27574554930180434, + -0.18476972202819997, + -0.1579282889857057, + -0.21097144152723094, + -0.2383835264375776, + -0.23761492392009284, + -0.2607028820813014, + -0.2582816391584286, + -0.2014190508717403, + -0.1848870594292383, + -0.24200430762087344, + -0.17353928259200538, + -0.1598684893838471, + -0.2784946812475443, + -0.2774811851507823, + -0.2888555118032504, + -0.22649255604099638, + -0.26703363993417106, + -0.21021201577031912, + -0.170447386069685, + -0.18208809253448943, + -0.22737021696120446, + -0.19009794070835923, + -0.18386996621113968, + -0.19160490972953798, + -0.2919608903361222, + -0.16330883024900025, + -0.24274889470983668, + -0.23610246134301818, + -0.2216029105285937, + -0.18974493484119256, + -0.2937326076735185, + -0.2294104129427879, + -0.27846552793949486, + -0.1898443976339229, + -0.2539249317306671, + -0.19332500315052675, + -0.24673389623228312, + -0.25091459058318066, + -0.257058248357978, + -0.26053314500909613, + -0.1959028876536349, + -0.2505280908928854, + -0.2959683759511429, + -0.19636963054915288, + -0.21569214740194861, + -0.22573601989976183, + -0.24747363451572899, + -0.1596555083503319, + -0.2833648211755428, + -0.1957899675098851, + -0.17358351581362746, + -0.2984728529013744, + -0.2538749532912662, + -0.21696934225877118, + -0.1665824057091451, + -0.21747646459924552, + -0.2904808698821975, + -0.1996083562377019, + -0.2081087768978131, + -0.2545023874337851, + -0.25569449018029156, + -0.2937569675930053, + -0.1745414820318376, + -0.24102558124013737, + -0.23145398667041717, + -0.20653841282299965, + -0.2782876434943574, + -0.24602477698859604, + -0.16336808894320276, + -0.2306804863588077, + -0.26312619744684634, + -0.29099740135145047, + -0.261324943118799, + -0.23161941908346514, + -0.15864941353825163, + -0.23610380934276454, + -0.21987416368953655, + -0.26997467595678626, + -0.17765803146656362, + -0.20038188045687572, + -0.18870650793961596, + -0.2943714468181862, + -0.26186203416544895, + -0.22610612376953754, + -0.15591553131315058, + -0.21129187868714766, + -0.20536455534626763, + -0.19905639144364382, + -0.246275128494031, + -0.29069080893035953, + -0.2202054226307801, + -0.27588181794395505, + -0.1957467968593346, + -0.2045518609957509, + -0.2585748587042647, + -0.2601904526183994, + -0.29160989887900796, + -0.16427129356455095, + -0.18666951951116373, + -0.17491260226500932, + -0.158335585172892, + -0.2883974013613693, + -0.17176539310885738, + -0.2154876108941412, + -0.22326329852623839, + -0.1619564015553239, + -0.22218369047954867, + -0.24905125210558784, + -0.20139034631334218, + -0.23964142176828368, + -0.1945056542049139, + -0.24186140727298702, + -0.26984955296356355, + -0.2576019101298893, + -0.21694124964728523, + -0.26821023854022946, + -0.2791551237693377, + -0.1883166380082637, + -0.23758733716585448, + -0.17829024937518229, + -0.20826542901789466, + -0.19341856154045206, + -0.1715409113301429, + -0.2639173657147058, + -0.22477800678255774, + -0.15537135047963985, + -0.16572976169794143, + -0.2127699463973023, + -0.26056757925530405, + -0.15500530726317624, + -0.24919226698800787, + -0.2673333272031764, + -0.22116216055498383, + -0.2386009405974308, + -0.19054561567930062, + -0.17228185080107944, + -0.23852172253835338, + -0.23062944449573175, + -0.19005529451928294, + -0.2489227701738831, + -0.16076727999503795, + -0.24949615518427268, + -0.2762882382952504, + -0.22935845727807283, + -0.2856443846600259, + -0.21479877966158212, + -0.22377484049188284, + -0.2672019316842947, + -0.1917990635810035, + -0.2294073613195231, + -0.2161455461170646, + -0.18377576792624953, + -0.2754796380817055, + -0.21514264767730346, + -0.1558318181537742, + -0.19327605172387569, + -0.19653772894666066, + -0.22325746538369912, + -0.1934511084232432, + -0.2744706644460483, + -0.27514386051164924, + -0.16234045579423909, + -0.25231373444670596, + -0.20292378628542912, + -0.27593604536283983, + -0.16204298800042696, + -0.2833966693960411, + -0.19853041799541393, + -0.19551279389288978, + -0.2930891090813815, + -0.2395633974124808, + -0.18797387819376032, + -0.27476043586037174, + -0.19149823486266762, + -0.21697001515744352, + -0.19011920430950902, + -0.19225915441886027, + -0.17894269591158335, + -0.2187373243158423, + -0.21758510983160564, + -0.26739388406183107, + -0.17500048657144635, + -0.19022710882996507, + -0.2187488786730789, + -0.2220010476131335, + -0.1730891754527691, + -0.24661674004740997, + -0.2032804987140588, + -0.22698922809305747, + -0.2234495829825084, + -0.21808097800295398, + -0.25122901166956285, + -0.23851502465808871, + -0.16845217455725023, + -0.22055751250022482, + -0.22961498578798878, + -0.25835470007258915, + -0.18588471435420606, + -0.23559399223960376, + -0.15632483562500465, + -0.1588609544200318, + -0.24720376809660094, + -0.2889878054605122, + -0.18606411011657098, + -0.28686286235533326, + -0.2533383804469974, + -0.26688744277856785, + -0.2200323903582918, + -0.28489476534704883, + -0.1576911715217735, + -0.24556301841005826, + -0.20570571889360062, + -0.29858268648218145, + -0.27671201724453126, + -0.20715772564497387, + -0.1592650410974372, + -0.1573272364696465, + -0.27474157388338427, + -0.2584440108004965, + -0.22796951675675928, + -0.259417756303958, + -0.1778428770446251, + -0.21832346171058514, + -0.21216104645971162, + -0.17320484126165098, + -0.25946820012679794, + -0.23584541126262343, + -0.17499184695539788, + -0.24442544870663263, + -0.18204681036139397, + -0.29807743579139595, + -0.16211039956212256, + -0.269714823449896, + -0.21925975389582225, + -0.253838585071268, + -0.2763459648935104, + -0.21340852181288525, + -0.16699038727514803, + -0.1615213630998241, + -0.19586020851365188, + -0.2955017988999464, + -0.1671829686278697, + -0.21778882543503864, + -0.2975565381890079, + -0.20422420834147875, + -0.236191679973218, + -0.18484919618457074, + -0.2591303935932557, + -0.23231661147404087, + -0.29323888201291437, + -0.21244765701930873, + -0.20572713474622323, + -0.2712792866381345, + -0.24327380209872637, + -0.266255284226829, + -0.18494296045121528, + -0.21742211421003055, + -0.19331985231061719, + -0.20499763697348433, + -0.2955602489485276, + -0.17863198147051776, + -0.2767093307442339, + -0.24796805804720443, + -0.2046323306782078, + -0.2134626250082255, + -0.27718174590752676, + -0.17239928830259685, + -0.15877765007500746, + -0.24349385011187624, + -0.1850209699688385, + -0.1836489640512366, + -0.19758610928608544, + -0.2638597339911734, + -0.2691773423362487, + -0.15821789308403647, + -0.20872804977131154, + -0.2391556671478564, + -0.2282627797679093, + -0.21952598095620957, + -0.17512038294103094, + -0.16783468915191146, + -0.2761593026437872, + -0.23288747724616787, + -0.27104856399355937, + -0.25796709620808916, + -0.21465721332537513, + -0.2885921474602799, + -0.27943069396583603, + -0.2062868511197592, + -0.18104138260117592, + -0.22155636837569015, + -0.2837120375993513, + -0.19984747549474974, + -0.23974531737550248, + -0.24727166914999016, + -0.24898384799569578, + -0.27992966366752964, + -0.22101219030763042, + -0.21096822138863075, + -0.2344039786573008, + -0.21942502506991268, + -0.17518385203350206, + -0.17077702398791111, + -0.17649644419412447, + -0.18703407523363527, + -0.18006807951302484, + -0.22504022726549022, + -0.23886408295719339, + -0.1642849656516848, + -0.26120532137642016, + -0.22854698222885683, + -0.2887809455042552, + -0.289854321747655, + -0.18005027131907614, + -0.2534001509662349, + -0.24764260870261598, + -0.16086606450380556, + -0.27265056786339165, + -0.24494143580504707, + -0.2985820614462208, + -0.24997272266331103, + -0.2480044720457666, + -0.29138819663363935, + -0.22418772916126695, + -0.1990710573078016, + -0.23370678475977788, + -0.23995978959275485, + -0.2378197884258798, + -0.21780974434913364, + -0.2605579139783315, + -0.2870432772733906, + -0.2111172925297018, + -0.20027543837759684, + -0.2093964013222702, + -0.24257167294619214, + -0.279228234618587, + -0.273870539154731, + -0.2934182632476438, + -0.20840231542599735, + -0.28054014110107095, + -0.23630472423125426, + -0.18579724737589567, + -0.263776685754733, + -0.27490382971868516, + -0.22471315368240583, + -0.2125077632570391, + -0.23987498499577609, + -0.24189522144562464, + -0.2610078899843657, + -0.2965894476768638, + -0.2452858092322912, + -0.28053852988276484, + -0.27438323511128954, + -0.22193951295340325, + -0.15527927825854015, + -0.24178934668698607, + -0.16915964221712174, + -0.18358844979978026, + -0.24948462196234436, + -0.2880034120946917, + -0.1810549753181893, + -0.2523508939089492, + -0.19073458284287453, + -0.26128274999473394, + -0.2556119505428832, + -0.25098323615773094, + -0.2597112213406069, + -0.24307176753798881, + -0.28382090078524963, + -0.22784531127447105, + -0.23269008320717866, + -0.20801273394741027, + -0.2635769802606836, + -0.16760810459808484, + -0.16279048401461704, + -0.2969364891479866, + -0.2152686635471679, + -0.2416052495199128, + -0.18725960250017465, + -0.1812515980537126, + -0.2571484424603848, + -0.2412062988311953, + -0.2853706003831876, + -0.2413040506579559, + -0.22225280518464482, + -0.21559632507269688, + -0.1895903131498698, + -0.179266615789329, + -0.2128407657956819, + -0.2859003268139915, + -0.24219060480123414, + -0.26276760847077407, + -0.23436475145778818, + -0.27796377550213414, + -0.2937589558532296, + -0.28822534839371555, + -0.1563872113663553, + -0.20399548662480127, + -0.18296974396754173, + -0.17269641490857526, + -0.22697330382012204, + -0.1774502189623679, + -0.19506749293941944, + -0.26472130032202407, + -0.2191206568488157, + -0.2949531397520033, + -0.25818965377328895, + -0.23756460861638454, + -0.2852751200970768, + -0.2725649217436478, + -0.22001214764454427, + -0.1672463371350618, + -0.20442793185219396, + -0.2587252675273864, + -0.2898655343431341, + -0.2976130451181993, + -0.17217350808749296, + -0.165849643892281, + -0.19903558255154252, + -0.26382290738541647, + -0.2670503372822436, + -0.21659637731538633, + -0.240907285246011, + -0.2315208463802523, + -0.2292090835004631, + -0.22600407227198682, + -0.2214644566102421, + -0.21697759587256582, + -0.23752802199496548, + -0.2254713079352322, + -0.24400783916229057, + -0.287263090506811, + -0.18630871078437583, + -0.1861856444482184, + -0.1652378945060516, + -0.24453295727511695, + -0.16719203850271513, + -0.25650707156368, + -0.2034842009768791, + -0.2754579858991448, + -0.2494751082111738, + -0.20024957202517957, + -0.20058028215138812, + -0.18811394922134544, + -0.23909876005868264, + -0.2262025671504696, + -0.28085516846887854, + -0.25382613815714744, + -0.2807847925749782, + -0.17353908735161358, + -0.28890170968050743, + -0.28313630095303594, + -0.22862013438090106, + -0.2384425171574816, + -0.191695444127936, + -0.2967503382452959, + -0.16840063182774892, + -0.2577533120588091, + -0.1826711664852519, + -0.21056365136596505, + -0.17587451520805236, + -0.2795127896004062, + -0.23890452533170972, + -0.23162409971267695, + -0.2440625249329826, + -0.17727942068241162, + -0.16566491073899065, + -0.26896383431457566, + -0.2131334504967585, + -0.15844058495695543, + -0.2600263317754857, + -0.23286734760425962, + -0.1583469077496504, + -0.21922593532465698, + -0.19864641168849162, + -0.19622076544681596, + -0.15528102942263466, + -0.25977012050039705, + -0.2521140477029987, + -0.15549711910216565, + -0.1648376331262265, + -0.20419145455527798, + -0.21368395213959665, + -0.2096320720389569, + -0.2035284797162529, + -0.22370887377565202, + -0.2518847778653112, + -0.28937854214815645, + -0.19291558700201306, + -0.23448557956064303, + -0.16808392453627224, + -0.24890199147814282, + -0.2914873858565758, + -0.18172669296808122, + -0.21746227872621732, + -0.2782617057538976, + -0.22800012140514345, + -0.21409833435262843, + -0.1894707667688364, + -0.24925746042942906, + -0.19223743393381748, + -0.2727272245763237, + -0.26133206856457325, + -0.2435541386238948, + -0.2623681638571767, + -0.24186234701496895, + -0.2755134837359545, + -0.23279360671999239, + -0.2789507870421103, + -0.16402499361386236, + -0.2329961344247146, + -0.2507089533105581, + -0.216905884840929, + -0.2549503964216452, + -0.18231558302799933, + -0.22430968865243867, + -0.2550930722175073, + -0.17767221087440777, + -0.1783820379746917, + -0.19861952864178595, + -0.16687058699753446, + -0.2559291281620262, + -0.18818559365543397, + -0.22333887962448812, + -0.18320018097124707, + -0.29696618824279947, + -0.170068302645858, + -0.1981167457751296, + -0.26892951224722716, + -0.24847291861140663, + -0.18279703724094887, + -0.17693171087715387, + -0.2048143861608573, + -0.261922359304832, + -0.2848784599421413, + -0.16773772586973051, + -0.2196821894410103, + -0.2241198900620682, + -0.2316088281355334, + -0.2690381180607891, + -0.1683845980367056, + -0.29229356883424373, + -0.22958175708625755, + -0.2636833431569756, + -0.23735410031314366, + -0.29229152945369574, + -0.22900275709148013, + -0.2176934687491176, + -0.15486195920660895, + -0.26245764807411726, + -0.2334451576364588, + -0.23793647788345262, + -0.29712037020490467, + -0.20135792880872957, + -0.20766219589644502, + -0.22420989180979897, + -0.21010708084229363, + -0.16811432983564065, + -0.2482424902399811, + -0.18510523326720602, + -0.17594428214761082, + -0.27612747350717953, + -0.23721606412647245, + -0.2192860227894205, + -0.20481915745055423, + -0.25001629591689106, + -0.1821520208754482, + -0.21850269651526028, + -0.20797392025660028, + -0.2768080736777292, + -0.25326152904437454, + -0.25997603357361904, + -0.15883504779095337, + -0.24433314365638972, + -0.2719556093994741, + -0.25594924645883277, + -0.17500026635032923, + -0.2688488224533984, + -0.23389885744043784, + -0.16708527156806188, + -0.1914132888380505, + -0.22226768843966244, + -0.19004982227333667, + -0.20610386533242014, + -0.26530680918838634, + -0.23127376107411457, + -0.21101574730201067, + -0.2856254721901746, + -0.16359243260908432, + -0.19513434939442575, + -0.16730273239018958, + -0.2546387817994095, + -0.2117753844755616, + -0.27195837577786336, + -0.217111567720557, + -0.26502998185061416, + -0.18986724636914482, + -0.22221724099894127, + -0.15896523014177338, + -0.29007108760584227, + -0.2720530243689101, + -0.2929352656088545, + -0.2684014765229072, + -0.26963807708336546, + -0.2857120178681325, + -0.17240402644845176, + -0.20785551559774956, + -0.21053034954614935, + -0.2629312270376132, + -0.17362109720673946, + -0.1552566640531796, + -0.2656076748955861, + -0.1809460868144971, + -0.23900927510723904, + -0.25003015446089294, + -0.26229800978725587, + -0.25231535863373206, + -0.2275017965638857, + -0.2756442273573148, + -0.16971721948320212, + -0.15572025829358008, + -0.2944743231439736, + -0.26369379968343465, + -0.19591062470075435, + -0.26033653649008803, + -0.24385816527077703, + -0.24492945667024035, + -0.1673114137841258, + -0.27905739836051074, + -0.24357540938898, + -0.17895622281172768, + -0.2518035712986715, + -0.27393296160702507, + -0.24961317454725768, + -0.17176630955892583, + -0.25354295084420553, + -0.2067765705932494, + -0.21012899398025908, + -0.20193719451177788, + -0.22932358049869098, + -0.16771342361994943, + -0.22012515093621599, + -0.20237597640235652, + -0.27782149332180245, + -0.18396340187231836, + -0.23547469806828109, + -0.24325191857660944, + -0.2725404081481422, + -0.2317096930798231, + -0.2506011202676573, + -0.20513038328023248, + -0.292726737007625, + -0.18358645676595886, + -0.23024747480753732, + -0.17864927399984348, + -0.19782176223495052, + -0.24758877641764523, + -0.2648471900648179, + -0.2565872766978404, + -0.15868805370618985, + -0.1919406354180727, + -0.20500308054594082, + -0.17904337441529572, + -0.16132980184715456, + -0.16218653603087865, + -0.18678170542324674, + -0.23833831759088514, + -0.19319035704831666, + -0.22958289626529382, + -0.1691596465133634, + -0.16490833298897742, + -0.15465928618931568, + -0.18146759961809678, + -0.19840897469392083, + -0.2773148272539505, + -0.16813715259803652, + -0.1878758230867048, + -0.2651932182863337, + -0.19610903841310412, + -0.18111860302892258, + -0.2452366731354278, + -0.2379924749365086, + -0.24877372600609024, + -0.24405861835393294, + -0.26594939338796947, + -0.2711896834905621, + -0.17447856954820856, + -0.17512123036584593, + -0.2488369493607888, + -0.20247355741325684, + -0.15545905019897804, + -0.2007512040923866, + -0.23422451902423966, + -0.17802089614686017, + -0.15787794906248928, + -0.2699578175294132, + -0.20049860807967407, + -0.22333039592398876, + -0.2949665304656134, + -0.20285194774504509, + -0.16338979269835283, + -0.2207508100879708, + -0.17056452061827834, + -0.17507670811145395, + -0.19573154934746945, + -0.27855123545240235, + -0.1611673460515911, + -0.20799917778253268, + -0.28227726248033874, + -0.27915993369516956, + -0.15564957547952385, + -0.26552694724680825, + -0.28725251609285607, + -0.25733976862519775, + -0.18180278200559064, + -0.27244463439624017, + -0.25941147997895236, + -0.23285830269415048, + -0.22134504210735534, + -0.1829752232723271, + -0.23227296926221608, + -0.25108783337415574, + -0.2766845929627024, + -0.1915783727730428, + -0.288053514454794, + -0.1775906366222621, + -0.23523780454114301, + -0.27694353940562927, + -0.2230587760351826, + -0.29553061077712733, + -0.16618052573635125, + -0.2076854427365474, + -0.2569370336444386, + -0.23226497670309426, + -0.2322099411775153, + -0.297664303134563, + -0.20059726877474127, + -0.2033766284426347, + -0.18472815189932168, + -0.16181266406798026, + -0.27568257743264646, + -0.22789342647496555, + -0.27860149546701196, + -0.29822908141993637, + -0.24754774973226445, + -0.19296682719841668, + -0.18622045142330226, + -0.29141256504394253, + -0.1971904044021896, + -0.2592912982067644, + -0.16209024243435463, + -0.1548407258230557, + -0.18479599782751077, + -0.2403059948623341, + -0.23753964732564492, + -0.23843974104264784, + -0.18286297056643147, + -0.24903937457335518, + -0.22828368450907693, + -0.23674536308957564, + -0.16708828514863064, + -0.284253213817348, + -0.27321208862893265, + -0.2671135858107202, + -0.23974436550941144, + -0.21277690233404364, + -0.295534816532208, + -0.23348141162702407, + -0.20204168257733982, + -0.18071057212097957, + -0.2532546032403388, + -0.24915745102181497, + -0.15558540097772108, + -0.16838975352543825, + -0.2310606047127317, + -0.23334606922520207, + -0.19304870510290867, + -0.2852867184672493, + -0.2470742097983294, + -0.26651853167602113, + -0.28371680586413445, + -0.24082499512183822, + -0.16974770190905392, + -0.24057466465660193, + -0.1961371766144143, + -0.192123720645962, + -0.16106443397931736, + -0.27539997071146793, + -0.20952115324046422, + -0.23151894012390634, + -0.23929124945431712, + -0.17912424406610333, + -0.2451822686018142, + -0.2630364740451083, + -0.22212710372449443, + -0.1894674842159296, + -0.25976650101881177, + -0.21667256333620652, + -0.27960247507674124, + -0.18133728662745596, + -0.2685732506335126, + -0.19228677249666648, + -0.2638513446572185, + -0.18180573149569024, + -0.22746834333593552, + -0.23545871269582797, + -0.21961288991266065, + -0.29337460699738427, + -0.24761642218388133, + -0.21335933662388668, + -0.16548433200062332, + -0.22406374096380466, + -0.20860972753854307, + -0.2219345241775244, + -0.2026019119273032, + -0.21165498676035738, + -0.274200530447442, + -0.22450285504769218, + -0.2111510948358047, + -0.22458285705532044, + -0.19962520768467612, + -0.21197058607941954, + -0.24366934567854007, + -0.1707970105858408, + -0.23607394914077312, + -0.2538548234354848, + -0.2026333061914838, + -0.2563308967995872, + -0.1918512891159142, + -0.20997147899176072, + -0.24479929440945872, + -0.2651032525815804, + -0.2730195763386181, + -0.18062575034869272, + -0.234704071780557, + -0.1916612351521187, + -0.2106741082507685, + -0.21973200682801491, + -0.21745640987392462, + -0.2144062820856143, + -0.25358799371646656, + -0.23915087425914083, + -0.1792313805284606, + -0.15510342888449635, + -0.21199692596125314, + -0.16536665528149838, + -0.24073357109558982, + -0.2601977607341164, + -0.20563614523257548, + -0.1835385832768765, + -0.21183313499860976, + -0.17730433411875937, + -0.2668858874894081, + -0.19501281172741558, + -0.24777300744202715, + -0.1842848429242723, + -0.2976010940727367, + -0.27362660351199586, + -0.25957966999284204, + -0.22298682562973654, + -0.2521242294658149, + -0.23398854210394016, + -0.29152562388977726, + -0.18438287855967267, + -0.24620609404394173, + -0.16870065639379578, + -0.19101765703821727, + -0.17126072594999664, + -0.2195959968036631, + -0.18545831416668904, + -0.2064060998112513, + -0.16730964617661498, + -0.24296356220668885, + -0.2659942246783509, + -0.1818828719577113, + -0.25831933153127745, + -0.22440656179424168, + -0.22134477455206314, + -0.26726152300810235, + -0.22445765094982945, + -0.20783098251942425, + -0.19913035243849542, + -0.19132330315295737, + -0.24422129838960116, + -0.277190894080872, + -0.2651305826189883, + -0.22519780437142015, + -0.2462983512215357, + -0.29782023085760617, + -0.22547034862403276, + -0.2663414461115074, + -0.16152181678333077, + -0.2931599010575257, + -0.2335871368356397, + -0.16208638926770597, + -0.29399942182341726, + -0.1789375347570375, + -0.24182673589335207, + -0.20496503108330466, + -0.19708708831654176, + -0.27497438821994163, + -0.2482322193996485, + -0.1821481513597294, + -0.19396462304475373, + -0.19154645957883, + -0.22301569773930507, + -0.2783048755542714, + -0.2277065088718463, + -0.25667687102272796, + -0.23014078972427482, + -0.29562718749531103, + -0.20258579198004492, + -0.23220684814234963, + -0.16142808182696453, + -0.16417886216365274, + -0.29721889066197144, + -0.2729402292335602, + -0.18848370051228439, + -0.2843227003824646, + -0.20462520103025802, + -0.18005211937546967, + -0.17189909641804874, + -0.26125958091226903, + -0.2938545611827767, + -0.2632537634274426, + -0.2782703962351983, + -0.15515457926522064, + -0.16337879473302286, + -0.19295317653936467, + -0.1935911778664101, + -0.2313529412292919, + -0.24779557565382826, + -0.2863153583849467, + -0.16238253205864314, + -0.25324467776848797, + -0.29738640436335206, + -0.17379522573041659, + -0.21292742547254762, + -0.28924291430393073, + -0.2882474729535906, + -0.29348927959372767, + -0.22349227678417394, + -0.27155365993557923, + -0.18095906852089583, + -0.2709486400854469, + -0.20041968686750344, + -0.2917854227545754, + -0.20606211464255575, + -0.19188669769199096, + -0.24582229070133566, + -0.26531648711079914, + -0.190054893034234, + -0.24929086052650798, + -0.1939453287279405, + -0.1619412807391406, + -0.2495335275158314, + -0.198061852961109, + -0.239470335810762, + -0.2670862172944309, + -0.2237991432571804, + -0.22157535297653583, + -0.2715744992052974, + -0.2221837961159709, + -0.1746244056730292, + -0.1909464469675996, + -0.2723188191398491, + -0.18448523447890747, + -0.2196740812720665, + -0.23555023164910233, + -0.25883190291039004, + -0.2879123969077365, + -0.23618952452257908, + -0.19877452076469815, + -0.23796638196960296, + -0.2721888834022584, + -0.27938625907591286, + -0.18029024696508134, + -0.24286023836425713, + -0.2611717511168136, + -0.2703947818725325, + -0.2870428898959045, + -0.27669384385946494, + -0.21214175982495687, + -0.17210122089264768, + -0.25771386539714874, + -0.16144006550193402, + -0.2566979011303446, + -0.18926037473683016, + -0.21930176748626903, + -0.17741083093893173, + -0.24995991087503214, + -0.2475604205283633, + -0.24945260352213797, + -0.2278950453949383, + -0.2874399300988727, + -0.21378988785028719, + -0.17405437277929284, + -0.19524403314463556, + -0.25200259314583706, + -0.18161011602243904, + -0.24828351633044507, + -0.18668888548241247, + -0.26753421953754525, + -0.23355115363699142, + -0.1884688045001399, + -0.15716948386777785, + -0.22063198449819463, + -0.24705527970821992, + -0.21588936923066798, + -0.23046857858460212, + -0.15486566057431925, + -0.1743919885679352, + -0.26466737865383905, + -0.2682651666400864, + -0.15547411091016614, + -0.23073836574748108, + -0.20641214749308243, + -0.2299224059294182, + -0.19624904505367813, + -0.24065073313288987, + -0.2864048209042344, + -0.27258149142108096, + -0.22649258365097164, + -0.23085075890436402, + -0.18705861473233526, + -0.2882163957362829, + -0.28440868051355034, + -0.2517371452831022, + -0.23768525983171992, + -0.2776452145033096, + -0.18536394868032213, + -0.25324391059793155, + -0.1933485112603081, + -0.16716795254150577, + -0.1810543684850848, + -0.2680605399527975, + -0.2403662094455844, + -0.24308763270981018, + -0.2193714750571475, + -0.2703227960107798, + -0.2720576116366699, + -0.25278284453859357, + -0.26718601062429875, + -0.23428720260757258, + -0.2320055751843, + -0.2781576707281481, + -0.15512248905970852, + -0.22310022803120555, + -0.2598890623221637, + -0.2850257101296204, + -0.2953161682658717, + -0.25088413666681575, + -0.2966290453486931, + -0.2185194845165465, + -0.272033447197828, + -0.2745505469053829, + -0.2743358056252761, + -0.15913577856674171, + -0.26365676848517705, + -0.22689334239978493, + -0.23245429450043084, + -0.2986074454724565, + -0.29095673782771675, + -0.2715437167675001, + -0.16693232316772683, + -0.22002134494042005, + -0.18105833428311968, + -0.1864952119360132, + -0.2876893767096255, + -0.27002402415790927, + -0.16567875661938888, + -0.158218480629074, + -0.28694730488665726, + -0.16020946330857722, + -0.26642754520175155, + -0.27940124432106445, + -0.29856180133178273, + -0.26138817766511413, + -0.2719662352908059, + -0.29501811356930246, + -0.23375933622888814, + -0.22196869115282114, + -0.2787291519005569, + -0.24636205419229654, + -0.19152068536419237, + -0.2388813667935988, + -0.2135988111573987, + -0.19176643142308317, + -0.25931162633885124, + -0.23535781951662185, + -0.2757581831586758, + -0.225722506487122, + -0.17810645485606874, + -0.21586825163584158, + -0.28187822107642396, + -0.25843022241825186, + -0.22287664686001402, + -0.22763378609416912, + -0.2768013810174655, + -0.22039356977836128, + -0.1737412049836372, + -0.2429901750487649, + -0.2304752933663951, + -0.2665110737968123, + -0.16910031541284115, + -0.26808325878059347, + -0.2723732672035766, + -0.24313747054253002, + -0.2086794346900669, + -0.20480821313381903, + -0.2986758313857103, + -0.25326168919580005, + -0.2532169756180104, + -0.26595668290173324, + -0.16761605520320016, + -0.2785679046709057, + -0.28610390114455636, + -0.18276773619491032, + -0.2846818359490919, + -0.15463506091907608, + -0.2716664409909939, + -0.167186508789419, + -0.23417529885724675, + -0.2467715185674105, + -0.21515480050536234, + -0.15790190900241388, + -0.22237198095558267, + -0.23200830055672378, + -0.175085471707514, + -0.24248800256338943, + -0.247843741659896, + -0.1882534824374767, + -0.17000516450235537, + -0.2938979311956551, + -0.24003860752362538, + -0.22336486011706122, + -0.21789369129422054, + -0.265335771472063, + -0.28624766377653726, + -0.23631108909881976, + -0.19858374777355997, + -0.25429517144132235, + -0.2726170799619092, + -0.1889738522886239, + -0.29468686345143474, + -0.15640335417915543, + -0.22541673235335646, + -0.22470218946444886, + -0.2001344704766348, + -0.20328225471871625, + -0.20130605279110644, + -0.23059547111824555, + -0.21425587466578125, + -0.28186125264772294, + -0.22758013616823786, + -0.198179302945611, + -0.2444783609234615, + -0.20824667613063158, + -0.1815509153820079, + -0.290370150377934, + -0.15750202241626063, + -0.29580610643803423, + -0.21620394034159693, + -0.23009238955311392, + -0.25040514796299695, + -0.22818865035168134, + -0.2333120205696128, + -0.26900105222769816, + -0.2840911427771365, + -0.21572591474418573, + -0.2922585685023924, + -0.23432931314986463, + -0.17116420562533202, + -0.1948810359489077, + -0.21563041754298315, + -0.2535220048490605, + -0.23666840380765905, + -0.2546969998339898, + -0.2808201145826171, + -0.2421034593231789, + -0.22278956154232704, + -0.2748487751222153, + -0.15504245962966617, + -0.22210400665817256, + -0.20788004775099186, + -0.18760594369159622, + -0.15807595658353923, + -0.28547488499249296, + -0.234917724649018, + -0.2661701277868722, + -0.2826550043618697, + -0.27177728756495106, + -0.18906172079861877, + -0.2807111016133405, + -0.2774787271838607, + -0.19386400513868354, + -0.1597817670871697, + -0.2043210899609167, + -0.2346532971904574, + -0.2558519117506681, + -0.25361441312686867, + -0.17497813642015458, + -0.29472030379162356, + -0.25407684709705713, + -0.2729991515825917, + -0.2918758033535547, + -0.20884555071510147, + -0.232655484449201, + -0.1635913945990338, + -0.1662976532451329, + -0.2748573458400242, + -0.20434220837514333, + -0.18783462937213766, + -0.20565893909853583, + -0.19332320358512148, + -0.16550193887480202, + -0.20858689926352733, + -0.28187577129986663, + -0.24961759967618113, + -0.2572973735005518, + -0.23701293244588445, + -0.21877895379408807, + -0.2070216258757283, + -0.16586224910739703, + -0.21793008001519693, + -0.18081941871730578, + -0.23658414309762718, + -0.17701794954104094, + -0.23164122357879252, + -0.21328769781805074, + -0.25075081811289723, + -0.23172370085838856, + -0.25737413058711456, + -0.25486771390411267, + -0.26819299840841326, + -0.28149585690225487, + -0.27260070437682893, + -0.23592386674432658, + -0.27600518794881534, + -0.2249235361652208, + -0.20563377126489654, + -0.268370444592518, + -0.20476136761489233, + -0.28017892817404655, + -0.19907655117340187, + -0.2875241879376347, + -0.1910132171218104, + -0.22271669577645992, + -0.1964045937187444, + -0.28057174792817147, + -0.2819308952531678, + -0.18036269008753902, + -0.17121091440000713, + -0.2731254977042324, + -0.1992891758495326, + -0.24767573753017072, + -0.24226505753393351, + -0.2127956245972677, + -0.15681722462377717, + -0.2144279019324416, + -0.25683400007894186, + -0.2920458584676462, + -0.18892182839248647, + -0.2421738057623001, + -0.277492821364758, + -0.27795895815336796, + -0.15750950494813776, + -0.2140428967807665, + -0.2428033993210357, + -0.2933869625960949, + -0.24733303923485345, + -0.1756684782211207, + -0.16814085568641518, + -0.20869476611762477, + -0.2935929589583401, + -0.18963355536712023, + -0.24270972081144254, + -0.2681065252998808, + -0.17011090820958644, + -0.2526908934888434, + -0.28664337168393045, + -0.24055941753998605, + -0.16791283138581697, + -0.2516419452680482, + -0.2079464916466402, + -0.19874735731634588, + -0.19811124275134462, + -0.24667781892993199, + -0.267458908426194, + -0.2943634558945611, + -0.2906569948747615, + -0.15556867026328028, + -0.23306322542776214, + -0.21360357157720233, + -0.225599033288883, + -0.24561973381226615, + -0.20947977255900752, + -0.1729889199882773, + -0.2576719239665102, + -0.2674926528035442, + -0.17676805605591783, + -0.16387580598915769, + -0.2634247674772295, + -0.214557792720527, + -0.17353436725174703, + -0.20203120426030535, + -0.22724968294588674, + -0.1571170736567819, + -0.2938638500307179, + -0.18644762435226608, + -0.17047110137048405, + -0.16180593552045097, + -0.23644818272044982, + -0.16676089427532692, + -0.2778681586857383, + -0.29784367574660797, + -0.24203817077585316, + -0.1837479299006942, + -0.24820630879981903, + -0.188861624315952, + -0.2711713567344128, + -0.163755590076462, + -0.24841674947925685, + -0.2919693041045338, + -0.1669663314498562, + -0.25608280848471515, + -0.2897452332539818, + -0.2322823016221192, + -0.2752914578596975, + -0.21033168818853049, + -0.25652233123808593, + -0.21969629805881122, + -0.24436382969068926, + -0.26249390162769537, + -0.292630569530194, + -0.21220039525953566, + -0.27729200122004455, + -0.2365117273113576, + -0.16576034040640905, + -0.21940012979819007, + -0.29761037783910094, + -0.25393193245919893, + -0.22447266551382533, + -0.2553732839335421, + -0.20215018445234967, + -0.1955600611131864, + -0.21458577257161185, + -0.25640016788633324, + -0.24019848364266658, + -0.2515666994344108, + -0.18053753683031007, + -0.2970123248147782, + -0.2985788945270083, + -0.17155961645536486, + -0.29780259905167955, + -0.24322393982857973, + -0.27934588595880333, + -0.2892461591407426, + -0.2120477934776786, + -0.2567302880869156, + -0.2899145817661041, + -0.1779409134980089, + -0.20680915238779424, + -0.19841500656172245, + -0.24046368194899947, + -0.2377273280301917, + -0.27704731755002804, + -0.16126282032270106, + -0.1643810902233841, + -0.19072657983267, + -0.17421741395785537, + -0.18033466127658682, + -0.1665050639951311, + -0.27906362128612566, + -0.29826992136890207, + -0.25056395856243596, + -0.28270663660758094, + -0.23355182369205885, + -0.2282081378780822, + -0.175707762532832, + -0.290551974777713, + -0.15492729546312217, + -0.19331148823208277, + -0.18020106340451103, + -0.19431829326539518, + -0.2004054928197152, + -0.2301270188366818, + -0.20812425449498034, + -0.19821710019010874, + -0.23046527944430012, + -0.20882762772442304, + -0.244145804914832, + -0.16549829410709105, + -0.23091954943378293, + -0.15952326369084108, + -0.25336954392073724, + -0.29131589652724305, + -0.23500059277381852, + -0.2827416631877927, + -0.1592097505057558, + -0.289307914573287, + -0.18400643970120079, + -0.26573081118141845, + -0.264400963020222, + -0.16065042033159138, + -0.26052033720278783, + -0.16623860589418352, + -0.22968258918259715, + -0.18735653546141542, + -0.2092079789555933, + -0.2954246395246143, + -0.229564713610747, + -0.2891197380528369, + -0.2450912250664056, + -0.23585922738138665, + -0.2818527351213236, + -0.2715781219743653, + -0.2227420539300183, + -0.289093891636458, + -0.19745060521415636, + -0.17891363776542618, + -0.15968594147183088, + -0.2172007352409075, + -0.15557443284402867, + -0.2796631167640418, + -0.2834106620395686, + -0.21100329738985096, + -0.1797604524390526, + -0.25958584387594485, + -0.28451374020362435, + -0.29072644831719724, + -0.27540284855830255, + -0.28761792509052864, + -0.28859049182595486, + -0.1932883672001402, + -0.1706022868352063, + -0.233529056359273, + -0.22132383564876412, + -0.2930815571596483, + -0.1943928264148378, + -0.1582452040727294, + -0.29587914884966865, + -0.1831173023325771, + -0.19547394861232292, + -0.19004345384881877, + -0.18291985503454344, + -0.22082315468819996, + -0.19436751062354107, + -0.1769950686962306, + -0.24183308453669902, + -0.29822002863536456, + -0.20523522281748163, + -0.2679771046436125, + -0.19725863242177083, + -0.23624028703820005, + -0.21674166747495413, + -0.1954462023292562, + -0.26726646186091474, + -0.25399100916616335, + -0.1849701910302542, + -0.27118664029689465, + -0.20806159302619764, + -0.2881471053964293, + -0.29099650569862945, + -0.26537898359431206, + -0.23976015118510013, + -0.2909912748644976, + -0.2694175934397559, + -0.23038335461268647, + -0.28981713250728297, + -0.16010035140598453, + -0.2831777100360077, + -0.20131132317229666, + -0.1764221025168481, + -0.2156041134543885, + -0.16454816066393768, + -0.17585954695094996, + -0.2385258053213341, + -0.2805866544291171, + -0.2396526153871255, + -0.275012197995089, + -0.1693850610124275, + -0.2814619586326509, + -0.2310712993225686, + -0.2110899835733674, + -0.20884705451370866, + -0.21786013555058753, + -0.2853842687443575, + -0.28514872263884067, + -0.27520062401845774, + -0.2383862650264175, + -0.17137275091835893, + -0.26956212906114385, + -0.16633906184677694, + -0.20947310852485046, + -0.29232296675203434, + -0.26975458362601323, + -0.284411028064552, + -0.26449370754856394, + -0.18355040693206298, + -0.2942730618679205, + -0.2561858294859592, + -0.1715920027153733, + -0.24842960983978776, + -0.24709253622155125, + -0.22202154091146017, + -0.286689514797608, + -0.19476926268342443, + -0.18036238070274194, + -0.19641226879620938, + -0.19777336206245422, + -0.25236520435591775, + -0.23948091255077344, + -0.20213956437077174, + -0.26783994934073174, + -0.1881943508246951, + -0.2911918259205574, + -0.1693203626894783, + -0.2907168159950706, + -0.29324598811147384, + -0.26813599944561906, + -0.2962195433651182, + -0.17738975963131454, + -0.22937399926952043, + -0.15634290805128478, + -0.23316559922283198, + -0.17953263596014774, + -0.2430668653848808, + -0.1708072157903067, + -0.2771152192133732, + -0.26617823602423024, + -0.2040023572440402, + -0.23333981165438084, + -0.29780842189646367, + -0.2708566633538235, + -0.1915755481175339, + -0.27827345568516454, + -0.16461683990699194, + -0.18654995282905432, + -0.15914607932534228, + -0.19362907313018804, + -0.15931617680021656, + -0.17112279417403295, + -0.16444742948588437, + -0.23667818631486467, + -0.18412854703671194, + -0.16342623408669416, + -0.2011591439774313, + -0.24195681300923821, + -0.1971016358688314, + -0.22495937560052048, + -0.19736245093693938, + -0.21369481184274797, + -0.16613568187852326, + -0.1676589986764459, + -0.25511750938646693, + -0.27141024491703236, + -0.2693098162750775, + -0.19744159382423537, + -0.25276101535891715, + -0.16928894106329795, + -0.2962013906000088, + -0.23886965979920347, + -0.19208333221179913, + -0.16527224481515873, + -0.29500077783871, + -0.24696059735245846, + -0.287467709021018, + -0.20624326842460522, + -0.1610296078062, + -0.2704561429821393, + -0.27646561527532837, + -0.19753124018677848, + -0.2766682285552032, + -0.1720100376837751, + -0.2551754873855757, + -0.2260070034078511, + -0.1977277625865595, + -0.21351928801676184, + -0.20611893084898147, + -0.27512791627317723, + -0.22188859142877887, + -0.28358844227491226, + -0.17034428770273857, + -0.20536008955593105, + -0.17772618959134817, + -0.28703956136371156, + -0.29360826453617866, + -0.2734957185010581, + -0.25314627223243835, + -0.18602686205102775, + -0.20074597973894506, + -0.21053401453954437, + -0.29420532659636217, + -0.2846744594814058, + -0.22366037898629465, + -0.15658538539261405, + -0.17139421379601527, + -0.24209061552836808, + -0.19740304030006955, + -0.23290840240814734, + -0.2734281428083904, + -0.28293179725298323, + -0.20290236709552154, + -0.19115228930946282, + -0.28700139436181615, + -0.2414385103196055, + -0.24961862992934533, + -0.23697237252923692, + -0.27146593798529084, + -0.1823390996227468, + -0.156158914831719, + -0.19132430121473848, + -0.21109851371761185, + -0.23500317460211553, + -0.28612729506175016, + -0.21475288514772806, + -0.16701998826643982, + -0.2474190937399698, + -0.20417648175063904, + -0.17834280440687866, + -0.15594216261063906, + -0.25619958472508125, + -0.20191640538440753, + -0.19514978374234215, + -0.2306700026356498, + -0.16829002419785694, + -0.19731234895121103, + -0.19172410899436687, + -0.2570408457982584, + -0.1744188106884827, + -0.19459732603663588, + -0.2747535954494389, + -0.25731793587684754, + -0.2312796150863363, + -0.18285671361770403, + -0.16646026951440446, + -0.21655052610343029, + -0.260654296530895, + -0.2554144510399435, + -0.26720227228454696, + -0.1696434105458705, + -0.25565234768424533, + -0.1881026930743782, + -0.2683283256547844, + -0.24824780919232417, + -0.1675352814121954, + -0.26559823416899253, + -0.2244128955139572, + -0.21512625475257607, + -0.2855442368030223, + -0.2875769259393953, + -0.2828814129314643, + -0.2349578795510782, + -0.21940019330349364, + -0.2743263166742408, + -0.17861612534892202, + -0.17167385278904904, + -0.2846086804109812, + -0.18901230095804822, + -0.2353703559958778, + -0.2310098476025113, + -0.2779048363753017, + -0.22664129731095242, + -0.15685321708474068, + -0.16941971903453526, + -0.23568055066720028, + -0.29125723532718756, + -0.16257992167743643, + -0.1573674579989456, + -0.20521474718760208, + -0.2351488419698169, + -0.19840337694619048, + -0.28043820050145224, + -0.26454266993947445, + -0.16511998299510094, + -0.27416814254372435, + -0.16022032892762783, + -0.16386088442476782, + -0.2176963537562213, + -0.23957928245461857, + -0.19830938188978475, + -0.20427599971344917, + -0.2435606366257964, + -0.16373006113225513, + -0.21304003038111002, + -0.25719177340530275, + -0.16096160350549743, + -0.29555707384647184, + -0.25736175901807845, + -0.19442137370311235, + -0.16750199854469494, + -0.23895369822535495, + -0.1901176614932354, + -0.25212860889772537, + -0.21139143449875458, + -0.1828221126037219, + -0.17279735417927916, + -0.2363336213769771, + -0.254618548274193, + -0.22644362381209862, + -0.243850494928331, + -0.2551525027605032, + -0.2867233706607813, + -0.2323595668784747, + -0.2629528530107486, + -0.23558761254983518, + -0.28697250827861587, + -0.29485963832833895, + -0.23877978247511383, + -0.1731332930370038, + -0.2137181057219601, + -0.2256366604870414, + -0.15598532518826116, + -0.2442591541593605, + -0.23905159587022112, + -0.22099856870321122, + -0.16511332276403057, + -0.28957691215507037, + -0.2603946440597147, + -0.23765282341487634, + -0.24735394352612036, + -0.2445541718041462, + -0.2747241363846801, + -0.2535186967489731, + -0.19675319506623246, + -0.18121281218943103, + -0.19101468505420557, + -0.2935702580041241, + -0.21905218790294573, + -0.183026249761918, + -0.2918527977226828, + -0.16291709511246977, + -0.17492938083769377, + -0.29618971212346196, + -0.2360423428534321, + -0.2641648684643624, + -0.20694266603996575, + -0.22470159217355165, + -0.2707512328266898, + -0.2580520229536113, + -0.2795654726448582, + -0.226707234270897, + -0.21522808983645086, + -0.18738568556386626, + -0.17365911237556708, + -0.24165396175295345, + -0.29441103748156494, + -0.20754243722722027, + -0.20266166795053464, + -0.24844416772896194, + -0.176723457086031, + -0.23604428165854535, + -0.22338278408341172, + -0.1630491103421096, + -0.15558952339110643, + -0.17007168029384614, + -0.27752901653692535, + -0.16997050682403037, + -0.22724205513261264, + -0.21626119521094156, + -0.29762567068804857, + -0.24015047805711354, + -0.18448918864687497, + -0.27262333519195814, + -0.15701903027146352, + -0.2019106226815418, + -0.16699539940800154, + -0.25784290370826585, + -0.2561210080775735, + -0.18518064809400947, + -0.2756991252390322, + -0.25551760442420907, + -0.28088511763229296, + -0.16542439010409649, + -0.21198218715446668, + -0.2177142691814481, + -0.2802862166789981, + -0.2929209619970901, + -0.2962209441857187, + -0.17184626252170637, + -0.18015488547126202, + -0.18138567338194816, + -0.28394427959916696, + -0.20900400714946032, + -0.23031790090080972, + -0.20221581083819143, + -0.23884247275174644, + -0.17211081094079844, + -0.27408707804557586, + -0.17042373722667772, + -0.23399884492400302, + -0.25339113558230886, + -0.28904585823694445, + -0.17729893189905593, + -0.18647519435054416, + -0.21818932671844016, + -0.17637621143350404, + -0.1967302514681325, + -0.2891874755674843, + -0.24331332292644225, + -0.18090212023328564, + -0.19002651132478354, + -0.20086993827744692, + -0.2900143721155275, + -0.19143919202646978, + -0.1739312213968322, + -0.24529400477501384, + -0.17435424074695338, + -0.18610581245578128, + -0.24105553929265502, + -0.18934575434328238, + -0.18058735547998334, + -0.28436390801380285, + -0.2531617628941006, + -0.24578832943253248, + -0.19557964594556035, + -0.23983021341054328, + -0.27683525939159387, + -0.18320919904053537, + -0.2812658608517574, + -0.22607345273787766, + -0.2542201585613711, + -0.15848876765917003, + -0.23427019687089418, + -0.1889912284094718, + -0.15703526321840233, + -0.1762874377497065, + -0.20584730439606985, + -0.24172320927093727, + -0.23036213009383882, + -0.17796416901976667, + -0.27135914808031825, + -0.1946771362756378, + -0.2914367060191126, + -0.2280102194192697, + -0.16998570150319456, + -0.2518769609786485, + -0.18374921365038657, + -0.22356616499017323, + -0.2802830943934591, + -0.23891474408038355, + -0.17959631057167819, + -0.16833481112980034, + -0.245776609952894, + -0.16132934178413055, + -0.2609064106360666, + -0.2368340092983608, + -0.1787487440679128, + -0.2693868154334281, + -0.2087727350647959, + -0.28357028275124313, + -0.17363312416986368, + -0.2987998372135368, + -0.16724686491495375, + -0.25946127389033863, + -0.2136734733491549, + -0.24876971783236723, + -0.29286819157735633, + -0.1931398231236298, + -0.18975206036189426, + -0.28176528681727014, + -0.2983147633173229, + -0.1580847845564298, + -0.20833154294872275, + -0.22109480441607787, + -0.2919516404285861, + -0.23812614469686386, + -0.22289627808498724, + -0.24048036344788093, + -0.2938372220271892, + -0.16873674441012118, + -0.16578065796670907, + -0.2629564327505306, + -0.1730846878974077, + -0.16427282071564284, + -0.27493312143731163, + -0.2203989726059496, + -0.2725923095927339, + -0.19015049366933132, + -0.1578623166984013, + -0.2894980602913705, + -0.2964976284620615, + -0.22608204277594485, + -0.2720998352297286, + -0.19433234259230042, + -0.22445643392139342, + -0.16352290327286817, + -0.28614077940417637, + -0.24923216968695314, + -0.22761383168487942, + -0.18944778862077144, + -0.2043261575365241, + -0.2916804476163479, + -0.252374812643334, + -0.16058033584209666, + -0.28264889890249845, + -0.24541146732339805, + -0.2860565478602965, + -0.22612731315964854, + -0.2789252342532694, + -0.1963488777309264, + -0.16325739847667145, + -0.15682402794672484, + -0.18655395367905092, + -0.2322358761885671, + -0.17408217362932304, + -0.23401764522413418, + -0.16376542963838572, + -0.1816597566722039, + -0.2822923258505757, + -0.15826790482721378, + -0.24267822947283557, + -0.23603984243020248, + -0.28537038102488715, + -0.17001460683382932, + -0.2863970352018663, + -0.28864853260085954, + -0.24486374793134766, + -0.18457776406059861, + -0.16792791902111778, + -0.26314519321057384, + -0.15869682863861118, + -0.16295710063146449, + -0.22609208547835896, + -0.21302749189745185, + -0.17977988705459563, + -0.20189150564946615, + -0.1860543559729589, + -0.22184543005207155, + -0.1619284933897675, + -0.2168899466377976, + -0.19844690443969892, + -0.2628602301810491, + -0.18005454183223965, + -0.16524815119307268, + -0.26413326792601327, + -0.2653593609906151, + -0.27755760244999506, + -0.2806854329981446, + -0.2375669493390042, + -0.23921054874098932, + -0.1601662961665772, + -0.2539629907748288, + -0.21240585354878033, + -0.2683228225719431, + -0.2808346001867846, + -0.18618600423441903, + -0.28659405195808324, + -0.19848654762916618, + -0.24528044101550825, + -0.21237011418170523, + -0.16787577546703067, + -0.20836331606626735, + -0.22809745228503467, + -0.23167771712409413, + -0.2369628912106292, + -0.2832937321990772, + -0.2011223641090497, + -0.1734153336091827, + -0.248063874407113, + -0.1605597610930305, + -0.21010893111012496, + -0.29586335314393875, + -0.29344194560212356, + -0.26811470128846215, + -0.2799835862150989, + -0.26860890820245326, + -0.18899587818779973, + -0.17415603770666732, + -0.29761458980128286, + -0.22495527899840212, + -0.2689497604700062, + -0.2726457056608248, + -0.18667198502172552, + -0.2004573247265634, + -0.21493485630810505, + -0.19174780946210127, + -0.21437690379193652, + -0.1640140108319958, + -0.21996897168342205, + -0.1637189916362054, + -0.23571021676354878, + -0.15744271990868608, + -0.21492244270464497, + -0.23289885062903243, + -0.16976622438784397, + -0.29534131324985197, + -0.2891296130681822, + -0.218803107519001, + -0.22728297262340855, + -0.20444467910932873, + -0.22354909250745644, + -0.21712134235669245, + -0.2738088485243505, + -0.2568273033643611, + -0.27567184595306915, + -0.24842531010687527, + -0.19392806233774199, + -0.2943869537909535, + -0.26476618510406474, + -0.22276649840902824, + -0.2544136663397825, + -0.27922354992949144, + -0.20379617176852477, + -0.23751825808199806, + -0.1641315627980659, + -0.20391123724629612, + -0.24798169416660615, + -0.23313630034610297, + -0.27845540573018646, + -0.17320660859349182, + -0.19601136607110722, + -0.241431985009883, + -0.29608031619615793, + -0.16103169945392956, + -0.17212085393151597, + -0.269463902541192, + -0.2715837549593379, + -0.16537510624915702, + -0.2548359067034175, + -0.20592628823454923, + -0.18680596981867786, + -0.16392063053580525, + -0.21744058825147156, + -0.2359290636610658, + -0.23301300310031203, + -0.29261034123843355, + -0.29136532732835857, + -0.2911449343468013, + -0.27373378996514647, + -0.21147989118824229, + -0.2452596669449463, + -0.17959299762125897, + -0.2737927972126932, + -0.28146517532823834, + -0.22786547113202044, + -0.2768516433969177, + -0.17084419001225554, + -0.27799898952027285, + -0.2563155203101846, + -0.18310462750043088, + -0.24003421997768257, + -0.16351608610535487, + -0.26467466097852466, + -0.25640884225956073, + -0.21046041849788058, + -0.1908426519568816, + -0.2637444602073828, + -0.22722925535024874, + -0.17981206933673216, + -0.1904994708034364, + -0.2943137790159001, + -0.2741540680189174, + -0.2526621645045205, + -0.2779657464642563, + -0.2590081547494608, + -0.2516746539242725, + -0.266555680008303, + -0.21317092893525413, + -0.16321091247863487, + -0.17516756450434035, + -0.24473724212318348, + -0.1688142112714669, + -0.22516917557598334, + -0.276927362827408, + -0.2160473985589473, + -0.21178730443841637, + -0.2617174223045378, + -0.19316645702597007, + -0.26413890591483885, + -0.15862932212324066, + -0.28724964215613014, + -0.1635738222436822, + -0.29505862042276, + -0.1580986436824303, + -0.25075799483863426, + -0.21937307736473285, + -0.24585870947389152, + -0.20083024106189717, + -0.1807313504887853, + -0.24054313118565612, + -0.180046199805208, + -0.217224074853673, + -0.18991122381842285, + -0.1956649783238498, + -0.17586703456089914, + -0.29320321675305294, + -0.2478932620757336, + -0.23201963503686435, + -0.25298747195164734, + -0.2622390777848309, + -0.16502591360905478, + -0.1670668173592407, + -0.16719692708715997, + -0.2443059335589659, + -0.18596536149305937, + -0.17556729528999793, + -0.2762096394400966, + -0.157183031607924, + -0.25797094614371063, + -0.28190870221967357, + -0.2702414987256002, + -0.18421919203123333, + -0.2077553827183032, + -0.2418134378335353, + -0.18706656006319503, + -0.218346820517994, + -0.16031389687807512, + -0.23935683579251008, + -0.1644134178313641, + -0.2424458683503447, + -0.23845723051020237, + -0.2773793406285009, + -0.29705852845387104, + -0.15471464748635375, + -0.17513137762388398, + -0.22973770978513813, + -0.28155549101865884, + -0.2616877050440426, + -0.2066125139610795, + -0.17062753538836511, + -0.2534231150015268, + -0.24165614478971317, + -0.2957282633320616, + -0.23959591723271811, + -0.17618119737944066, + -0.2890634941395467, + -0.18586176073832597, + -0.28600206720571614, + -0.23012314166357922, + -0.23356575108139147, + -0.2921855532731104, + -0.16800589078360637, + -0.1590446431947371, + -0.23713997950353247, + -0.23638250418273246, + -0.2126036576209025, + -0.18515290379778648, + -0.2829010514797878, + -0.2953284155609896, + -0.22253789257804002, + -0.15585958100375064, + -0.2503244844992744, + -0.29802385488588967, + -0.2692254571025656, + -0.15744615202994866, + -0.24070477664354942, + -0.22097172217580419, + -0.2641842050363157, + -0.2615711156734569, + -0.28973770508188146, + -0.26362471033732976, + -0.2970132703844088, + -0.18114910695568642, + -0.28756347388012543, + -0.20041220103667523, + -0.22012560326452704, + -0.28681393148080314, + -0.2283020815657058, + -0.20822257265109578, + -0.24721145779265352, + -0.22139966744671796, + -0.27467568484006355, + -0.2963026033790749, + -0.2287586653740878, + -0.268235319237686, + -0.17064417101949333, + -0.1683219182206369, + -0.17260175286837554, + -0.1789866606227276, + -0.2212456629611024, + -0.29189840437520265, + -0.20539794960854907, + -0.2594189861992811, + -0.18604899704660255, + -0.22604308076024437, + -0.21183071193382302, + -0.2964337328069762, + -0.20032861367721078, + -0.16230480619252102, + -0.2428539759025069, + -0.26591652493566253, + -0.20019075237943867, + -0.19688670759201282, + -0.1628231556674187, + -0.1987440408355521, + -0.29833724948379786, + -0.1702173432794904, + -0.18953847284789951, + -0.15608213886337793, + -0.24841020446437465, + -0.1907926914664833, + -0.20683211002707103, + -0.24647186438660257, + -0.281210744589254, + -0.29238830755247897, + -0.20757856917526718, + -0.20968337468813314, + -0.24427745696284076, + -0.2863228643546992, + -0.25846526941256115, + -0.17687745421768827, + -0.22177823540747185, + -0.2218124458268952, + -0.23012079774320512, + -0.26580359136149884, + -0.28987824573168414, + -0.2754693165755468, + -0.23695473530164016, + -0.2737032986283498, + -0.25816429061950036, + -0.21297738274851086, + -0.1944934182240206, + -0.2295643339038133, + -0.2539208048092406, + -0.29074101527193125, + -0.27954251779880934, + -0.23486191079166882, + -0.28157783491868743, + -0.2922235548212341, + -0.2747416828607271, + -0.206524131966214, + -0.2833340115763244, + -0.2489650618740813, + -0.1652905186463871, + -0.16312642374148098, + -0.19631446778020983, + -0.25598790595846976, + -0.1589095542682768, + -0.2862072671388742, + -0.15452887986004796, + -0.18375326763013333, + -0.16462432702324772, + -0.20113350346577752, + -0.1940891916393216, + -0.2862764230664602, + -0.15795724316193394, + -0.2581262805962352, + -0.24275670337170382, + -0.2792690142849098, + -0.19595979659281115, + -0.2530816765215147, + -0.23857448393462954, + -0.28777026668154415, + -0.28964677865906957, + -0.23011297525269736, + -0.19617019541150194, + -0.2802746853019511, + -0.1637298190012136, + -0.2773080026793279, + -0.18107900132273838, + -0.26185656398952506, + -0.21260672975392236, + -0.208116566316812, + -0.2169054884041861, + -0.2550473236949125, + -0.2971528980133395, + -0.1749402561382663, + -0.18884217054461994, + -0.2536214385220338, + -0.25496763216692814, + -0.1984368214145485, + -0.21864744806719932, + -0.29874652981212996, + -0.29182606735419053, + -0.29583148084413324, + -0.2835596538430153, + -0.2269411600869889, + -0.2682216260758429, + -0.20277998347833542, + -0.296158559347545, + -0.1707874851764039, + -0.16259391773132806, + -0.2260845218492757, + -0.20506142603420163, + -0.21000838284184387, + -0.27250449461984166, + -0.15762906007301528, + -0.18273490966077793, + -0.23466987553000068, + -0.1998879434339509, + -0.2774541022801565, + -0.23789681662175235, + -0.26294959346910546, + -0.26237431376302367, + -0.17892181329892415, + -0.193968532546561, + -0.2901410560561762, + -0.20882950580868842, + -0.1760537515384596, + -0.2766656867889314, + -0.24804915687148604, + -0.15881908219481927, + -0.1853028578798265, + -0.22999631152701905, + -0.2144065461126561, + -0.29331152783559844, + -0.17940907459186908, + -0.2984863661171396, + -0.24146951920504656, + -0.28577749549806347, + -0.19945405100342806, + -0.27254242432727754, + -0.26190352011917234, + -0.2342790646425416, + -0.2667880564882266, + -0.19549788526099302, + -0.16827495826958191, + -0.16118100424229354, + -0.2618711861540247, + -0.16696320231239742, + -0.19499803378550684, + -0.28869742341881927, + -0.24298006182381005, + -0.1960726980689857, + -0.2593287436277685, + -0.24648376002601577, + -0.18024751997589172, + -0.2659372420443854, + -0.20502557043987812, + -0.24967851696954635, + -0.2859594849631587, + -0.2688280738917871, + -0.20995169312594467, + -0.1815102381618877, + -0.27976483573742816, + -0.22147667521081033, + -0.228935602531111, + -0.2328212619384521, + -0.23907264344738138, + -0.18468088464881116, + -0.20807480675310136, + -0.22549208302986562, + -0.15586347151110544, + -0.18698680190343714, + -0.237628281980655, + -0.2925627679999972, + -0.2676661207398447, + -0.20980427407026586, + -0.29370967436652984, + -0.22103533620912458, + -0.2803200827330844, + -0.21588598898645558, + -0.2037099931908252, + -0.15956665970339, + -0.1741133089483292, + -0.21967397622581358, + -0.19472336284748445, + -0.18786014196777118, + -0.28880030253510774, + -0.27055638896192497, + -0.2959214571949956, + -0.18576616660151696, + -0.279849015998232, + -0.2129256584930713, + -0.16819075472755218, + -0.27886434871673105, + -0.20383734933063552, + -0.15787353660655645, + -0.2872107307935387, + -0.15620675569085263, + -0.18273187794440998, + -0.21465664024035747, + -0.22317586683368168, + -0.21539621902518583, + -0.2605953231291759, + -0.20466362514387104, + -0.280504093199458, + -0.2551794892667101, + -0.19047473885541794, + -0.2506700192250768, + -0.28396115666860994, + -0.1766484980630214, + -0.27352179329338805, + -0.16675981856199135, + -0.18784895029601356, + -0.19995130078199091, + -0.274501279935957, + -0.2222835447910766, + -0.19770572697964883, + -0.2630720452333958, + -0.260074573478333, + -0.2653376195178805, + -0.21172144239967555, + -0.2735549794298465, + -0.24816877146155436, + -0.25427941175671875, + -0.20085528022392152, + -0.2149197639548167, + -0.24175730771504816, + -0.2848978035872134, + -0.19179477230675418, + -0.25755682001103775, + -0.251205780945615, + -0.20646211950461574, + -0.22115470552390704, + -0.2584929959666634, + -0.2063975100251368, + -0.2608987901184431, + -0.2266883470675961, + -0.1791757789136993, + -0.1781518332511936, + -0.16652889175131147, + -0.2972572534594199, + -0.25871832205509, + -0.2843837478773163, + -0.26150077984967623, + -0.18894992569927477, + -0.21345153341258535, + -0.19636767833120883, + -0.19400235336567004, + -0.18234509199544197, + -0.26643198092385106, + -0.20081866056723313, + -0.17567952437694853, + -0.18899696192878118, + -0.22694102350926906, + -0.2697498050538324, + -0.21826540994897964, + -0.23878157332246158, + -0.29822816528486923, + -0.26640190425476373, + -0.24443623401755088, + -0.17904855737441777, + -0.18534572445520014, + -0.191723778038435, + -0.23031264231727983, + -0.23830269316542535, + -0.21962337301038048, + -0.23882059627541127, + -0.22038878189451333, + -0.28656519327167324, + -0.2744915960417352, + -0.17495750328556703, + -0.26375998253858746, + -0.21051743709961493, + -0.2803719347126216, + -0.2026677001560363, + -0.2928360379110007, + -0.22217904348870032, + -0.28722047318496974, + -0.1896517788604573, + -0.23563421649491828, + -0.27088438765406, + -0.2835340428695661, + -0.21117777778679214, + -0.20043817967437172, + -0.17049527351860486, + -0.27674263654216547, + -0.15533115116871063, + -0.2531141337336552, + -0.23866591900442968, + -0.227586865292223, + -0.26872635323769084, + -0.1855218132179844, + -0.18395900460155665, + -0.1595685877569377, + -0.27149754212249055, + -0.27512185715440385, + -0.26573708032469034, + -0.22067809676273017, + -0.20861335747985849, + -0.28429608510217175, + -0.18819524874400317, + -0.21953748906889597, + -0.2652440927756281, + -0.19491202219247533, + -0.2409219642315064, + -0.22458426889674135, + -0.28169183618243726, + -0.16682070348718817, + -0.24543304093199717, + -0.17539250205149598, + -0.1548983317618587, + -0.28735835029185475, + -0.18992394801565596, + -0.2844983882109146, + -0.18223372187328518, + -0.26860632134420775, + -0.16654771041997085, + -0.24707603649834717, + -0.19627976684731563, + -0.20573871669465713, + -0.22123393334633173, + -0.2751332206436687, + -0.22855376845262007, + -0.16641321707892662, + -0.20728635126152287, + -0.17818660997427538, + -0.2700001665810981, + -0.22924370482546808, + -0.2905183181472083, + -0.2705244235479682, + -0.1713794629707514, + -0.25638438201047054, + -0.18097604840364256, + -0.16392865132938614, + -0.27563694247065373, + -0.26674003685973335, + -0.2115918336153511, + -0.1733950123625703, + -0.19196894285149357, + -0.2946062293610254, + -0.24299472362097768, + -0.1577789829285967, + -0.22564447190282055, + -0.22085682056589043, + -0.16871552030469134, + -0.2043656136468362, + -0.17420177581491678, + -0.21174887805885673, + -0.22088505229254968, + -0.16324127295339314, + -0.2860050483254116, + -0.2784176448847399, + -0.25292127637354395, + -0.2977638119362483, + -0.16253845826308833, + -0.28997051109433475, + -0.20358409577751824, + -0.19131431137033164, + -0.16873096908421187, + -0.28341891114954276, + -0.25562137882826774, + -0.16636441163289936, + -0.2362133536120075, + -0.26790735648284203, + -0.19663413866139198, + -0.220017191368229, + -0.16289284918171051, + -0.18103334106402133, + -0.29065898439433857, + -0.20428100807690297, + -0.23248721622146584, + -0.2216727217885182, + -0.1649545064474274, + -0.18598806971927892, + -0.18346748737574764, + -0.2457751945397286, + -0.20008616970697934, + -0.24634455161456936, + -0.16789688716891377, + -0.21149241135270191, + -0.270509418954598, + -0.24280921436010622, + -0.23755153247052452, + -0.2500787633472482, + -0.19611095564525832, + -0.19137830880094708, + -0.21948999646332157, + -0.2871240066479833, + -0.2562355962791679, + -0.19716749300513778, + -0.19363481607906108, + -0.1780779317682635, + -0.21012422190664798, + -0.22199924877887273, + -0.2465344708215496, + -0.29662421433406855, + -0.2722668900865061, + -0.24756869442020177, + -0.23502104297413035, + -0.18484931618214215, + -0.27900983492761555, + -0.2081804299180139, + -0.16929123817936126, + -0.26774073596165665, + -0.16285639687766862, + -0.16421458377535184, + -0.291784737629482, + -0.2363485867022783, + -0.15767730514807826, + -0.17325392935020603, + -0.28951202161623446, + -0.236643570557353, + -0.1748013966570252, + -0.229205561626264, + -0.2782920926542291, + -0.2512305375082128, + -0.28991286895718515, + -0.2459247903948331, + -0.29049317338375713, + -0.23866505599020413, + -0.18851769260521656, + -0.16988832365862302, + -0.26855170820185265, + -0.23746706438651982, + -0.24639616131685743, + -0.2671739111402751, + -0.2797764471680275, + -0.2345356570178352, + -0.22519685482708662, + -0.28857374404306235, + -0.2079019765183016, + -0.21776223331672923, + -0.2920302310142925, + -0.21689587846578218, + -0.22196318821643013, + -0.2809208237675298, + -0.25549306434457864, + -0.17684958698288666, + -0.1852887389473722, + -0.18981651366624458, + -0.1957752938265911, + -0.2692311056648166, + -0.1957334894170748, + -0.21027198177879183, + -0.154450481283206, + -0.16609774846589903, + -0.29073680247048866, + -0.2466983306614845, + -0.18174828579891156, + -0.24380624257109373, + -0.2678954031787995, + -0.2966481558732616, + -0.2629789498653186, + -0.28607374993852935, + -0.2268117526157551, + -0.21352340499911482, + -0.18528634655127602, + -0.2688749953798047, + -0.2383767154752709, + -0.23126786514065759, + -0.23305072408173377, + -0.18946313077688004, + -0.2937636175560277, + -0.21491530310942014, + -0.19606226091522838, + -0.19848629825823333, + -0.22504042708414507, + -0.2661752609417053, + -0.2507147675997562, + -0.16218601902211896, + -0.2802521747158863, + -0.22465027386215425, + -0.17858197935229214, + -0.1763878727221363, + -0.18143769043544183, + -0.17386704132412106, + -0.20067264067448165, + -0.17855757218713586, + -0.22636877039119, + -0.26005205357887473, + -0.24167228662769577, + -0.2330756252277103, + -0.286957642409853, + -0.2694405524149722, + -0.2790292524988708, + -0.20526330170211274, + -0.1777286969618031, + -0.22583951553959128, + -0.2561955216022013, + -0.2875503419209421, + -0.20923114188418068, + -0.15797389208279267, + -0.23697562268406616, + -0.2216592538198719, + -0.29104531613335066, + -0.21638542281531506, + -0.2283662106922416, + -0.23886606900659704, + -0.2119591057600717, + -0.17358264493169934, + -0.29342716124479545, + -0.1990725004090924, + -0.2699993956397127, + -0.1634032108647618, + -0.19549342991844146, + -0.29498582372076415, + -0.16226751456908198, + -0.27647054818084893, + -0.29607864940681333, + -0.21363969304766928, + -0.24493422662622596, + -0.19757043581531006, + -0.27985552273175274, + -0.2980796822388472, + -0.2186329009172883, + -0.17234728020604853, + -0.2171709969769139, + -0.19671386517359438, + -0.17216734335461858, + -0.19848403996504857, + -0.18533362966308964, + -0.19301238009264232, + -0.24465047888994018, + -0.20938761602459882, + -0.23763180185145708, + -0.2269669461539407, + -0.2846055394407672, + -0.19682339672683083, + -0.17404763766179415, + -0.17602221737966656, + -0.274831002413918, + -0.21533069057386173, + -0.16691100418227614, + -0.17886195170354216, + -0.23862918520268558, + -0.26267833866812884, + -0.19794156988041448, + -0.17091911215991418, + -0.18942618138060976, + -0.23580669716677705, + -0.15968401558024678, + -0.18786433749793596, + -0.17679448747019844, + -0.28397307354564305, + -0.21306856337785776, + -0.2532482122451402, + -0.22852579971839992, + -0.2387268278421135, + -0.19210228969535892, + -0.2833245277202519, + -0.20103633586719047, + -0.19163708429449583, + -0.2481960445795351, + -0.22653993903260117, + -0.273063590214065, + -0.15773934103185142, + -0.18033574572138175, + -0.24961070201373553, + -0.21227432038204952, + -0.20778349979639607, + -0.28266807254445325, + -0.17484265217452744, + -0.25661162254568304, + -0.19613740123391987, + -0.21791400712036005, + -0.17163169247573287, + -0.25061251573213617, + -0.26862398336387405, + -0.19123328090427183, + -0.27338332500672685, + -0.29216428867140615, + -0.19738365210946174, + -0.19890088773097336, + -0.24916643952418055, + -0.19981312222971184, + -0.2871348173238268, + -0.2746500465710294, + -0.2694200517017492, + -0.24195161321592207, + -0.24973047557481384, + -0.18159314444966534, + -0.169170180275518, + -0.15640734803205666, + -0.2611384044002388, + -0.2729186593258271, + -0.2780260285599955, + -0.16681341017144377, + -0.22034732504749177, + -0.23993495279511878, + -0.2585583313747446, + -0.22759936479519732, + -0.15563397425040393, + -0.2543890098111428, + -0.2365082128317653, + -0.20171658081866323, + -0.23324506059424638, + -0.18183595258683677, + -0.25193441549062634, + -0.18624574754158563, + -0.29651015575733325, + -0.2754494544034242, + -0.17798972042589561, + -0.2310239993738774, + -0.18792991662608116, + -0.2884344450707471, + -0.18961409670910628, + -0.17912670688270327, + -0.2695306307549618, + -0.1919054118447618, + -0.22873252475455597, + -0.22216696224980625, + -0.2322285474434013, + -0.2381962686494289, + -0.18659757650300715, + -0.18685406446187908, + -0.16632660499649055, + -0.2965869300392804, + -0.175304930085718, + -0.22067696415332938, + -0.28376458066316973, + -0.27741529860444963, + -0.2907779659665044, + -0.20716396953949814, + -0.21699831561831526, + -0.2863002245688904, + -0.267407372658206, + -0.27436951093095097, + -0.23498682998077391, + -0.2929708658314244, + -0.2680324137183877, + -0.17845982124474893, + -0.23456957955520136, + -0.26006494874698466, + -0.1751520364746808, + -0.16032870426823342, + -0.16675420183974513, + -0.23854271706209554, + -0.2424103908285697, + -0.17265590461391236, + -0.25706158664240447, + -0.27492306551394935, + -0.26084627505402225, + -0.19606714347124876, + -0.17711282863646807, + -0.22477522829839922, + -0.286033099301357, + -0.21388133750524468, + -0.2566256006760476, + -0.24448457280064462, + -0.1828661943481933, + -0.2880479952419772, + -0.16374978208912205, + -0.15741106071703162, + -0.28147937790985034, + -0.27675242797098687, + -0.2777063830439838, + -0.2432792833129352, + -0.16222419050285003, + -0.18358346086365546, + -0.2432651949410701, + -0.18378808331940705, + -0.2896501396897709, + -0.24628974193526854, + -0.2510990756519034, + -0.1711318016248657, + -0.16094659588952306, + -0.2116554886987025, + -0.1809967934014865, + -0.23341918475662882, + -0.2537897856027739, + -0.20839799160835162, + -0.22983087772972288, + -0.15443319927506988, + -0.24901234840369307, + -0.18670869152711628, + -0.21597104795385236, + -0.17257852342724928, + -0.21260042977463905, + -0.1925952001912487, + -0.22815031209105308, + -0.17218039587499054, + -0.16977721991494432, + -0.18770979118876313, + -0.23163876867333838, + -0.2698165947360169, + -0.15959797935932563, + -0.28180476481174715, + -0.28138530456585703, + -0.24075458262386365, + -0.2774993670931506, + -0.21600608160823237, + -0.25595839246260066, + -0.29205674765853185, + -0.1740633658678382, + -0.25319881603025834, + -0.2887777335397084, + -0.17887195330634245, + -0.17202985387116254, + -0.28968802105406377, + -0.17755487221042243, + -0.2583843299887278, + -0.25919066544072933, + -0.23756083442617382, + -0.21085511459416423, + -0.18109554451244497, + -0.2417061880890793, + -0.2544026386414949, + -0.2060356520904071, + -0.2641777382324544, + -0.252087872575116, + -0.18750357854303362, + -0.19076089979027128, + -0.21619739237817392, + -0.22715145762253092, + -0.17845666598891807, + -0.1917479776999727, + -0.18116311286634917, + -0.2781249626600089, + -0.15652634472671648, + -0.17462407869363522, + -0.23972849506180702, + -0.22943805734117925, + -0.1881749443029256, + -0.24556949324071883, + -0.21423448536665896, + -0.2987985850965366, + -0.2506173551362635, + -0.2510074054915423, + -0.26247746841338143, + -0.27088678723294435, + -0.288447485225916, + -0.24005711803824414, + -0.22501590231711613, + -0.15473210142910881, + -0.24502545778280366, + -0.26607525452302494 + ], + "type": "scatter" + }, + { + "mode": "markers", + "name": "Expectation", + "x": [ + 0.4741729497909546 + ], + "y": [ + -0.22661489248275757 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines+markers", + "name": "Mode", + "x": [ + 0.3408585786819458, + 0.6074873208999634, + 0.6074873208999634, + 0.3408585786819458, + 0.3408585786819458, + null, + 0.3408585786819458, + 0.6074873208999634, + 0.6074873208999634, + 0.3408585786819458, + 0.3408585786819458, + null + ], + "y": [ + -0.29881715774536133, + -0.29881715774536133, + -0.1544126272201538, + -0.1544126272201538, + -0.29881715774536133, + null, + -0.29881715774536133, + -0.29881715774536133, + -0.1544126272201538, + -0.1544126272201538, + -0.29881715774536133, + null + ], + "type": "scatter" + } + ], + "layout": { + "title": { + "text": "JPT" + }, + "xaxis": { + "title": { + "text": "relative_x" + } + }, + "yaxis": { + "title": { + "text": "relative_y" + } + }, + "template": { + "data": { + "histogram2dcontour": [ + { + "type": "histogram2dcontour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "choropleth": [ + { + "type": "choropleth", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "histogram2d": [ + { + "type": "histogram2d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmap": [ + { + "type": "heatmap", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmapgl": [ + { + "type": "heatmapgl", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "contourcarpet": [ + { + "type": "contourcarpet", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "contour": [ + { + "type": "contour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "surface": [ + { + "type": "surface", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "mesh3d": [ + { + "type": "mesh3d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "scatter": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scatter" + } + ], + "parcoords": [ + { + "type": "parcoords", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolargl": [ + { + "type": "scatterpolargl", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "bar": [ + { + "error_x": { + "color": "#f2f5fa" + }, + "error_y": { + "color": "#f2f5fa" + }, + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "scattergeo": [ + { + "type": "scattergeo", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolar": [ + { + "type": "scatterpolar", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "scattergl": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scattergl" + } + ], + "scatter3d": [ + { + "type": "scatter3d", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattermapbox": [ + { + "type": "scattermapbox", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterternary": [ + { + "type": "scatterternary", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattercarpet": [ + { + "type": "scattercarpet", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "baxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "type": "carpet" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#506784" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "header": { + "fill": { + "color": "#2a3f5f" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "type": "table" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ] + }, + "layout": { + "autotypenumbers": "strict", + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#f2f5fa" + }, + "hovermode": "closest", + "hoverlabel": { + "align": "left" + }, + "paper_bgcolor": "rgb(17,17,17)", + "plot_bgcolor": "rgb(17,17,17)", + "polar": { + "bgcolor": "rgb(17,17,17)", + "angularaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "radialaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "ternary": { + "bgcolor": "rgb(17,17,17)", + "aaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "baxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "caxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "sequential": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ] + }, + "xaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "yaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "scene": { + "xaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "yaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "zaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + } + }, + "shapedefaults": { + "line": { + "color": "#f2f5fa" + } + }, + "annotationdefaults": { + "arrowcolor": "#f2f5fa", + "arrowhead": 0, + "arrowwidth": 1 + }, + "geo": { + "bgcolor": "rgb(17,17,17)", + "landcolor": "rgb(17,17,17)", + "subunitcolor": "#506784", + "showland": true, + "showlakes": true, + "lakecolor": "rgb(17,17,17)" + }, + "title": { + "x": 0.05 + }, + "updatemenudefaults": { + "bgcolor": "#506784", + "borderwidth": 0 + }, + "sliderdefaults": { + "bgcolor": "#C8D4E3", + "borderwidth": 1, + "bordercolor": "rgb(17,17,17)", + "tickwidth": 0 + }, + "mapbox": { + "style": "dark" + } + } + } + }, + "config": { + "plotlyServerURL": "https://plot.ly" + } + }, + "text/html": "
" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "modes, likelihood = model.mode()\n", + "mode = modes[0]\n", + "mode_model, _ = model.conditional(mode)\n", + "mode_xy = mode_model.marginal([relative_x, relative_y])\n", + "fig = go.Figure(mode_xy.root.plot_2d(), mode_xy.root.plotly_layout())\n", + "fig.show()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:43.819932Z", + "start_time": "2024-03-12T16:15:43.324066Z" + } + }, + "id": "eac2e7e063da5b10", + "execution_count": 8 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "# fpa.policy = mode_model\n", + "# fpa.sample_amount = 500\n", + "# with simulated_robot:\n", + "# fpa.try_out_policy()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:43.822414Z", + "start_time": "2024-03-12T16:15:43.820834Z" + } + }, + "id": "1217769a7ed0ab5b", + "execution_count": 9 + }, + { + "cell_type": "code", + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n", + "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n" + ] + } + ], + "source": [ + "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"apartment.urdf\")\n", + "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", + "model.root.update_variables({relative_x: relative_y, relative_y: relative_x})\n", + "\n", + "# milk.set_pose(Pose([3.2, 3.15, 1.04], [0, 0, 1, 1]))" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:46.316401Z", + "start_time": "2024-03-12T16:15:43.823070Z" + } + }, + "id": "90d7cb5e1e1cc7fd", + "execution_count": 10 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", + "fpa = FunkyPickUpAction(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value], policy=model)\n", + "fpa.sample_amount = 200" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:46.320004Z", + "start_time": "2024-03-12T16:15:46.317282Z" + } + }, + "id": "ea11db8c3db4075e", + "execution_count": 11 + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "data": [ + { + "hovertext": [ + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 5.963717193567754", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 5.963717193567754", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 8.805685480602348", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 8.805685480602348", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 21.567555592524567", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 15.603838398956814", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 21.567555592524567", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 15.603838398956814", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 15.603838398956814", + "Likelihood: 30.373241073126916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 50.9631055879433", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 56.92682278151106", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 50.9631055879433", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 30.373241073126916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916", + "Likelihood: 24.40952387955916" + ], + "marker": { + "color": [ + 56.92682278151106, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 56.92682278151106, + 56.92682278151106, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 56.92682278151106, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 56.92682278151106, + 56.92682278151106, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 56.92682278151106, + 56.92682278151106, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 56.92682278151106, + 56.92682278151106, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 56.92682278151106, + 30.373241073126916, + 30.373241073126916, + 56.92682278151106, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 56.92682278151106, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 56.92682278151106, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 56.92682278151106, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 56.92682278151106, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 56.92682278151106, + 5.963717193567754, + 5.963717193567754, + 56.92682278151106, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 5.963717193567754, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 5.963717193567754, + 30.373241073126916, + 56.92682278151106, + 56.92682278151106, + 5.963717193567754, + 30.373241073126916, + 56.92682278151106, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 5.963717193567754, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 56.92682278151106, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 56.92682278151106, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 30.373241073126916, + 50.9631055879433, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 56.92682278151106, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 50.9631055879433, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 50.9631055879433, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 50.9631055879433, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 30.373241073126916, + 8.805685480602348, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 8.805685480602348, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 8.805685480602348, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 21.567555592524567, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 15.603838398956814, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 15.603838398956814, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 21.567555592524567, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 15.603838398956814, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 15.603838398956814, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 15.603838398956814, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 15.603838398956814, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 15.603838398956814, + 30.373241073126916, + 56.92682278151106, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 50.9631055879433, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 30.373241073126916, + 24.40952387955916, + 56.92682278151106, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 50.9631055879433, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 30.373241073126916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916, + 24.40952387955916 + ] + }, + "mode": "markers", + "name": "Samples", + "x": [ + 0.45915172942014404, + 0.5474996426980006, + 0.5491974909294062, + 0.49038497469498227, + 0.5279689831728162, + 0.7030391939757641, + 0.759680234047925, + 0.6479476081440215, + 0.7237797408089242, + 0.5894109231015993, + 0.7719438843109594, + 0.576461957925967, + 0.8065781003289041, + 0.5550819457863128, + 0.5044674182217166, + 0.48186732833458834, + 0.6715370858541645, + 0.5750425529677408, + 0.6506834234232752, + 0.4676445092230069, + 0.610430494489527, + 0.5027172422472963, + 0.600478408058785, + 0.6524530415346526, + 0.742621773863327, + 0.4523068549090507, + 0.4543529843468379, + 0.5847415238520016, + 0.7415030467913204, + 0.5004822417760282, + 0.6162129313205793, + 0.5971915123122298, + 0.776362461311499, + 0.49587766351711404, + 0.5110378646169509, + 0.7620443082464161, + 0.4579965870077458, + 0.5534580408537453, + 0.7745760139616513, + 0.5379501298065366, + 0.5740798217927998, + 0.6924137164558318, + 0.4702367645606388, + 0.7093579578254097, + 0.7044635983762502, + 0.6128903517060786, + 0.4448302214095761, + 0.44372310927534075, + 0.7064843930454545, + 0.5438948403394119, + 0.5785273313286909, + 0.5024063915428711, + 0.5707072455614297, + 0.4538377396840833, + 0.45517608648228086, + 0.7811137452370926, + 0.6595261302383874, + 0.757524082539657, + 0.7816859211845498, + 0.6549073863868689, + 0.5839372389955572, + 0.5931531999624207, + 0.5047436617952118, + 0.6926425050605554, + 0.7486580415943709, + 0.6675618490346937, + 0.8079523836120788, + 0.8059621124183991, + 0.7732445322846089, + 0.48846627363865325, + 0.45070148977928576, + 0.4455966796203828, + 0.760965635451365, + 0.7647234684089693, + 0.7248928319836295, + 0.698277426442458, + 0.49898372853343, + 0.7329972417642002, + 0.5729445473174256, + 0.7543221841829479, + 0.5588383559881107, + 0.4486438691604228, + 0.5849465719958549, + 0.4720804565919624, + 0.4587176130050891, + 0.6225117031981043, + 0.7208039279689673, + 0.5368010021047627, + 0.7785092733162661, + 0.5734391861669699, + 0.7476080542538643, + 0.6932889373127942, + 0.5995720914630349, + 0.48860277312825384, + 0.6619678966965956, + 0.7273043097332906, + 0.48465530611651747, + 0.6751359006912228, + 0.6686502117411932, + 0.4737746803893892, + 0.5820942353835656, + 0.5218684296704388, + 0.7045792317280195, + 0.49241387531621905, + 0.5846871266004925, + 0.6536239197490125, + 0.4828802903306827, + 0.6335339744287175, + 0.6787110603199681, + 0.6701160766443937, + 0.47483638134876616, + 0.5629960900408019, + 0.6990784672034445, + 0.4847090819899131, + 0.792598668596941, + 0.45298756034555115, + 0.7529084232409268, + 0.4892408060250163, + 0.5807892237856797, + 0.5880678715866807, + 0.759754863366052, + 0.7718471443839194, + 0.7153970809924197, + 0.5112722711198183, + 0.7012410825143068, + 0.4559926985590271, + 0.7728801621351752, + 0.7042440548614342, + 0.8018969006787677, + 0.4647635723616219, + 0.80346176296344, + 0.761272756378317, + 0.5234792834484003, + 0.7800773525210534, + 0.5544152747598988, + 0.6959074213108739, + 0.667215609108354, + 0.7795268818934666, + 0.7372947615156666, + 0.7812394866183572, + 0.5839035853384069, + 0.5046707851772894, + 0.7519356964234671, + 0.578294753039893, + 0.5233705349594879, + 0.7875688924346962, + 0.5893688228863219, + 0.8094432005735951, + 0.7935884632626597, + 0.49276635127015467, + 0.5042019865685257, + 0.7551273602697519, + 0.48145566756046376, + 0.6062646617853498, + 0.5211932679557031, + 0.5792574047935624, + 0.5854149458887994, + 0.5989701502220779, + 0.7676355059957471, + 0.6402170365632303, + 0.5297721011115936, + 0.5112840533387845, + 0.5827809152599129, + 0.47996813978242614, + 0.7000626876932636, + 0.7990890854303743, + 0.8004964617763388, + 0.5630029918667978, + 0.573488001894978, + 0.757671074026981, + 0.5858144992919604, + 0.693851626241013, + 0.7366567560673933, + 0.48920868436769904, + 0.6694390088323926, + 0.6606040256843997, + 0.5578357314536906, + 0.6007839941609416, + 0.7177044383889928, + 0.4604384510211469, + 0.7973740131405158, + 0.7693324177676449, + 0.5224752111951413, + 0.5103232376996193, + 0.6248277298986886, + 0.6818946746657637, + 0.5094063506026164, + 0.5278839244631531, + 0.48967109524252156, + 0.45678779866963604, + 0.5585078167542308, + 0.6824438472327676, + 0.4711431954053256, + 0.5423148930511887, + 0.8106743292948408, + 0.5868498282565582, + 0.58404619163873, + 0.5191346948786933, + 0.5542930039676826, + 0.6413822090306387, + 0.6757954877655398, + 0.7439135456483905, + 0.7534778748139308, + 0.539315966519224, + 0.6038889685452483, + 0.7706925679485126, + 0.6844618828123, + 0.46545028167518854, + 0.5422205694285763, + 0.45141188318918773, + 0.7121137505453047, + 0.7047224865752487, + 0.4541747227612868, + 0.7196227230488328, + 0.5767420359755995, + 0.6737472798263112, + 0.6117750470795489, + 0.6306599433380427, + 0.794474400328349, + 0.6815694381503548, + 0.7498601912525553, + 0.5356883163228262, + 0.5032732996692326, + 0.7291990212918573, + 0.7584491093541543, + 0.5335621364458878, + 0.45273470248091763, + 0.46354984550350337, + 0.7325965282092202, + 0.5405344935309341, + 0.4501729329666017, + 0.5135637191389945, + 0.552080814762125, + 0.6039429417037339, + 0.7455635232489911, + 0.5068172696444593, + 0.5294362176372115, + 0.5088538176979888, + 0.6661785991579204, + 0.6817748702636058, + 0.5878470447913309, + 0.45633853181533385, + 0.505337402549344, + 0.6363590359971558, + 0.6296220464968598, + 0.5598957608305999, + 0.6118663268007817, + 0.6310153300153312, + 0.44121190919021436, + 0.6573426763655302, + 0.5843240268345018, + 0.5449404670042817, + 0.4789725049283129, + 0.6579695117703075, + 0.609721697712851, + 0.6156954578488913, + 0.5811570745025254, + 0.5233140541165554, + 0.5575846437174007, + 0.4995345174783796, + 0.5433183193388017, + 0.645931519521048, + 0.5398275838431909, + 0.6652492567977284, + 0.45662271624723844, + 0.5617353855038281, + 0.5238278806017145, + 0.6652013717936065, + 0.46385783218387927, + 0.5209661704630084, + 0.6072618340423501, + 0.6179422061324842, + 0.5685167273270858, + 0.4904155586915656, + 0.5716975251581004, + 0.5238995606607026, + 0.6160647983683756, + 0.6013271437420604, + 0.657694988939556, + 0.5750511943248195, + 0.6722790504467915, + 0.5852420074723219, + 0.6854195616667168, + 0.4926382164178246, + 0.46708265397682536, + 0.612264438269355, + 0.5736732891282674, + 0.6336610289032865, + 0.6596796061940504, + 0.5670262823746751, + 0.6466868704508378, + 0.6544807370114499, + 0.45780999581582776, + 0.5491151877244871, + 0.6208416390694778, + 0.6358562726476993, + 0.5131232677800712, + 0.6800655160526135, + 0.5307285494583514, + 0.5042608257681752, + 0.603634515098952, + 0.6297488706919772, + 0.47484816308921696, + 0.474821241716898, + 0.4703656547424043, + 0.6791579816357203, + 0.5162989725898646, + 0.5570085516491315, + 0.6035978748978841, + 0.5188062057350731, + 0.5296864553798523, + 0.5421311891751994, + 0.5243153122572657, + 0.4537942547721684, + 0.4461895700204479, + 0.44192876028947287, + 0.5361050221067057, + 0.6424898110590134, + 0.5487530154421144, + 0.4618429793820026, + 0.5787271667068007, + 0.6548543731553197, + 0.5859152452690455, + 0.49653468676589313, + 0.48490332517029, + 0.5983633869618261, + 0.6526169176257269, + 0.6491541569938721, + 0.6032098086470528, + 0.5441825106195066, + 0.5308395691381967, + 0.5210412863140177, + 0.6335948970020726, + 0.4944558681124176, + 0.6366226038282652, + 0.46427549839815613, + 0.5571969010221178, + 0.5398139040476315, + 0.5506658807813277, + 0.6050092315934628, + 0.5788649437202739, + 0.5226529392084179, + 0.6286241013277931, + 0.588003312704813, + 0.4486770966035396, + 0.5667917106785645, + 0.4936212959739395, + 0.5661503415906751, + 0.522724755383124, + 0.6476471001523708, + 0.4470794618909071, + 0.49917576067422703, + 0.5252556738832481, + 0.488797991377646, + 0.5789110235280346, + 0.5903471247103962, + 0.48589504865263977, + 0.5038324823196635, + 0.5359986372308144, + 0.46604578678262515, + 0.5815126685818451, + 0.4694984811899454, + 0.6447062990483557, + 0.5119992307222365, + 0.5442000400538582, + 0.6166925620287249, + 0.4716262400744912, + 0.51206033049888, + 0.49894725676112295, + 0.4839048349129577, + 0.44932030477905766, + 0.4544753310750908, + 0.44887359523547604, + 0.5263625973226296, + 0.6722009695832565, + 0.5270100072880094, + 0.5579620447961853, + 0.4429910547192217, + 0.452417121460591, + 0.6419009043595539, + 0.5075193888895917, + 0.5912735176706783, + 0.6503615291381155, + 0.5770648513330329, + 0.4590945329030214, + 0.5803493356352327, + 0.47203348083854674, + 0.6656581763314497, + 0.6056195514389977, + 0.6712207748634114, + 0.6797550473224221, + 0.49621144724111954, + 0.6162151590613919, + 0.6516596948739951, + 0.6808995826583819, + 0.6781471078548328, + 0.5117357205992917, + 0.4768552755513267, + 0.61179228613164, + 0.6172319697568311, + 0.536452532244017, + 0.656524893601108, + 0.671712087453995, + 0.6502675268992315, + 0.5316515665979553, + 0.4680842588631032, + 0.5153554525496266, + 0.5785154399993737, + 0.48567212234528595, + 0.6336133534633105, + 0.5342029505656524, + 0.4436780322079759, + 0.5447546555281627, + 0.586506305623054, + 0.6316227183213287, + 0.6832432688482626, + 0.6191520048725369, + 0.6301842861440817, + 0.6101238137265299, + 0.5781762431668918, + 0.46086025429558153, + 0.6496466525032448, + 0.6539973796298889, + 0.5681698246853439, + 0.4411763050961333, + 0.6780267106573348, + 0.6771259152174947, + 0.5383947524536469, + 0.6511108501924449, + 0.6573532368039743, + 0.5506605742693781, + 0.45403320454561796, + 0.6438026607516811, + 0.47557457034793565, + 0.5205190020798709, + 0.5867068636178728, + 0.4520272440333092, + 0.6402002807357408, + 0.5403161767037703, + 0.49211279523688933, + 0.6508747103483519, + 0.46468172049522216, + 0.4675114401473938, + 0.46178999836312445, + 0.642601349058965, + 0.6541161506774332, + 0.57190310074535, + 0.5375625399702294, + 0.45706949601822366, + 0.5880290092719884, + 0.5497896676108512, + 0.48796557526715345, + 0.4426996938855564, + 0.6101132871591015, + 0.6555824405857356, + 0.6702530938147537, + 0.5345028608104949, + 0.6330749196774288, + 0.6758895963688675, + 0.5316461267384336, + 0.506498534528388, + 0.6252560643606015, + 0.5337485800360251, + 0.6348058294100782, + 0.5037366872592618, + 0.44468995272896455, + 0.48858564465121296, + 0.4530961234096509, + 0.5488796749236826, + 0.6726669981135666, + 0.4598342151390969, + 0.5572281968844113, + 0.5812058871833963, + 0.5057396193905109, + 0.45117999922093693, + 0.4815620867015693, + 0.5604351785224723, + 0.6020575723899375, + 0.5358383230673486, + 0.6408729587898907, + 0.5493988331599142, + 0.6626152291736805, + 0.47117832557175887, + 0.4822843825773301, + 0.4577561985438559, + 0.4663335859127113, + 0.45594408776672457, + 0.45637994616580213, + 0.4478806374390009, + 0.6457435616114326, + 0.5982067630819705, + 0.6833062404308481, + 0.49779303012096343, + 0.5706370715045204, + 0.6794993617312257, + 0.4573182567036695, + 0.511020441402287, + 0.6171618389951848, + 0.6410190671108749, + 0.5874337324057297, + 0.6228135990340863, + 0.5686067400986963, + 0.517026757313386, + 0.6289887161590083, + 0.444363573067023, + 0.6230267566097041, + 0.6382050461789572, + 0.6713523398027876, + 0.5181661051041869, + 0.5647788817991077, + 0.6815413034459699, + 0.6197387045109748, + 0.6714489482698456, + 0.4632008053341787, + 0.5672227354471147, + 0.49372986755264087, + 0.654860178305893, + 0.5941604449270447, + 0.47882312466579374, + 0.4471852237559099, + 0.6804863601508508, + 0.4879223954178973, + 0.4619235649993174, + 0.6144054361211998, + 0.4773217614902493, + 0.6190807132661252, + 0.4557983487446129, + 0.5832836109936314, + 0.5107149860560749, + 0.49720532905988274, + 0.6455481204494731, + 0.6019443532632821, + 0.6292690398553569, + 0.508259164232367, + 0.5545030075060253, + 0.5391494246126386, + 0.510839208332796, + 0.5109859054626706, + 0.6760790568805043, + 0.5912748968794714, + 0.5148711407901777, + 0.6564261928761785, + 0.627454308540084, + 0.4956242894303058, + 0.6579017560604665, + 0.6583657851851071, + 0.6338594089869016, + 0.454146834444125, + 0.4527944687977861, + 0.5246408778696776, + 0.4622984982906331, + 0.6529188303974952, + 0.4426327189570165, + 0.6339396998360243, + 0.48377729526126556, + 0.46133069550568323, + 0.6331459309534502, + 0.6091853408442324, + 0.609869271724215, + 0.6269556763136219, + 0.5905990320671716, + 0.558037914270326, + 0.6215346942657776, + 0.573176135135519, + 0.5791881306692432, + 0.5274345961135443, + 0.5102259099144196, + 0.4847432177966004, + 0.5003879049695527, + 0.6211846041602989, + 0.5283100949145533, + 0.6586161061082424, + 0.46333943109111164, + 0.5937061168597542, + 0.6583718570319192, + 0.4632948789819427, + 0.4477230927667578, + 0.5270691788319498, + 0.6344605424682579, + 0.5534512277792355, + 0.6692792378437193, + 0.5006911612159592, + 0.5217394788225425, + 0.6379562663311901, + 0.5591850336435836, + 0.6332731970056718, + 0.5811431081632342, + 0.6789775977985137, + 0.6807837241396054, + 0.47045195191731093, + 0.4877410468189467, + 0.6658993060831915, + 0.4796963123214947, + 0.4964105945783305, + 0.5972344509081982, + 0.6434913971579845, + 0.5250845303160325, + 0.5268464777667752, + 0.44562415278450407, + 0.5592981116093527, + 0.5590183146649137, + 0.595741515359447, + 0.5675215763490913, + 0.44881281624161484, + 0.6244887270658785, + 0.48685045064416205, + 0.5624670424514003, + 0.4930045072843514, + 0.6469157771917947, + 0.48791911050447107, + 0.5161145146928123, + 0.49387534507307784, + 0.5998380082259606, + 0.6251823911422553, + 0.5542358103728111, + 0.5177184485322549, + 0.5251355346266126, + 0.44254099040064526, + 0.48920411006675474, + 0.5761743464598077, + 0.47489908206162457, + 0.604250653388749, + 0.47132007461514747, + 0.5179501336023604, + 0.6652045898804734, + 0.5832636992676121, + 0.6491997998928734, + 0.6497746738539082, + 0.5374675894916154, + 0.44383163962631805, + 0.665981496814907, + 0.4764975567942646, + 0.5364752413804432, + 0.6632896115269151, + 0.637787706672216, + 0.5227381983380447, + 0.5645952666899561, + 0.5721385367063817, + 0.5161632384871416, + 0.5607112219635797, + 0.4764820293139854, + 0.6330145209177023, + 0.6381688226718517, + 0.6472291346280188, + 0.6265727599673058, + 0.5628106589390862, + 0.6683379128667091, + 0.6488885973586348, + 0.49912691323537345, + 0.5776611093433675, + 0.44928213450591176, + 0.5261390800607721, + 0.5193348831338441, + 0.46355691278109706, + 0.5020394172787397, + 0.45827488214126916, + 0.6743781048228168, + 0.5199596477084647, + 0.4898061801540138, + 0.6227065651294823, + 0.5394361663699393, + 0.4471347703541837, + 0.4561824750836161, + 0.46297689847901824, + 0.5385868220658017, + 0.4549989583493303, + 0.51203351336516, + 0.6786409936914988, + 0.4567021216577284, + 0.5956890541317068, + 0.6177194304058946, + 0.5058448143059023, + 0.5074662474021415, + 0.5496846364660246, + 0.5010452869472911, + 0.5718820559669844, + 0.6527270113516321, + 0.49155780528864984, + 0.6804700727142128, + 0.6691743934059585, + 0.5264048087587335, + 0.5613438337244918, + 0.6275327553073157, + 0.5493520745131547, + 0.6583200905781511, + 0.44037256236859235, + 0.5032321266001023, + 0.6429431664890837, + 0.4848032343552609, + 0.606234518597266, + 0.5841408478954857, + 0.5575702907198563, + 0.5539314735938924, + 0.4873298189905388, + 0.5968656389731648, + 0.47039241269113813, + 0.5049019976334496, + 0.49856943122935254, + 0.5030513027845037, + 0.6156303733557055, + 0.5056695634725819, + 0.44728393597117383, + 0.583780111078257, + 0.5661316447640253, + 0.5984403563007952, + 0.5436670224546437, + 0.5665601295156334, + 0.44256033169392495, + 0.6328397799208555, + 0.624113735942646, + 0.6756567872981463, + 0.6298316227628284, + 0.47253197250695367, + 0.46472903188243814, + 0.6852291775043369, + 0.587620395747626, + 0.6799767309650568, + 0.5168182489849774, + 0.49825710678322144, + 0.5769776711386276, + 0.5123308372802065, + 0.5496326443366384, + 0.6591227163289497, + 0.6723582249825382, + 0.554462204573682, + 0.49282463914799474, + 0.5668520234624149, + 0.528155551794785, + 0.6414868758329655, + 0.4673049777535435, + 0.5410774329966711, + 0.5672266703629036, + 0.6665050490759274, + 0.47745339141865833, + 0.6266508031536203, + 0.6664043891168614, + 0.5712198009194832, + 0.6525922137096812, + 0.6170592820103513, + 0.5132788746626424, + 0.5505018469901162, + 0.600885236396604, + 0.573820247058425, + 0.5355408127231879, + 0.5471553102081869, + 0.4755819314839998, + 0.6804697794284158, + 0.5992149089705674, + 0.4575282617054079, + 0.6317357482421422, + 0.6065233944419374, + 0.46436209119987704, + 0.5651115428222062, + 0.5970793008011531, + 0.6372143012514113, + 0.4990188354407896, + 0.5483063457116042, + 0.6162048655156155, + 0.6760700653425984, + 0.6030101209731386, + 0.5844812219981701, + 0.5343897716091934, + 0.5881782643545472, + 0.572002486222618, + 0.6283764162994455, + 0.4724436525087782, + 0.594800851822283, + 0.6513293601237691, + 0.6806030559358557, + 0.5851838040419368, + 0.5915952687980398, + 0.5815423873141425, + 0.4454697493692299, + 0.6308242483849074, + 0.6352841901909829, + 0.6131321696541303, + 0.5328005461942372, + 0.6192057091661121, + 0.4708844322869662, + 0.6584278623247364, + 0.6426402222139777, + 0.5366802072687538, + 0.4846597354009292, + 0.5095687433782881, + 0.6103187159526646, + 0.4810463822863416, + 0.45694082567288097, + 0.6697664345578593, + 0.6107588849942163, + 0.5784245939781194, + 0.45245412981200983, + 0.5584556185292503, + 0.6519544253261127, + 0.5567590513459755, + 0.4791067799688062, + 0.6503525696389165, + 0.5620111742560432, + 0.4498956625652682, + 0.45407158490894073, + 0.5683348639865842, + 0.6316804607809832, + 0.582573798087481, + 0.6568235699307039, + 0.5036529282622791, + 0.5839608841035031, + 0.650300033591204, + 0.5152039619034645, + 0.53345888289116, + 0.5912690768925326, + 0.5856932009613326, + 0.6193259837961274, + 0.6721923531085976, + 0.44414369246743496, + 0.6386932716363821, + 0.6674287573934798, + 0.6176745403853527, + 0.590536041466211, + 0.5423645105165135, + 0.6285789652552096, + 0.49910877246099367, + 0.5521824548813984, + 0.5075392451959846, + 0.6449276679604778, + 0.6547004237601628, + 0.5840901661914195, + 0.4712694312383794, + 0.5661794298935394, + 0.48224434686386375, + 0.6467144648576701, + 0.5117098442577237, + 0.6493330192672665, + 0.5803662501941977, + 0.45236536546573447, + 0.46691435512318036, + 0.6351413486251622, + 0.49478208103867777, + 0.6500103936603059, + 0.6155780938053621, + 0.5818931472129969, + 0.5271470038023305, + 0.4419299139873304, + 0.5389758816691002, + 0.44554026751212406, + 0.6316655514052932, + 0.5445908627109942, + 0.573072354522437, + 0.6152850105140067, + 0.4427171459779564, + 0.47079608242410187, + 0.45641485258088976, + 0.557577752250823, + 0.6424962426668197, + 0.4518438041950611, + 0.5825202140911425, + 0.5275454873100476, + 0.44289998018798193, + 0.5068924509679754, + 0.5052183497445488, + 0.5738318045304678, + 0.6323073058821633, + 0.5254683234956344, + 0.6568878555590175, + 0.5120733324555597, + 0.5315243361335894, + 0.48657762278230937, + 0.5998053246565395, + 0.49103391507605304, + 0.6399204303908069, + 0.6157392746261554, + 0.6015964506140795, + 0.6169144276309882, + 0.5831121662048877, + 0.6827813607324338, + 0.5200161806345552, + 0.5395277204799408, + 0.4968989088525742, + 0.647421507107852, + 0.5510794567427066, + 0.525604783320078, + 0.5157716682175186, + 0.5799491300580851, + 0.4563831736517752, + 0.5613811284852219, + 0.47859543983859754, + 0.5806756886120343, + 0.4719643672940389, + 0.4942477192659255, + 0.502663348514532, + 0.6255401820110773, + 0.6742428729551677, + 0.44599717760757385, + 0.6083788873708745, + 0.48898098295673326, + 0.6593011027925471, + 0.5241830519043873, + 0.6463328763863322, + 0.5424419795552649, + 0.6681239105984379, + 0.6736395724887146, + 0.5934491676740155, + 0.44509482184517674, + 0.45500546404620795, + 0.47077140675979295, + 0.6040298806928501, + 0.6198527795708317, + 0.4592524059134645, + 0.5238363346151383, + 0.5777602118096066, + 0.5632679351765472, + 0.5606136932736163, + 0.4557287515848867, + 0.49707559755955594, + 0.5896771809498429, + 0.6547476976488448, + 0.5740832361775645, + 0.6391870839706564, + 0.5613577892375197, + 0.5367689693792417, + 0.515694001431904, + 0.5799921417411714, + 0.4727338345403361, + 0.4894004512762646, + 0.5483448123651282, + 0.5070974821680558, + 0.6489623246752557, + 0.4699243056586576, + 0.5208882557420452, + 0.47687990886093407, + 0.6848174652343276, + 0.48867800476102413, + 0.6744619128891741, + 0.6823546680206038, + 0.4506664243829889, + 0.6283683220279663, + 0.4744085752594246, + 0.5739434521943856, + 0.46064975108995465, + 0.6115263479368258, + 0.5011053949932728, + 0.6740047743924924, + 0.5041962860696187, + 0.4721047816116706, + 0.47618625467553677, + 0.47893001531545565, + 0.4425561115245646, + 0.6414004355375037, + 0.44317068323459585, + 0.6847737080632574, + 0.47236187907095745, + 0.6164394832667128, + 0.4799925401664615, + 0.5780096414899508, + 0.5733785675631108, + 0.643405559888619, + 0.5698311540760643, + 0.6256595845157442, + 0.5792827976227912, + 0.5433782515087038, + 0.5139808658380988, + 0.4469651787491632, + 0.5042079679657623, + 0.5786265122364093, + 0.5832243149332259, + 0.6429145703860153, + 0.5001527079286754, + 0.474181637342013, + 0.5115207442565123, + 0.6641147893060324, + 0.4639822548103484, + 0.6101892226636916, + 0.496429602412059, + 0.44617439704287615, + 0.5129635004509602, + 0.6387771140275907, + 0.5898471686027623, + 0.5594049558408757, + 0.5256413431246031, + 0.638078773444315, + 0.5633920147469048, + 0.4543234554023515, + 0.6577309418486026, + 0.4983154772942743, + 0.6192008653472104, + 0.5068866152797532, + 0.6024906535652911, + 0.6354449432432464, + 0.6517737064874473, + 0.5363004262464077, + 0.4683787262268302, + 0.6140258464276742, + 0.5195927808551966, + 0.6696582866748904, + 0.520754646220703, + 0.4453638554121534, + 0.6539969609247033, + 0.6792072678804201, + 0.5155563568139508, + 0.6527262843843147, + 0.46867550265816593, + 0.662217559874773, + 0.5548484167110739, + 0.6565724261560364, + 0.6081464794753608, + 0.47378341892108977, + 0.6288699162070779, + 0.6284684681927357, + 0.5268003401168635, + 0.5681957208572352, + 0.5529620379244379, + 0.6784855899916294, + 0.5310383510672846, + 0.6493087493034002, + 0.5980312410290349, + 0.6290248975564809, + 0.517338520073014, + 0.5102150118793077, + 0.667404395699329, + 0.6534568346638779, + 0.5199177279571027, + 0.6837672208246217, + 0.47672669197434575, + 0.5078853557421312, + 0.5037641082743557, + 0.6621655355900719, + 0.5704766767165579, + 0.6459813275867098, + 0.6243675129437949, + 0.669048362916095, + 0.6110428631399861, + 0.5342323556350566, + 0.5948920934287629, + 0.46095321946635137, + 0.5112364650846154, + 0.44913559444644446, + 0.533262230523908, + 0.5894130862016707, + 0.5419303088972547, + 0.6000802332827578, + 0.5623425225179336, + 0.5544332018617336, + 0.5430194933475518, + 0.4959870829387866, + 0.591839299910487, + 0.5989042942929192, + 0.6681426812615828, + 0.5227011555335184, + 0.6580442818777898, + 0.5566017899654278, + 0.5905804671756025, + 0.5304407942909122, + 0.6365318841495806, + 0.6537695096892367, + 0.5948614217288843, + 0.6129341626784957, + 0.6455394257076084, + 0.6599127895316607, + 0.6521773804384907, + 0.4874097580000812, + 0.6602896967563836, + 0.6725664504983523, + 0.5945955938541588, + 0.65974074492505, + 0.5203307163084101, + 0.48247893376348333, + 0.6372445804253458, + 0.44157712764396106, + 0.6819944375191354, + 0.5117605149252598, + 0.6565223119919372, + 0.6114366963921763, + 0.5584222880892883, + 0.6635090164565564, + 0.5666882193452736, + 0.6361744870518492, + 0.6657531001967122, + 0.5850936688138977, + 0.6141910079818561, + 0.4931485463879188, + 0.5081444284494371, + 0.5120278101749081, + 0.5985972447162491, + 0.6202372452527389, + 0.5253182616431902, + 0.5361630734657732, + 0.48722237931333157, + 0.5789840367839589, + 0.6242598317292599, + 0.4605226950561711, + 0.5635886080412305, + 0.4964988599661932, + 0.6008955098008699, + 0.6466344963403741, + 0.5882726492622153, + 0.660905508435517, + 0.5000952634421595, + 0.6729841958364575, + 0.5767435883282331, + 0.5034043060585418, + 0.5949031635286604, + 0.45021455363161095, + 0.5640123874497694, + 0.5386556409643695, + 0.667381002999618, + 0.5014455496062313, + 0.47192600850115457, + 0.5087030894643427, + 0.5527411200176524, + 0.49705457227722116, + 0.5602468992196022, + 0.6183927943113103, + 0.5187724453065141, + 0.4725594024425063, + 0.44601349699987664, + 0.4486444834068484, + 0.5086066780477442, + 0.4867001523525552, + 0.5315214175377578, + 0.4734211150094575, + 0.6649105169577649, + 0.6848245690605024, + 0.5167264246189438, + 0.5545106907939776, + 0.49115863183277997, + 0.46335490595905277, + 0.4451755982675752, + 0.6321856470418337, + 0.5607776130946022, + 0.5254140644221645, + 0.5496252918170134, + 0.6507291251946195, + 0.518720881663147, + 0.5737525627399348, + 0.4617835889098078, + 0.5644334491731912, + 0.5369710314525791, + 0.5989626258184141, + 0.600892731929638, + 0.5905810305356091, + 0.6602504979207653, + 0.47294038222156376, + 0.6422723435130282, + 0.5079516371218395, + 0.6630704461062724, + 0.6842537959708559, + 0.6413908105484849, + 0.4507749217586009, + 0.5949528084322161, + 0.5553298220620893, + 0.6231130660745264, + 0.5713446259113117, + 0.5277032707362641, + 0.4651679434126088, + 0.5293808880789291, + 0.4871260291655801, + 0.5760414623049509, + 0.5943807478013469, + 0.5891116592877037, + 0.6771391401691769, + 0.5746659809090255, + 0.5671443296086573, + 0.5473779812388522, + 0.6543383631236517, + 0.6594309743012245, + 0.6146829179863812, + 0.47360809075871957, + 0.5733546114607099, + 0.6737253919167563, + 0.6421763571412047, + 0.6825179337617259, + 0.5888005973510957, + 0.49850109203585574, + 0.4961524384197789, + 0.4909562944668212, + 0.5429442821800009, + 0.5772066723149241, + 0.46267020863709796, + 0.6627721764647986, + 0.5469108057735546, + 0.5042574800344439, + 0.5466182603358225, + 0.4722135280513995, + 0.5928986231469526, + 0.48944474971966184, + 0.4581805144767856, + 0.6084006533534541, + 0.6432287204491525, + 0.5794150299541144, + 0.45192402132710086, + 0.44368774139931905, + 0.46758702558021836, + 0.4808896325979098, + 0.598112778102292, + 0.6399892370125698, + 0.4986635272178834, + 0.640250896146116, + 0.6293123355569178, + 0.6532564204010503, + 0.4960127683580559, + 0.6632156552912274, + 0.4590246623168265, + 0.590403849578483, + 0.6280683319932757, + 0.6695098230895163, + 0.6681218837422851, + 0.4702448273564204, + 0.4596972378131722, + 0.5810279531402553, + 0.6857853746578431, + 0.5608592969942054, + 0.6305471332510403, + 0.4665507045704113, + 0.6356615277197737, + 0.46000828840919006, + 0.5868696460171909, + 0.558008570523817, + 0.5579720441242159, + 0.5569948484903857, + 0.6315648738475632, + 0.5761347895693185, + 0.5602997230468238, + 0.5233610919674557, + 0.6068038309754313, + 0.5900385329022584, + 0.47206131537681406, + 0.6349148660565493, + 0.6591000939600002, + 0.49760704343348416, + 0.6100267830176166, + 0.6348517661628166, + 0.4551513511076921, + 0.5994899256314381, + 0.5620910562168882, + 0.5195519674940732, + 0.6318860550816541, + 0.5413487031816975, + 0.6240238412004904, + 0.6248773999720594, + 0.5628897856226865, + 0.5585792691610748, + 0.6695098868518374, + 0.4936162108901382, + 0.5168917718802043, + 0.6027023692221902, + 0.4550048412895862, + 0.5492291600913987, + 0.5330258234507019, + 0.6854498321770213, + 0.4807954598459829, + 0.5714529225756707, + 0.5312024267802286, + 0.4883573337583427, + 0.5000163320258971, + 0.45757342204186074, + 0.4439152201173108, + 0.49604970089888484, + 0.6743538933017148, + 0.6467670715364408, + 0.5353576252269304, + 0.5164682079377856, + 0.571347376000154, + 0.5421730000548897, + 0.5961201177888613, + 0.5812623974951653, + 0.6262229617522919, + 0.5454317157574944, + 0.6254358475175413, + 0.6464712233073692, + 0.44763199397105613, + 0.47434514139065387, + 0.478853278644226, + 0.5361340616139976, + 0.574918785654438, + 0.6555869850308739, + 0.6709155148383188, + 0.5856768280640228, + 0.6727979974440791, + 0.5742015550355553, + 0.5034925621136086, + 0.669573431915469, + 0.5368069785326419, + 0.6155655290360225, + 0.44198256728160723, + 0.5415564730287799, + 0.6807124494016917, + 0.6779911297302611, + 0.5682116084288031, + 0.6614173791456628, + 0.5381024460207768, + 0.5332103807513887, + 0.6741998687787021, + 0.6180567312024148, + 0.5233725398516671, + 0.488696948904651, + 0.5272373244347627, + 0.6173488423707816, + 0.5931878650162049, + 0.5391117763967771, + 0.5917532426511509, + 0.5542251488473654, + 0.492474769481178, + 0.48389224709683487, + 0.5365739338758905, + 0.46372455181562033, + 0.5346283426243702, + 0.5471672391743301, + 0.5869466838491462, + 0.520100814606337, + 0.46800394950743684, + 0.46723939657347435, + 0.44517536102531957, + 0.5383277272522082, + 0.51190752969153, + 0.5018248038604433, + 0.6781600516730129, + 0.5334331792908766, + 0.5336444758601355, + 0.5224401439114021, + 0.5552749478878877, + 0.5564738022475624, + 0.6478202116246181, + 0.5552724887923639, + 0.5400615558317439, + 0.6839564419629425, + 0.5668438282531949, + 0.6022602748002379, + 0.5724433767324686, + 0.4479485268912028, + 0.6163906695151087, + 0.5292815468146227, + 0.6799604246946969, + 0.5284526022423723, + 0.5641769889167229, + 0.5615252475729601, + 0.5358474079929123, + 0.6653053635832293, + 0.4427269699557605, + 0.5444768546694646, + 0.5645513204947973, + 0.5354695179665607, + 0.6588868357059403, + 0.5813871904174762, + 0.5390757150108434, + 0.6696817691542742, + 0.4498960301094569, + 0.6027664963231459, + 0.6063760475134887, + 0.4904126410468203, + 0.4746900662357298, + 0.6259169079842481, + 0.6605464199099358, + 0.6435993509141602, + 0.5660697904770082, + 0.5045566187239335, + 0.47210556800131476, + 0.451722317383813, + 0.5706226259537057, + 0.6431672009936151, + 0.5668232982247561, + 0.517799570149357, + 0.6750285313215155, + 0.6530994831394874, + 0.6410992317987804, + 0.5656059269908449, + 0.5215741375386627, + 0.5315223299833658, + 0.5508921496720777, + 0.5324105946381678, + 0.46095421918201557, + 0.5521970643352924, + 0.49868218894837024, + 0.48965091331548277, + 0.47551870269625773, + 0.5546652192661589, + 0.5234386534412174, + 0.483640576691406, + 0.6764644476531124, + 0.6798089806094169, + 0.5140348596912535, + 0.5652885783751916, + 0.4619503301585736, + 0.48089974153968384, + 0.5550029315491278, + 0.6168392244552307, + 0.4541967104254731, + 0.5535682456660667, + 0.4788451083570953, + 0.6773111776779763, + 0.5602427531756998, + 0.5641029439153578, + 0.4795129030481348, + 0.45343991268392486, + 0.49901858329140564, + 0.47704247703555946, + 0.46007576740585787, + 0.4704448353529784, + 0.47368937252322585, + 0.5106714362986561, + 0.5774561674629067, + 0.6253077756605778, + 0.5441753149003488, + 0.5298309239893735, + 0.5389417070602776, + 0.6030866021558744, + 0.4497286256703177, + 0.6105262720661497, + 0.4918054848388659, + 0.4723552501339012, + 0.4741784372960602, + 0.5600580898634239, + 0.4517927248745343, + 0.6821258673886806, + 0.48562074017718737, + 0.6365758997432541, + 0.661457151960219, + 0.5800793745779834, + 0.5658655567509546, + 0.6202100797070824, + 0.5177459981473571, + 0.5210579988861291, + 0.5021399760166422, + 0.5634477269809025, + 0.5802421883545756, + 0.6624640255567609, + 0.5550473946977019, + 0.4721873564000713, + 0.5578708521150627, + 0.5089182023131145, + 0.5628437545910903, + 0.6248062170818313, + 0.5817496887808726, + 0.4817077719171631, + 0.545950186469808, + 0.45741805367683963, + 0.6546789978011984, + 0.6472643008882492, + 0.5333859400182972, + 0.5722297746531271, + 0.4587331024736274, + 0.4645848953054591, + 0.47014654569068653, + 0.4689348179585952, + 0.5842489800873916, + 0.5254928377488916, + 0.4433523033992543, + 0.5970672025103327, + 0.6505489035312986, + 0.6748462971318996, + 0.4839491467704821, + 0.6835684017764048, + 0.457253528112578, + 0.46858712847385053, + 0.49664882563820345, + 0.6527981582808984, + 0.5927952690773505, + 0.5538852432180068, + 0.5466136610483628, + 0.46524675270242766, + 0.6371234335248737, + 0.4652804582741862, + 0.6005678951145847, + 0.5287799771431558, + 0.667512575322655, + 0.6209431406309588, + 0.5024460906387075, + 0.5433748081443446, + 0.598498229358589, + 0.4710778578105901, + 0.5368695444108779, + 0.5289464631142222, + 0.6790175830076743, + 0.5919637240027114, + 0.6175503483241808, + 0.5933865652131802, + 0.5602006245546136, + 0.48321021751230475, + 0.5701857487652979, + 0.4766146130265106, + 0.4498431374375972, + 0.5189330596535123, + 0.6795764849133997, + 0.5815846110399387, + 0.5274453650819593, + 0.5202244456287151, + 0.6566074700406396, + 0.5269273777927852, + 0.62820683236998, + 0.6787681174695428, + 0.596321551925663, + 0.6657196961282907, + 0.6213510742630055, + 0.4960462237155066, + 0.536174608941838, + 0.6197651766296904, + 0.5493185801155781, + 0.5680186238268938, + 0.5875285942465918, + 0.45410358002406986, + 0.45402957893538265, + 0.48056987026457765, + 0.512094740790925, + 0.6634467183851825, + 0.612575031773422, + 0.5613205104680705, + 0.5577934966584744, + 0.6436659737619561, + 0.44829717638329075, + 0.6508927596236211, + 0.6191383854044883, + 0.4628234976031428, + 0.54376679956813, + 0.6106298259085499, + 0.5249198623313303, + 0.5437288735566118, + 0.6671303880792671, + 0.5248724318378846, + 0.44540154466546533, + 0.45807125950267813, + 0.625774217311661, + 0.5604195072252581, + 0.5486572552665118, + 0.5730176895562034, + 0.6686789080414116, + 0.6412382161965564, + 0.6349685303216583, + 0.632073805660129, + 0.611432625749623, + 0.5588301176093986, + 0.6781209762823017, + 0.6136463586612724, + 0.4654316310459342, + 0.6669636141012203, + 0.5638893033271705, + 0.6420185503250601, + 0.6221979250974197, + 0.6765839825897186, + 0.546702962422418, + 0.5235469436987832, + 0.5862977527731525, + 0.46477148381639904, + 0.6267452679748471, + 0.552148049659401, + 0.5505830678327976, + 0.4993882748636451, + 0.6570149331496697, + 0.5645293154818987, + 0.6835361369137547, + 0.4714207072971569, + 0.5736234570707648, + 0.6680001009893759, + 0.4544154677776447, + 0.5611835442955326, + 0.5259695497266276, + 0.6383683822664139, + 0.6083606743174331, + 0.5258081542346454, + 0.6561120995256932, + 0.6641533520405256, + 0.44368033474709184, + 0.6663028730563862, + 0.6399477353906304, + 0.46613787907340115, + 0.46247868507476564, + 0.6330079609730914, + 0.57269227900572, + 0.6828962471347089, + 0.454672526166914, + 0.6504805298370373, + 0.6593955730860681, + 0.6035606610738413, + 0.6336737365626478, + 0.592762256337138, + 0.47772029599210564, + 0.5497464347011536, + 0.5792893237837181, + 0.4756549475113364, + 0.46690823136211934, + 0.5233593657774966, + 0.6643099219817927, + 0.5746487522492539, + 0.5944528763209722, + 0.5294477801044197, + 0.45127158006888735, + 0.5406187357617795, + 0.5000397401535825, + 0.599581587710061, + 0.5708161560266791, + 0.6366982261780214, + 0.535231706705086, + 0.4521659871260903, + 0.6414317381838234, + 0.6573948369443499, + 0.5862127952959559, + 0.6323987410757926, + 0.49309155037261865, + 0.5038485291045752, + 0.5008624680726461, + 0.5146122549181881, + 0.684793211196608, + 0.4739979692233952, + 0.6054695637102046, + 0.6475038539853766, + 0.6381112990874157, + 0.6120262264880185, + 0.6585329024368393, + 0.570472633470615, + 0.47076129156754815, + 0.4967949247551656, + 0.4562769518854145, + 0.6052624006803884, + 0.625150870290681, + 0.6443364002729087, + 0.5577336135845075, + 0.6586470139290095, + 0.47995013425974264, + 0.5119262499759213, + 0.5538776591377508, + 0.4981177189530287, + 0.6668415060507464, + 0.6203126445261827, + 0.5075301334534694, + 0.6220358616046164, + 0.6668367996637109, + 0.45364228010422714, + 0.60820066229305, + 0.5869875269532938, + 0.4547070202971324, + 0.66034832295163, + 0.47418148196409954, + 0.644660068165381, + 0.4764940532498069, + 0.46083878880080137, + 0.5673736546765745, + 0.5183819110720027, + 0.5148341837053854, + 0.6855123155052611, + 0.5252128765169186, + 0.520644600092502, + 0.5345372397912245, + 0.6606005534649402, + 0.6573376014549501, + 0.6280988458565366, + 0.4928674580412137, + 0.4848838255400864, + 0.6186992557181691, + 0.6399522240185456, + 0.63931938441491, + 0.44072730595404525, + 0.6619732973775474, + 0.674837092100353, + 0.5683497802738433, + 0.6340024028748197, + 0.515144688545093, + 0.4548359263973176, + 0.65542307423796, + 0.5623644556370097, + 0.5747290855848805, + 0.5097815634413141, + 0.6211070738433878, + 0.6016514912381706, + 0.5191781019242748, + 0.6602245700488147, + 0.48909410152376587, + 0.6038951854938234, + 0.6177920241213369, + 0.5447120193444395, + 0.5285505565859976, + 0.6686518548092786, + 0.6560920220310031, + 0.499443166520624, + 0.47664177554184173, + 0.665641412525719, + 0.6099110495986113, + 0.4866725670628052, + 0.48944494759937435, + 0.49253072505605544, + 0.6528045006756902, + 0.5211808667625308, + 0.4954707224470911, + 0.634731442649873, + 0.6724173612884399, + 0.6436864337891562, + 0.6336982404787685, + 0.670436347065054, + 0.4560976188781654, + 0.5047274311433882, + 0.6055091671705878, + 0.63042301039543, + 0.6372040266961677, + 0.5382697165620723, + 0.47807068365671607, + 0.4517367458973354, + 0.5745479006960355, + 0.6329343757787492, + 0.5846397860786884, + 0.5510276807904427, + 0.6528159449898814, + 0.49774729361318293, + 0.6473025263838529, + 0.4791327100224797, + 0.5894902863350977, + 0.5040010105851592, + 0.4650752508789508, + 0.5644594434606441, + 0.6522413188769198, + 0.44173103575371037, + 0.5843560521041309, + 0.5556046172361794, + 0.5370363623861708, + 0.6801216084931214, + 0.6393721497884123, + 0.6581995544490622, + 0.5563454392851939, + 0.48376202446754607, + 0.550726748494842, + 0.5586788864048308, + 0.5830126164864786, + 0.5550930899215321, + 0.5587592512872869, + 0.6027955980395306, + 0.6638129993135126, + 0.6748420648390607, + 0.6774202239600107, + 0.4954857314957252, + 0.5110540759944552, + 0.6274490847082645, + 0.5339652194514801, + 0.5220506204792952, + 0.5521700249287496, + 0.4876410401859289, + 0.6342495870489663, + 0.6465940145343583, + 0.6361215389837682, + 0.5118765049322922, + 0.47045270356907243, + 0.6562201212498598, + 0.529134466854218, + 0.6824521193036007, + 0.5651753408426796, + 0.5412670120828863, + 0.6570139909783723, + 0.4938393797442794, + 0.49407634481643753, + 0.5232918202324282, + 0.5183293067013653, + 0.6079156299339246, + 0.5014805067980642, + 0.6046767803872438, + 0.47299102272716903, + 0.47092606695864747, + 0.48877872748790946, + 0.4742044150247897, + 0.5789040165832373, + 0.4699666053103068, + 0.5050072691293976, + 0.6496278299458581, + 0.5498002580537354, + 0.6831439658826146, + 0.6522365384172317, + 0.6072228347750961, + 0.5296673695392546, + 0.678689490367895, + 0.5182587234593763, + 0.5260841655448776, + 0.6571815011232439, + 0.6831634514961105, + 0.5128224726345065, + 0.531576325622914, + 0.5223538976041621, + 0.6501180344777551, + 0.5293406100863971, + 0.6407879467224666, + 0.5933370438019813, + 0.5492719179570389, + 0.49059769819298443, + 0.48469981031766446, + 0.4777443879799699, + 0.5692956423965249, + 0.6826593975105594, + 0.4867294614848677, + 0.6416655279783361, + 0.46797840847051136, + 0.6197871815327118, + 0.4883025414273153, + 0.6763416608896169, + 0.6059206831733797, + 0.4995955803614753, + 0.6149242083295869, + 0.6057853980591295, + 0.5214240274762989, + 0.5541184680165373, + 0.4995716310707799, + 0.5494549041817468, + 0.6544995323495598, + 0.45120404272708964, + 0.4711476724992193, + 0.5367311709582273, + 0.5909329208297489, + 0.47737532457402626, + 0.4594480105020925, + 0.6265064655058941, + 0.5902069695068766, + 0.4685438856935339, + 0.6203475233406893, + 0.6465707678419468, + 0.6552706855698835, + 0.44818837837472425, + 0.644880963039913, + 0.45521026310028856, + 0.4460072397735892, + 0.5370729450003058, + 0.4467093559427522, + 0.5553746955779234, + 0.5205809889924102, + 0.602886547771562, + 0.5038347943069957, + 0.5096220168856223, + 0.6128163499277199, + 0.5172314679406635, + 0.6842628265097428, + 0.524171324544091, + 0.5767676921092517, + 0.5436561955515746, + 0.46800854072404235, + 0.6357244024067636, + 0.4538102946491277, + 0.5494340748231604, + 0.5677923927962985, + 0.5331904527666192, + 0.627615408661044, + 0.6445845271795724, + 0.6224246023276773, + 0.5442997369951443, + 0.4986489497231524, + 0.5229271025538298, + 0.6653381982201578, + 0.5637847381336225, + 0.5955117670894015, + 0.48542819195552667, + 0.4584467864473233, + 0.5251846887945487, + 0.5883032723597738, + 0.45253008700142977, + 0.5149796814092447, + 0.5232717371175093, + 0.6133111175799494, + 0.45225236270314056, + 0.5041125600137008, + 0.6042008476846427, + 0.4837355719576277, + 0.5674698540664952, + 0.4902140778650039, + 0.5285612160635096, + 0.6026222233774337, + 0.6254905736927798, + 0.48210840255544757, + 0.5168788423802609, + 0.47662194980930317, + 0.48805497634752565, + 0.559352326557465, + 0.542219914088406, + 0.6118228247243507, + 0.5509484240232974, + 0.5045404884031738, + 0.5349834299050814, + 0.6113708567231433, + 0.48994257788576634, + 0.5554027652775233, + 0.5800453776398001, + 0.5201336882757822, + 0.5335959713785368, + 0.645601149548071, + 0.4799723149928523, + 0.5315300713526945, + 0.5767166402745398, + 0.6694192520823825, + 0.4408912633708767, + 0.4761584527507551, + 0.6287027733406139, + 0.6542466316264333, + 0.542826867462921, + 0.5229693638328993, + 0.526084564183943, + 0.4829708738061655, + 0.4955729615939835, + 0.651417063763857, + 0.48767404187186986, + 0.4879585870802194, + 0.6831590422337287, + 0.6194246053419348, + 0.6222345093812764, + 0.44785824870439866, + 0.5942941327090032, + 0.6119861377829964, + 0.6466510238712782, + 0.570816048141908, + 0.478204647963424, + 0.5114575792040499, + 0.6813381681447991, + 0.5619464964267636, + 0.635313721766641, + 0.6030390130348309, + 0.6553577567179071, + 0.4544106258292319, + 0.45215756700446186, + 0.6766897975051058, + 0.5920413197226186, + 0.6756061064022307, + 0.44264379898209344, + 0.551426781376963, + 0.6726857092536163, + 0.6694121751258557, + 0.5085154751652137, + 0.5245414734694054, + 0.6501756676813785, + 0.6399892999488677, + 0.6655972240365301, + 0.5152259973666686, + 0.4882474709536019, + 0.5390800063091485, + 0.6743511767380761, + 0.5886600764262957, + 0.4715834471116961, + 0.5260452238587159, + 0.6508383257347901, + 0.6189818067799164, + 0.4987178287465214, + 0.4505198549706938, + 0.6852468585158767, + 0.5602467476764629, + 0.617316056692305, + 0.5253675598175246, + 0.5934840957890125, + 0.5077618225641795, + 0.5919170255835421, + 0.6650494232958826, + 0.6406015003620666, + 0.6857646409377405, + 0.4963920151089923, + 0.44701074286461495, + 0.4417266348056806, + 0.5955020908400426, + 0.5705415456382325, + 0.4655658609988797, + 0.4577941417988384, + 0.5690345075274159, + 0.6552727617532549, + 0.47170562247944914, + 0.5666353868898655, + 0.6351264257938992, + 0.6179017421411496, + 0.5113316759312507, + 0.527080559152964, + 0.5274544989256977, + 0.4436813090108846, + 0.47404544553015343, + 0.526606282679318, + 0.5663138836048871, + 0.4970436458675379, + 0.5304860150756745, + 0.5609269424494322, + 0.4652747350376166, + 0.4648763236580914, + 0.6046854727353633, + 0.5732141707878683, + 0.6178811458057719, + 0.5339248062067822, + 0.605939096744302, + 0.5070595164979497, + 0.44443029780205107, + 0.6037900419099844, + 0.5745009772253222, + 0.647297636852217, + 0.5528117375685785, + 0.466739053420056, + 0.5890063431633383, + 0.544115061144074, + 0.49383219263140365, + 0.5450637537500318, + 0.5171187075343255, + 0.5180509315232908, + 0.6410444180082651, + 0.6793772260704173, + 0.5366573925926119, + 0.5067935385922238, + 0.6383313443786299, + 0.6130770599096226, + 0.6613245030092428, + 0.5522810326379, + 0.5471554798747489, + 0.6374074831040584, + 0.5343602999631032, + 0.6358966256081575, + 0.5768651067093961, + 0.6132737340834256, + 0.5450275626251142, + 0.5850649775339334, + 0.61207322093137, + 0.6399946339622813, + 0.5090592500934035, + 0.48590649735160685, + 0.6711427045938428, + 0.5598164942334798, + 0.6282415269377757, + 0.5444645572692706, + 0.5240145357573807, + 0.6434199160530246, + 0.4621085918835168, + 0.6298096844347411, + 0.44212024419302715, + 0.5534262838111063, + 0.49750860057195484, + 0.6141302404639832, + 0.5796938324202855, + 0.5766615198836311, + 0.5001057047432665, + 0.46083264481956765, + 0.6409108022989424, + 0.5537649637276103, + 0.45320073011303974, + 0.50102729178407, + 0.4763338418115967, + 0.6703301303686076, + 0.5330833367861124, + 0.4482098614550655, + 0.5958889125962819, + 0.6237832875794962, + 0.6541682601116032, + 0.6091248773680136, + 0.6413833091297669, + 0.6697402742708163, + 0.5199630740490189, + 0.45699981443206356, + 0.6508079363158598, + 0.6088573749500438, + 0.6794674148309893, + 0.49915172022729887, + 0.46722840888639033, + 0.6464032957944674, + 0.5525505915763667, + 0.6650783881984301, + 0.6269662190340847, + 0.5903085062341392, + 0.6554393731704228, + 0.5549743701118497, + 0.4400347967633047, + 0.6035919663764103, + 0.6671348272583495, + 0.6619599622973751, + 0.6260404809185179, + 0.4722314670618607, + 0.6437852173873456, + 0.45629999985000047, + 0.5629998273618325, + 0.495756236834514, + 0.6229752624658278, + 0.49842720390048234, + 0.5377393394462672, + 0.5481903318919453, + 0.5982760621744545, + 0.6146772076112443, + 0.564098577991494, + 0.6102960045976494, + 0.617108082742306, + 0.45432874572549126, + 0.6684641490312079, + 0.44011307943691386, + 0.5020904131637214, + 0.5120337297797652, + 0.44611686632093916, + 0.4561709165064356, + 0.5357175142226067, + 0.6263428300697226, + 0.6048322521853936, + 0.6141668482457081, + 0.6074602898772411, + 0.6031546167136032, + 0.6133948052903307, + 0.6026541464943224, + 0.5677029481815465, + 0.6160108967535562, + 0.45624565885501256, + 0.6631233476929221, + 0.5527050282866286, + 0.5020925383676533, + 0.5432364421218322, + 0.653292349192339, + 0.515252358250047, + 0.6291312249550632, + 0.6428100029634759, + 0.6432655159427457, + 0.4472658517941974, + 0.5762763986915236, + 0.618540391970108, + 0.5128800791441517, + 0.46528241075640014, + 0.6747512719847313, + 0.6376352979843901, + 0.5556770793507635, + 0.5000603531927442, + 0.5893553604946562, + 0.6795915767998804, + 0.5226680625589077, + 0.5824700510378695, + 0.6037010709237844, + 0.5428292780192554, + 0.4800574149937442, + 0.6817941148261162, + 0.5394062942061245, + 0.6271057720129216, + 0.4659081256550738, + 0.5052942249266389, + 0.4930923456860563, + 0.6081925232144816, + 0.6791804872561729, + 0.6105527786516869, + 0.6008180805743506, + 0.6821623067441862, + 0.4572457326497355, + 0.6204683166764596, + 0.5339810474628955, + 0.5253429822276452, + 0.47106263067143156, + 0.550227336429305, + 0.5173252148717481, + 0.6106301456774432, + 0.6348485353489726, + 0.5833337102400085, + 0.5309917346195049, + 0.6374272447953427, + 0.5477753756632078, + 0.5492466798370743, + 0.552419164486361, + 0.5608960318064634, + 0.5885747979431227, + 0.6519445618397803, + 0.4913280306632312, + 0.45603339363853757, + 0.46231548913791326, + 0.46344875683692943, + 0.4424680073482086, + 0.4425873868633462, + 0.45444088114484243, + 0.4475386200526053, + 0.4542471150264557, + 0.4593183564334706, + 0.46361026942994243, + 0.4570343117849752, + 0.44952863420540945, + 0.4459802594607051, + 0.4520573667656606, + 0.44246018785901675, + 0.45324632180443963, + 0.45570674972820624, + 0.4627121737994615, + 0.4631687418627924, + 0.454619452339615, + 0.4589672395629665, + 0.44203949259743197, + 0.4485877906315598, + 0.4614774235768304, + 0.45284258758116175, + 0.4621062685155843, + 0.44564720959564974, + 0.4496981220821719, + 0.4512557787865811, + 0.44208885561950556, + 0.44675337620228706, + 0.4421901727453063, + 0.44976839514567146, + 0.4589345208226392, + 0.45753099855037227, + 0.4579720951298283, + 0.45686043936038406, + 0.45331293511376447, + 0.46143629259162033, + 0.4574328983531346, + 0.44363649385445314, + 0.44343517875688204, + 0.44036328559251897, + 0.44206453076492247, + 0.44809886079035777, + 0.4491339662501841, + 0.4613261052401351, + 0.45538060021677657, + 0.46293109676261557, + 0.46291973689271154, + 0.44003526405071436, + 0.4576952370546423, + 0.4624658766439772, + 0.4531047553017271, + 0.4513871192436252, + 0.4588905184053309, + 0.4486350265552649, + 0.4576133509077297, + 0.45338271354530374, + 0.46065824057963023, + 0.4621318149647086, + 0.4447102338463974, + 0.45039744522310915, + 0.45575141801489943, + 0.44599581452239373, + 0.46033194501359886, + 0.461084109277259, + 0.4561413574429113, + 0.44397016346893126, + 0.4468792831203738, + 0.4437814125729184, + 0.4625895005069994, + 0.44872181307528236, + 0.45109190530393845, + 0.45102709870055047, + 0.45383289688693557, + 0.4500331441727927, + 0.44133000665439664, + 0.45116337824286623, + 0.4514745422403179, + 0.4471537652892119, + 0.446727987748923, + 0.46260859455273406, + 0.4502438095267574, + 0.4478722464305479, + 0.4588434994813714, + 0.4483320150050167, + 0.4577339308173773, + 0.45699155071356706, + 0.4584132443105738, + 0.44075605703409504, + 0.4576852232902182, + 0.4439696383841615, + 0.4477226230876727, + 0.4412372041105438, + 0.4453599345096742, + 0.4584623963280101, + 0.4496403023522733, + 0.45522349938936657, + 0.44658252486958416, + 0.4617657121947599, + 0.4563426768226051, + 0.44265693439043824, + 0.45951652746314825, + 0.4405107340835382, + 0.4487338212526696, + 0.44716756710383626, + 0.46030424103911494, + 0.462778388577532, + 0.4417321575747928, + 0.44837148873442634, + 0.44496444398644214, + 0.44344897206227224, + 0.44666817905952505, + 0.45334074153366044, + 0.4568851482202455, + 0.440389632870352, + 0.44755323480108533, + 0.45480501897432607, + 0.45000163569816043, + 0.4416082699730659, + 0.4574922901399517, + 0.4621554252306077, + 0.4635835076014503, + 0.448081893664561, + 0.4590936343398673, + 0.44968354725509513, + 0.45662770074777126, + 0.4508831153773791, + 0.4567225070561411, + 0.457085415780591, + 0.4565187150918643, + 0.46353234862084874, + 0.45722514336046904, + 0.4561439070006606, + 0.44859218192326983, + 0.45441284965666084, + 0.4478691992272497, + 0.4625338376484757, + 0.45379852995251757, + 0.4492965072159789, + 0.4597464477509867, + 0.4562641177385836, + 0.4615599658842696, + 0.4563522674409956, + 0.4526982289104713, + 0.45078553089427986, + 0.4569229202591709, + 0.46269092198703454, + 0.4412332984958055, + 0.4508320006283283, + 0.44888337905595277, + 0.4411291856746842, + 0.4549984484247526, + 0.45478480935709875, + 0.4462695761821891, + 0.4521872708000008, + 0.4407796321530118, + 0.4410779123566733, + 0.45899126081526803, + 0.4547271499803354, + 0.45794164462299947, + 0.45173239654358777, + 0.46106439852492526, + 0.44328213476402756, + 0.440084932730712, + 0.44949719730763155, + 0.4468097479450875, + 0.44512355362694, + 0.45195408937884857, + 0.44824738499100025, + 0.4453746322895916, + 0.4478672258453297, + 0.46379346779927605, + 0.44686683173887326, + 0.4613415362364842, + 0.462718053210013, + 0.44030396816280587, + 0.44074121959573304, + 0.4563675464142131, + 0.45311830470237574, + 0.4498946819676726, + 0.4579970282794218, + 0.45911183784270865, + 0.45066868621682626, + 0.4493362919222872, + 0.4559879996977192, + 0.4412097227012472, + 0.4489835518193629, + 0.46078378398801134, + 0.45531878479420573, + 0.4488430841752591, + 0.44823935004713333, + 0.45712282420301437, + 0.4566348345076386, + 0.46357784933589324, + 0.45262928495046795, + 0.4514922905443621, + 0.45823739509823513, + 0.4404313655762367, + 0.4448818733256688, + 0.4514308337378587, + 0.4529015647008634, + 0.4602103168645039, + 0.4522923621779976, + 0.46380864632810104, + 0.4543847100006708, + 0.44873591951006636, + 0.44857868992533567, + 0.45099571058414323, + 0.45657859554961866, + 0.4494377080564312, + 0.4623022080568176, + 0.4630678610249477, + 0.4454116078729532, + 0.44235567824695127, + 0.45421882716755063, + 0.46268424449440476, + 0.45713236646764355, + 0.45459369719516096, + 0.45850334883681654, + 0.4548783306898229, + 0.4613587525369469, + 0.45322123919835017, + 0.4479853087143996, + 0.4569830885669062, + 0.4410009894279965, + 0.4545628936699633, + 0.4516622021870135, + 0.44256005415357275, + 0.4441445735277767, + 0.4540087257064599, + 0.45250159894814673, + 0.4442691840303769, + 0.45013148030361655, + 0.45985888359796556, + 0.4452464196703777, + 0.45108544779653176, + 0.4451907586439555, + 0.4553615015622577, + 0.46338390009722774, + 0.4565082364137164, + 0.4502564195021807, + 0.455327338430175, + 0.440341269440663, + 0.45687419874914476, + 0.4545380449239715, + 0.4419559004005813, + 0.44908808142826884, + 0.4507237456419724, + 0.4480938280641278, + 0.45239886257501116, + 0.4563460107191394, + 0.4575704104615154, + 0.4510733811069653, + 0.4479668595523907, + 0.44690250248486363, + 0.4472863616838509, + 0.4624156919538296, + 0.4634770375886114, + 0.45295658187501653, + 0.44211955351766596, + 0.44285057561114105, + 0.6369362115254968, + 0.6657626954784601, + 0.65004155952808, + 0.6885239787454943, + 0.652644488364838, + 0.6714477061109684, + 0.6533272649692031, + 0.5155158739666248, + 0.4801719298487125, + 0.5720232651234901, + 0.5084351666458858, + 0.6013344826014102, + 0.4756176370966742, + 0.6408845522685611, + 0.452126435884871, + 0.6766435141802936, + 0.5613935142088131, + 0.5803761632017427, + 0.6299088622321387, + 0.48017808030100617, + 0.45650201657005907, + 0.44881107728563946, + 0.45187792959816564, + 0.6015961202226301, + 0.6560699457505255, + 0.5151214116592557, + 0.5747856449347248, + 0.495843150282695, + 0.47535600138692563, + 0.6089994611458828, + 0.551371873210565, + 0.631676073453085, + 0.668226622496779, + 0.5851602441594469, + 0.601691398394382, + 0.6163004788083637, + 0.6851423731675521, + 0.6034410065526026, + 0.6811711640332836, + 0.5981370040814361, + 0.4492274598817192, + 0.5900740386137912, + 0.5029690601697262, + 0.4474809812994321, + 0.5396970678842589, + 0.5736737023773644, + 0.5476590282315098, + 0.45218908779250483, + 0.453032114257786, + 0.5296857405543447, + 0.5485710944255899, + 0.5889428915375325, + 0.4705892086749124, + 0.5171840816898963, + 0.6575487776203599, + 0.6459825693487882, + 0.5437749436461348, + 0.5810087614912853, + 0.4682024343625176, + 0.6412834314722857, + 0.5892192616042851, + 0.6147633837080273, + 0.6190114204110733, + 0.5611328125361542, + 0.6830412120798929, + 0.4872322231748509, + 0.5858798939072049, + 0.6410822381336136, + 0.47609750294154296, + 0.6105908218317112, + 0.5470680049740488, + 0.4445984171308372, + 0.49937382603622743, + 0.45358096383073543, + 0.63012006524824, + 0.46938421796554947, + 0.4703920035082346, + 0.6079783082610777, + 0.6729012911377077, + 0.44698573887548826, + 0.5373145562986157, + 0.6793891718131352, + 0.48346613837913877, + 0.45551142355158303, + 0.4514305140608501, + 0.5325185857918131, + 0.6382287738709005, + 0.6809180643640167, + 0.45801228921183346, + 0.5433783407168473, + 0.5442188210076576, + 0.6418331818923612, + 0.6284311633277687, + 0.548890705035394, + 0.5259886324972022, + 0.5195982012865034, + 0.5894482731520329, + 0.605634649672404, + 0.6763451243316237, + 0.6401554171550663, + 0.6787235552756565, + 0.5800799202615334, + 0.45130991741326454, + 0.6873647780314229, + 0.6396826640603748, + 0.5629644411591019, + 0.6180748646375275, + 0.4790827492116528, + 0.60170444454738, + 0.45619942850593975, + 0.5810444038172977, + 0.6649516691838924, + 0.5881047872157236, + 0.5438655167573996, + 0.5696416600048495, + 0.5819235995977312, + 0.6540021216710257, + 0.44163317537762065, + 0.5078083018451583, + 0.6765166142078323, + 0.6568460878446893, + 0.632615892721744, + 0.494641686538149, + 0.6074488321772631, + 0.5293384902453266, + 0.6024810418168011, + 0.5776516654090348, + 0.5679355442723798, + 0.6391798225735441, + 0.5405547031758847, + 0.6866537728167871, + 0.4704728739478746, + 0.4748383323131176, + 0.6331700467444747, + 0.5753565606604114, + 0.6408211782217603, + 0.4462414620076116, + 0.5297543236444311, + 0.6744842126669743, + 0.6641431874268519, + 0.5722550030360255, + 0.6769390581304078, + 0.5880713229257281, + 0.5828629172099061, + 0.6751143393033757, + 0.4812722314021394, + 0.47301025336963043, + 0.4704941659224975, + 0.4709954955200064, + 0.5519450939044799, + 0.6756682743359452, + 0.5941960334811898, + 0.4424163115432106, + 0.46864932336975773, + 0.5060516265291117, + 0.6875849329770581, + 0.47839130668423024, + 0.5115704393855867, + 0.5004370796470137, + 0.6374423665009311, + 0.47069262875957446, + 0.6861318102251948, + 0.5971010012756507, + 0.5679182635688382, + 0.5728778510630581, + 0.6494060158759665, + 0.5648772341166584, + 0.6517789816563895, + 0.4577096111393605, + 0.5523126601420596, + 0.6296378499995264, + 0.5335796078765914, + 0.5167634179415745, + 0.5034448212738356, + 0.6063184986330697, + 0.610729872785593, + 0.6240974699175937, + 0.6122895951604048, + 0.6629632471375553, + 0.5225371011978163, + 0.6317902441775534, + 0.6143421671745476, + 0.4942333795431436, + 0.6010571679692125, + 0.5114099881447858, + 0.6623031873834789, + 0.5715820068800616, + 0.6808593024683014, + 0.674863821560148, + 0.6437260843267356, + 0.49712426306718605, + 0.556852075401107, + 0.44732858120934393, + 0.4991124307525429, + 0.5166472646028563, + 0.6745034967780279, + 0.4771525949035472, + 0.5750543422577391, + 0.5898124389749206, + 0.5160754301691766, + 0.5457775163732546, + 0.47128909456741863, + 0.6782746051678352, + 0.5466324838871996, + 0.5685381919175053, + 0.6699637446881002, + 0.458104461651296, + 0.5985662462349872, + 0.6253632912440413, + 0.485303507977232, + 0.540208940099221, + 0.4620550342260913, + 0.5414576693208135, + 0.6280222989862156, + 0.5012538186048379, + 0.6740777260259467, + 0.4627768527552769, + 0.6781257113526302, + 0.6792804702100856, + 0.5734389182387724, + 0.4587488358896558, + 0.49018490392482916, + 0.5284762623492507, + 0.45412863534551584, + 0.5707253612433139, + 0.576726729916862, + 0.5287272395656056, + 0.6758802526801815, + 0.5151924555659624, + 0.6060858600460388, + 0.4682910244630679, + 0.48241823440369946, + 0.46521903533992254, + 0.5382794389684822, + 0.6527781886454631, + 0.5150809066220512, + 0.5029313115333338, + 0.6338360974887487, + 0.44766493571131566, + 0.45102300743895446, + 0.6629242606554738, + 0.5198550030652267, + 0.6401131486353613, + 0.5870686568408576, + 0.484099073220651, + 0.4785763692061416, + 0.6080133833426753, + 0.50977982533784, + 0.5631466933247029, + 0.5856184802392537, + 0.570218354894509, + 0.4731294800651183, + 0.4757212430207985, + 0.6871472310404307, + 0.6533500594543888, + 0.46980360160736573, + 0.5245988662672428, + 0.496547136811919, + 0.5728035205791207, + 0.6292496102806646, + 0.553224293231945, + 0.4882743748275563, + 0.6102278256732786, + 0.5692106330033122, + 0.49475769562143257, + 0.4551171833347837, + 0.547234836376278, + 0.6587985759913855, + 0.6562688830825814, + 0.610200454888603, + 0.5060756061561921, + 0.5397622998805203, + 0.45699402777563863, + 0.6268205767786786, + 0.5996562638018881, + 0.6003052438713176, + 0.5656567404338275, + 0.6056221052806523, + 0.47513199725211175, + 0.5264571318460711, + 0.6586198598704833, + 0.632539456522349, + 0.45409510497071676, + 0.4792128991268118, + 0.683955513641842, + 0.46150573254111893, + 0.4838009606717995, + 0.6204448111570201, + 0.6206969846845378, + 0.5161722136698746, + 0.4448141035518563, + 0.5903910025054953, + 0.538867752303656, + 0.5283488891444345, + 0.44975788420065366, + 0.6639355562174305, + 0.5340155814156726, + 0.5291680859585379, + 0.5264054055106373, + 0.6481286619283477, + 0.6470487071421851, + 0.44739826045576536, + 0.4883595971360524, + 0.6272633379956611, + 0.6540963088474501, + 0.5977631576047702, + 0.6737708306241403, + 0.6854841944568096, + 0.6535113167183616, + 0.5504853305095649, + 0.556198197174203, + 0.685116439277216, + 0.4640329356751391, + 0.4507207499773124, + 0.5448278833624931, + 0.5701025018646058, + 0.5271528257722973, + 0.6012655413557375, + 0.47518595149198695, + 0.4581848796754358, + 0.685814207253969, + 0.5623594413965075, + 0.6791991907982582, + 0.4519807536876245, + 0.4777288896626275, + 0.6705124524986276, + 0.672299285058809, + 0.44413992421194654, + 0.6268297994889408, + 0.6414156522043463, + 0.48723329553741007, + 0.5454625814333481, + 0.501842746140446, + 0.539243193273628, + 0.6432525065503343, + 0.5735455511822174, + 0.5575008036596468, + 0.6457306702650685, + 0.5925417545310789, + 0.5058522910128272, + 0.4915999224332679, + 0.46234810941549387, + 0.6725188407813447, + 0.519295450769065, + 0.6783597022985702, + 0.48956654503353275, + 0.5136491431618643, + 0.45136748029284834, + 0.6026381040356569, + 0.6735495968627027, + 0.5310484576738718, + 0.628436783938939, + 0.5761693136753372, + 0.6000707668449841, + 0.4940144075015996, + 0.6014505093171189, + 0.5476328954342664, + 0.5864553611443339, + 0.6095974171273494, + 0.4862843094115489, + 0.45341628387764576, + 0.5970884248581454, + 0.6018939490406963, + 0.46010594034650687, + 0.6374680534148237, + 0.6603967975241855, + 0.5296581654466256, + 0.6675741280853135, + 0.6089588891227324, + 0.46018451119525, + 0.5645889365227186, + 0.5578324652629193, + 0.5059789750837159, + 0.4490273973281317, + 0.5480928595474317, + 0.5995197201561232, + 0.49670666471952585, + 0.6637431453518673, + 0.6169558337526967, + 0.5797415044115011, + 0.658737083365576, + 0.6022005221300426, + 0.5179652625024724, + 0.518346738841812, + 0.4680486660854586, + 0.6741228807369923, + 0.45741138176250995, + 0.504378055830762, + 0.49219302875607973, + 0.6570669206271326, + 0.645093543788625, + 0.547168707704359, + 0.4837591063737455, + 0.5189949453767478, + 0.5227707051938502, + 0.6391622550696902, + 0.5025905250582227, + 0.6573829401338516, + 0.5446023653218486, + 0.5450415666913478, + 0.6607621247241815, + 0.5728657102076687, + 0.5897822824731883, + 0.4694265649146601, + 0.672601696464963, + 0.5875503869338297, + 0.540884431375847, + 0.5407083705537002, + 0.5507228990886381, + 0.44091807743774597, + 0.49047456396741235, + 0.4811800726619049, + 0.46407015630600007, + 0.485344518766317, + 0.4928663605268882, + 0.6736656989981497, + 0.527151151545708, + 0.628996627720017, + 0.6866274542932183, + 0.6865701291306742, + 0.6362434301956474, + 0.5069381849041732, + 0.5360969873874181, + 0.47292450430178234, + 0.46617112985850107, + 0.6531451975919425, + 0.4660662279545214, + 0.6783131905803093, + 0.6245571921090487, + 0.50782971433604, + 0.6018526872594726, + 0.5778127684890756, + 0.5925632027274931, + 0.5511203138241737, + 0.5151743727115723, + 0.4901914701022127, + 0.6264777251823248, + 0.4821460651417126, + 0.46355022801246915, + 0.511478843378451, + 0.449603645975869, + 0.5356240765315585, + 0.5717102114885382, + 0.6224375776801159, + 0.6305345210032292, + 0.6314813585474583, + 0.5185084450333094, + 0.6412142073394849, + 0.466134360711886, + 0.6251088574024869, + 0.6286355946414593, + 0.516194565438314, + 0.533280459699521, + 0.5992753730297348, + 0.6444078766844952, + 0.642220681112383, + 0.46621982493867925, + 0.5182166779525927, + 0.5939896849672338, + 0.5176654201304456, + 0.5530228760234939, + 0.6362112589091157, + 0.6328534250200153, + 0.45251171930227346, + 0.5311040527689186, + 0.5728870913064288, + 0.4987954249443429, + 0.648547798654207, + 0.5793790760579348, + 0.6012386180990188, + 0.5538031986265197, + 0.6402077835934107, + 0.6163656085353111, + 0.48081855414837543, + 0.44822831868297, + 0.4567213767777074, + 0.6554835271753222, + 0.5593931924268337, + 0.5734273190128112, + 0.6622712508077055, + 0.5037226613537923, + 0.6206105698955933, + 0.6177095971609816, + 0.5171324976584566, + 0.5061262693869074, + 0.5340190147295046, + 0.45056359487634084, + 0.44509258772675975, + 0.6097480825261443, + 0.5181607462281105, + 0.4902905428054021, + 0.6381056270535115, + 0.586581782297423, + 0.6818369634587904, + 0.4675707840797423, + 0.6866465457859678, + 0.5159655185089028, + 0.5251344315583976, + 0.4633915915619286, + 0.6449316512680757, + 0.6534448614224101, + 0.5776623163511762, + 0.45503679851858136, + 0.4971769301333007, + 0.5958678946450533, + 0.6029081984272957, + 0.6801384432295283, + 0.4560126446761988, + 0.48601503991654554, + 0.527900595467448, + 0.5254390034696971, + 0.6662095074944387, + 0.6438982831942117, + 0.6734248380684424, + 0.5784006312329191, + 0.6245824979186331, + 0.5587905994457443, + 0.5286624254156153, + 0.5683378989649206, + 0.6582586315149774, + 0.5295622334209601, + 0.45205466102666403, + 0.5098868921969408, + 0.5669520744911716, + 0.45438612217637825, + 0.4924188608206746, + 0.6639376705511488, + 0.6319750910734302, + 0.6491827006983778, + 0.44592320930217605, + 0.5398339696681842, + 0.5725448240925527, + 0.4572775402903683, + 0.5375521958236338, + 0.5336257135206928, + 0.5329868741522443, + 0.5943969808746139, + 0.564852381173135, + 0.6138426568154574, + 0.6348958400802011, + 0.49467958625662384, + 0.5868778243404852, + 0.532858585973484, + 0.6621536675823184, + 0.6454748075498862, + 0.5477947342029882, + 0.445102616291365, + 0.5200762500272992, + 0.575404418787964, + 0.5683303086142542, + 0.4866266214044403, + 0.6813028325691671, + 0.6046206869622177, + 0.6058957976293182, + 0.532920863495986, + 0.5749143782899654, + 0.44703689971371463, + 0.5890637731573295, + 0.5053107922921996, + 0.5681168363059987, + 0.5479804698835966, + 0.5622004081745722, + 0.4512399664103231, + 0.4699137796954954, + 0.6166863918955995, + 0.5420324516470667, + 0.6576626774081862, + 0.6586030623183964, + 0.49660569933891774, + 0.6035409576593864, + 0.5343975581241623, + 0.64430440007148, + 0.45860531976512303, + 0.6768489336689111, + 0.6350195195756974, + 0.5624032956186611, + 0.6261503523666789, + 0.6481342858799197, + 0.6442140405349057, + 0.632272697609428, + 0.6527374272536657, + 0.6142895181404253, + 0.46559405163759826, + 0.5925190996164945, + 0.6860507893664176, + 0.46134735572080837, + 0.5867594016938882, + 0.6385369099599445, + 0.6744524027868217, + 0.6019461902770491, + 0.4730318102663766, + 0.6409973984373456, + 0.4556932209053698, + 0.4786211670532474, + 0.6809598686837894, + 0.6442023020426996, + 0.6696038420038171, + 0.6582168604045777, + 0.5435268344171013, + 0.6775768670723799, + 0.5702621893054642, + 0.6252795637450028, + 0.6103791793755036, + 0.5366787125580281, + 0.6862471484192739, + 0.5540518750576818, + 0.5572916643185485, + 0.4629563446471639, + 0.49844053414189526, + 0.5876980981580158, + 0.5739905945987147, + 0.6067137147997215, + 0.6068687957308775, + 0.4423252380424413, + 0.46591446082562404, + 0.6283434113603457, + 0.5782823386502183, + 0.543498660826423, + 0.6227817408802834, + 0.44975740976039186, + 0.5286009624587882, + 0.6740081389744543, + 0.4497385635290738, + 0.5137227963452833, + 0.6871724247384509, + 0.6395733544287063, + 0.6471493316508915, + 0.6442629242547077, + 0.5184674640229439, + 0.6049926489946339, + 0.682861822602342, + 0.6805085545079493, + 0.4935598291113042, + 0.6220184064601292, + 0.6529945901501883, + 0.6773730973640929, + 0.5242495998402167, + 0.5393053113644963, + 0.5935715529099976, + 0.582109597641311, + 0.6145596284349288, + 0.6227880714410611, + 0.4497034983930753, + 0.5676099036450346, + 0.6228600922151372, + 0.5106893231402011, + 0.5173482660878976, + 0.5127685003262777, + 0.4850042416804243, + 0.4535300839557262, + 0.6433609060696374, + 0.5345685819272452, + 0.6195946228576203, + 0.5787045208896802, + 0.4685385666133252, + 0.5674137899404804, + 0.4811890491477065, + 0.47249121918362386, + 0.592479711895224, + 0.5521684165781697, + 0.6663400972330055, + 0.5068073275981786, + 0.45669525010154954, + 0.4968077371010732, + 0.5457873308928848, + 0.5735291060798939, + 0.6726098102548461, + 0.46030997158105247, + 0.6213885496539016, + 0.4646186113876012, + 0.6493448267549085, + 0.6719727248807239, + 0.5899402071141182, + 0.5470329701862431, + 0.5410550231501745, + 0.488523981531005, + 0.5386116575614581, + 0.4655232613569855, + 0.668242919834355, + 0.5885159552700501, + 0.6045301342970906, + 0.5016057558064743, + 0.5653946896730272, + 0.4798157979806071, + 0.5635248767045811, + 0.44162973353781637, + 0.534049808860496, + 0.47091611767931113, + 0.5977567614149466, + 0.4519654938859319, + 0.4473752038248143, + 0.5894256471098466, + 0.6709339214770064, + 0.5424336049734995, + 0.6150322286012626, + 0.5856639295003374, + 0.45847702611653146, + 0.5964210894220747, + 0.4740592969149767, + 0.5094280621895367, + 0.6870476842228173, + 0.6553030730660241, + 0.605140346988474, + 0.6341044348902318, + 0.5279887300123953, + 0.44142587510397663, + 0.5720378503051181, + 0.4862989853799054, + 0.5174388156603998, + 0.5302273639251173, + 0.6856081383148053, + 0.47685690621554533, + 0.49880222656699863, + 0.625941250473181, + 0.5991673260320003, + 0.660828677209375, + 0.5230816761151418, + 0.5407056267788859, + 0.5377936566314411, + 0.6532862374530489, + 0.49768889820204243, + 0.6788706230613636, + 0.539084200377995, + 0.6082860896803288, + 0.5139335489301503, + 0.4995543451673172, + 0.4447896086239449, + 0.5964512681118402, + 0.614420962786363, + 0.6330417286917511, + 0.5438410934435004, + 0.4496993957188362, + 0.6224138737201956, + 0.6628631584804062, + 0.4914928394541417, + 0.5389221144876825, + 0.5803224543391057, + 0.5060174667897105, + 0.5200917036202763, + 0.4873620593903558, + 0.47001527726219283, + 0.5724126118129278, + 0.5616163641989986, + 0.650658516766696, + 0.6599880939258056, + 0.6753551529856874, + 0.684024370146653, + 0.45906492124468845, + 0.5328555265408187, + 0.46156388107052054, + 0.6472061881390425, + 0.6514075731068962, + 0.6113610338374741, + 0.6012983330541916, + 0.5725603482361835, + 0.6821543428770789, + 0.5831261954174831, + 0.6297716181761721, + 0.48038694207985017, + 0.6425287148810298, + 0.643020643301807, + 0.510101963125371, + 0.6003640121169552, + 0.5128303269807403, + 0.5576825155073148, + 0.5704720999599877, + 0.4940008061285125, + 0.48565012165101185, + 0.5248761022054671, + 0.44483592547162093, + 0.6510503998903293, + 0.5834197864280017, + 0.68062252568805, + 0.6280441194003349, + 0.49070152177219106, + 0.5806548068938004, + 0.5104338516635113, + 0.527255683015098, + 0.6166721773403686, + 0.5749326932081897, + 0.4683058011696998, + 0.5142687981698082, + 0.5288912403782923, + 0.6220501855460354, + 0.6639762781061865, + 0.5724432369611546, + 0.4711253353705647, + 0.5781853792487452, + 0.6475350646445427, + 0.627712032456838, + 0.5358578861760621, + 0.5937763494114576, + 0.5082749597386835, + 0.6610635638069144, + 0.6798361679485165, + 0.474314176289336, + 0.565882813062673, + 0.606551110667628, + 0.4594350779721959, + 0.6326195555010963, + 0.4869173649952052, + 0.5386301986411335, + 0.6464953803135574, + 0.5693920973261934, + 0.6534657265902037, + 0.5539806999382884, + 0.5660653870789142, + 0.5394285057885252, + 0.6745005043965311, + 0.4533244373313024, + 0.581833447452664, + 0.6658402868636892, + 0.5121390862465822, + 0.5055853671770616, + 0.5703185299940601, + 0.5972519119671714, + 0.5873128234456702, + 0.5742221234623685, + 0.6696281535017352, + 0.6843337541040957, + 0.5159493500109102, + 0.526551790407858, + 0.5748025203653823, + 0.5679751946714118, + 0.6823846720789614, + 0.528666947773083, + 0.6388650440154303, + 0.47939263604502835, + 0.6563482230866884, + 0.5795395583034819, + 0.6762149952228803, + 0.4551439443325208, + 0.6034337192149122, + 0.6292034038641641, + 0.5282145556377091, + 0.49162642711087284, + 0.5522000512975365, + 0.5193978091906614, + 0.549414002359202, + 0.4486606095614775, + 0.6884448213025489, + 0.4587363242633381, + 0.5727687041341591, + 0.6781437585660073, + 0.5578877373565767, + 0.4984010290460324, + 0.4913201634815977, + 0.45042123316890004, + 0.6087095077038858, + 0.6260439459368623, + 0.6103030772823523, + 0.4864812816617473, + 0.506473235474217, + 0.45960080261120523, + 0.5703491190829901, + 0.4665622539488563, + 0.6402187131499525, + 0.4808365404740706, + 0.6369500503392939, + 0.549181826748048, + 0.4514398053190846, + 0.6515224773972215, + 0.5924333073892739, + 0.5451330399481916, + 0.4850838837808883, + 0.5517412613359325, + 0.47789852545701916, + 0.6641540405721915, + 0.5556917207565184, + 0.6714098219158262, + 0.5192126286679668, + 0.5922119668439177, + 0.604171364145654, + 0.5605677322301347, + 0.67558673207308, + 0.4670882197886331, + 0.6835362629711512, + 0.624197815143708, + 0.597699143550647, + 0.4624286526657625, + 0.5507482399909547, + 0.4518010282001913, + 0.6767667512198002, + 0.47730211661013955, + 0.6798218658397546, + 0.440966940668895, + 0.46270366060126106, + 0.6673691193685449, + 0.4418689698480737, + 0.5646102356233456, + 0.6117837779258541, + 0.6451685587363637, + 0.6511351927673789, + 0.44704439791046413, + 0.6699734543935687, + 0.668421914639142, + 0.5847771642679304, + 0.5534719903831008, + 0.6055099349661487, + 0.5258177192272996, + 0.59551345154331, + 0.6024956600390182, + 0.5254149466284743, + 0.46433411316742457, + 0.6161570906270832, + 0.654373692009713, + 0.553903085756208, + 0.6362674361730387, + 0.4877838827014525, + 0.5046020203777297, + 0.5813927768174197, + 0.6206589890461898, + 0.6740172179942356, + 0.535148751967006, + 0.4928308796799094, + 0.5632746217801683, + 0.6677415879526287, + 0.5041748997079236, + 0.5242351934617597, + 0.5972872671246127, + 0.6793417882065496, + 0.6573310219171067, + 0.6052898907201882, + 0.45553537264483634, + 0.6841106670247499, + 0.5726472034517118, + 0.5994856169114808, + 0.49506810409392943, + 0.6732375501636794, + 0.6494446567713464, + 0.583154350170261, + 0.579903161450622, + 0.4555058582284606, + 0.6071226016659617, + 0.6328073713885425, + 0.5052069878901968, + 0.5088350994067548, + 0.6411911436158164, + 0.6019391648021166, + 0.6763522020045454, + 0.672747779751589, + 0.5118606272305253, + 0.571559015347009, + 0.5375934231672295, + 0.5030094271818668, + 0.5634965332424701, + 0.5919988149355371, + 0.5034318812604406, + 0.658769925314348, + 0.45784680768568553, + 0.47235947472179307, + 0.585585591032155, + 0.4808862256301218, + 0.6713186902776695, + 0.5689855260525569, + 0.45261360079798946, + 0.4937853001868551, + 0.6686300968198124, + 0.5632109456639839, + 0.4948593529012134, + 0.4627875592202484, + 0.5894351943085903, + 0.47832733697403057, + 0.4487318852301373, + 0.5525155289181365, + 0.6145022209554947, + 0.6295627998748311, + 0.49099856224806865, + 0.5059031083285725, + 0.5431587245571332, + 0.5487151188209569, + 0.5894080770589616, + 0.49420843833931805, + 0.521353687052268, + 0.4831647110384026, + 0.6494431069871757, + 0.6119606505489773, + 0.4854797269535703, + 0.5088993939442861, + 0.6451475432351979, + 0.5562972702330755, + 0.6539509838867933, + 0.5434800732591242, + 0.673904653046993, + 0.5226760516304043, + 0.5409785713563228, + 0.6771176624347548, + 0.4976660577874668, + 0.6382102667730793, + 0.47898108414465945, + 0.44556985105094327, + 0.5510137105369298, + 0.6402165548248198, + 0.615382184465809, + 0.4833592539421878, + 0.677285695889803, + 0.48323848548941256, + 0.6466942012499027, + 0.4595072992318837, + 0.5647028197769733, + 0.47462537186084064, + 0.5654705415483564, + 0.6613208531265329, + 0.5000943340903493, + 0.46086830394176376, + 0.5058181366001157, + 0.6760919098789633, + 0.6478049400046977, + 0.4914230371002378, + 0.5671909854057755, + 0.5632414509063659, + 0.4636730173409638, + 0.6071245111734196, + 0.44354992071227695, + 0.4795313582283294, + 0.5517754631378086, + 0.6318782521906354, + 0.4447024189768246, + 0.46814191014061907, + 0.6484783730929925, + 0.5133782874939943, + 0.667045827105132, + 0.5383693800964141, + 0.5178818600735227, + 0.6876590179038674, + 0.539807394488223, + 0.48997822722023265, + 0.45037730366944445, + 0.6225451595813346, + 0.6744519769176467, + 0.46339619186774444, + 0.515958086194703, + 0.5579432511493341, + 0.6867656056545877, + 0.6729830095034052, + 0.4767156376435558, + 0.5186396012495605, + 0.6745340600101684, + 0.6279765825163709, + 0.4710063356710421, + 0.520872281639728, + 0.5945700610739018, + 0.5382084732901835, + 0.4731657557333987, + 0.4704300006669973, + 0.6534115070877824, + 0.6794651610604481, + 0.6571952909466955, + 0.628842471924761, + 0.6342787791882804, + 0.5639703744383446, + 0.531516391517824, + 0.5884144671805095, + 0.5716044526796114, + 0.5705905004575772, + 0.6055497042139728, + 0.6263599788633746, + 0.47986553533227627, + 0.6244330742556811, + 0.6366315191574223, + 0.5992617832699613, + 0.5701996224721517, + 0.5295704876215911, + 0.5572469470353346, + 0.6849764265079352, + 0.6088501874018333, + 0.6406897040084586, + 0.5232542466100336, + 0.5700589375538009, + 0.44134963490381546, + 0.462949080182871, + 0.5128054396250481, + 0.543502896905484, + 0.5684240258980295, + 0.4827147200203485, + 0.5559174991011248, + 0.6030952710604011, + 0.47596236350698906, + 0.49308213727731043, + 0.5239814470501666, + 0.631740994905952, + 0.55507428265167, + 0.5425357076888905, + 0.48906492567869336, + 0.5070138648685453, + 0.5957283116706116, + 0.5022947576234521, + 0.6310703654754526, + 0.5410480493758002, + 0.5936268816910333, + 0.6152485183605141, + 0.6019153468122858, + 0.5904690171809698, + 0.550580088271778, + 0.5693485263503114, + 0.5259470632141499, + 0.6744679721154335, + 0.5575038611589263, + 0.6120965035611737, + 0.652379135254755, + 0.5743793443261486, + 0.4942946635987465, + 0.6009121042449371, + 0.5864771142106431, + 0.5586810969172193, + 0.5706570650929743, + 0.5311880117998191, + 0.673619463398722, + 0.5799992237628467, + 0.4440587595109389, + 0.5988217095462831, + 0.6736726565785074, + 0.682970587163916, + 0.47377596539907607, + 0.5628540710533246, + 0.568856137851119, + 0.4573138198146103, + 0.4844793674689632, + 0.5966354535090176, + 0.6662356266115059, + 0.679336374906655, + 0.5804199101085432, + 0.5014857071594849, + 0.6837384101029702, + 0.4772420889351513, + 0.5124822760256158, + 0.4697554004714607, + 0.5207728552601107, + 0.6250608259624442, + 0.6058250718183327, + 0.5598443167057839, + 0.5047472585593742, + 0.5795005726378578, + 0.526535406654409, + 0.6533191610378161, + 0.6884668867369557, + 0.5609489142621971, + 0.49942906045687974, + 0.5307469052338573, + 0.5054287358378047, + 0.5941941616079083, + 0.4532136370966078, + 0.5747373117178785, + 0.6737431931287451, + 0.6216675096699658, + 0.5638636411005467, + 0.5465943363581587, + 0.5893287738430781, + 0.5030238679104163, + 0.5607624933907343, + 0.4859961132142636, + 0.4504073679634489, + 0.4910502972258297, + 0.4919874660200801, + 0.6237972874554154, + 0.5637090085254791, + 0.6587226587048596, + 0.462424910529019, + 0.6421592990060998, + 0.5088580151366588, + 0.6335598280064274, + 0.6643392237648633, + 0.4635136064912452, + 0.6799528490873818, + 0.5586589783483433, + 0.5331258048629777, + 0.6264804434363432, + 0.495898020118284, + 0.6001334781918629, + 0.6524807847546381, + 0.5856361649217355, + 0.5157842358792528, + 0.6828717882590492, + 0.6687577835415507, + 0.6051355721279076, + 0.5417271939945546, + 0.6212380592283518, + 0.5876021090262347, + 0.5288217214772142, + 0.44150888608305133, + 0.6423758042481521, + 0.4515262778726809, + 0.5429087531264607, + 0.5139630252799946, + 0.5322465190672218, + 0.5999456939932436, + 0.6393148610488075, + 0.5533290084870663, + 0.6073461500745555, + 0.4472217318759155, + 0.5297273771016748, + 0.6032420899850519, + 0.47324203487530975, + 0.5733692197368009, + 0.538225458102784, + 0.6634826142601109, + 0.6229964919800677, + 0.49830932255631605, + 0.48877935875956896, + 0.6628765600952393, + 0.6846098951631688, + 0.6098390165180592, + 0.47965865720235, + 0.6105401431650024, + 0.5484524110214773, + 0.6052300125461899, + 0.664715968675089, + 0.4571277725972301, + 0.5465010950742598, + 0.6335190121342945, + 0.45375165554634556, + 0.6882429289965395, + 0.6689535094697546, + 0.47236465904260344, + 0.5514912488768843, + 0.5546272593364463, + 0.596275492963826, + 0.5590877628210764, + 0.6522935254789405, + 0.6651508896074293, + 0.569563896676845, + 0.5663084760939225, + 0.6804576772211912, + 0.5480733589866853, + 0.48984776421665555, + 0.45997204203802833, + 0.4797468875293018, + 0.569607683194871, + 0.440319525054345, + 0.6575372905955671, + 0.6268745979859892, + 0.5871975912093363, + 0.584482501848647, + 0.6126097278004335, + 0.4455996977383903, + 0.5769058184648959, + 0.6096197921302567, + 0.5831362319738275, + 0.6148466300766433, + 0.6771635210286384, + 0.6674303452404472, + 0.6204734112404864, + 0.6800249339375942, + 0.6421925030682959, + 0.6619940832208643, + 0.6682183624423778, + 0.5803886019983735, + 0.587184380836295, + 0.5269761195179875, + 0.6353157630933245, + 0.6722161372394239, + 0.6864427852113746, + 0.5243680563430896, + 0.5684673000668305, + 0.5649526488642276, + 0.5582579631800137, + 0.5074871980136139, + 0.513519890612971, + 0.6661161849734771, + 0.5607389010218171, + 0.617389079358936, + 0.660606990957509, + 0.49224220889598097, + 0.4856369449100375, + 0.4898324479646311, + 0.4768212761862734, + 0.5822690410479149, + 0.526205647336572, + 0.5448227385294699, + 0.5795279624843512, + 0.4677931741490968, + 0.4449450975019241, + 0.5428957562172239, + 0.6207364854424864, + 0.5934801714285705, + 0.5661291774064032, + 0.4855331223692906, + 0.575012025475879, + 0.6852398683939924, + 0.6494394026776471, + 0.5901551769110917, + 0.4713116368326482, + 0.5311112237557719, + 0.6764568652376393, + 0.47822932111606714, + 0.5515547246490327, + 0.5577760312469905, + 0.4731645825679273, + 0.5990649967298999, + 0.6529559558833604, + 0.6376555067425265, + 0.5592542401403241, + 0.5018979594813812, + 0.5490417611917213, + 0.4694773679046013, + 0.6183683943599438, + 0.4458115161655807, + 0.6832346067335632, + 0.5074548689476313, + 0.5141048030593822, + 0.6131219789729894, + 0.6002530929390341, + 0.6774350971868326, + 0.6454999780281538, + 0.6523794111887629, + 0.5592160496907175, + 0.5881920390764103, + 0.4607485012808513, + 0.49242120945784096, + 0.6414657924245791, + 0.5953743444762659, + 0.45955504147702136, + 0.5604489928932712, + 0.4927359032033327, + 0.5530144845098364, + 0.5781647113036079, + 0.6590833401699095, + 0.4593828576950503, + 0.4682900002189653, + 0.6396531592484485, + 0.48064429240246753, + 0.5409803202413958, + 0.5862221594553219, + 0.4848427355861327, + 0.4847713861582809, + 0.5821131781566629, + 0.522062755633827, + 0.5419566621021186, + 0.46933172411929547, + 0.5658085210751018, + 0.5855488884995789, + 0.5033111450709978, + 0.47271447853972903, + 0.5129275079747355, + 0.522664917857377, + 0.47985547947833745, + 0.5097504373059597, + 0.45744993780358156, + 0.6439062697886293, + 0.5782088902300881, + 0.5791579055768448, + 0.5994084651724271, + 0.610188203750347, + 0.6744481033419928, + 0.6882453660136088, + 0.5840544360530815, + 0.5005738127257989, + 0.6454375291665775, + 0.5260411868708355, + 0.5843262346891536, + 0.5209426215014427, + 0.46558708254690023, + 0.6632203204436457, + 0.5030588578394819, + 0.6395945005962396, + 0.6479929130224287, + 0.4671125138933459, + 0.6246598759939217, + 0.6445516397937595, + 0.4522131051176452, + 0.5615155151834565, + 0.5646651869427126, + 0.6017660259019426, + 0.6738023818585194, + 0.5538517813871904, + 0.5085196186242703, + 0.4677007397164674, + 0.5386201529333937, + 0.6799901613695266, + 0.4715471981738236, + 0.6297760442780096, + 0.5614366458727992, + 0.46160888136921596, + 0.45604333426597443, + 0.5706865866189975, + 0.5956215926505996, + 0.6314201445725759, + 0.5710033106564107, + 0.524591046863642, + 0.5630824233747346, + 0.6295454579469548, + 0.4750334301813216, + 0.5911539367953582, + 0.5695233559449899, + 0.46683373747522333, + 0.4601299412256765, + 0.5052218278259925, + 0.6847921441939692, + 0.4937548134709694, + 0.5844341090578983, + 0.4501053523748018, + 0.6074450510940983, + 0.6357248200028822, + 0.5568915522776933, + 0.6309466978566545, + 0.5491791918422532, + 0.5613415626395368, + 0.5760798098902326, + 0.5046962116321239, + 0.5474559060943763, + 0.46288788592804536, + 0.555153443389069, + 0.5238102105740232, + 0.6682121494942643, + 0.4615803898478721, + 0.6655492494599473, + 0.6356207598314192, + 0.5342702277343359, + 0.6194446292930498, + 0.6651974625063469, + 0.47335307575267843, + 0.6856786968192703, + 0.558442758852018, + 0.5923753804736971, + 0.6599113931588696, + 0.6283701359603017, + 0.5732304651297288, + 0.5924518537562824, + 0.5845915524515476, + 0.5770768886204636, + 0.583885162196961, + 0.6119723585349833, + 0.4535003506093453, + 0.5490306314002278, + 0.5138167538093632, + 0.4636761018116219, + 0.5055262783558542, + 0.5559516977184931, + 0.47557046331637093, + 0.4988414191470308, + 0.51483666273669, + 0.6658049657494183, + 0.4441848485205156, + 0.6861149576133069, + 0.6050139182855224, + 0.6548117537683371, + 0.5663690696599901, + 0.6031480944619716, + 0.447781358323557, + 0.5147753694335878, + 0.5549520102981134, + 0.5433703966708963, + 0.6414613758577871, + 0.6777315240716393, + 0.6426863463485555, + 0.5707789225303013, + 0.5888199360830484, + 0.5067233033384191, + 0.6097978054695892, + 0.5494691896143861, + 0.5376569550377657, + 0.4697748884039076, + 0.5249966394107826, + 0.6548658436822156, + 0.5912091335557993, + 0.5999224814024458, + 0.605202559022689, + 0.6242628211214815, + 0.5785609613286696, + 0.5066369968198385, + 0.47758002075889155, + 0.5017169426799414, + 0.679188213565856, + 0.6279588267917168, + 0.44491915115675434, + 0.5721915106667167, + 0.4850675746213991, + 0.4913816593767619, + 0.6482738889681978, + 0.5523137354778315, + 0.6103264254568912, + 0.5023870508231965, + 0.6720274377539994, + 0.5565353307834588, + 0.5831328526312224, + 0.5116451886138181, + 0.5607456028886986, + 0.6268716548442526, + 0.5165635524520288, + 0.6551776808343309, + 0.6049296034320039, + 0.6172781770140374, + 0.6655463606696893, + 0.5894756751417425, + 0.5406567759898389, + 0.4674857409722783, + 0.5395750262718032, + 0.5619019356015483, + 0.6234538095166483, + 0.5963235149406535, + 0.6293670640140124, + 0.6595099495045779, + 0.6290337989630927, + 0.5861452035769874, + 0.47386451035818344, + 0.5313745159110076, + 0.6694171958382686, + 0.5205688464646808, + 0.5260892009399377, + 0.45507792494475535, + 0.5449470527389404, + 0.5999267223371406, + 0.6062489589769811, + 0.5094607428158962, + 0.5092933456325072, + 0.6577963986268445, + 0.6069718371359598, + 0.5784362764415685, + 0.4995022480220932, + 0.6036941062147725, + 0.579581904408296, + 0.5243498287176509, + 0.4672049622294723, + 0.5016621058630274, + 0.45041962288375126, + 0.4461026078298861, + 0.5696363255547017, + 0.5246143081562937, + 0.49603322331487965, + 0.6523190011738217, + 0.6818572448252562, + 0.6111725516162931, + 0.6328544560651372, + 0.5677470810898415, + 0.5032669451634091, + 0.6662411879907626, + 0.5226354030782134, + 0.48511468740015384, + 0.6350299395175896, + 0.6864107877017528, + 0.5679410413282147, + 0.44636394469820534, + 0.497663847876471, + 0.4644783820386539, + 0.5103613648295482, + 0.6135140106192226, + 0.6581935680027985, + 0.6860170381429731, + 0.5387052391808496, + 0.47120464140336504, + 0.4957076152022888, + 0.5744586678313455, + 0.5448366783534337, + 0.5058851276297318, + 0.501921804210888, + 0.5183700845893449, + 0.596581085558163, + 0.5463670336731998, + 0.6258130980159107, + 0.5025955913464512, + 0.6807639620788468, + 0.611865997472592, + 0.4925617979824381, + 0.5545956337127486, + 0.5561047826093092, + 0.5527964848580527, + 0.5751753791927515, + 0.5423653257711056, + 0.5270335885875324, + 0.6390571231418682, + 0.648608674308, + 0.5555080799674103, + 0.6543681252678549, + 0.550137418301941, + 0.6340790093685449, + 0.5437784877793186, + 0.515479344831588, + 0.45532859466144715, + 0.6137592377714416, + 0.5739861585773934, + 0.520522283038203, + 0.5351736847104525, + 0.5307231762571503, + 0.6182280501467837, + 0.6076221731822311, + 0.5689253079268367, + 0.49079117042381065, + 0.629343109842914, + 0.5512665332784893, + 0.6439740526779876, + 0.47191634377725517, + 0.5362710160548703, + 0.618757458860187, + 0.6114093554303457, + 0.5659347120056702, + 0.6437400008215439, + 0.5303929724523462, + 0.6305872090130746, + 0.562741426631933, + 0.6506049840311504, + 0.4887064414096123, + 0.6572539334271468, + 0.5542296974431148, + 0.6308765745423339, + 0.619416755264039, + 0.6135115936655473, + 0.506001216369548, + 0.48031571995748096, + 0.4911030591828801, + 0.6130311662037682, + 0.49024133978737067, + 0.50292429609994, + 0.473123734207829, + 0.6592697994997037, + 0.6503578186427281, + 0.4565489637383493, + 0.5791387536501676, + 0.4916108530889437, + 0.6843928792340753, + 0.5171250052343721, + 0.5554849604235743, + 0.5337086589428601, + 0.5787702999169133, + 0.6723497048806999, + 0.5000639015796415, + 0.6248358443411289, + 0.5231913760236423, + 0.6290479575509236, + 0.6810866832686759, + 0.5801640393375911, + 0.5040441115812153, + 0.5739467284436732, + 0.5653145486092961, + 0.480742006616088, + 0.6601519960996363, + 0.6339267529179364, + 0.5082356559453478, + 0.6211937606671758, + 0.5990692658070504, + 0.44760606643715806, + 0.6721155558574352, + 0.5946204686214115, + 0.5763090272302718, + 0.6096023163271538, + 0.6261159859007202, + 0.5460142215311226, + 0.662389636096378, + 0.4662893909256803, + 0.6298769876109889, + 0.4535450424174243, + 0.534811794407085, + 0.6426381784066575, + 0.5715967667773157, + 0.530831243035157, + 0.6671911531339534, + 0.6700675212548037, + 0.6619141783912412, + 0.5385556935745656, + 0.5227690464466558, + 0.4692569575468703, + 0.540922936820996, + 0.5115643832365901, + 0.46065044077275424, + 0.6203548499090934, + 0.653667887660246, + 0.47509319555959817, + 0.6544491700784325, + 0.4551383226134034, + 0.450450640474174, + 0.4866515171278782, + 0.6843853369163141, + 0.5245738446747779, + 0.5185419720481108, + 0.672672816276028, + 0.5713439154961526, + 0.44049241591861354, + 0.44422717383439503, + 0.657259087752813, + 0.6570984544958697, + 0.545126030057857, + 0.5414955183211909, + 0.577663725685497, + 0.6004076397319085, + 0.5884152434164102, + 0.5752531982704425, + 0.54498887061735, + 0.490589303360351, + 0.45728642199909897, + 0.4402916517292048, + 0.6829918263173759, + 0.6696454836429694, + 0.6135141916516095, + 0.6512426038896242, + 0.513862303970084, + 0.545229734659028, + 0.4760384906419035, + 0.6729544140104884, + 0.5671297087415716, + 0.6637863996607283, + 0.5861809241970433, + 0.5354700043916204, + 0.546030442368207, + 0.6864088442139352, + 0.6496560564051592, + 0.5530391838222402, + 0.6695975821999897, + 0.48799068178961874, + 0.6580380734055158, + 0.48712715734853507, + 0.5634709976073352, + 0.49957184673387095, + 0.6229390013949347, + 0.663238940332672, + 0.6065250026429021, + 0.6650631972438145, + 0.5495018506870465, + 0.6140192036344871, + 0.5402461912882306, + 0.46026561278501893, + 0.6776490266947645, + 0.5773326864601489, + 0.48347691059597553, + 0.5289023353508914, + 0.5174758460529506, + 0.5602681227238855, + 0.5127282216832127, + 0.6459329832280793, + 0.5079863527664145, + 0.5298781798470565, + 0.6531526943887489, + 0.4857400002728198, + 0.6879866360477491, + 0.45954871177391726, + 0.5705553866311024, + 0.6329720532325089, + 0.6605197943114838, + 0.44727674785273724, + 0.6696793175480694, + 0.581971085115249, + 0.6107505013345237, + 0.4869699734618382, + 0.5622871449308853, + 0.45266994962646684, + 0.5553878513817837, + 0.6151144638917121, + 0.4789716332624184, + 0.6130113099103204, + 0.5211902732977253, + 0.47846212183150827, + 0.6581615850714346, + 0.6133680266439527, + 0.4857936524161744, + 0.4941078033695345, + 0.5946213222889406, + 0.5498488411607984, + 0.49315604283898706, + 0.5143413768487853, + 0.5922001139203094, + 0.45563172892066617, + 0.44585265370403515, + 0.6745894573647406, + 0.5542243789624269, + 0.5699425346168765, + 0.5504012070121399, + 0.6062918121111669, + 0.4500842985891548, + 0.642201814835665, + 0.49588594763300126, + 0.680381005126089, + 0.473134723175398, + 0.6537092378669349, + 0.4790821169844169, + 0.6680943083042798, + 0.6465661471727064, + 0.6440419539611386, + 0.5782144640826576, + 0.560467958718289, + 0.6433241941226722, + 0.5728914010797155, + 0.6553715573505339, + 0.49976695407147687, + 0.49949624816641663, + 0.5384075626743257, + 0.5994428311735366, + 0.4764095771739246, + 0.6521783484275044, + 0.49813449925754155, + 0.6393939025266782, + 0.6843684512966867, + 0.5171614545247966, + 0.508095612721649, + 0.5732710746849866, + 0.6392066304481554, + 0.6741546450101981, + 0.646064634978614, + 0.4848749618354084, + 0.6055211365092887, + 0.5863892245223865, + 0.5083783414621039, + 0.48019680211591825, + 0.5977966971336852, + 0.6873984040950477, + 0.5999333936179739, + 0.6195628477280042, + 0.5272961467690067, + 0.6544471367399578, + 0.6612034900399816, + 0.5095351315156275, + 0.5621353639145797, + 0.4718611507863758, + 0.5029576359963713, + 0.5453310468673892, + 0.6652138981948806, + 0.5722121159929809, + 0.6323901553623337, + 0.6200811717981181, + 0.49149000052323455, + 0.5997244822455281, + 0.4476689888408407, + 0.6598263895647427, + 0.5680236075771956, + 0.542373081476176, + 0.5846491841839361, + 0.45725925406856005, + 0.5714912354222478, + 0.4811697153312192, + 0.5233098847444714, + 0.5109092095420757, + 0.5345978392960308, + 0.5144049280917351, + 0.6764949780364138, + 0.6546738435157464, + 0.45792617235478394, + 0.6453641500676828, + 0.6176536193409411, + 0.6260690025250117, + 0.6602015670961341, + 0.497282755646826, + 0.6776888884722645, + 0.45835184441268334, + 0.518921430313978, + 0.6103608204213324, + 0.6569406413703034, + 0.5835804732507996, + 0.6225111430597483, + 0.6599402659783347, + 0.44884657932083893, + 0.6758684503357555, + 0.46877207660267434, + 0.6808756522245234, + 0.6687736215170074, + 0.4640203824079174, + 0.6008774651316807, + 0.4687599975686343, + 0.6232946701081785, + 0.5011072763765265, + 0.5073431055365699, + 0.5520293729392027, + 0.6441725320940563, + 0.597072908335481, + 0.5604387624705028, + 0.49495515555062214, + 0.5159808296866706, + 0.6524326119279334, + 0.5744569439519915, + 0.48625529719024757, + 0.6635599582061078, + 0.665097892570035, + 0.5045095571645021, + 0.5881579411883139, + 0.44488350126326187, + 0.5632656230195942, + 0.6821588349704167, + 0.4501680021105125, + 0.6653675806777144, + 0.5163257185184145, + 0.600547781582753, + 0.6671021243853761, + 0.5335672543007625, + 0.6154187253042026, + 0.45771132999193853, + 0.5384498859218089, + 0.5761751284354308, + 0.515218156850023, + 0.5146437975176527, + 0.5469636209176256, + 0.6341686611809934, + 0.5414763686332822, + 0.6487433761857646, + 0.6245315814010884, + 0.627163699450774, + 0.6673125194629701, + 0.5394040862837843, + 0.5021065396943547, + 0.44092340904100225, + 0.46533086764363946, + 0.6174462353960437, + 0.6075520414001586, + 0.5737400728091564, + 0.6786525116017282, + 0.4842062140433758, + 0.4679236329857899, + 0.49054019284841605, + 0.6283925822538305, + 0.4702612696676651, + 0.4443944888578893, + 0.6628723212695697, + 0.5355912063171548, + 0.6589584451288297, + 0.5150325051251106, + 0.6711721099026727, + 0.5123087340892188, + 0.5037447656303302, + 0.6162656488630784, + 0.619599361422996, + 0.6046252456050136, + 0.4611771557210714, + 0.5391061256131465, + 0.6463374421927625, + 0.4549920099045702, + 0.5494132881543735, + 0.5159347762634048, + 0.5100723648538249, + 0.5424409450107159, + 0.506989728083868, + 0.5612124522091089, + 0.6874553251596524, + 0.5196605954154382, + 0.6203694285092928, + 0.5153827779198185, + 0.6537856237700367, + 0.4879797387974937, + 0.5942391448823383, + 0.5855642950482018, + 0.4746266073188346, + 0.6187225257096116, + 0.5467172604313816, + 0.5379061747619794, + 0.6232619676909381, + 0.509029240334056, + 0.5128338598499239, + 0.6250194039251961, + 0.6485758101168704, + 0.46020414216616157, + 0.49674141658991405, + 0.5176551129414938, + 0.5499904674897489, + 0.6705247407331182, + 0.5444397808487854, + 0.5118676623704074, + 0.6615571915443237, + 0.44464795679173563, + 0.46369425288215627, + 0.524008249905481, + 0.5847281000153312, + 0.5469765887319689, + 0.6852591052557582, + 0.6736554595654483, + 0.5233150363733843, + 0.4869156434605909, + 0.513856629182026, + 0.5952310717868572, + 0.6393525653978558, + 0.6232497363222266, + 0.5629802696515539, + 0.5819009530977824, + 0.45758560047915975, + 0.5099644702119424, + 0.5641837995299126, + 0.5342145498791376, + 0.6160662209238967, + 0.4860866014656637, + 0.5599507492979504, + 0.5952803895313301, + 0.6517384339172442, + 0.6553799648232066, + 0.4601971955094367, + 0.46862387393247606, + 0.4695212129603824, + 0.6140022134275014, + 0.6615106199694405, + 0.5403944275630872, + 0.67938576069402, + 0.6694881001609607, + 0.44649382064577253, + 0.5902527370091393, + 0.6462829285041688, + 0.6590313670345166, + 0.5537111795883071, + 0.6581827168078428, + 0.5045641078456505, + 0.6298111481831834, + 0.5556526741945, + 0.5521309512536925, + 0.5519100974305906, + 0.6742460062839654, + 0.5835313380269124, + 0.6354579542433372, + 0.5832763164856503, + 0.5362977343840231, + 0.6382885892062732, + 0.5589611617203923, + 0.45908029512982973, + 0.5863751701987958, + 0.45566233476333506, + 0.4624877904719899, + 0.6522977773120642, + 0.6832071234768, + 0.6212314237018872, + 0.5977833685789412, + 0.6489620582167146, + 0.560985010441036, + 0.46305156637275025, + 0.5841373877593588, + 0.4835769043362254, + 0.6487262449321946, + 0.4470960772257594, + 0.521680732225333, + 0.5790122995173419, + 0.5345892937000382, + 0.45347184388480277, + 0.6103556803078568, + 0.6511223546736093, + 0.5369758246603841, + 0.48686500980805125, + 0.6050601566700138, + 0.5098194440640547, + 0.6246739491899855, + 0.5011178560895705, + 0.5501015774109463, + 0.5501210138398658, + 0.6500846007763914, + 0.6056793303560879, + 0.6398763614362791, + 0.6105717427412304, + 0.5764497961524643, + 0.6839624141099795, + 0.5428538986429721, + 0.6187484955594114, + 0.5059917774378163, + 0.5401284774104076, + 0.685107682818523, + 0.5891996010321244, + 0.520351268886658, + 0.6619901397007939, + 0.5077272087474178, + 0.6763404343094328, + 0.48949724736006095, + 0.6839452827074465, + 0.5829066480090447, + 0.6538994098761723, + 0.5098166346277315, + 0.5092728280591636, + 0.4485858229326921, + 0.5771545209578074, + 0.5415618646150089, + 0.5998598395617666, + 0.48533100070843654, + 0.5590215326774415, + 0.5197456647089524, + 0.6227416071342037, + 0.5535138267166655, + 0.4800869232182128, + 0.6089404578734054, + 0.5246895944880692, + 0.6823623179345192, + 0.6585088908481568, + 0.6013181492718591, + 0.49050570042942854, + 0.4445470880586133, + 0.6629270618786712, + 0.4643000207730223, + 0.5022656426973747, + 0.486524198104312, + 0.6163222432322505, + 0.46655521170895986, + 0.5391947773074942, + 0.5328958077357309, + 0.5447708949024195, + 0.6220701166114179, + 0.5283362861969381, + 0.6350062712082241, + 0.5513670130034928, + 0.5306503095799379, + 0.6022007455024856, + 0.6548036881613569, + 0.5003770897881071, + 0.49274490466680965, + 0.5251076383019274, + 0.4477501542730252, + 0.672770180523826, + 0.6812943892576175, + 0.6223127417787272, + 0.5883740495429566, + 0.4783429685918613, + 0.5826151198401351, + 0.6611524051909117, + 0.6639026308622665, + 0.4582947636906923, + 0.6842924166807584, + 0.6379254904536835, + 0.5932599451212489, + 0.5484417920643749, + 0.4861573131016955, + 0.6122073152581302, + 0.508749192979649, + 0.45785488456832096, + 0.6289875123178692, + 0.6757765768482292, + 0.5821276081257547, + 0.617893719758347, + 0.6877791431914818, + 0.5073305233842073, + 0.6006005609881351, + 0.518383127372612, + 0.608766648314672, + 0.5564339485302031, + 0.6528111877842839, + 0.6066279557013735, + 0.4802560522868241, + 0.5171413427932167, + 0.5237885940493258, + 0.6459823751035322, + 0.452680235702043, + 0.4852279636364282, + 0.4532187183310656, + 0.5445880704433932, + 0.49520839071118994, + 0.5489302628053484, + 0.6796273009558792, + 0.5975627298378718, + 0.5325212355561555, + 0.6484831678023841, + 0.5659538101328176, + 0.5702243381240086, + 0.47564055350239254, + 0.5046998748212571, + 0.5134558366072096, + 0.6759907026161261, + 0.5009483976132615, + 0.6708094636732214, + 0.5491593174425095, + 0.4735973610048871, + 0.5369271663149024, + 0.5700876715650587, + 0.5861671290261231, + 0.6623573118503014, + 0.5157046808824112, + 0.47664120072512495, + 0.5991227211406474, + 0.5394461543812064, + 0.5762088134329347, + 0.6343946532493296, + 0.6026938861028385, + 0.5350226691341093, + 0.6266648519942175, + 0.5689561033568482, + 0.5948700184772966, + 0.5415206628135852, + 0.6273342910676745, + 0.4864915323974527, + 0.49754799597030086, + 0.5935788383819305, + 0.6318770560368379, + 0.6652397483014921, + 0.6461605175020405, + 0.46457911815838304, + 0.4876532741831556, + 0.6721658076466858, + 0.4549948956007423, + 0.6751282080706265, + 0.5066620775200005, + 0.45745976617503664, + 0.5587267223851271, + 0.5235557727610146, + 0.61932291328902, + 0.5614809044542409, + 0.6770320369316594, + 0.5147858571433801, + 0.5317661544529552, + 0.5735270504578415, + 0.5594949485554531, + 0.6688832711859525, + 0.46533991057628943, + 0.6026056319131985, + 0.6609151405209581, + 0.4917086708772584, + 0.467519219744807, + 0.5743176159320686, + 0.5332672707323111, + 0.48644328638593864, + 0.5454858056731176, + 0.5422694152918429, + 0.6710676097438179, + 0.6447224525986643, + 0.6249046065525313, + 0.5374283794673806, + 0.6180449001918733, + 0.4470269895504511, + 0.6293395183234738, + 0.6846117435049421, + 0.5400166562629642, + 0.6201473225570471, + 0.49199742844059347, + 0.5600047217121326, + 0.5916895275965386, + 0.4861792066162054, + 0.46344797169530194, + 0.5397613355613934, + 0.6575160089176786, + 0.57046675585739, + 0.5900976874135411, + 0.6233938761521802, + 0.45071113164655424, + 0.44411648107329854, + 0.4772744765010661, + 0.6736616657476073, + 0.5349378670149125, + 0.6790972645855022, + 0.688418906900533, + 0.580459520259601, + 0.4958253053697415, + 0.5110243107717471, + 0.47286700717024205, + 0.5171702878208336, + 0.6557819086178801, + 0.46080771757343975, + 0.6302871730958612, + 0.6720399334756872, + 0.63785386273174, + 0.6628478902987767, + 0.6073282593468032, + 0.5305884308475555, + 0.6403329440271108, + 0.612523054927751, + 0.5726026402356172, + 0.6810613516975076, + 0.6737477660490385, + 0.5777057241994598, + 0.5949577044130847, + 0.5079663022267633, + 0.6305740542175959, + 0.5633448499306525, + 0.5298784335944121, + 0.47594453613662535, + 0.4543115039076745, + 0.5360348867448483, + 0.5992627594353064, + 0.6488801278232712, + 0.5203982185174928, + 0.570855375940902, + 0.5565990573592149, + 0.5082444282208429, + 0.541224602099551, + 0.6371839384791258, + 0.5545795833672293, + 0.5866941747585929, + 0.6104656599704044, + 0.6793906863769346, + 0.649000814708868, + 0.5050049949772218, + 0.505290544011391, + 0.6512237678819919, + 0.5454985577144491, + 0.6682696157804399, + 0.4492770875216058, + 0.6363166369373892, + 0.5398248689102958, + 0.6261716921225101, + 0.47495802240236795, + 0.6496465277835312, + 0.5397161120499412, + 0.5270946231630333, + 0.6759260597741766, + 0.4782351668691652, + 0.5465102813893006, + 0.5042788113410759, + 0.5873537692287394, + 0.5312122988678314, + 0.5400895295297271, + 0.5333589046223847, + 0.621120411016689, + 0.6300477994833444, + 0.6704153402787473, + 0.6099034258892274, + 0.5993677384840124, + 0.473681057758156, + 0.48638303642087455, + 0.4553856268010249, + 0.5121732987820442, + 0.47117721746006114, + 0.4611157411812807, + 0.58871075183627, + 0.6813294173681466, + 0.5767365639412079, + 0.6209029989790792, + 0.4420247610522552, + 0.5075463771024872, + 0.6381788874854437, + 0.6585090034806038, + 0.44688523232490135, + 0.5603895898682518, + 0.4922976321271781, + 0.6668182212140906, + 0.6480484999936643, + 0.6536068292715083, + 0.6415076399731957, + 0.49392715200004195, + 0.5156014749638985, + 0.6555315820418028, + 0.520880580454417, + 0.452507176545225, + 0.5825923818025156, + 0.5746169579288015, + 0.6197140122301901, + 0.6663206011097872, + 0.6125868442427759, + 0.520759588771704, + 0.5770476199277546, + 0.6317796255273171, + 0.5979350766597775, + 0.6878727008284481, + 0.4953881624202081, + 0.5055835892980932, + 0.6455357929735017, + 0.5828349019426506, + 0.5488844781091924, + 0.510053732508797, + 0.602448534753106, + 0.6578146958330826, + 0.5872752462320134, + 0.6231127425886915, + 0.51411010473866, + 0.5906964428412144, + 0.6235620973479499, + 0.6589348374348173, + 0.5058558413209598, + 0.6133236037798588, + 0.4553568501411271, + 0.5837508568172296, + 0.6847319404181388, + 0.6464966411508045, + 0.5045937750748417, + 0.596801279746143, + 0.4953829381851132, + 0.6221764692744409, + 0.6490762518886326, + 0.5820951650244303, + 0.4637442345513976, + 0.4485009321217292, + 0.6020508641708835, + 0.48910850024806274, + 0.5136491433064744, + 0.5928477295773652, + 0.5187846546028957, + 0.6647687022523642, + 0.5694188900638919, + 0.5100734475184782, + 0.6809891734768069, + 0.4415034885134082, + 0.59806893126845, + 0.6682750161796296, + 0.6170196353356325, + 0.4752526706447212, + 0.6675075238997277, + 0.5365920569840825, + 0.6028632425148858, + 0.5718983159314278, + 0.5161666562288232, + 0.6864591962274613, + 0.6461565819205466, + 0.45195064988748535, + 0.5273758052602588, + 0.5963193520373982, + 0.46842978902967114, + 0.44040568680232894, + 0.663599497955135, + 0.4996286661559152, + 0.5310964915691021, + 0.6064636189832846, + 0.6724956196990224, + 0.5549224678597031, + 0.5343767972804702, + 0.4510618203864506, + 0.6802593070153203, + 0.6713009387206551, + 0.6502589501801443, + 0.48853354585148406, + 0.6533911110567924, + 0.575201878388209, + 0.5382009065520142, + 0.6630102267723061, + 0.5909527846568671, + 0.6822621215663061, + 0.5829930815045646, + 0.5387541042814421, + 0.6818453223862013, + 0.5644236882580194, + 0.47356312941826784, + 0.5737930300367988, + 0.5419617775999377, + 0.679573181143447, + 0.4983700349317091, + 0.6540785516494995, + 0.5543618074213594, + 0.6745591204012894, + 0.47180443245598164, + 0.6353534765310168, + 0.5132174749485202, + 0.47522666737931085, + 0.6477698838565659, + 0.5909291122683032, + 0.49314378107208195, + 0.49413744220732414, + 0.6120921739871817, + 0.6240857735796161, + 0.676741642013726, + 0.4461032605783101, + 0.6680158727367953, + 0.562367691646534, + 0.5493809306312918, + 0.6657891858228522, + 0.647323906744831, + 0.5904704798806705, + 0.5610914237342892, + 0.4574910656540736, + 0.44711246269207483, + 0.4574073263518592, + 0.6584002189540772, + 0.4711861333072987, + 0.6230464684606345, + 0.6664925887494677, + 0.4874991719441998, + 0.48768578450858957, + 0.673253523460956, + 0.6195507059562215, + 0.5712599641859164, + 0.5928846595571706, + 0.5245421608182054, + 0.6674174828607122, + 0.4981343565978367, + 0.6749099538871053, + 0.6285286724812368, + 0.4798466143595557, + 0.6375986834556651, + 0.5379913947900841, + 0.677232257862376, + 0.4770981167624788, + 0.5813039311466119, + 0.4812659491905324, + 0.46565608018250304, + 0.5983020023364553, + 0.6771897882905611, + 0.588365257075346, + 0.5038784331705632, + 0.5870042117685544, + 0.5156012697600094, + 0.6390028571164954, + 0.4465845929897713, + 0.4834287568552667, + 0.6435338381236233, + 0.4719564282450519, + 0.6615399564586779, + 0.5841487758256522, + 0.6768229276706309, + 0.5137289162817298, + 0.47458147431616454, + 0.6410537265373663, + 0.5993423708038758, + 0.6255905748407818, + 0.6418677829657461, + 0.5583520925285561, + 0.49711816857129915, + 0.5743507998488486, + 0.529172300951572, + 0.4646750579205994, + 0.5656955661570603, + 0.600524699402453, + 0.5055794211525587, + 0.4845196374654296, + 0.5928565474083993, + 0.6423532511863816, + 0.61943830863567, + 0.5424779197937997, + 0.49484403080563033, + 0.5204864741736048, + 0.542197583894015, + 0.533406489091549, + 0.5031736898832778, + 0.618420219800552, + 0.523406774156385, + 0.5524990973457703, + 0.6316590412863994, + 0.5146160407087266, + 0.46111895266441977, + 0.5435379718541178, + 0.48461606594411655, + 0.5330754524046176, + 0.5163496312670226, + 0.47241813970064034, + 0.6353998415766445, + 0.6033665305413192, + 0.6216983855397142, + 0.625235601076527, + 0.6453143141545388, + 0.5367146211264028, + 0.5759659480892226, + 0.4586804509029464, + 0.5236516156013363, + 0.46341914300525605, + 0.44373395421149303, + 0.5864011007018778, + 0.6628093107579794, + 0.5501261721994056, + 0.5008962633259116, + 0.6268404303127675, + 0.6337865244364751, + 0.5677150406432929, + 0.5376053499451408, + 0.6256421697007901, + 0.4479520217231885, + 0.6029021741424636, + 0.6533066482311221, + 0.44073948339569874, + 0.6852288159952605, + 0.5033079696934951, + 0.6407004387008444, + 0.5407359893872612, + 0.4858453294113767, + 0.6748294004336531, + 0.6072447821742426, + 0.5507531490612361, + 0.5556638470779973, + 0.5999761261646155, + 0.6002801654766594, + 0.6264377819299418, + 0.4799363148647046, + 0.4409319833084819, + 0.5202886248720847, + 0.5856081454024942, + 0.5266054148541247, + 0.4928972054246613, + 0.6784094076009245, + 0.594144232676878, + 0.4467061885575061, + 0.5242769389679874, + 0.5977239575864146, + 0.5313010458338008, + 0.6663181746181677, + 0.57838628442191, + 0.45548401041143244, + 0.4696854870239617, + 0.5502510520150259, + 0.6191333361019009, + 0.5901087915246737, + 0.6846006025623126, + 0.623072408490327, + 0.4666208883246648, + 0.4407422273830585, + 0.4685041671440134, + 0.44634302320509855, + 0.5538806614175227, + 0.511742756582038, + 0.5848830472229165, + 0.46065678244142994, + 0.6395330833020576, + 0.6631679818499749, + 0.530823576653358, + 0.595964073161044, + 0.5664666762670318, + 0.6105823011400332, + 0.6760483570257254, + 0.6560387257470377, + 0.5380538631885678, + 0.681561023472872, + 0.61044574981332, + 0.5451876947807309, + 0.6534431608833478, + 0.4696830584239785, + 0.6283715659903822, + 0.6091530069198182, + 0.6644667557196912, + 0.49400908875181737, + 0.5145750355429021, + 0.5636409611751932, + 0.5703201999854615, + 0.6561462970099134, + 0.6507188861870264, + 0.6731972642489823, + 0.5641505437065089, + 0.6364305137303803, + 0.5974410397931831, + 0.4661001428892439, + 0.5499410585076306, + 0.4713236989136648, + 0.553335155880864, + 0.6597702556411773, + 0.6157139936270204, + 0.5544573054042432, + 0.49572066570793116, + 0.5618286383063963, + 0.6808228025686677, + 0.5885397523208873, + 0.6313816809845088, + 0.5530649333508254, + 0.5259510497843658, + 0.5944323636566966, + 0.47499729848155475, + 0.533056020923961, + 0.6640611921823883, + 0.6517167488960545 + ], + "y": [ + -0.6668315582497104, + -0.6607717232360909, + -0.6734836085326449, + -0.6648484340627668, + -0.6601144095520328, + -0.6735782744568081, + -0.6741068489839217, + -0.6708113710956819, + -0.6600021148484858, + -0.668209560908767, + -0.6810238564043525, + -0.6747319386960823, + -0.6655083002309671, + -0.6676342688126873, + -0.6709127696259357, + -0.6616939113576187, + -0.6670043758446376, + -0.6794089951474087, + -0.6806595873674365, + -0.6729146476292305, + -0.6801393222295911, + -0.6635532737253048, + -0.6761271632408935, + -0.6781492576694402, + -0.6708015327553323, + -0.6815640661247026, + -0.6786101698233435, + -0.6601226732382303, + -0.6803427840437134, + -0.6684230617207001, + -0.6800345398912112, + -0.6624305937040923, + -0.6686817701917931, + -0.6814082479615897, + -0.6752499599964129, + -0.6759448102887547, + -0.6608604929434724, + -0.6780391263180388, + -0.6784596482206593, + -0.6685874680754338, + -0.6611364528019225, + -0.6616305468791639, + -0.6725095680669281, + -0.6752618577346545, + -0.6684685331479833, + -0.6754861192468661, + -0.6669095255806634, + -0.6719759039655189, + -0.66349545825677, + -0.6624690980716645, + -0.681029124398183, + -0.676027169688359, + -0.6663724132530578, + -0.6790151977333169, + -0.6656955458896762, + -0.670999153115518, + -0.6732636740285202, + -0.6716583646720663, + -0.6623301189181595, + -0.6789748946897183, + -0.6660518943417102, + -0.6804023854773296, + -0.6635999590430296, + -0.6625833488718693, + -0.6686482839808547, + -0.665034923412679, + -0.6651386206256462, + -0.6812021962585506, + -0.6656023595105909, + -0.6743101003938928, + -0.667408855496101, + -0.6638889131156603, + -0.6786386466972024, + -0.6644583037912002, + -0.678241459782015, + -0.6658637406616716, + -0.6713321407718726, + -0.6663589768210818, + -0.6683963424076872, + -0.6649152540724507, + -0.6614391902671382, + -0.6600870545974268, + -0.6638714852310684, + -0.6722783250295027, + -0.6791038037896756, + -0.6616972033603041, + -0.6699963982079004, + -0.6814622752642873, + -0.67037772541873, + -0.6697524898165127, + -0.6624838842108858, + -0.6750077294553942, + -0.6621166120604769, + -0.6794448064972691, + -0.6727153389069879, + -0.6700439335381183, + -0.6653334581972157, + -0.6706500805230011, + -0.6696248859901208, + -0.6736595122836092, + -0.6647474016030142, + -0.6784742833247671, + -0.6682247727373081, + -0.6793404918928848, + -0.6789879552552042, + -0.6665522918001517, + -0.6725687217495101, + -0.6763828889435609, + -0.6633478271918115, + -0.6734779172672405, + -0.6718755825237295, + -0.6634644739458591, + -0.6728388974892653, + -0.665893028598915, + -0.66360927940724, + -0.6668630446581929, + -0.6805694219166992, + -0.6600016685609515, + -0.6767993365018428, + -0.6628784142771201, + -0.668069430459897, + -0.6630094378498275, + -0.6649792741340865, + -0.6736256754221178, + -0.6601854044099229, + -0.6681298835958325, + -0.6675139484154593, + -0.679485271337036, + -0.6630549548190117, + -0.6793751383270976, + -0.6641212305458718, + -0.6747589995581781, + -0.6800306494730497, + -0.6800537857301149, + -0.673189707894642, + -0.6785363773867807, + -0.6806655175984281, + -0.669791406194355, + -0.6709297505587711, + -0.6665925397240791, + -0.6777822316262804, + -0.6657868434021211, + -0.6746257728753862, + -0.676934378120157, + -0.6816606478853694, + -0.6792935384036003, + -0.6620972125197958, + -0.6715282627579485, + -0.6753875599138137, + -0.6711049291320145, + -0.6811630728978785, + -0.6813101183842576, + -0.6730046082188708, + -0.6789471339915577, + -0.665484754660063, + -0.668484303431873, + -0.6790132675532744, + -0.6724087861492395, + -0.6816738098633567, + -0.6708724694540651, + -0.6799395157869776, + -0.6667230311336361, + -0.6613888214394994, + -0.6722024560387154, + -0.6705229606974431, + -0.6732628502299816, + -0.6774032351932198, + -0.6819048051556147, + -0.6687292734290918, + -0.6644799955488142, + -0.6630744810459788, + -0.6669542907348902, + -0.6665104130871184, + -0.6678838495507202, + -0.6760620629373462, + -0.6707632403373756, + -0.6821754864903348, + -0.6775827486676745, + -0.6697086158399632, + -0.6652845109826999, + -0.6675286318015882, + -0.6699829165754368, + -0.664129998508875, + -0.6674554434783793, + -0.677712654442334, + -0.6715523181026741, + -0.6739968027378956, + -0.6674155691879449, + -0.668388401030937, + -0.6751776573390158, + -0.681385694785165, + -0.6788438261114769, + -0.6632623111584615, + -0.6701012429670912, + -0.6658784799883879, + -0.6657982390325247, + -0.6697534288233896, + -0.673410422068826, + -0.6716731203352927, + -0.678414365784445, + -0.6772358935718839, + -0.6704569079089455, + -0.6774115684936481, + -0.6634089080342599, + -0.6654988762997748, + -0.6766630069211315, + -0.6704526114722102, + -0.6638563205904499, + -0.6623522212722996, + -0.6720971565525999, + -0.6618848024544746, + -0.6672966837142845, + -0.6767390334295673, + -0.6635898629605181, + -0.6671732890960824, + -0.6711029287955335, + -0.6743143672926114, + -0.6664002013520213, + -0.677022068617002, + -0.6803103453781107, + -0.6627961287367365, + -0.6731622466425224, + -0.6622332555396757, + -0.6753688675178237, + -0.6688690194134916, + -0.6798733339734938, + -0.6803010995969407, + -0.6709962067337474, + -0.6710277458115799, + -0.6759657168545066, + -0.6623809848059093, + -0.6807805626940766, + -0.671197998465091, + -0.6626505924223711, + -0.681108552956101, + -0.7550480737375442, + -0.7700508042743419, + -0.7782544080505506, + -0.7716517340380081, + -0.7459698860230158, + -0.813258205662125, + -0.6653744576128835, + -0.772372774959879, + -0.7881544620345647, + -0.7385543501162286, + -0.7570717632350344, + -0.7564802024617285, + -0.7443714043123986, + -0.6684741534165765, + -0.8264514242214777, + -0.7382607176484661, + -0.6722380126078511, + -0.6722736714783935, + -0.8247960180349698, + -0.8238968211581758, + -0.7389379574180137, + -0.7197925232855579, + -0.7346160509791788, + -0.7929974608198715, + -0.8222229324433125, + -0.6822929243449354, + -0.7646085699190248, + -0.6783515914506314, + -0.715703320879585, + -0.7039495728807266, + -0.7779935560887778, + -0.6846362563479755, + -0.7507331193740083, + -0.7625099337739474, + -0.8229018467229415, + -0.7141719539403572, + -0.7744426924392408, + -0.8085757987463338, + -0.803262131328913, + -0.8307839794714205, + -0.8115977636024669, + -0.6616305749318847, + -0.6682572064817258, + -0.7265224026351195, + -0.7528886414006531, + -0.7476803467922635, + -0.8062595007602467, + -0.6799270062216481, + -0.7658867536367069, + -0.779675706103769, + -0.7565805315241936, + -0.7019927592301515, + -0.7233288049630601, + -0.8195303470675402, + -0.7103901484647628, + -0.789926476780958, + -0.6751284502208781, + -0.7744874902187052, + -0.7409722201890181, + -0.6738623139557299, + -0.725912780009047, + -0.7088820976523971, + -0.6943214731562302, + -0.8194206874593121, + -0.7105287272107857, + -0.8187459219875597, + -0.7901574789411663, + -0.7237477193293037, + -0.7303245668159615, + -0.7350174367353821, + -0.7737531164683726, + -0.7864612212084223, + -0.834426886674589, + -0.8075993178938186, + -0.8301893159543754, + -0.6822211093225895, + -0.7249852174989648, + -0.7478896072643013, + -0.7058525700990499, + -0.8234900933902415, + -0.673486018855391, + -0.6820582938331424, + -0.6626685224627331, + -0.7678152559593878, + -0.6637675045502154, + -0.8098493871281369, + -0.7761539374046893, + -0.6730984506310912, + -0.8237310635007012, + -0.8034088857432466, + -0.7094067384896414, + -0.673147489554224, + -0.6615175411413035, + -0.7058869052823308, + -0.6801505426516146, + -0.699163005139636, + -0.793145743091007, + -0.7272759780073839, + -0.7455548045425309, + -0.7508776300501376, + -0.6774609452416194, + -0.7063711552609242, + -0.7272619435902099, + -0.7191066762401417, + -0.7281229875288082, + -0.6811349741114315, + -0.7157349784026603, + -0.6646109788614872, + -0.72916632493988, + -0.7032535081282314, + -0.6726745225410686, + -0.7939063601483893, + -0.7846332043571312, + -0.6673516576861149, + -0.833690093725783, + -0.6781974856458242, + -0.786460791705098, + -0.6710350384553365, + -0.8130793980382292, + -0.8161282027834666, + -0.7924785827970315, + -0.707601712295763, + -0.7703341650338985, + -0.7903560701375452, + -0.76894070077479, + -0.8121487718308653, + -0.7778342724029614, + -0.7644168685291115, + -0.8340558384257699, + -0.8099223431097283, + -0.7668808416440193, + -0.6938201226897618, + -0.8163594330642331, + -0.6864247168143086, + -0.726556942246358, + -0.7244998671420729, + -0.8250902157580843, + -0.8154055161595841, + -0.6771907144736422, + -0.665518589521108, + -0.7401015585212822, + -0.675725574620545, + -0.6684483636941078, + -0.70319476751211, + -0.8056608122368586, + -0.78103247853344, + -0.7941383790635234, + -0.6763479786704576, + -0.8230671888626349, + -0.6804016976654421, + -0.734018290962105, + -0.7758108305168734, + -0.810578489574495, + -0.8328521296909948, + -0.7055825457727347, + -0.7271653094124735, + -0.7438833815468646, + -0.7530709813849679, + -0.8340066856453975, + -0.7635882684524131, + -0.7651097620020356, + -0.6810507902582957, + -0.8135457328114536, + -0.7951062543748123, + -0.7731134945082683, + -0.8240208119638317, + -0.7855281286460393, + -0.7435555440835219, + -0.6980094194044031, + -0.7243783499017039, + -0.6782157852678071, + -0.6743299916685357, + -0.6795029957609606, + -0.8169138127958112, + -0.8071792831357405, + -0.6649093174140212, + -0.7107651788426641, + -0.7671627671547131, + -0.8263489534758648, + -0.6888742171614677, + -0.6802714311373391, + -0.7541625412922905, + -0.697543279125809, + -0.7051697939011387, + -0.7563976354261818, + -0.7987879114369322, + -0.778251822752214, + -0.8063394711458748, + -0.7511400220169278, + -0.822130120712597, + -0.7029070066387854, + -0.7667100315918466, + -0.710075193567092, + -0.6856854678644342, + -0.738068310579318, + -0.7534921703739801, + -0.730566801240356, + -0.8008915400753656, + -0.7782593909557118, + -0.6907498347548435, + -0.7434121961664377, + -0.7495233296291057, + -0.7913549498229313, + -0.8247877089659689, + -0.8338639450946366, + -0.7376435930412029, + -0.6602984878796936, + -0.7325481423223247, + -0.7785467405402002, + -0.8229733499431098, + -0.7364987700080374, + -0.8333856528734969, + -0.7224646329880053, + -0.7188285312502795, + -0.744996544658949, + -0.6610901454131257, + -0.6657632512685674, + -0.6865572705948827, + -0.6712657636208094, + -0.82297249928589, + -0.7084903986398872, + -0.6923047165980777, + -0.8350832760221285, + -0.7843329564879894, + -0.7016088072904788, + -0.664595471234724, + -0.7089511475145462, + -0.7943069869850155, + -0.8039659388281586, + -0.786032646584564, + -0.8355581074821987, + -0.7676399950250029, + -0.7325807122922863, + -0.7313089828757705, + -0.7445447025929075, + -0.8126207703888411, + -0.7522482617598435, + -0.6673336736344954, + -0.7841366678125136, + -0.7533505739557564, + -0.7620782889164662, + -0.7973802874162664, + -0.6814494711604994, + -0.8308241210591553, + -0.7823243778473227, + -0.7255866563706734, + -0.667956276819303, + -0.7722823404694855, + -0.6738741949185535, + -0.7075307939421692, + -0.7737450496760783, + -0.7241299116454691, + -0.8056051026073199, + -0.7787698186371698, + -0.793520506547801, + -0.8221576940215211, + -0.6804121469044682, + -0.747936122848166, + -0.7992463745631503, + -0.6745299914069663, + -0.6900487897941718, + -0.7608287034626816, + -0.7614107044100887, + -0.6821101218936483, + -0.6862242856914691, + -0.7882844604303259, + -0.7749655371147081, + -0.6632308063885255, + -0.6886394522228545, + -0.7162415367498481, + -0.8047731402026982, + -0.7824005295844706, + -0.7702952696125301, + -0.7195918179831468, + -0.7238913091640233, + -0.7058713242532055, + -0.7920935722716821, + -0.6799519040032227, + -0.7985243941537684, + -0.7034530292601273, + -0.7942616689733097, + -0.7534608628090214, + -0.8071758874887176, + -0.7072224724718614, + -0.727193809867404, + -0.8355877940318558, + -0.6636482907044227, + -0.6885194167696791, + -0.8354475492910146, + -0.8296952538928686, + -0.7791096848062058, + -0.7935005023416783, + -0.833137344867706, + -0.7316111299640603, + -0.8278965658709779, + -0.7406299474363365, + -0.6708307866022678, + -0.666594281092812, + -0.7201542310819646, + -0.7501050255315991, + -0.6959459346888494, + -0.7665397683466448, + -0.7648761928732528, + -0.8157962444737346, + -0.7246562812234288, + -0.7989153221918939, + -0.6811843173904725, + -0.7118526975068795, + -0.7130582125677072, + -0.7600229605332812, + -0.8132641233383618, + -0.6960006471484601, + -0.6711677578745348, + -0.8092669985751347, + -0.6806271179322796, + -0.8309918968511073, + -0.7015330178711308, + -0.7099908022480316, + -0.8120013626181489, + -0.7690642094681567, + -0.7949442586177609, + -0.8126108547148896, + -0.7975269209209525, + -0.7723684904899175, + -0.7236285003560037, + -0.824875182178552, + -0.6737105831032661, + -0.6746334710088274, + -0.7713829270909439, + -0.7982173079035647, + -0.7146767285383223, + -0.7456110333103381, + -0.7299202112068949, + -0.7361616550135257, + -0.7651962362302359, + -0.6798911816834488, + -0.83453105243257, + -0.7827480013744251, + -0.753314430634882, + -0.712287068354362, + -0.8171208786368336, + -0.6928055708181534, + -0.7034587008303026, + -0.6998306982838088, + -0.7659412983191896, + -0.7626933613702673, + -0.6987831112980343, + -0.7665664945388198, + -0.732514630242331, + -0.835159971395085, + -0.7960555728150671, + -0.6624521158284828, + -0.6650825972842178, + -0.8285385099974382, + -0.6768630818028816, + -0.7502354658669186, + -0.6621892235599265, + -0.8259347929896327, + -0.7666720422135725, + -0.8042976825764987, + -0.6857761871204634, + -0.7075588493116662, + -0.673633584352862, + -0.728091397956582, + -0.7751308091432209, + -0.6610808409837761, + -0.8084960003272387, + -0.7078558951070324, + -0.8033976602390185, + -0.7440054139058898, + -0.7326996170383223, + -0.8217380337655922, + -0.7783837521232595, + -0.8319449741572128, + -0.6886211580497246, + -0.6973604113516507, + -0.796571700829335, + -0.7114886982815574, + -0.6633207047796961, + -0.8255043165648837, + -0.8009799877328936, + -0.6734112140683804, + -0.8280576759126022, + -0.6996544065731518, + -0.7322424703153588, + -0.8304458832137517, + -0.7976890023669266, + -0.7646890258212374, + -0.792286884473739, + -0.822125915635598, + -0.7219766170090036, + -0.6605889253978399, + -0.7086872672082686, + -0.7852445739073513, + -0.7160767119241964, + -0.6633185619406062, + -0.726054234693227, + -0.8293310762188671, + -0.8320401958649182, + -0.8316494912736815, + -0.803854845508691, + -0.7888193969133659, + -0.7960190631085732, + -0.7505276094705273, + -0.6767603275038945, + -0.7049210060063188, + -0.7353275845889917, + -0.8025438841823124, + -0.7201546807622272, + -0.7393459328623858, + -0.6677600989575214, + -0.786978161646176, + -0.7255891408335892, + -0.7828770783003566, + -0.7314847853858286, + -0.805461239606957, + -0.7056861763113156, + -0.7124435416094477, + -0.7531815230053943, + -0.6812520998681151, + -0.75615195508744, + -0.7997099837361972, + -0.6840702574872144, + -0.804761430949785, + -0.7572440414987219, + -0.7266948311677792, + -0.7560997790725758, + -0.7722250094117946, + -0.7478681657272592, + -0.6783133002265753, + -0.7584735172959645, + -0.7990892325650848, + -0.8045439541675973, + -0.7434760750343037, + -0.8274151171301566, + -0.6996466290896213, + -0.7115570412810566, + -0.7500916489844847, + -0.6902268960474726, + -0.8344938979503924, + -0.7297201921129342, + -0.7437123509264861, + -0.8022632346433138, + -0.8330157591233298, + -0.743357994863301, + -0.6813794762397211, + -0.7305855162698736, + -0.8331256784393194, + -0.7290266064077335, + -0.7485449078323348, + -0.7949242791668527, + -0.7109712203661526, + -0.7510818447807749, + -0.7996534976173831, + -0.8321253129231411, + -0.7144568106354885, + -0.8207453465836858, + -0.6783704283170919, + -0.6912559083059868, + -0.7139967925361151, + -0.6666448175472063, + -0.7711233600541455, + -0.7132241347843964, + -0.7390717446711452, + -0.721828050290381, + -0.7119120505561063, + -0.8114976905985238, + -0.7829850909761285, + -0.6841761431622809, + -0.6615905243696381, + -0.6788139471188979, + -0.7728528954634926, + -0.8159593446313599, + -0.6659238273067507, + -0.6951811517705647, + -0.8035158155011675, + -0.7803408644296642, + -0.8287676702173308, + -0.8074423015070183, + -0.7499322844434906, + -0.6737840634886919, + -0.7923996084907751, + -0.8169983280885328, + -0.6648049424514686, + -0.7785648062938746, + -0.7567159784680273, + -0.746932457371329, + -0.802441079404493, + -0.7000652769415209, + -0.835673825787137, + -0.6647551480505209, + -0.7857803673353725, + -0.672913883975, + -0.7816910464585823, + -0.7755546233631542, + -0.7439295233336051, + -0.775440374217991, + -0.7870928972483304, + -0.7992329237875478, + -0.6612956831065583, + -0.7441024931198996, + -0.7215773729977581, + -0.665257318207789, + -0.8047264632541332, + -0.7604221650305723, + -0.8279681265558309, + -0.738676173055996, + -0.7418581703490731, + -0.835709536504665, + -0.7261271417791573, + -0.8078057528105949, + -0.7465157559694033, + -0.7749339271613063, + -0.8263867478926271, + -0.7453028269647722, + -0.6969171792197236, + -0.7549130816265922, + -0.8151184059520992, + -0.7906197103355908, + -0.6630752825549934, + -0.7412698704141925, + -0.785330824419205, + -0.7273784598432189, + -0.7357355439250436, + -0.7469507995939915, + -0.7212474402653175, + -0.7888838470958228, + -0.7564756554530346, + -0.7232900486496534, + -0.6917251813625291, + -0.8067060415609156, + -0.7719156967215148, + -0.7654965587628239, + -0.8164718496625423, + -0.8219605895512176, + -0.8161122505354237, + -0.8161500645755572, + -0.8096866886643492, + -0.6787468886564013, + -0.7706365107823824, + -0.7951521324844868, + -0.8092899159023343, + -0.777332389857948, + -0.7759687100662466, + -0.8352152211834936, + -0.7197199504840377, + -0.7801804992294646, + -0.7308554381272105, + -0.8280623881223121, + -0.7693943536377885, + -0.7371779219692853, + -0.7034101699601231, + -0.7910848173148903, + -0.8349981932379735, + -0.6974372675759715, + -0.7381984925581548, + -0.715535901388076, + -0.6998256184429644, + -0.6979932276366669, + -0.7754708100408968, + -0.6920802609921068, + -0.6886628996121655, + -0.6766018190457601, + -0.7484783102271553, + -0.7560516975358652, + -0.7328270544855708, + -0.678773764967832, + -0.7449644225246008, + -0.7637869652995816, + -0.7255118281905292, + -0.8103129361028525, + -0.7770071804160785, + -0.6706668009689783, + -0.8344878608657206, + -0.7943092680973416, + -0.7824450276842315, + -0.6678327002890945, + -0.7869631612227626, + -0.7822380402712741, + -0.7571226227783765, + -0.7604863120597768, + -0.6842137451717931, + -0.7559195421027028, + -0.7550895581561887, + -0.7136606088209911, + -0.800045847374686, + -0.7009079370916312, + -0.8184933279961524, + -0.8263777656275307, + -0.6621661536276746, + -0.6779654560405483, + -0.8116133611117536, + -0.7457236486032972, + -0.7001659749943312, + -0.8231029416828308, + -0.6650849404656826, + -0.6671684342059201, + -0.8317382737237229, + -0.7139294452796198, + -0.7106955238036106, + -0.730812450457298, + -0.7515542078777542, + -0.8089913665926969, + -0.7281694590586684, + -0.7725550675105991, + -0.7982875376616315, + -0.7819822482206791, + -0.7539298483958087, + -0.8004776317709147, + -0.6783110748045309, + -0.7302089046958276, + -0.6672611518741829, + -0.829087994132587, + -0.7330825955712212, + -0.6839201866267168, + -0.6767094103319478, + -0.83326313253032, + -0.7523868813319714, + -0.6963540270840974, + -0.6903931018659589, + -0.7178522826496758, + -0.7063427532628819, + -0.7112262257384644, + -0.8172146500231713, + -0.7182015300548624, + -0.8014205015639055, + -0.732279688565351, + -0.8086280890351819, + -0.8260936111909047, + -0.7715564747786698, + -0.7284311993361339, + -0.7626640848466565, + -0.8306834924544417, + -0.6744156936064473, + -0.8116898244082678, + -0.8293661271975058, + -0.6655153139915966, + -0.8234774193450263, + -0.746351646398022, + -0.7316559677828094, + -0.752314766086528, + -0.8346448360483761, + -0.7069861935141787, + -0.7315273242568833, + -0.7945086097040398, + -0.7586570372140273, + -0.7695445964658535, + -0.7742175445632238, + -0.6761759489637708, + -0.7248990350225196, + -0.748681360151267, + -0.7057106724260827, + -0.790420953434917, + -0.8348965730830888, + -0.8028652136636467, + -0.7088433535414069, + -0.8155027213726929, + -0.6877195090259133, + -0.7837838653062755, + -0.7070060843110465, + -0.8146410546856672, + -0.6652947606734037, + -0.7895254858707297, + -0.6929497377223192, + -0.772051910427223, + -0.7333356620688575, + -0.6792012054630188, + -0.7783760585342844, + -0.7696835904521142, + -0.7766805461085348, + -0.6844125199228139, + -0.8051397612346801, + -0.689884881862723, + -0.7302611723326736, + -0.8034874249970195, + -0.7511510691018026, + -0.7669609887945885, + -0.7505242944126276, + -0.8162291454006615, + -0.8060288167538795, + -0.8061009501676896, + -0.7885667704241367, + -0.765463722562502, + -0.7765839602677905, + -0.682403970234991, + -0.8090869208282194, + -0.7084390927646979, + -0.6723051008730145, + -0.7780501130713312, + -0.771464405199108, + -0.706998587949819, + -0.7383621084803403, + -0.7115971198065165, + -0.7224740116839953, + -0.7261845473607556, + -0.7328367436124184, + -0.7697121748669982, + -0.8044770647533237, + -0.8051838114206711, + -0.7958976981706649, + -0.734049860433513, + -0.699829620517348, + -0.7353963160207255, + -0.7723421076811362, + -0.6750230122671342, + -0.7346533717368113, + -0.8017417549541268, + -0.805668412722908, + -0.6874572215726654, + -0.7467324511456784, + -0.7822494644316924, + -0.7649293826709853, + -0.6630421681098388, + -0.8035963733056171, + -0.7635645939534003, + -0.8170287350576222, + -0.8060169266774926, + -0.7918707669550552, + -0.8051358621337209, + -0.7741067206211896, + -0.8077212383340002, + -0.6807760859981533, + -0.7187772100857811, + -0.7933457021474601, + -0.6615052893213798, + -0.6741572907543824, + -0.7785994436612443, + -0.8249807938112317, + -0.7402675479582005, + -0.7751471934311521, + -0.776291600870174, + -0.8189482270199596, + -0.7945314391030577, + -0.702718455703975, + -0.8036860635812616, + -0.7150123253670456, + -0.8354460706463761, + -0.7146609132437063, + -0.6928516309249201, + -0.7704349143873858, + -0.6942822104510235, + -0.7504579291559716, + -0.763112830647559, + -0.7205830804577067, + -0.82032726349891, + -0.7475677655424439, + -0.7127978330187558, + -0.7092803207374717, + -0.8018971119821258, + -0.8316813444429473, + -0.682523513255846, + -0.7159776809268822, + -0.6731297407582348, + -0.805910630998889, + -0.8283754342897819, + -0.7042379129449897, + -0.7972233308080927, + -0.7021873060219943, + -0.7434034321690656, + -0.7347559394010152, + -0.7525435181050375, + -0.8065255640823976, + -0.8338430009025073, + -0.8153673822388482, + -0.7970690321916177, + -0.8112296656354614, + -0.8043127025017974, + -0.7535848586865637, + -0.7326354073132793, + -0.7730364703417674, + -0.6675352550399752, + -0.8255603338906623, + -0.6852088449044348, + -0.8274072481300085, + -0.8026447171746541, + -0.747703513042769, + -0.7658503300229599, + -0.7471666112370076, + -0.7580032505495681, + -0.8342322641264293, + -0.7859220400234854, + -0.6872998585749354, + -0.7684483229237675, + -0.8066101631950652, + -0.677770246794372, + -0.723694908025973, + -0.6996691121088756, + -0.8148528797745798, + -0.7227017020013761, + -0.8166476300861195, + -0.7071687273101697, + -0.8141905940277032, + -0.8129619417145891, + -0.7194192198301161, + -0.7122707755840421, + -0.7857517846497359, + -0.7926710110841614, + -0.7070409566039204, + -0.7494900489057295, + -0.6755839612614174, + -0.7381459082320976, + -0.8276393321481019, + -0.6883847050414982, + -0.7217052646367582, + -0.7825551186335278, + -0.6634665469862714, + -0.784291942017626, + -0.7907334963652433, + -0.8065640516749798, + -0.7485717078283011, + -0.7678453711297649, + -0.6776964031086968, + -0.8193504199164221, + -0.7853757449635526, + -0.8169233627294413, + -0.7329427765449498, + -0.754607355927222, + -0.6884872565306829, + -0.8049356812271311, + -0.7748003027592272, + -0.7183090814306557, + -0.8300828749619248, + -0.7726917697935423, + -0.6607448410221008, + -0.8318726598912668, + -0.7882032595404511, + -0.7124974519039113, + -0.691137499715052, + -0.6837527952355513, + -0.7269070751800313, + -0.6783790573243587, + -0.7974739059351071, + -0.661704893877711, + -0.7039593966939751, + -0.7288792659398644, + -0.7502824124093853, + -0.7257299897347189, + -0.6668237377763447, + -0.7685250976886537, + -0.7582545213400018, + -0.8175848547057764, + -0.8086795758561933, + -0.7202160221634921, + -0.7240793229355125, + -0.8041405991828462, + -0.7012423663225209, + -0.8289979776523071, + -0.6953247989489955, + -0.8197763507818808, + -0.7927126541871123, + -0.7745419597179259, + -0.6801143729638446, + -0.8098724958902469, + -0.7348721038117916, + -0.7649306368589943, + -0.7348572211068845, + -0.6823670694372289, + -0.8060209172621804, + -0.8190100614740629, + -0.808553853518254, + -0.7161198019140839, + -0.7395639535860393, + -0.8322813532893987, + -0.8057015329867047, + -0.7791900001795238, + -0.6759807202418799, + -0.7639058925083695, + -0.7992165229540897, + -0.7476245808867266, + -0.685615890970291, + -0.7512287558250097, + -0.6617690247928405, + -0.7241425113138633, + -0.7290470797058661, + -0.821492233718176, + -0.8145018293681907, + -0.7003419851179377, + -0.7324948341553764, + -0.7962927654674683, + -0.6624895778162612, + -0.7266546226682051, + -0.8009930241524401, + -0.700852625615311, + -0.7634817401927231, + -0.7613871781015813, + -0.741091480770212, + -0.7912443457456497, + -0.7717614660336781, + -0.8002760625135981, + -0.7808477616969531, + -0.7496711040529912, + -0.7887606046847084, + -0.8246485434315804, + -0.8007564421932661, + -0.6869591827563879, + -0.6642675384109239, + -0.8036040330109782, + -0.7450933264740762, + -0.6608016171364255, + -0.8329415699109566, + -0.8321364994685067, + -0.7759188771994832, + -0.7755071741930234, + -0.6611745637437869, + -0.7309749261477662, + -0.8195902874572819, + -0.8261760327022998, + -0.8261586953274711, + -0.6827776776475227, + -0.6902231989375408, + -0.708227284957025, + -0.8158871757125837, + -0.7771068785820622, + -0.7737474557102303, + -0.8137618404209013, + -0.7735390739430816, + -0.7389586846898676, + -0.7189207398199595, + -0.7694985166748853, + -0.8298615251018159, + -0.7711944938844584, + -0.734795732758682, + -0.7809437272989682, + -0.7664604022926084, + -0.7887763981056101, + -0.7519157750762033, + -0.819830118528508, + -0.7515263739758558, + -0.7237344391187804, + -0.7860231797675834, + -0.8347552056466568, + -0.7294609681988183, + -0.6985062381167275, + -0.6808715661910868, + -0.8085178954059372, + -0.7244798528453924, + -0.7232160491756314, + -0.800797835775985, + -0.7054689468340118, + -0.720670130107994, + -0.7092463656939829, + -0.671820909535419, + -0.7590494527427148, + -0.807008902527885, + -0.7413864118880518, + -0.7244461997335826, + -0.776193826870054, + -0.7685091383255443, + -0.7652657193928317, + -0.7295497213799542, + -0.6808803482337809, + -0.6671628284013221, + -0.7806204817373563, + -0.8332563176372794, + -0.7145707210949834, + -0.6658795727112901, + -0.7757095774297136, + -0.6791343084594479, + -0.7463593103037941, + -0.6879905471900265, + -0.8269538574941087, + -0.7925331975679658, + -0.8019306055751858, + -0.7978583191546155, + -0.7734415404982076, + -0.7733343612694255, + -0.6916864640815464, + -0.6710886236805942, + -0.7226408201571899, + -0.7859705474192591, + -0.7634724698948168, + -0.6754121736191556, + -0.815645963843626, + -0.7015606044965963, + -0.6766902552265069, + -0.8056857483889694, + -0.7512103607743637, + -0.7242051930540835, + -0.7034927414664988, + -0.7644210325254672, + -0.6985041687876037, + -0.8137719012085264, + -0.7510487557273047, + -0.6860044270890852, + -0.7500411828615946, + -0.7197451424514932, + -0.830638614304874, + -0.7199718731989564, + -0.8314210276356309, + -0.7184036089895018, + -0.8044190368108821, + -0.820957468138641, + -0.7979890372097239, + -0.8042246810532775, + -0.6834695183321303, + -0.7043042887732047, + -0.7442144910315847, + -0.7295397188909724, + -0.7041743229616958, + -0.7381115766596469, + -0.7451473388818608, + -0.7153301474356891, + -0.7851549124557691, + -0.7511779642321408, + -0.7218631007774687, + -0.6668972042094347, + -0.7945609716809614, + -0.6657518109030722, + -0.6661076487711511, + -0.7694383576041753, + -0.7187240255152396, + -0.7555192846222175, + -0.6940101966358655, + -0.777932778304707, + -0.6609640292035812, + -0.7031838221917944, + -0.7335809396037626, + -0.7281572752683747, + -0.82091815341052, + -0.7037962623268386, + -0.7725861280295447, + -0.6694798268529818, + -0.7258854904482572, + -0.6832106474707197, + -0.7905373629952333, + -0.6860189091101749, + -0.7498827646623354, + -0.7638921259094349, + -0.8225116637352682, + -0.7693301370245322, + -0.7017809560298673, + -0.7047341453883474, + -0.7935616053116399, + -0.6861092463462275, + -0.7814985440824099, + -0.7072259255499815, + -0.6922690179865233, + -0.7426461574662276, + -0.6611945475830058, + -0.7231773382144205, + -0.719223964442057, + -0.7415867277832808, + -0.7179975301204921, + -0.7534681434488055, + -0.7860827883247687, + -0.7150949434955256, + -0.7308553493343819, + -0.6849028276418915, + -0.6764321102877389, + -0.6912005550809454, + -0.7432787035275765, + -0.7581180847950434, + -0.7472308484003043, + -0.7339372042938143, + -0.7631376539593494, + -0.8236479719014453, + -0.753062659291688, + -0.7984319156272884, + -0.7591345048835786, + -0.7579324042786085, + -0.7321359378941679, + -0.7785891401863844, + -0.7654892022003195, + -0.7949554251081881, + -0.7220861382522039, + -0.6808029399560391, + -0.7874756762583942, + -0.726929736918245, + -0.7641723617157434, + -0.7870224358159312, + -0.7879327291664412, + -0.7676571732826308, + -0.740431915391115, + -0.7679786383553772, + -0.7205372495369959, + -0.6975937021489694, + -0.7984711500612328, + -0.816469032352262, + -0.6685605630967106, + -0.8158462750467356, + -0.7893214936805573, + -0.7209847205452403, + -0.675417172302675, + -0.7734205002872983, + -0.8163565423758142, + -0.7719428330031695, + -0.7200134944667342, + -0.7588359898622119, + -0.6942996270913391, + -0.6697364849664151, + -0.8196440229927361, + -0.7046144024794697, + -0.828878239171896, + -0.6745797460875506, + -0.7530246774811886, + -0.7042711287884228, + -0.8228147586469786, + -0.7053419147861161, + -0.753361607475682, + -0.7080246516002944, + -0.7066039653153351, + -0.7981780089178778, + -0.7380695130039006, + -0.7791852432128147, + -0.8062438171949244, + -0.691496866387765, + -0.6743026761158973, + -0.6797087247861324, + -0.7327445936998955, + -0.6730243507250218, + -0.7732333123630395, + -0.7536145588731309, + -0.7498907692552839, + -0.7092754783123563, + -0.7495629908781501, + -0.7134289407506087, + -0.7463221327569596, + -0.6661622298962875, + -0.8285140449305086, + -0.7217572085746564, + -0.8220509300373624, + -0.7032915905183276, + -0.7161266250466307, + -0.7497051998319542, + -0.7820504412334047, + -0.7215447463978629, + -0.718045886364628, + -0.6778062283371656, + -0.7045454676515164, + -0.7106286181896644, + -0.7594126538312894, + -0.6949473218762512, + -0.6735034892128875, + -0.7389811509205935, + -0.7966650507067484, + -0.6918493097444389, + -0.751538493058997, + -0.7194805126732625, + -0.826196891002607, + -0.8153632693412347, + -0.8195141186499557, + -0.7827880002190707, + -0.7113166376436426, + -0.7395509236636356, + -0.6845417835262262, + -0.6854195631446274, + -0.7939024567269681, + -0.726074138407989, + -0.700731378024858, + -0.7845095278228229, + -0.7329134112294323, + -0.7520678729193697, + -0.7098857098358355, + -0.6794296404658182, + -0.7954394734514968, + -0.7557763893374474, + -0.6982614671267724, + -0.709142820670944, + -0.7977602729639949, + -0.7304511929860439, + -0.7754903169111419, + -0.6866660702978364, + -0.6997394407979506, + -0.6806519161211915, + -0.7276667918817327, + -0.7037420724277814, + -0.8203494698491011, + -0.7382092927953118, + -0.7714691200082443, + -0.7456051302915591, + -0.7974742599530495, + -0.7795967521275193, + -0.664379911621959, + -0.6615359733048406, + -0.7122503239816743, + -0.8256374463516919, + -0.6722095887993098, + -0.8104573104176716, + -0.7262293761833939, + -0.8092179840389538, + -0.7481136957500293, + -0.6847036210995765, + -0.7478660833733526, + -0.7164314324049454, + -0.6695236789104371, + -0.7810500698125677, + -0.683012686863545, + -0.7746784094328473, + -0.7423412883439156, + -0.8120217343455189, + -0.68248489609433, + -0.7405647162081581, + -0.8223979041826204, + -0.8175848045187644, + -0.7577098286790351, + -0.6794382166682077, + -0.8102449800247057, + -0.6840159323938512, + -0.7115584430121399, + -0.7668303229166046, + -0.7532469961082087, + -0.7990926790016285, + -0.7908255359452269, + -0.7400648413333076, + -0.7806700319235775, + -0.7842981696573146, + -0.762849915750882, + -0.7359400974683139, + -0.7047783025312175, + -0.767068839734436, + -0.8320602314722507, + -0.6670746657543932, + -0.7396351112109698, + -0.7536904608351366, + -0.8122634391595059, + -0.6951727136926101, + -0.7108038100111121, + -0.7844716874369032, + -0.7386993854468169, + -0.7279561013390949, + -0.8141869854023561, + -0.6900177383585533, + -0.7456729952707224, + -0.7407088796393096, + -0.781234383256789, + -0.6824979592225305, + -0.8221075455756078, + -0.7361236420648409, + -0.69308728219416, + -0.7747336245240868, + -0.7285329654781827, + -0.6767785103834496, + -0.8106984851086882, + -0.6888939656418084, + -0.8113533793162885, + -0.7305416945207548, + -0.8118828167612738, + -0.7032115757803034, + -0.7110258813370773, + -0.7591466210619, + -0.8127886372697263, + -0.784543498887396, + -0.8332989355676585, + -0.6710397450917972, + -0.6667437436354945, + -0.8004916446960344, + -0.7740814276897928, + -0.6604128545049874, + -0.7809763698216374, + -0.8038788285614448, + -0.753773136289042, + -0.7967655064171028, + -0.6905375822929567, + -0.7686370140260429, + -0.8140466770851745, + -0.7360340439702867, + -0.676735329088197, + -0.705237244505745, + -0.724647213591253, + -0.708963250059781, + -0.8215858371427736, + -0.8280040066721611, + -0.7349758273530529, + -0.7878369674024881, + -0.7250247983606811, + -0.6775795574345846, + -0.8235549996497469, + -0.6613628171092509, + -0.7567113956537406, + -0.7589707049447523, + -0.8194633981066791, + -0.7434889607823605, + -0.6818577035263504, + -0.7715294389482633, + -0.7167509954601008, + -0.7604048375544813, + -0.7054460241109296, + -0.8308992549764317, + -0.7546339478847073, + -0.750998150561476, + -0.6839588171951025, + -0.7716787007805824, + -0.7752666894887743, + -0.7161152126569863, + -0.7935220510910086, + -0.7580917450527451, + -0.6725822493768121, + -0.7242977605214833, + -0.6965282300964566, + -0.7744894328112399, + -0.7068385456965384, + -0.8212802579924492, + -0.7205256624347034, + -0.7920606815346167, + -0.8192799600774374, + -0.7933332996209679, + -0.7349484572872734, + -0.7961269604063901, + -0.6876281856002915, + -0.7130989669732152, + -0.7643713222313075, + -0.8045448666193349, + -0.8318307283382318, + -0.6853877556516594, + -0.6784130150577691, + -0.7562586877076289, + -0.7753508645815662, + -0.7953627331150457, + -0.7858019954143771, + -0.6785642533327275, + -0.8318395520168014, + -0.6648549293764454, + -0.8325995359906213, + -0.6695559471688548, + -0.6907691391077199, + -0.8135955328727532, + -0.7120416818879115, + -0.8239336001817399, + -0.768269374422795, + -0.7970751856398991, + -0.8178047080490431, + -0.8162270700174056, + -0.7158506400014848, + -0.7709995541003154, + -0.8166335800469126, + -0.751792538455927, + -0.7606186245446659, + -0.7651915370435478, + -0.7781480168942141, + -0.6865471942091674, + -0.7975362119685578, + -0.7969845754535908, + -0.8093153287885395, + -0.771659152074682, + -0.7942510395246813, + -0.8073374400056346, + -0.7333838526717467, + -0.7821639125213337, + -0.7391198924219494, + -0.7978474450590188, + -0.811495374562393, + -0.6983899025422676, + -0.8072353782434892, + -0.8012768544211631, + -0.7094020257005068, + -0.6683326907725906, + -0.6733970537594458, + -0.6676018346252802, + -0.721397211425746, + -0.7186306975915865, + -0.6911298871903371, + -0.8184269336468265, + -0.8281801572713521, + -0.6826344738759813, + -0.7657413349271521, + -0.6648588231667041, + -0.8092975933556769, + -0.7664759600692458, + -0.7457665487106175, + -0.7383053791422212, + -0.7504579523006969, + -0.8252192557045882, + -0.7005449278793203, + -0.737527191472829, + -0.6635705867617753, + -0.6923023467969469, + -0.6759150086327271, + -0.6843045834150845, + -0.7965392001381394, + -0.705653586179075, + -0.8018724936232989, + -0.6758168980456765, + -0.7918443063109248, + -0.8214582722709775, + -0.7314537556130944, + -0.8009709748338796, + -0.6764500967540623, + -0.6915668356311722, + -0.8312898339377107, + -0.7726748841728975, + -0.6965879202278589, + -0.7470851416197308, + -0.8313066538944718, + -0.682748121296475, + -0.7416834329395237, + -0.7611711731989547, + -0.8252507900406041, + -0.813825085329273, + -0.717494227256099, + -0.7691354344162027, + -0.6699336837511043, + -0.6730105935219345, + -0.7876955126942233, + -0.7324726314575846, + -0.7737317664505395, + -0.6645787903049056, + -0.7811352246086984, + -0.799200938283895, + -0.7814403160231742, + -0.7160540390051745, + -0.7655759360988834, + -0.7129478870316048, + -0.7789882061106579, + -0.8268434811997617, + -0.7841068547246258, + -0.7831749553378087, + -0.6839181926719339, + -0.8351825098346952, + -0.7302108879103117, + -0.7636264847784875, + -0.775483545769101, + -0.7425379741428254, + -0.7099585866903056, + -0.7861056575824714, + -0.7830208749374514, + -0.8055514238274318, + -0.660773093972125, + -0.8358841388498345, + -0.7048998746068054, + -0.7401549894372459, + -0.8025733541637019, + -0.7357449293194307, + -0.7611882409207187, + -0.8098859406395319, + -0.7323269402094833, + -0.6909956073469895, + -0.7799368937875159, + -0.7117247053058924, + -0.6613071453271804, + -0.6753700490851033, + -0.7927748551599882, + -0.7994485489772362, + -0.8099137011892654, + -0.7010529901652411, + -0.8087175398356181, + -0.7135163849125548, + -0.7586508233893062, + -0.7062316024858314, + -0.7682167080005123, + -0.7482843856512988, + -0.7229194426807078, + -0.7995152463480076, + -0.7332686140310025, + -0.6869401736803206, + -0.7305076350884497, + -0.674854162064197, + -0.8356358471599818, + -0.6636312898081743, + -0.7764537974617706, + -0.6897455646008337, + -0.6798335406904626, + -0.7676401097370988, + -0.8315478728686988, + -0.7438644913641481, + -0.7876235904628198, + -0.6808924454891211, + -0.7405584847985626, + -0.6676475654898453, + -0.811080802971218, + -0.6792044208397449, + -0.7752790452014913, + -0.7380639420852709, + -0.7258777289821976, + -0.7317734739784144, + -0.744072993238142, + -0.7079495988044497, + -0.7761891360365165, + -0.7288068411436536, + -0.8026480820348187, + -0.7026274756584785, + -0.8323063438201126, + -0.782942974322496, + -0.8200614715197956, + -0.8205305384242583, + -0.7847023448973346, + -0.7846857785850245, + -0.8266765491526725, + -0.7891510508477445, + -0.7764420495822333, + -0.7772478777716779, + -0.7076141650990112, + -0.7588012693255143, + -0.7693398328936056, + -0.6634090217450743, + -0.8006647946541813, + -0.8317276107683453, + -0.8236852362867886, + -0.6613407531277427, + -0.7121511939805926, + -0.7273871854636302, + -0.699483234269611, + -0.7358701702782288, + -0.7008126597263785, + -0.6622539192972634, + -0.7951924292543845, + -0.7739769972461268, + -0.7080672327614783, + -0.786884380831872, + -0.7330646917682212, + -0.8194735988776558, + -0.8314938074204492, + -0.7416361504334708, + -0.7611312826530304, + -0.8271539274088199, + -0.8222010847740376, + -0.7866916083459111, + -0.7320742677705355, + -0.8069729813866909, + -0.7774455674454624, + -0.8352841296521067, + -0.7627695181225148, + -0.8019446882087568, + -0.8239111176647634, + -0.6622858794028101, + -0.7520137423937931, + -0.8080282434918173, + -0.692835282718838, + -0.6649923117005649, + -0.7506252116873774, + -0.6980226682149715, + -0.797719625128018, + -0.7063739527464252, + -0.7678134126339198, + -0.6913914369585744, + -0.7734019326230863, + -0.6830284724455336, + -0.7703138941466035, + -0.7389241728508642, + -0.71302599253426, + -0.674839230117878, + -0.7642710901714822, + -0.782873185849708, + -0.7707423479973685, + -0.7172355062248998, + -0.788802455135331, + -0.804686094305138, + -0.8026827216372704, + -0.7882310113457905, + -0.6864033656607605, + -0.812215882334819, + -0.6721314031202156, + -0.719597389404678, + -0.683164610070369, + -0.8087504339157573, + -0.6798316835323163, + -0.7579677153484684, + -0.7539097608888665, + -0.6674656162174057, + -0.8263989730318662, + -0.6620551644708624, + -0.6910158184319656, + -0.7582883150133537, + -0.7037951066377042, + -0.7024624720683066, + -0.8076264367243802, + -0.8152997458837348, + -0.8288246185679935, + -0.7917911637196536, + -0.6812220919916494, + -0.664308227301323, + -0.7826146428293614, + -0.782447993938662, + -0.6606454107253428, + -0.7440653723467493, + -0.8299504594155356, + -0.693179419681839, + -0.7282963024276686, + -0.6791304445336313, + -0.7998045083155763, + -0.7672253331088373, + -0.6905446539728451, + -0.7337298939700755, + -0.6993413991617704, + -0.825901445842009, + -0.7788415616916489, + -0.7165467405037731, + -0.7180214918234682, + -0.771500630424489, + -0.7151511148912182, + -0.7018722201162026, + -0.6728526456544803, + -0.8326784384637975, + -0.6784828396161667, + -0.7784643666092782, + -0.7329971335286525, + -0.7735020427458172, + -0.6621258984958223, + -0.7232531073359083, + -0.787589283465821, + -0.7746831836660802, + -0.8045323652565645, + -0.7179541553381972, + -0.7694717941383017, + -0.6941056748746596, + -0.7702966736109246, + -0.7448562438386152, + -0.6722283644194363, + -0.828492643746557, + -0.7502034528156023, + -0.7073088306451782, + -0.7214525488729439, + -0.7666351162093875, + -0.7735386204015631, + -0.7238287299268903, + -0.7109473237048167, + -0.8066167033953473, + -0.7741653626719712, + -0.7691878387018904, + -0.7380624023971228, + -0.7665768102733374, + -0.7205576827023933, + -0.8124347642260332, + -0.7197071829810621, + -0.7192450845187403, + -0.6731636430929384, + -0.8121780616775691, + -0.7720623164060517, + -0.7181826866223167, + -0.7270143350231884, + -0.678295400204909, + -0.7526072035117867, + -0.7863855937427195, + -0.7573381701570495, + -0.6882202536986054, + -0.8192288256930537, + -0.748778190013142, + -0.8053069331139274, + -0.7584637259375208, + -0.7016556786469088, + -0.8122889626844647, + -0.8292867322712717, + -0.7057184977229533, + -0.6641891755837882, + -0.7090452090042663, + -0.7105007586209013, + -0.7558335956109399, + -0.7085232052570101, + -0.7311854633743115, + -0.7532222535772631, + -0.7457093713682843, + -0.672582431690807, + -0.7634048008406426, + -0.7680280082123172, + -0.7537963718624925, + -0.786533236910003, + -0.7439839481459515, + -0.8214227767297742, + -0.711798716625998, + -0.665408852804908, + -0.7658158089857918, + -0.6887780454905543, + -0.7843748695002801, + -0.7772619391147395, + -0.7826785510962203, + -0.7613954826928331, + -0.7467529128305681, + -0.685227823149004, + -0.7196163649525104, + -0.6911997810352191, + -0.6670706690880562, + -0.8088188362744609, + -0.6923889892100654, + -0.7815769158095158, + -0.6958973861318207, + -0.7224288247666503, + -0.7506689749411308, + -0.689860399803416, + -0.765986847860089, + -0.7742246572170413, + -0.8210468000696892, + -0.7041249255697257, + -0.7485625893804728, + -0.6644427095846414, + -0.748290709687444, + -0.7882278405209534, + -0.6740529138517121, + -0.8014630288483189, + -0.6704229796755659, + -0.6848065173653581, + -0.7708680734420473, + -0.8016482407298737, + -0.817967500806751, + -0.7051403024166181, + -0.7408157981590975, + -0.7705343841400165, + -0.7295172988887132, + -0.735078108585817, + -0.715820312983704, + -0.7746152737460866, + -0.6917846364962217, + -0.7291654862533974, + -0.6945711639843601, + -0.7165370383697387, + -0.7067749188555518, + -0.8327993355511836, + -0.7243638473046023, + -0.7158980363565967, + -0.7718824586176167, + -0.694699471973532, + -0.7319262419080422, + -0.7443928517813513, + -0.7018085784723157, + -0.7661785607421961, + -0.7857507023380268, + -0.7206882097625404, + -0.7416244079080381, + -0.7209748273585741, + -0.7840999278225913, + -0.7965702931927962, + -0.7802291710251833, + -0.694823611188755, + -0.7641867509758875, + -0.8241221938608613, + -0.7167473981279896, + -0.763651119709172, + -0.694122427996568, + -0.6894281482715325, + -0.7078885220713224, + -0.7884303697899383, + -0.6881841199472305, + -0.7594279089604838, + -0.6784920675657741, + -0.7850915590834834, + -0.7807761325803779, + -0.7089037019819099, + -0.7007404947138404, + -0.7995797395391876, + -0.803981925640787, + -0.775208488962035, + -0.677530813872016, + -0.8211024995683268, + -0.7227762729256462, + -0.6976693165275509, + -0.8309155293807097, + -0.7788814928707753, + -0.7405203049235508, + -0.7026273049436987, + -0.6731907721100703, + -0.719430739827556, + -0.7179181583697698, + -0.7757362596394408, + -0.789118439598744, + -0.8028365569212542, + -0.7648539865479678, + -0.6836672528670076, + -0.6886726955592153, + -0.7269457259231578, + -0.8153430407409478, + -0.7807233200928526, + -0.6840368545168826, + -0.697400802747393, + -0.8157644059781701, + -0.7608199640356522, + -0.7919828748098375, + -0.6988150432915108, + -0.8327952993690166, + -0.7981474243507827, + -0.739206721970271, + -0.7036010983678126, + -0.6960314744742295, + -0.7997925337557086, + -0.702504629083232, + -0.690166061666402, + -0.7185859306465301, + -0.7467330060922527, + -0.8084954955862991, + -0.7184962181010185, + -0.7200877185551794, + -0.6730002218358153, + -0.668590024134411, + -0.7974478627090138, + -0.8262096780551178, + -0.7960746536460206, + -0.7980977603195735, + -0.685406722098223, + -0.8302475794178399, + -0.8269194481029756, + -0.7987335467307324, + -0.6820548242623, + -0.74872761105126, + -0.6641602747067508, + -0.8215352844984787, + -0.7934845537760115, + -0.746192624688613, + -0.794091696661699, + -0.8329832244317164, + -0.6775733989190932, + -0.6718587612412789, + -0.792939693796751, + -0.8155376444522638, + -0.7083779525336069, + -0.7734024516001902, + -0.676433270561092, + -0.7189698374556373, + -0.6674344849910336, + -0.814684113195289, + -0.7071799547967623, + -0.7214992912999105, + -0.8225744936165406, + -0.6756261088503228, + -0.6898576764753916, + -0.7326685849703103, + -0.7609197600499025, + -0.7097936702110901, + -0.662437081194257, + -0.6938572552079012, + -0.8069093034137973, + -0.7655983234714591, + -0.7759488353255686, + -0.780955366346362, + -0.7828087965417894, + -0.8105215680584504, + -0.7920140322587005, + -0.7914157869145495, + -0.7180842480021095, + -0.7454967948235828, + -0.7686163385358816, + -0.7076489420125213, + -0.816395495481654, + -0.6870638530596842, + -0.6914928640250513, + -0.8041700986902829, + -0.7491605748446507, + -0.7834925503826718, + -0.8114888073530143, + -0.8047161594693161, + -0.7123958185965478, + -0.778960197617429, + -0.7732979052158118, + -0.8130616562914552, + -0.8116547688536546, + -0.8334692169772818, + -0.7582310613070489, + -0.7033707474741336, + -0.7866926079641952, + -0.7129154976847731, + -0.8069798406970006, + -0.6746038551367683, + -0.7730132445684097, + -0.7843846947397131, + -0.6606929224367721, + -0.6802528740331801, + -0.6633688917075415, + -0.7458066797315935, + -0.7787348188631554, + -0.7618395455875453, + -0.6968842690209862, + -0.7609474285931052, + -0.7246337963493594, + -0.6827803232899489, + -0.8145717312001683, + -0.7455117719730733, + -0.7000107668985519, + -0.8071824191877426, + -0.776368101855257, + -0.6832860488521583, + -0.7978758577712183, + -0.7198383643880413, + -0.7508349368074587, + -0.6706418148780326, + -0.695114633890763, + -0.688454532739884, + -0.8265799833743859, + -0.8272614777579479, + -0.7295322201330164, + -0.6648828235852047, + -0.8191755055260052, + -0.8057337002799988, + -0.6904467837097326, + -0.7045649001056291, + -0.749475141907838, + -0.7230244001575628, + -0.7146338573902837, + -0.6839120808539183, + -0.8308919717389577, + -0.7586601736105696, + -0.8299302387378442, + -0.7210026576424, + -0.7742242861781652, + -0.6673907615039216, + -0.7353170845792262, + -0.7820382860645443, + -0.6765518587274234, + -0.767019116382483, + -0.7414333524926885, + -0.7199755526767849, + -0.7744612190541185, + -0.720774100803813, + -0.782783164258668, + -0.692012106986209, + -0.6794037175174654, + -0.7856564326809042, + -0.7553298507857753, + -0.7647989078519367, + -0.7904677843484541, + -0.7463035538480616, + -0.6803633507228349, + -0.7554081016862922, + -0.6875744924335155, + -0.6966180631792217, + -0.8116689914357033, + -0.7147447369355158, + -0.7398393753762119, + -0.6870809261893713, + -0.7207029438454544, + -0.7397539347457216, + -0.7164000632063964, + -0.6779391351339177, + -0.6825027060650593, + -0.6903993151626571, + -0.7146843431815442, + -0.6657161780126462, + -0.6606811312809291, + -0.6609523541540016, + -0.7325740322360254, + -0.681654939059207, + -0.680514937988712, + -0.7097694119385616, + -0.686563687370579, + -0.7080793774816584, + -0.6844565567763781, + -0.7022059540537429, + -0.696138512658293, + -0.6785335292241138, + -0.7171061236260258, + -0.7269568799816714, + -0.7244616896460998, + -0.6707530182519136, + -0.6955710416742479, + -0.7301531338974137, + -0.6746099400667356, + -0.7243237448771551, + -0.663324822910843, + -0.6981392840247731, + -0.7358663876753019, + -0.7034572663128762, + -0.6815960602851839, + -0.7205315259082978, + -0.7120079761457381, + -0.7156416109326508, + -0.6977206738671594, + -0.6715492140047975, + -0.6947935791519237, + -0.7408469284476042, + -0.7143018286213157, + -0.7095207110124669, + -0.7232009507741171, + -0.7197457516642011, + -0.7032442407990638, + -0.7186021634579992, + -0.6788478933224878, + -0.7132355277277183, + -0.7166389739845774, + -0.6902332032955866, + -0.7208822531526549, + -0.7237692781633056, + -0.7401748204686424, + -0.7334190821461853, + -0.7395745393750718, + -0.7165105124508767, + -0.663447563729557, + -0.698862988642829, + -0.6770397466215917, + -0.7145252740874397, + -0.6967036332834973, + -0.6899915986580373, + -0.7409650726779877, + -0.6638575657710848, + -0.6951862867222199, + -0.6891006696628466, + -0.725806883668863, + -0.7298767461031218, + -0.7186987780709523, + -0.698687932881345, + -0.6648245226203949, + -0.7143614739254073, + -0.7230428374005452, + -0.7261335439011105, + -0.7218953395880984, + -0.7338525987121869, + -0.7373006126167996, + -0.674932158389489, + -0.7065419075411361, + -0.6912002366558687, + -0.6775495914689761, + -0.7301060687356491, + -0.6741852144020517, + -0.7230832795243839, + -0.7059537718794543, + -0.7235451023806392, + -0.660802138568918, + -0.7087205080551562, + -0.6974739056214395, + -0.7289567195353682, + -0.7146020512123427, + -0.6838944103561445, + -0.6755341756064761, + -0.6853398754917264, + -0.7285350369338494, + -0.6692755251859226, + -0.662247367444439, + -0.6932029040838337, + -0.7024799635490039, + -0.6677692242022112, + -0.6705381858478252, + -0.6817457481218122, + -0.6707402557361372, + -0.7076295541308262, + -0.6981886375445263, + -0.6697688197285583, + -0.72295866773357, + -0.6633243019335462, + -0.6657686896161082, + -0.6793355362903688, + -0.7308106859569066, + -0.738205756370067, + -0.7260137503546421, + -0.6831930788748004, + -0.6696140768867691, + -0.7401516744246344, + -0.717075611471796, + -0.7337629925076069, + -0.6844640726563304, + -0.6798930795659295, + -0.7367174472249257, + -0.6927252287695728, + -0.660942374928809, + -0.7094138464642835, + -0.6601565332594437, + -0.7326214860656747, + -0.6889184698153845, + -0.6751234128702743, + -0.6916408290425458, + -0.7010395190659062, + -0.7176443597421616, + -0.7024823015725765, + -0.6903052994661368, + -0.6867979713398102, + -0.7242638114957901, + -0.7177853078692806, + -0.710847524849726, + -0.7083712967608666, + -0.6784711603502289, + -0.726202609188827, + -0.7411852718918394, + -0.720026805309684, + -0.7345346284069376, + -0.7191729802937926, + -0.6856787520675728, + -0.685849865921384, + -0.7160284957797902, + -0.738249937491938, + -0.6984980981557187, + -0.6984956763950636, + -0.7195036121006874, + -0.7106480590703853, + -0.7024153326339632, + -0.697518013848476, + -0.6927089628524562, + -0.7031970134329562, + -0.6776925715822895, + -0.6819567209211339, + -0.6910441278610485, + -0.7270244400419613, + -0.735099625680584, + -0.6701816191432974, + -0.7095105951844224, + -0.6698197268788407, + -0.7056330623838301, + -0.6672144666661758, + -0.7061795007987517, + -0.6675743998259359, + -0.6918846979869226, + -0.6790174265436282, + -0.7169321588762543, + -0.6670031635987064, + -0.6818069390566122, + -0.7055136037549846, + -0.7254253648096448, + -0.714032013798357, + -0.6624198021239868, + -0.6905723609866838, + -0.6961037186809591, + -0.7125293794701137, + -0.6850950623672554, + -0.6747175655836504, + -0.6900436235702356, + -0.6747107761064648, + -0.6746749696563246, + -0.7258018471096026, + -0.6614578368718831, + -0.6655220892825405, + -0.7129272332357123, + -0.7064475507775732, + -0.727424788555391, + -0.6952556145093735, + -0.6757767156292923, + -0.6966910755997426, + -0.6997914372975103, + -0.6811138757349476, + -0.7246147685366975, + -0.7171350022573629, + -0.6645456162002429, + -0.6930619283331058, + -0.7079248267045035, + -0.7130969782520002, + -0.7293205881471678, + -0.6971774359994671, + -0.725310489026047, + -0.7075702365942077, + -0.6615180072329084, + -0.7027346337127643, + -0.6990095217144919, + -0.7232056382641655, + -0.6798904474396947, + -0.6696893030387503, + -0.6906849493844687, + -0.7391064524400639, + -0.7164595275239851, + -0.6602865766666627, + -0.6715254209444602, + -0.7067369865408321, + -0.6909036965889475, + -0.7287374735384746, + -0.7001443000658325, + -0.6980018555427979, + -0.6809346291280155, + -0.667978651197521, + -0.7374933067017216, + -0.7206379110277688, + -0.6924448726708018, + -0.6881172490370889, + -0.693273677970714, + -0.6782549275449525, + -0.690156360058418, + -0.7246762061182653, + -0.7184540468530201, + -0.7029653564480751, + -0.7359283321466289, + -0.716122806896269, + -0.673244788748572, + -0.7244669609293265, + -0.6660730583394664, + -0.6851815106766264, + -0.7324223801821452, + -0.6763719695470456, + -0.6777237244973755, + -0.7238121618864257, + -0.6862283579442228, + -0.6761106955410897, + -0.7166948990892119, + -0.6740927021320074, + -0.7178519127671621, + -0.6723249124214566, + -0.692015773307457, + -0.7071304277385335, + -0.67929383041275, + -0.6741566620730988, + -0.7029338239649362, + -0.7053435913161673, + -0.6669100697564232, + -0.7257544459558718, + -0.6975186231239142, + -0.7267260077667174, + -0.7406618558112238, + -0.6612624407882999, + -0.7197810913834206, + -0.7612138506525566, + -0.7661733951217942, + -0.7285922264843173, + -0.7840314454225794, + -0.7456981618518047, + -0.6955087048396986, + -0.6989665009319239, + -0.7735564686763708, + -0.6840594773483558, + -0.7432239408864878, + -0.7852723141870912, + -0.7869106001350699, + -0.7327520856498558, + -0.6716326467155871, + -0.7544926881266725, + -0.7275410471425273, + -0.7373619938670902, + -0.683041458621694, + -0.75163069739167, + -0.7174266060439713, + -0.6962006336770347, + -0.730710508840399, + -0.7920084064752426, + -0.7688050672025155, + -0.7858308094952371, + -0.7459134627183248, + -0.7407217221949448, + -0.6750211641696822, + -0.7607624144113626, + -0.6630678723031989, + -0.7004596041251901, + -0.676086908283074, + -0.7043729001809872, + -0.7758876463068454, + -0.736191721515838, + -0.7410300381042004, + -0.7588515894421598, + -0.6752839013670213, + -0.7797315802688349, + -0.6653780694860076, + -0.7826442829713955, + -0.6607490098690394, + -0.6771570801353978, + -0.6781978685783667, + -0.7103506666589694, + -0.7606025808712592, + -0.6929949990640343, + -0.7267621491988147, + -0.7620889900543102, + -0.6875280305036101, + -0.7054604355647951, + -0.7330356564309912, + -0.7871673097583658, + -0.6736558030547137, + -0.66142364499131, + -0.713358177626659, + -0.727529428558536, + -0.6747110064518138, + -0.7749390427898954, + -0.7587773394814645, + -0.6611396089499518, + -0.6844989094991462, + -0.7874460898859705, + -0.6677975575800361, + -0.6918061308167902, + -0.7004104848973456, + -0.689529853619403, + -0.7810160448640193, + -0.7515837587235368, + -0.6688634351797954, + -0.7896187517857214, + -0.7004225907070274, + -0.7551161908180267, + -0.6973708504537516, + -0.695908244755647, + -0.7409467178934142, + -0.6716014385402159, + -0.6824408914285665, + -0.6625143656225634, + -0.728888218526349, + -0.7860064965230621, + -0.6765723463760749, + -0.7826111456791516, + -0.6656127378014417, + -0.7891438078647316, + -0.7110854386587045, + -0.6930106142340435, + -0.735396933037655, + -0.7058134129518078, + -0.7450208076097008, + -0.7881578825202344, + -0.7359506004616192, + -0.7074023568616222, + -0.6780852993491143, + -0.7667166289062719, + -0.7356768405198194, + -0.7720795059424861, + -0.732235051806834, + -0.744684171353979, + -0.7730479664040448, + -0.6751071992115766, + -0.7647983755470047, + -0.7405366466476989, + -0.724420473392408, + -0.6939045655720744, + -0.6701318110034351, + -0.7629074114511736, + -0.6900760737174298, + -0.7164950625321094, + -0.7376481407286327, + -0.706354409584695, + -0.6708720661323611, + -0.7302554974253149, + -0.7530622935339375, + -0.7291521798786549, + -0.6811059005215738, + -0.7326443256299026, + -0.7604169250867502, + -0.6773486989442553, + -0.7891550862705525, + -0.789570566333363, + -0.6948996908824292, + -0.7027298769254285, + -0.7891707957849813, + -0.7079190152779784, + -0.7714214644548549, + -0.6948392535867927, + -0.7474935365575212, + -0.7177729457585799, + -0.7531058774840627, + -0.7319644994822756, + -0.7126296178399365, + -0.762024511038469, + -0.7359779735093454, + -0.746839108341208, + -0.6767496766609241, + -0.6906965143270645, + -0.7267539957483793, + -0.7207461634594403, + -0.7410100123890507, + -0.753204460309697, + -0.7863118243862106, + -0.7367961315323224, + -0.7460639942677231, + -0.7346862263683025, + -0.7230760923814178, + -0.7484876552327336, + -0.7496881973004701, + -0.7153811068540611, + -0.7779821720970412, + -0.6649230329863375, + -0.7865702401492247, + -0.7757984286197038, + -0.6917061246280171, + -0.7114690044318177, + -0.7599952086031081, + -0.742332698150795, + -0.7445024236073778, + -0.7340743082362712, + -0.7226274578202586, + -0.7594813825428787, + -0.7133112353887298, + -0.6834312523599047, + -0.7173523249505507, + -0.7299866501598874, + -0.7004675307592659, + -0.7283729782368354, + -0.7559866417345368, + -0.7309334452850541, + -0.6669891061037252, + -0.7925117773791109, + -0.6918344896471145, + -0.7794519033514012, + -0.6959717663126632, + -0.7738174196177411, + -0.7385989984798228, + -0.7375764980225336, + -0.7583431626164696, + -0.6798087443182518, + -0.7180513773111198, + -0.7732214056084893, + -0.7653030333377212, + -0.7562075817813091, + -0.7853895291620788, + -0.6617690625370399, + -0.6890041666612599, + -0.7532887584140356, + -0.718974333943016, + -0.7243658500163104, + -0.696640991636492, + -0.6692152880494824, + -0.6720878179058757, + -0.7374705139225949, + -0.6889980940753644, + -0.7312493701414138, + -0.7068269183816569, + -0.7048188087048086, + -0.7689974128961663, + -0.6793512637815715, + -0.778627309016016, + -0.7571084618492665, + -0.7660957806903346, + -0.7572553803884642, + -0.7742080077030788, + -0.7733768559138917, + -0.7487472289102298, + -0.7710784359681676, + -0.7534169598754283, + -0.7801210040265782, + -0.7055677571936817, + -0.6982948004391678, + -0.7462399237340004, + -0.7721887317042636, + -0.7674231937459647, + -0.7114688166285209, + -0.7511037279336107, + -0.7029512590018154, + -0.7704895193989291, + -0.7924914123368006, + -0.7057501996606259, + -0.7433383047582434, + -0.7620934092514152, + -0.7754505238097386, + -0.7460441340103401, + -0.6920334562593407, + -0.7029654510308073, + -0.7759797978754606, + -0.6727555402277174, + -0.791774783341456, + -0.7152607724121953, + -0.7579157154666354, + -0.7034336280441295, + -0.7510779488877338, + -0.7859333874129206, + -0.7650503506870979, + -0.778525590845515, + -0.7157922926556416, + -0.687897415179517, + -0.6851908983076673, + -0.7652963449808206, + -0.7638815472917676, + -0.7331682336035708, + -0.7582070100346686, + -0.7755793807148209, + -0.6958848315300302, + -0.718650639073141, + -0.7575408698399525, + -0.7219907751240031, + -0.6993611707024752, + -0.680173387235101, + -0.7473414083301873, + -0.6662963036206836, + -0.7728972482605302, + -0.6832353754757255, + -0.709020309063636, + -0.674136523143112, + -0.6868598169901816, + -0.7601289347036205, + -0.7880262169362123, + -0.7038623719565767, + -0.6867445183494265, + -0.7065694402875635, + -0.6742694661616639, + -0.6902360304066018, + -0.6841411190206336, + -0.775346219434428, + -0.697670555915903, + -0.7626655116750621, + -0.6882328248649251, + -0.7310376706989677, + -0.7512943235987024, + -0.693034745400313, + -0.6814284570685141, + -0.6744525177500612, + -0.709078098218859, + -0.721649812535284, + -0.7880809672185284, + -0.7455894932683041, + -0.7850781063346775, + -0.7553654269662049, + -0.7700060298074459, + -0.7933683425690574, + -0.7024648525883512, + -0.7107815384244155, + -0.7324806874791312, + -0.719916741477775, + -0.7529426824434438, + -0.7828788351944137, + -0.7871866865070808, + -0.7203703314023655, + -0.7003692263830686, + -0.7879156733231205, + -0.750445385471616, + -0.7723798564095782, + -0.7469473385131101, + -0.670340992919906, + -0.7681265195724634, + -0.7262202593994742, + -0.6980275440260677, + -0.7292135627455796, + -0.706347386939748, + -0.7902702178221689, + -0.7636570279142777, + -0.6776746838539539, + -0.6987417849596101, + -0.6711943170165013, + -0.769042423564139, + -0.7661711106915932, + -0.6687697961504657, + -0.773006213288996, + -0.7540527026646469, + -0.7456471413135747, + -0.6627539180668379, + -0.7370825773118554, + -0.699086586126271, + -0.7376102413381547, + -0.7282587980524428, + -0.690936375906557, + -0.7166613171261659, + -0.7753529319801619, + -0.6678904206596771, + -0.6713875821444069, + -0.6977543938448502, + -0.7504649263529412, + -0.6803350732665161, + -0.7275318389145201, + -0.6767094713442174, + -0.7781765748911168, + -0.6753178202534208, + -0.7570100500223466, + -0.7681603656818025, + -0.7513718295545878, + -0.7187181694385911, + -0.6896030589677329, + -0.6701591623329296, + -0.7806567475811977, + -0.7331013494909167, + -0.7858505756302813, + -0.7816151790227348, + -0.7308882518307596, + -0.6659801603339788, + -0.7507991577828824, + -0.742261613506733, + -0.7369185651421225, + -0.7056999858806045, + -0.7772895972916074, + -0.6636707903066184, + -0.7843838055227049, + -0.7698155282610051, + -0.7449372151052839, + -0.7314906536008275, + -0.6795561019759615, + -0.7439353374183223, + -0.6640095904459042, + -0.7052171042894722, + -0.7871088947702292, + -0.7138549246308035, + -0.7852857937788741, + -0.6685857781456416, + -0.6955517047836253, + -0.7131085700539589, + -0.7802496672942439, + -0.6701569262855339, + -0.7902426731936466, + -0.7198371231320125, + -0.7489797738802659, + -0.7604467720392606, + -0.788216451213891, + -0.7626912753889679, + -0.6733982617924311, + -0.7114225442157793, + -0.6973804699083482, + -0.7841768171727856, + -0.6907444912254532, + -0.7750212351609654, + -0.7856144605708917, + -0.7280552414674637, + -0.7474978807268309, + -0.7140833469706015, + -0.7870264211266712, + -0.6718115023299156, + -0.7834331886742747, + -0.7491844098272957, + -0.7282583325191814, + -0.7286240153499892, + -0.7753726536312721, + -0.7386134414347734, + -0.71108793729606, + -0.7155405489659307, + -0.7188805003401277, + -0.7389372802864105, + -0.7645122079182615, + -0.7322899698113203, + -0.7306722514174742, + -0.7612274043093967, + -0.7184155160865133, + -0.7083480702574568, + -0.7029624256064102, + -0.7412726182757933, + -0.7026524403706265, + -0.7082449886701163, + -0.6942582070649178, + -0.7522699740453455, + -0.7618467532919639, + -0.7318491556462896, + -0.7373131647564447, + -0.7502691552797076, + -0.7347051203382331, + -0.7015234790850625, + -0.6631355574445981, + -0.7212602804676328, + -0.7767592464741244, + -0.787122750603658, + -0.7385091302125427, + -0.7214247224682295, + -0.7189580645649163, + -0.7237146710616247, + -0.7244880534744849, + -0.7765147410522945, + -0.7765559194481255, + -0.6610040969989724, + -0.6719433920975159, + -0.7569444031252742, + -0.6606868814976133, + -0.7391419382448261, + -0.7832914593613741, + -0.6799027070606422, + -0.6899924607178303, + -0.6815469939400042, + -0.6961503704777064, + -0.7325660449466309, + -0.7592975745050735, + -0.7884620516518598, + -0.7544158036300531, + -0.7118286775257733, + -0.7422938491274108, + -0.7764796487971463, + -0.6970751170059463, + -0.6710286171790097, + -0.7371640101306157, + -0.6932355772724068, + -0.7055846640484339, + -0.748448953351575, + -0.6649783046691249, + -0.7785272785807449, + -0.7302730409026703, + -0.6964000950214906, + -0.7206647644775508, + -0.7790336308347331, + -0.7718874470001588, + -0.7824951918536095, + -0.6969837554615208, + -0.7606349339479259, + -0.6922007566078444, + -0.6610167688108322, + -0.712688604620632, + -0.6617889433127355, + -0.735556149565699, + -0.7135368593828129, + -0.6785363977360946, + -0.7078612279523694, + -0.7485478202936837, + -0.6909725995279917, + -0.6937927766626932, + -0.6784960959872108, + -0.7894905042340764, + -0.7343288752328955, + -0.7621687370455248, + -0.7321921255315691, + -0.7272316379329258, + -0.7425226445389377, + -0.7243529131144518, + -0.6971871375890558, + -0.7711459007876258, + -0.6772038027927161, + -0.7669239265292161, + -0.667390498377437, + -0.6885357437044174, + -0.7175177042093518, + -0.7613146906377765, + -0.6937600462465386, + -0.7676762154741272, + -0.7007582013287728, + -0.7824642305862878, + -0.718832881583269, + -0.7354183429041896, + -0.7566819965346036, + -0.6974226798334358, + -0.7125742372458581, + -0.7513592165918296, + -0.7774906429427165, + -0.7239705110744864, + -0.7919462332625916, + -0.718892770366961, + -0.6943928230198154, + -0.7759928984251614, + -0.6719705805031065, + -0.7218687969243661, + -0.7205140586455523, + -0.7346626517082309, + -0.714378378650384, + -0.7490828833720498, + -0.7194527891651115, + -0.7414854349040635, + -0.7104003672676488, + -0.770519117833553, + -0.7729040894487895, + -0.7745546389668541, + -0.7537533044659959, + -0.6727248995350683, + -0.7915962075738164, + -0.7215561698185744, + -0.7810519782241139, + -0.6986446522339623, + -0.749410180668191, + -0.6771464926217363, + -0.7083693331531048, + -0.7711727723016868, + -0.6959448737888603, + -0.7574728839818395, + -0.6765751629875204, + -0.6968936569492051, + -0.6623057735122712, + -0.7516696488080818, + -0.7176992920858777, + -0.7354431694514953, + -0.7531595183870752, + -0.7696248380996882, + -0.776818771769105, + -0.7022116687559743, + -0.7773652400722487, + -0.6894820396524055, + -0.6949595040612617, + -0.7649002305638656, + -0.7706009209854914, + -0.6639146984749459, + -0.67110610402689, + -0.6938914552844822, + -0.7041603372134824, + -0.6893406684345499, + -0.7451028736724007, + -0.6706977790894455, + -0.7004014679819066, + -0.7264037739839855, + -0.7486642948769976, + -0.7660310289700486, + -0.6766515330869267, + -0.7915883758787895, + -0.7409115194706907, + -0.772424374353662, + -0.7289969756103009, + -0.7357285431288603, + -0.716638632052911, + -0.7294346543973669, + -0.680398690282496, + -0.7776117809734262, + -0.6784087535918463, + -0.7571695035478389, + -0.7095085198348625, + -0.6988670378565502, + -0.6614569632967826, + -0.6603857812467727, + -0.717410967543275, + -0.7284076713121677, + -0.7568890192391666, + -0.7458288433922525, + -0.7613111301983184, + -0.7234786884687161, + -0.7070609144607971, + -0.6805322946739588, + -0.6874915964801943, + -0.7644242140521154, + -0.7338886233790288, + -0.6819570092017377, + -0.7422066215011061, + -0.7089907161693729, + -0.7449530739222532, + -0.7334885667586183, + -0.779866203364422, + -0.7187896082464702, + -0.6735948090504937, + -0.6939075957160047, + -0.6730661171910668, + -0.7130893060719325, + -0.7032274185499451, + -0.663385595312373, + -0.7760622326982958, + -0.7800186489847659, + -0.7453191696542059, + -0.7129808003726115, + -0.7331331354675925, + -0.6968368144220121, + -0.7281824571856313, + -0.7155359080115724, + -0.7861471564230222, + -0.7123620182584881, + -0.6814319252003004, + -0.6980623503205277, + -0.7530199438176152, + -0.7361872411016046, + -0.6812580407116312, + -0.6754220808703691, + -0.7455777633071126, + -0.7623413149689001, + -0.6614061183974889, + -0.7888063845952593, + -0.760531916177178, + -0.6753596187062375, + -0.6776635851322809, + -0.7159207924192799, + -0.7506103117480108, + -0.780782615441186, + -0.735176837002029, + -0.7553658456433262, + -0.7120342930509832, + -0.7378104571583529, + -0.7012799335899578, + -0.7359827340180846, + -0.7303360323722778, + -0.7441956274888322, + -0.6946801228362115, + -0.7871208164578748, + -0.6719683128015339, + -0.7014677020343695, + -0.6933575963082349, + -0.7723496471117552, + -0.7101446040555477, + -0.7387710295796189, + -0.6758840603880655, + -0.7386083049168739, + -0.7499785330269599, + -0.7470589831650011, + -0.6990074023189606, + -0.7887333902123275, + -0.7322307798136265, + -0.7384564401662702, + -0.700522637426116, + -0.6886919117047233, + -0.7839753103499091, + -0.7542097381043705, + -0.7400359074799371, + -0.7375726966344662, + -0.7324888489346938, + -0.7003696898882238, + -0.7180578023619282, + -0.7408142456591116, + -0.7628205253998336, + -0.704114861643289, + -0.7375412472320888, + -0.711156245601874, + -0.7014820279250682, + -0.7139648204240078, + -0.7007802284554772, + -0.682386424265512, + -0.72144775821592, + -0.7268166199494047, + -0.7811518107139868, + -0.7164933716297855, + -0.7892935046281789, + -0.7796224199048566, + -0.7306670723043452, + -0.7552756108507571, + -0.7136337824571183, + -0.7008479318836591, + -0.771382784383165, + -0.7002949046744327, + -0.6945169251944892, + -0.7898353768996168, + -0.6745775361352506, + -0.7324985201024935, + -0.7245519764663734, + -0.6827099899363893, + -0.6611722271829027, + -0.718717331378071, + -0.6847145471147708, + -0.7381845459906535, + -0.7131084645359611, + -0.7847821317435132, + -0.6779086548319351, + -0.7399204362024042, + -0.785292046568165, + -0.6974169950595005, + -0.7498471178300754, + -0.7795070169928411, + -0.7720325695343926, + -0.7358882166741159, + -0.7125122669183006, + -0.7427896066023377, + -0.6852857106953968, + -0.7476431169891243, + -0.7561029566696603, + -0.7599473383784996, + -0.7493920617188029, + -0.6830079724119967, + -0.6648967384583807, + -0.7235987854800834, + -0.7122119629090848, + -0.7175485145694477, + -0.7423468673618144, + -0.7585914920383742, + -0.7055529225703023, + -0.7406712544896985, + -0.7510531211840812, + -0.7703918720405007, + -0.7476249761768019, + -0.7192352291176866, + -0.7279907933047625, + -0.6772876921756701, + -0.7425253945464907, + -0.7070176419626714, + -0.7109207140057872, + -0.7501143179851694, + -0.7612215717600113, + -0.7165610572474537, + -0.6967213342374272, + -0.719586601770678, + -0.7097946220563094, + -0.742645761022978, + -0.6900662662437234, + -0.6915513521289208, + -0.7272041458718704, + -0.7505032644254582, + -0.7437448610910219, + -0.7357163684389642, + -0.7194221919734131, + -0.6644894884711365, + -0.7445271755330118, + -0.7821706764175587, + -0.6782767671800096, + -0.663979829362119, + -0.7827604510641925, + -0.7138548584257174, + -0.7455351051641859, + -0.7249979966319754, + -0.6870112743623693, + -0.7334263225057285, + -0.6633200143165202, + -0.726617848893464, + -0.772646097959678, + -0.6622334018061904, + -0.7012718762231734, + -0.7156931723284705, + -0.7475985404203866, + -0.7600334043666591, + -0.6853465402341113, + -0.7225921708364553, + -0.7680969609499382, + -0.723356539039939, + -0.7510885631953225, + -0.7082193100355192, + -0.7543028390478671, + -0.6644908924249613, + -0.7057565645262427, + -0.696852780049082, + -0.7667027595019651, + -0.6768488144081708, + -0.7216810613568568, + -0.6778401479029242, + -0.7873026383512134, + -0.7076945950241964, + -0.7657788766597997, + -0.6831293664587573, + -0.7120181427121651, + -0.7292564832055868, + -0.6714724045221444, + -0.6648736868880293, + -0.6887826585397909, + -0.7756268299130102, + -0.6950776159517089, + -0.6880068089787571, + -0.7642571330816161, + -0.7787465016117806, + -0.7245442639243743, + -0.7097743190780296, + -0.7276743820556586, + -0.7882216738610296, + -0.778930469164527, + -0.7182297918798016, + -0.6983933748410984, + -0.7917547917122867, + -0.7172675183098851, + -0.6923782657026956, + -0.7904721878738389, + -0.7629018103987261, + -0.7490945635300295, + -0.6656994980732476, + -0.7681894066443206, + -0.7072506905054413, + -0.7087868166439644, + -0.687957622732382, + -0.7008864235368952, + -0.7032056481815031, + -0.7932006429730489, + -0.7636413452793079, + -0.7177973330803242, + -0.7537314357874256, + -0.7185572443733088, + -0.6619221533300598, + -0.7039353966954981, + -0.6770773738495268, + -0.7164252775025991, + -0.7666817516901692, + -0.7490726649682048, + -0.6783479053887382, + -0.7859419920052321, + -0.7456897713633283, + -0.7831646249539982, + -0.7187298869995818, + -0.7689518034978369, + -0.7612996522910361, + -0.7321882332020007, + -0.6609035121585075, + -0.7605894544145504, + -0.7178114591175957, + -0.6865683174891059, + -0.7363526315219118, + -0.6682403844254243, + -0.7722992351275437, + -0.6732417066101104, + -0.7630613763706896, + -0.6646491699038528, + -0.7123501196119659, + -0.6744932800726066, + -0.7625233898461745, + -0.7399082956187386, + -0.6899116593634511, + -0.7101595604872158, + -0.6777468622548583, + -0.7851517568928947, + -0.7514256227328291, + -0.6938853874732267, + -0.7460439833627616, + -0.7666548402081207, + -0.7372415639749079, + -0.7235098860921906, + -0.7910718483430815, + -0.6814028361154786, + -0.7761420826126831, + -0.6635400044152544, + -0.689189520352806, + -0.7086557427597193, + -0.7067217868769743, + -0.7126251762628519, + -0.7111209038479833, + -0.7251699660914326, + -0.7356967463400869, + -0.7794670430682232, + -0.6755467309930956, + -0.6682188004295472, + -0.6736525724963437, + -0.7687623554041344, + -0.7043086000585794, + -0.6670560534790709, + -0.7600928512924022, + -0.7076274231024007, + -0.7612614173900515, + -0.7305243825208764, + -0.7286711460738095, + -0.6636492389953352, + -0.7357837178680294, + -0.6933641712992697, + -0.6695312444538657, + -0.7784747067129161, + -0.7473069369437862, + -0.7725907544512487, + -0.7091291997548909, + -0.6821048808895842, + -0.6700928383001762, + -0.7389207619819397, + -0.764529739510383, + -0.7249304223215295, + -0.7596580496197499, + -0.690084838633227, + -0.755120041056349, + -0.7002040354966856, + -0.7144785289373099, + -0.7344506911348964, + -0.7799755430277956, + -0.6790632660777638, + -0.7196671494788489, + -0.7393540188766414, + -0.7863977172377669, + -0.6909296639916147, + -0.7604641454007852, + -0.7836069591925151, + -0.7725309658604472, + -0.7472498020488578, + -0.7331763112031566, + -0.7161451659267187, + -0.6675199004936734, + -0.7428413701655773, + -0.6883313533383497, + -0.7245210578212373, + -0.678562497431805, + -0.7318684368357777, + -0.7218305317930199, + -0.7103469523045243, + -0.7302065378107876, + -0.7534304418144844, + -0.7921066473789138, + -0.7465375705457971, + -0.6759056165260031, + -0.6911994062193341, + -0.711387251815371, + -0.6795036314238864, + -0.7933967261633517, + -0.7662905645826003, + -0.7925174962382421, + -0.7812187815384384, + -0.6673055821111058, + -0.7222740005262035, + -0.7578577352578397, + -0.6833285404660824, + -0.7090574449230489, + -0.7250032491869965, + -0.7448797768493397, + -0.7170525589571225, + -0.7124719250052058, + -0.7091560321731076, + -0.6612517746473274, + -0.6998804108530264, + -0.7896268210566775, + -0.6714835057341259, + -0.71750281965762, + -0.7452629023762027, + -0.6880995752950292, + -0.7762601164329297, + -0.7272689653111268, + -0.6794977670828763, + -0.7051404400800919, + -0.6860676548315772, + -0.7423859715954064, + -0.7003342713760553, + -0.6984570051867236, + -0.6746331965872662, + -0.6621179717549506, + -0.7208169170007366, + -0.6930234416643093, + -0.6933664069590534, + -0.7515585524998295, + -0.6600636391653566, + -0.6814469072220009, + -0.737651219078433, + -0.7271210627872399, + -0.6901111236383348, + -0.6881115941837143, + -0.7328935383634642, + -0.713131589360002, + -0.6845265022841737, + -0.7518952788282312, + -0.7579439155082808, + -0.6847662335221548, + -0.685623632471824, + -0.6982941683443602, + -0.7159037548656542, + -0.7644262626664471, + -0.7729870904037156, + -0.7484713835363835, + -0.6925914496991485, + -0.7333567920783703, + -0.7009734467556612, + -0.767244152308779, + -0.697219790542696, + -0.7637882629001681, + -0.6974160983392066, + -0.6659823057995526, + -0.6995063807860913, + -0.7021319595481617, + -0.749937676957209, + -0.7272184597466136, + -0.7757948781195031, + -0.7015104152003863, + -0.789407110796192, + -0.7714740375367937, + -0.7827159728449564, + -0.7560838898005572, + -0.778911666586186, + -0.6926139796447254, + -0.7599012841367562, + -0.7557680503291013, + -0.7913270981411912, + -0.663211373581691, + -0.718694547655036, + -0.7288975590411614, + -0.6742725683024885, + -0.790290405496449, + -0.7121613157124821, + -0.7918323983072586, + -0.7813712490137618, + -0.6621167666627271, + -0.7364936292555273, + -0.7195099379057659, + -0.6703281509735022, + -0.7392284347046109, + -0.7889153198728952, + -0.7053668981427561, + -0.7589106726101614, + -0.6603521786459536, + -0.7201661000032684, + -0.7841219411893563, + -0.7293526321998455, + -0.7622450340703899, + -0.6806764247039293, + -0.6870357321583995, + -0.771328961639428, + -0.7283066100065227, + -0.7617270466796093, + -0.7675343972979007, + -0.6984727675478932, + -0.770592773164756, + -0.7053358868033897, + -0.7840752032590859, + -0.6835338681919414, + -0.6616200324346863, + -0.7446330606245324, + -0.6692474211233692, + -0.750046341864173, + -0.6855907036601477, + -0.7525272987981243, + -0.767177436535108, + -0.764816308394601, + -0.6858722969161504, + -0.7844123547012425, + -0.7903999832022965, + -0.6612480467655476, + -0.6852292593480898, + -0.6890313920942008, + -0.7162536112534885, + -0.775461465551039, + -0.7294288635757344, + -0.6945530588316138, + -0.676367840587077, + -0.6891013617392397, + -0.7411483249304639, + -0.7396753212555683, + -0.7719674505778793, + -0.7283196587168052, + -0.778409966132129, + -0.785630092637226, + -0.7767567376429012, + -0.6626383008603975, + -0.7674646385506597, + -0.7277429583758764, + -0.7722337023953284, + -0.6938273570132761, + -0.7750650783567911, + -0.7382276413719464, + -0.680419725218517, + -0.7246494952253969, + -0.7828180247998998, + -0.726512141415322, + -0.753372263411675, + -0.7023601555439044, + -0.7317265874360831, + -0.679559978834537, + -0.7551149976640553, + -0.6828450432230263, + -0.7222361458999766, + -0.7542832377051735, + -0.7035920009415126, + -0.7781207378094627, + -0.7298771256607937, + -0.707486091635463, + -0.7161247988070026, + -0.7855886422682065, + -0.7573722312596334, + -0.7306982141577723, + -0.6686655148413924, + -0.7499979387468483, + -0.7582107902165943, + -0.6831997010744882, + -0.7127476888382888, + -0.7102745917180444, + -0.6649088512659305, + -0.7816449582003131, + -0.7299194020431747, + -0.7689229261755004, + -0.6690722368354562, + -0.6836869580383604, + -0.664287900600478, + -0.7015444256353833, + -0.6687266097318143, + -0.732817084901176, + -0.6666379473303735, + -0.6948603005381829, + -0.6692785156326262, + -0.6936095116761151, + -0.7249319493024885, + -0.7548623508313451, + -0.7867302149093027, + -0.6609732815109406, + -0.7827842416701224, + -0.6729620390326048, + -0.7624159785594428, + -0.7630226402213771, + -0.7871114680470256, + -0.7064733348312152, + -0.7320281399051937, + -0.7742597271629638, + -0.7294748261616112, + -0.742632868264119, + -0.670406928560177, + -0.7003141765431155, + -0.7255544035156678, + -0.7489557078624991, + -0.7212390625867054, + -0.7143525003995211, + -0.7876572385501235, + -0.680049296474288, + -0.7469208043036081, + -0.7256770930454043, + -0.7800171847714863, + -0.7323990890694072, + -0.7526506799456051, + -0.6753988899632908, + -0.7450924730996256, + -0.7225521500186944, + -0.6950878341704684, + -0.6795708812857147, + -0.6908634535800413, + -0.6923321046340652, + -0.7347333135722512, + -0.7474596056742102, + -0.6885683848689147, + -0.7356779574063216, + -0.7910518567732041, + -0.692166735655898, + -0.7329988219236011, + -0.7381215877395697, + -0.7642318496758315, + -0.7463263098148168, + -0.7459435850996691, + -0.7203824227644879, + -0.6976413729351073, + -0.7880415117762898, + -0.6942007134136632, + -0.7162533668962313, + -0.7004542034814547, + -0.6928994756408541, + -0.7814584927385158, + -0.7264380053169848, + -0.7694789786089202, + -0.7420100278071804, + -0.6817138414572625, + -0.6688890368410095, + -0.6760961200923593, + -0.7695276021735852, + -0.7522771212408812, + -0.7465035847821064, + -0.7038584530846861, + -0.7191244651659228, + -0.6981936482614083, + -0.7149912608038695, + -0.7223628885095584, + -0.6828131130968275, + -0.7057785842542594, + -0.7896880507500487, + -0.720962723688091, + -0.6813708495025074, + -0.6978920534177852, + -0.734490701198463, + -0.7211506281126612, + -0.7690135369389149, + -0.7755731337927465, + -0.7201601359278142, + -0.7144615023453307, + -0.7810681003894031, + -0.6701957049777759, + -0.7267204335822826, + -0.7073242716583552, + -0.7318193770471388, + -0.7169923433713121, + -0.7494229734361703, + -0.7916874337469588, + -0.6630925187318772, + -0.7328883774577559, + -0.7543256116234008, + -0.6949295304644634, + -0.7361314283734178, + -0.7871018500827123, + -0.7163406980350709, + -0.667097915777576, + -0.7744204840846554, + -0.7231401585560325, + -0.702220095179315, + -0.7205700099854013, + -0.6644777620278456, + -0.7822377274934911, + -0.7788499979807948, + -0.6822966386206745, + -0.7342951375005734, + -0.759751470645311, + -0.7545234996468818, + -0.7741964014615784, + -0.7324758310974466, + -0.7778204674597735, + -0.6816374788602063, + -0.7871484302799934, + -0.772601018912985, + -0.6691481024452207, + -0.7488523778500041, + -0.7023497287862753, + -0.7590819193700639, + -0.7174853957343187, + -0.7264699434592471, + -0.7902202415043401, + -0.7096960264565124, + -0.661577666754948, + -0.7104651596583266, + -0.7123529074695261, + -0.7543139357257024, + -0.7613420420817516, + -0.7460876409122583, + -0.7034571904699846, + -0.7059423057741938, + -0.7037137912565451, + -0.7912923665929832, + -0.7506707961518322, + -0.7620596952146439, + -0.7742696043774379, + -0.7127870420256351, + -0.7547278745356172, + -0.7233222704843956, + -0.7927151232577723, + -0.6693025596551619, + -0.7583726612544781, + -0.7602618514551087, + -0.7151526041817621, + -0.6777522635153673, + -0.7483560323850444, + -0.760369981636729, + -0.7067401530046367, + -0.6652205040088, + -0.715958182492279, + -0.7678539879031042, + -0.7308538724572168, + -0.6910077995564279, + -0.7208859986773778, + -0.7360012026430016, + -0.6639821603702639, + -0.6719371838928703, + -0.7146571479892747, + -0.7311527543586047, + -0.7015378513200017, + -0.7765645599768957, + -0.7930890417177898, + -0.6692134214548031, + -0.696232015878327, + -0.7303205435785163, + -0.6620486361039104, + -0.662397322294557, + -0.7303911452212003, + -0.6871626525605917, + -0.7080123959569378, + -0.7688599843764196, + -0.7452278763217794, + -0.6917991896317756, + -0.6749302702494737, + -0.7130505511018963, + -0.7730680157485068, + -0.7905765402576719, + -0.671050822968695, + -0.7818890241583932, + -0.7022887109805807, + -0.7776091359722069, + -0.7771887769990486, + -0.7791992754237934, + -0.6857010904301442, + -0.7788652915854476, + -0.7230929165985507, + -0.7718742777842934, + -0.7575278336779339, + -0.7464339474488734, + -0.7532853573358221, + -0.7728080141052223, + -0.6948564696082803, + -0.7018548322551695, + -0.6711890707109882, + -0.6891518363538857, + -0.7821289902647871, + -0.7436325041546744, + -0.7092183134561679, + -0.7386252119566098, + -0.7505682341351196, + -0.717163486584754, + -0.7206078764173895, + -0.6649067988435393, + -0.6641384078814121, + -0.7910480694977355, + -0.6750597915272001, + -0.7563785822535143, + -0.7247202396080431, + -0.7730272680830468, + -0.7796018048846898, + -0.7479857222133435, + -0.6870822736585784, + -0.702948717574758, + -0.7420155952728003, + -0.7486991364411216, + -0.7807635576559213, + -0.7814530711253239, + -0.7899685617263431, + -0.7381406546315522, + -0.7636681024797602, + -0.7411163764167703, + -0.7817950699173472, + -0.6779355422730092, + -0.7856377859345619, + -0.674905474947248, + -0.6970737234115918, + -0.779000027346798, + -0.7497980049952886, + -0.7554996823410927, + -0.6622106245899566, + -0.7346957383289923, + -0.7171864728148496, + -0.7918375482160105, + -0.7512980040122325, + -0.6986691358197753, + -0.6896326814990436, + -0.6928258611492187, + -0.6753624418606101, + -0.6782604421779665, + -0.6971505248874861, + -0.6906259220792677, + -0.7056360124267653, + -0.772133850616159, + -0.6759423351075996, + -0.7407848204694758, + -0.6883967275042684, + -0.7177918703715743, + -0.6987015666085803, + -0.6692997510187385, + -0.7508146659855066, + -0.7203782441610116, + -0.6850333136548667, + -0.7619527506046803, + -0.7114934827328077, + -0.7088386269195772, + -0.755630809307482, + -0.7060676981555477, + -0.7119805609322541, + -0.7431719674441976, + -0.7704305162690759, + -0.7346603821455496, + -0.7870351288145984, + -0.7696687206771701, + -0.6632532767603426, + -0.6820724300343508, + -0.7023826517638815, + -0.7771570310691284, + -0.7902984902812573, + -0.7636965036121021, + -0.6739381250970167, + -0.7182075199418966, + -0.7340458154980338, + -0.7550194496079781, + -0.786965747343985, + -0.6976639840402192, + -0.7538197196722471, + -0.6983481408984499, + -0.6937686482971375, + -0.6603220096014273, + -0.7834744093619698, + -0.7470661442409952, + -0.7273992695714497, + -0.6742589533581997, + -0.7540128673393652, + -0.7435656370708092, + -0.7404663215236893, + -0.7074274392859147, + -0.7553888367121396, + -0.6730794862346292, + -0.7714777721662033, + -0.6948050422601943, + -0.7818665097138392, + -0.7055297590750482, + -0.6821813917312866, + -0.7734884741919531, + -0.7025317074596461, + -0.7912927418560592, + -0.7379460681657558, + -0.6706372846348289, + -0.6700212239896051, + -0.7823999571330935, + -0.785652571000665, + -0.7346606213756341, + -0.7230062976542728, + -0.7537562122837119, + -0.6988267927272445, + -0.7704289737409166, + -0.6973398792040524, + -0.6664141061387225, + -0.6978493660442376, + -0.7544392390621321, + -0.7231558019099471, + -0.7260357097762377, + -0.7917373712146498, + -0.7132860410262605, + -0.7712060988337933, + -0.731770224034745, + -0.755094376703736, + -0.7310497444421585, + -0.7107092098038278, + -0.7445111365487698, + -0.7754383754443123, + -0.760491792991625, + -0.7202198486372404, + -0.7150534445183394, + -0.7549580084388917, + -0.6672956681506552, + -0.6755238756787076, + -0.752486809639476, + -0.7839279068792895, + -0.7706735713148285, + -0.7918698293762791, + -0.7846493140652192, + -0.7609061652402581, + -0.6725284846864298, + -0.7611684075035129, + -0.7641624947855914, + -0.7858414635150895, + -0.7797194195838989, + -0.7868745340875682, + -0.6747623362335544, + -0.6783127266859142, + -0.7274528080144762, + -0.7853751069420496, + -0.7412248782997507, + -0.7503657975670526, + -0.6944285948900086, + -0.717815860110518, + -0.755941903060007, + -0.6678949299300182, + -0.6693105980605887, + -0.6811630428421567, + -0.721538199055092, + -0.6680966480799839, + -0.7440984672339446, + -0.6674787678367989, + -0.7036971802262826, + -0.7612339730019776, + -0.7908711194671902, + -0.7188091181755581, + -0.6960962889210682, + -0.6751548572090589, + -0.7718019401279401, + -0.713667795759753, + -0.726635131193389, + -0.7776122933778211, + -0.6888434179425396, + -0.744986830891863, + -0.7616798724641265, + -0.7887833131122904, + -0.7728055257673834, + -0.7902815075482784, + -0.7580271183830016, + -0.7304632537285966, + -0.712790449399856, + -0.7561548596490814, + -0.7197612722109851, + -0.733831421814376, + -0.7292890523448541, + -0.6951308145223105, + -0.748559371386328, + -0.6944460848959855, + -0.7590671381134741, + -0.6699749947022103, + -0.7788927127955823, + -0.6856484183620389, + -0.7136472885682795, + -0.7509278046720426, + -0.7616869769746836, + -0.7560297558639837, + -0.7828739588382764, + -0.6785226700448475, + -0.7053281775817425, + -0.7687889290265115, + -0.7268506114407817, + -0.6801314279487539, + -0.7678648691040615, + -0.7860977597678808, + -0.6816295356132908, + -0.7242811994357972, + -0.681350050560529, + -0.7709560186083231, + -0.6633967724435706, + -0.7765017474749051, + -0.7253894317301989, + -0.7254234350549144, + -0.6717628520176074, + -0.7402634784459807, + -0.6860474076649732, + -0.6629786486571058, + -0.6683004880776642, + -0.6704133820456233, + -0.6864758279757663, + -0.7391917428289893, + -0.6604550401260219, + -0.669735638120622, + -0.6914463175861779, + -0.7551326082920379, + -0.7645876648806211, + -0.7626624205989175, + -0.6635096922127244, + -0.6687765545631423, + -0.7413052775587777, + -0.7892620290325564, + -0.7699572142205192, + -0.746204797447436, + -0.7586062764473946, + -0.7871679271990872, + -0.7401913558331906, + -0.6880199156807539, + -0.7225370658122752, + -0.6632643494079297, + -0.7858413339602058, + -0.672989303542084, + -0.6611777248555936, + -0.6623266249931735, + -0.7704626322433398, + -0.7463994801709499, + -0.7291519954167528, + -0.725527144144819, + -0.7495485005603075, + -0.779736368045884, + -0.6983291655607163, + -0.7024522985178538, + -0.7536014627400749, + -0.6662527469183457, + -0.7338601386340575, + -0.6945606281093344, + -0.7268944944046938, + -0.6940049003810123, + -0.7644888699809751, + -0.7131588299675705, + -0.6844288936414613, + -0.6868176448287601, + -0.7585294313598834, + -0.7350230044833801, + -0.7763013015479117, + -0.6781503571645634, + -0.6788108679731846, + -0.7772292060541236, + -0.6726964763975136, + -0.7005244540370841, + -0.7863822526906092, + -0.7152302717782383, + -0.6894375682842567, + -0.7046028901017979, + -0.7564765716691249, + -0.7288997525124036, + -0.7637215282406622, + -0.7158218833417955, + -0.7638709522384095, + -0.6836951976857815, + -0.7467189913922031, + -0.7778638609632018, + -0.7169766424155202, + -0.7136676929632827, + -0.6903045438186217, + -0.6842132712067062, + -0.7613876696710963, + -0.6937186945552845, + -0.7295108027782439, + -0.7719706832067743, + -0.7230158533476622, + -0.7598199735621449, + -0.6949613701436601, + -0.7151914283439664, + -0.7748992742146773, + -0.7624341313052617, + -0.7839442763349191, + -0.72254325796125, + -0.7630893164704505, + -0.7890633058303822, + -0.77211765308414, + -0.7192778847070509, + -0.6601446841372607, + -0.6909881177764496, + -0.7773398426104936, + -0.7465174051345252, + -0.7784780927195951, + -0.7069473681501663, + -0.7910189106650795, + -0.6650502646501248, + -0.7005351322184635, + -0.6707159289020185, + -0.6624653622692075, + -0.7491461073846746, + -0.7548036301395137, + -0.785783537980899, + -0.6880759024991837, + -0.7181825012040994, + -0.7199255542501797, + -0.7497035252856077, + -0.6940242570701558, + -0.773375624987192, + -0.7360363464805371, + -0.7636692435561362, + -0.7451692682969511, + -0.7008309268469483, + -0.7255191622034874, + -0.7209046286330769, + -0.6625364191829546, + -0.7323919915483167, + -0.7828250043437753, + -0.7410531287588848, + -0.6978496743133813, + -0.6800644019857853, + -0.6704767225352686, + -0.7900951474687674, + -0.7529629837189267, + -0.742923519123742, + -0.6909433510933313, + -0.711823561692166, + -0.7559478796538424, + -0.709412090308412, + -0.7451277539751535, + -0.6878748457884354, + -0.7064444948037997, + -0.7009894477076037, + -0.6760768757102205, + -0.7130716737309017, + -0.7895426991094812, + -0.6714767151538535, + -0.7385213476075023, + -0.6867726897417656, + -0.6944868179194859, + -0.7247068639023044, + -0.6693523844630636, + -0.7909334603158485, + -0.6656553184691629, + -0.6645376197948718, + -0.7597848498784839, + -0.6917497526157149, + -0.7637220258278872, + -0.7710814571386858, + -0.6773401356708095, + -0.7435439952688506, + -0.7753284754375361, + -0.6788076105620736, + -0.6975693452098438, + -0.7115025183547994, + -0.7108858886567299, + -0.7452672887148093, + -0.7683730193050065, + -0.6715286171791767, + -0.7746676017099453, + -0.6678232107294997, + -0.786280366749422, + -0.7262038353888026, + -0.7734319357456446, + -0.7062587333574842, + -0.7786229952031362, + -0.709742918134622, + -0.6854084099677382, + -0.7124694555454048, + -0.738867230943208, + -0.7361921234916371, + -0.7859682945445187, + -0.7055982420950695, + -0.7804068783680767, + -0.7050388383797551, + -0.7436637423429131, + -0.7598125915678969, + -0.7075075668468809, + -0.6867286571743074, + -0.6952856472010718, + -0.6907407708953504, + -0.7846802748623034, + -0.6920189590123942, + -0.7924821489173973, + -0.6970148959442258, + -0.7930353966544945, + -0.762116484602487, + -0.7664371535412953, + -0.7581887666495079, + -0.7904247384567066, + -0.7695398849006778, + -0.7880493475391662, + -0.7647810555741671, + -0.7270245781044198, + -0.7820540914325239, + -0.7253133624688781, + -0.7511345573394835, + -0.7229393238678783, + -0.7423811317674963, + -0.7754436052407564, + -0.771080303841912, + -0.6675599684426794, + -0.7230335822212806, + -0.7334874943089574, + -0.7084987741559745, + -0.7533053154282845, + -0.7494802186348591, + -0.7154046078854293, + -0.7292946938874697, + -0.7523475392019519, + -0.7000789341534509, + -0.7185911690261765, + -0.7404547021078034, + -0.6942419539653794, + -0.7534164362416838, + -0.6843716082848986, + -0.7469572351597716, + -0.6639608078554782, + -0.6959954160089091, + -0.7626788383995536, + -0.7251218743593211, + -0.7345856347393458, + -0.7187712668189736, + -0.7291943357220243, + -0.7483613126892849, + -0.731353033907309, + -0.7868077029123867, + -0.6785971478349068, + -0.7784488553962987, + -0.726944139359684, + -0.703390959089319, + -0.7640613930976243, + -0.7609139820420198, + -0.7429015460902133, + -0.6971727520139087, + -0.7919485015930616, + -0.7043617714958562, + -0.7413422286648365, + -0.7427197073781949, + -0.7891877009435699, + -0.7744287634327021, + -0.7054704155199789, + -0.7687781887777771, + -0.7294390995458824, + -0.6837966554540426, + -0.6618852755463258, + -0.695184445839306, + -0.7704180446230362, + -0.7484872278244303, + -0.7637707280252302, + -0.7075711460776406, + -0.7054017414703463, + -0.6652301326594229, + -0.6933763510852915, + -0.7461808429860451, + -0.6900865324694582, + -0.7545392105843066, + -0.7195074604723657, + -0.7150953980262152, + -0.6800921836197303, + -0.7802194794734005, + -0.7863043297607282, + -0.733290351050651, + -0.6673643190447415, + -0.6853734270584366, + -0.7752346434139565, + -0.7639509080787544, + -0.7003296994831948, + -0.7100497156715055, + -0.7187035317866136, + -0.6989801819529475, + -0.7389835345855557, + -0.7175871276838394, + -0.7167980532342788, + -0.7743977585667015, + -0.7288800657002157, + -0.7577815401511155, + -0.7164708112012714, + -0.7658263139353663, + -0.7737871156369406, + -0.7028859854147487, + -0.6616277256678637, + -0.7521779154108171, + -0.7180145132915585, + -0.7801480015348309, + -0.7878673976627354, + -0.6679889272908827, + -0.6625123759643755, + -0.7286966207105525, + -0.7517309033029754, + -0.6777991213459756, + -0.7535431394066081, + -0.6760434335766088, + -0.6851808149927527, + -0.6732482359458625, + -0.7465871323203471, + -0.7069248423913624, + -0.6934463626948157, + -0.7435663340381217, + -0.7511253104312323, + -0.7824442709179216, + -0.6611899479378263, + -0.7262016993864038, + -0.705471673945625, + -0.6630821611173446, + -0.7121535969885896, + -0.7724180775883663, + -0.6713935262383781, + -0.7585898826249708, + -0.7335217107798697, + -0.717388392465319, + -0.6848761490661406, + -0.7626147471655272, + -0.6674826413706805, + -0.7684148090755083, + -0.743661082063406, + -0.6888914891871291, + -0.673854223464377, + -0.7783524987660436, + -0.7144484988135447, + -0.7748266969922148, + -0.7485103972968414, + -0.7157104412652588, + -0.672200711791632, + -0.6754380159505122, + -0.7030542871096414, + -0.7428149697714906, + -0.6846927660947251, + -0.7103322414425761, + -0.763224338353633, + -0.7556365941227752, + -0.6688310291801133, + -0.7574274962470051, + -0.7476093058029121, + -0.7470510023290083, + -0.7377431434139028, + -0.7288633857631914, + -0.7376721078240797, + -0.7913038629186153, + -0.6910455828413339, + -0.7699331808915422, + -0.7124024610292584, + -0.6896487339968659, + -0.6920744368496707, + -0.7266969092471759, + -0.6873596369259426, + -0.7679529341158918, + -0.6857759511735099, + -0.6730903560668454, + -0.6837684132631293, + -0.7911051948048802, + -0.6924835531488621, + -0.7127694114011534, + -0.7522704290755332, + -0.7213697633594578, + -0.7875596273911064, + -0.6952352663322523, + -0.707691642556335, + -0.6870096453468654, + -0.6687646492551442, + -0.6650304812208341, + -0.7450460827433362, + -0.7048291659687478, + -0.7684042833208984, + -0.7694336148571517, + -0.6720656591383259, + -0.6781538614170746, + -0.72917815814226, + -0.6721306738197879, + -0.6649408379018213, + -0.6921053830267813, + -0.7236279855284365, + -0.7455180215297086, + -0.7860487205817391, + -0.7905566197499383, + -0.7471064696300665, + -0.6868951450539528, + -0.6860037283292482, + -0.731973770325746, + -0.7637536732274133, + -0.6918101298412377, + -0.7209989670304072, + -0.6822972693659775, + -0.7542884612103856, + -0.7432630686776326, + -0.7829698941502272, + -0.6761196885075718, + -0.7589941710229658, + -0.753747082539743, + -0.7907022262523654, + -0.6895132064713134, + -0.7682378027544065, + -0.6666362329516161, + -0.7915350951354292, + -0.7206709452493107, + -0.6659476723715682, + -0.6806902862121317, + -0.7070643378282963, + -0.6819117415208183, + -0.6701608916020774, + -0.777593246649664, + -0.7358372602154438, + -0.7841338351230638, + -0.6897339499643366, + -0.7082590664680384, + -0.7558261023947245, + -0.7279878243445491, + -0.6618436419988312, + -0.7063579440291889, + -0.6643844264401749, + -0.6669962815520131, + -0.7071092333082564, + -0.725206709582251, + -0.6923852127238487, + -0.7162021458874348, + -0.740043155702995, + -0.719279124111275, + -0.6993494765407768, + -0.7597599644518738, + -0.67496894260513, + -0.7237602939392201, + -0.7790728639947935, + -0.7226492373705069, + -0.7876248569292139, + -0.6968624343497426, + -0.7931897187674792, + -0.7119857535310316, + -0.7308207401715304, + -0.675857689404193, + -0.6735255032871692, + -0.7876839348816447, + -0.6990946387504042, + -0.662692595786778, + -0.7620424819112448, + -0.6606521928087692, + -0.6628480347015621, + -0.7064871783559199, + -0.6754126551394972, + -0.7358105217428231, + -0.6867021440133754, + -0.688074434017044, + -0.7394702524712188, + -0.7637108639058809, + -0.6819863222227002, + -0.6668604557597405, + -0.7632345670087508, + -0.7216344029364028, + -0.6873446749563398, + -0.6958819505425081, + -0.7674578935430433, + -0.695793871724397, + -0.726764647123481, + -0.6775408296335886, + -0.6671198217208214, + -0.6733494784522838, + -0.7652716696290417, + -0.663304111338288, + -0.6878133316468812, + -0.6810915746627204, + -0.7930189866028612, + -0.72444256202778, + -0.788488148338851, + -0.7237792892380902, + -0.7048494047122364, + -0.7135782037746825, + -0.7377067285028063, + -0.7581833939660177, + -0.7716075024009429, + -0.6684334678899501, + -0.7462937620161627, + -0.6656531872591908, + -0.6609539751431199, + -0.7362199309784278, + -0.6958479488738901, + -0.7369698543950131, + -0.7791866092176915, + -0.7314130670401096, + -0.7018898736291705, + -0.7495612899935772, + -0.6937121885280119, + -0.7029886682837125, + -0.6688240392990175, + -0.7576445399537988, + -0.710671259737002, + -0.6799962707386544, + -0.6769657416995496, + -0.7166791810934692, + -0.7814625252729444, + -0.7675017591180877, + -0.7343835970549903, + -0.7188054046641993, + -0.6825482381785387, + -0.7229244015060438, + -0.7379507410900277, + -0.6743672538241188, + -0.7428814807042009, + -0.7635442715284808, + -0.7547684763228221, + -0.7311507799251454, + -0.7556543482443584, + -0.7703298819460153, + -0.7071071896072145, + -0.7567090361156384, + -0.6660281115710447, + -0.6933172449054777, + -0.7533576638501565, + -0.741908735378679, + -0.7591449630812699, + -0.7606059965442561, + -0.6939043594543728, + -0.7533191708518738, + -0.6747067905845349, + -0.7054718599232497, + -0.7883868056667045, + -0.7052046793426918, + -0.6693413902508569, + -0.7762994347459378, + -0.7232016672432131, + -0.6661876904011359, + -0.7383575367247859, + -0.6950114459089307, + -0.7606321352691345, + -0.7036501196132618, + -0.677468839858865, + -0.718069446707716, + -0.6898977336455796, + -0.6734420753530523, + -0.7345925541420902, + -0.7602578653464531, + -0.7539809283986302, + -0.7323058855001303, + -0.7798761809874117, + -0.7724733832366838, + -0.716002865776737, + -0.6820148189843674, + -0.7605655631440075, + -0.7368348972970623, + -0.7800837709740631, + -0.7594667752070218, + -0.7244951034487207, + -0.6941053640330539, + -0.6991374298172804, + -0.7753353535568313, + -0.7091357180944691, + -0.7815767082996439, + -0.6942868227199206, + -0.6730668987034568, + -0.7200882760396172, + -0.7116556098058708, + -0.7029704631552238, + -0.7204643188284683, + -0.7442228097212165, + -0.6976861845261283, + -0.787359565756124, + -0.7591772665399472, + -0.7418265935939964, + -0.733427553707475, + -0.7753464809751822, + -0.7416787477918138, + -0.7781065958401353, + -0.7903746314588366, + -0.73927634214213, + -0.6621879087751682, + -0.7756854832325084, + -0.7611463735063762, + -0.7167834360526245, + -0.7498116177659507, + -0.7751438093817576, + -0.7462392213276227, + -0.7688351101543801, + -0.7312963602521447, + -0.7619825362728141, + -0.7566681186313153, + -0.6628731331195651, + -0.7249842619980585, + -0.7505577667701125, + -0.695065824489254, + -0.6758785703447011, + -0.7211672397198852, + -0.7311633499120457, + -0.7812366406206993, + -0.6689364351107369, + -0.765332105033398, + -0.7789453930416627, + -0.791407784118351, + -0.758706780955165, + -0.7396451741649833, + -0.7073098338263231, + -0.715864196496372, + -0.6756323066290932, + -0.7498082430938154, + -0.6970725349449698, + -0.755651311717798, + -0.6614046652054397, + -0.6891889029408063, + -0.7080973126715949, + -0.7721442867304991, + -0.699879535851349, + -0.7090367021067178, + -0.7525694854150928, + -0.665531092355097, + -0.7361744273467983, + -0.7886146607222839, + -0.7163592505413342, + -0.6757318884973504, + -0.6642888875288695, + -0.6844782283988963, + -0.7740202446707087, + -0.717771494463103, + -0.748546157533701, + -0.6905827086847619, + -0.6785835094183648, + -0.667196919430401, + -0.718057321437347, + -0.7729184081323612, + -0.7635847377628672, + -0.6889725939293676, + -0.7165010290094409, + -0.6873018325306578, + -0.6926665259571408, + -0.6990694154784209, + -0.790887887128747, + -0.7580035756255878, + -0.7895079177333936, + -0.7860183103804038, + -0.6711411010409052, + -0.6872079191794083, + -0.7017497072319275, + -0.7294361428417222, + -0.7281154444286498, + -0.6749379276237463, + -0.7813221842032481, + -0.7780122209563731, + -0.7124494199481795, + -0.7258491691628722, + -0.6762098316207998, + -0.7656471721596336, + -0.6726753189994771, + -0.748445248431297, + -0.7516925550543561, + -0.7890510715633097, + -0.711279843374019, + -0.7217364348916847, + -0.7358964320540587, + -0.7236449467758588, + -0.7336235264339732, + -0.6799291946441484, + -0.6739077961393475, + -0.77564079295587, + -0.7609616833331138, + -0.7817291483850689, + -0.6959719546857701, + -0.7204358398498263, + -0.7471280384405431, + -0.74919050854115, + -0.75248869265689, + -0.7260604043888979, + -0.7031328568711934, + -0.7724747350365253, + -0.7931812556611203, + -0.6851240406415358, + -0.6744221708885194, + -0.7658066297999608, + -0.7170690106026203, + -0.7099904642107321, + -0.6989879188999713, + -0.6688887661749185, + -0.774691991941232, + -0.7101394180734952, + -0.7496774048985264, + -0.691501079723581, + -0.7170873088934621, + -0.7185293399406893, + -0.7579358128600773, + -0.7882267043826683, + -0.6878104149157473, + -0.6768813239235315, + -0.7781083601580234, + -0.6919092871184092, + -0.728446818906695, + -0.6973154344906932, + -0.716906613868148, + -0.7497172626166083, + -0.7034032205151893, + -0.6765645305323884, + -0.6949024464979333, + -0.6765859783331714, + -0.7909524827640942, + -0.7128254138950942, + -0.7922664773484692, + -0.6846116528682697, + -0.7049144511485318, + -0.7477617464465754, + -0.7371108839511578, + -0.6772207357860527, + -0.7182155694659729, + -0.7863864638358857, + -0.7547031983207688, + -0.6804729602222492, + -0.688186582790938, + -0.6919566097232204, + -0.746040910088004, + -0.68266527242062, + -0.7708041821478111, + -0.7730888443978756, + -0.7131892446608868, + -0.7465663293564164, + -0.7334239925548753, + -0.735351297084726, + -0.7336072223791115, + -0.7441760889127248, + -0.6927771810059792, + -0.7483592304039232, + -0.7270073642213171, + -0.733395720613198, + -0.6987234772116713, + -0.6959043350202588, + -0.7560787799269347, + -0.7393074777517274, + -0.7197030393389049, + -0.7048229681178677, + -0.6979282633504839, + -0.7507957381269407, + -0.6634310216290185, + -0.7279864429616825, + -0.6729122423440207, + -0.7035193264994702, + -0.7546472889047543, + -0.7831463749812322, + -0.7575730770264668, + -0.6789549572770288, + -0.6930204583675318, + -0.7861680798484366, + -0.7796959275958607, + -0.6930268464663852, + -0.778933770931836, + -0.7687473735338285, + -0.6841832725532414, + -0.6989824278087209, + -0.7433411034828237, + -0.675764564226538, + -0.7105518394708837, + -0.7868805219964067, + -0.7595454146660784, + -0.7886563989056484, + -0.7743184226329126, + -0.7081550340225226, + -0.7018660995589481, + -0.7044019153481341, + -0.7644615104346044, + -0.7351996345288233, + -0.768529148816276, + -0.7562563459921665, + -0.6718310662052696, + -0.7536777357230565, + -0.6781005543826713, + -0.7577600881395024, + -0.7266301713799898, + -0.7687349983291951, + -0.7265595821823859, + -0.7218637688992181, + -0.6787050773396897, + -0.6737211770010485, + -0.7314612731308378, + -0.7784167580929866, + -0.7671295787766635, + -0.6666310526941499, + -0.6664326151612712, + -0.7317147430017626, + -0.710685329242566, + -0.6693946357933784, + -0.7750153127860352, + -0.7185073993026052, + -0.778882703221871, + -0.7928515830156879, + -0.6784076184143271, + -0.6775920935225748, + -0.7634482648022406, + -0.7086154760044789, + -0.6913776006456438, + -0.7789423451626581, + -0.7013791485335181, + -0.7221098815947491, + -0.7343592283570665, + -0.730626975006115, + -0.6833591234235066, + -0.6693637737453563, + -0.6898069594584096, + -0.6955981351924282, + -0.7288593246467129, + -0.6870596527911523, + -0.6952955974902765, + -0.7641587441574229, + -0.7555550818318985, + -0.7890061733936796, + -0.7146400828513093, + -0.77551666897533, + -0.6766716176279078, + -0.6801829342352913, + -0.6974104091653897, + -0.7717570033513562, + -0.7794242637833303, + -0.7928213797803041, + -0.6683367678870935, + -0.7459271771431962, + -0.693450370694483, + -0.7891619811541803, + -0.6763196516886315, + -0.6756311608570803, + -0.7468210825286181, + -0.6791145407338013, + -0.6981885615826404, + -0.7846834718251552, + -0.6948847182837116, + -0.6640215062630319, + -0.6775781177402268, + -0.782481795746626, + -0.7391520067747523, + -0.7103030120325926, + -0.6964224177306173, + -0.6881999319008776, + -0.7197416885566338, + -0.7267307923912687, + -0.7615172200027943, + -0.7615117771232797, + -0.6646782478280503, + -0.7155674252298084, + -0.6758944237125408, + -0.6704522475086863, + -0.6896267024379947, + -0.7606845959408144, + -0.74143280597504, + -0.7473859072000016, + -0.7007881551201587, + -0.7636090215408848, + -0.6801183542473633, + -0.6719527403189154, + -0.7073578676801471, + -0.7429066827753162, + -0.7386146060827888, + -0.7931371922196938, + -0.7122514446066788, + -0.7801166739122692, + -0.7287760183153684, + -0.7525674419482771, + -0.7294486372588402, + -0.7934033451566359, + -0.6968947123875086, + -0.7781245370823958, + -0.7371759731170419, + -0.7716980004344216, + -0.6617529068780305, + -0.6993628795486031, + -0.7209259717833413, + -0.6995312174070636, + -0.7554454530864066, + -0.7770879498540828, + -0.7169106622568469, + -0.661820569922148, + -0.7633817091099525, + -0.7771743959353676, + -0.6610780063085435, + -0.6753582868982752, + -0.6762891917963371, + -0.6815282002495577, + -0.6713746581403977, + -0.6959441193453643, + -0.7210514431236255, + -0.6603124643627473, + -0.6778041530117662, + -0.6913399267853132, + -0.7375738021818667, + -0.6824038273013369, + -0.6858631946448925, + -0.7584350891895039, + -0.6800728375080933, + -0.7356356410264668, + -0.7867687562095133, + -0.7185782944578624, + -0.7065212551996503, + -0.7144215175935222, + -0.7427611822761238, + -0.7510751440236052, + -0.6745521187536692, + -0.7843223082759855, + -0.6842246725831492, + -0.6899306270980132, + -0.7113733040539859, + -0.6769670972247075, + -0.7120018651290967, + -0.7018949910346932, + -0.7352318244732772, + -0.7885244514015306, + -0.6828736460727675, + -0.7560945681457497, + -0.6753809828697935, + -0.676411142941336, + -0.7289189605162723, + -0.7908568405301125, + -0.7514153859711836, + -0.6792540747313371, + -0.7302198397009709, + -0.7328722254454337, + -0.7673040684920613, + -0.7880603067976241, + -0.7488294188140664, + -0.7023402794497438, + -0.6820413050280324, + -0.7776684374801729, + -0.7146966657718968, + -0.7177229276596654, + -0.6832511539367492, + -0.6774529846495103, + -0.691646552963121, + -0.7749192215258347, + -0.720921801660826, + -0.6607671260389953, + -0.7495917097999376, + -0.7125755426354798, + -0.6836241983393448, + -0.7404974089006153, + -0.7746470374181003, + -0.7750379485457795, + -0.6695396646344774, + -0.7386927563423793, + -0.7098883176266827, + -0.7368947326962252, + -0.7683326752924893, + -0.6847808849284335, + -0.754580645089243, + -0.7017761397632701, + -0.7715585666368627, + -0.7012951303763169, + -0.7764836060419428, + -0.7132737216098912, + -0.6893601041507389, + -0.7458406145026968, + -0.6942980487282876, + -0.7230070691864268, + -0.7502268749077965, + -0.7419232619714704, + -0.767126625478878, + -0.7053061558506877, + -0.7809902866508712, + -0.7055432454971439, + -0.6984549877143266, + -0.7790135408309519, + -0.6780249449393908, + -0.7384390316376934, + -0.6949559139889685, + -0.7836468959866837, + -0.7008486098790752, + -0.728401003975054, + -0.722988406051982, + -0.7761908437899945, + -0.6835234678202415, + -0.6741861701416721, + -0.7608847773414453, + -0.6612948454460185, + -0.7247857605127922, + -0.6936055215113586, + -0.7374228855611196, + -0.7734250014612665, + -0.6664662847123369, + -0.6908434497948552, + -0.7121652187300602, + -0.6755131627278834, + -0.7313516246009414, + -0.7717323449721964, + -0.7347061182210496, + -0.7515459294569763, + -0.7849684007693336, + -0.7867165431990044, + -0.7843817932129608, + -0.6904315129206301, + -0.7418950213641257, + -0.6692060232136029, + -0.7865156493004938, + -0.7701703889853974, + -0.722622453286989, + -0.7542026176147206, + -0.7515732632573109, + -0.7182752492542437, + -0.7472024490936408, + -0.713882467354427, + -0.7544913643208925, + -0.7807548981393861, + -0.7026236906101335, + -0.7669179466123415, + -0.7177004046737073, + -0.6679310566305136, + -0.7072706840922229, + -0.7621175296713278, + -0.7896290096324168, + -0.7296673845356334, + -0.7816541036552126, + -0.6921577163293655, + -0.7151563616200197, + -0.7928046481411422, + -0.6804613301086488, + -0.7763872550240056, + -0.6624983179389125, + -0.714091720025113, + -0.7321104825366814, + -0.7033914010733908, + -0.7121634955023587, + -0.6639209196656691, + -0.7591881115188981, + -0.6673095737023407, + -0.7610887530855286, + -0.6639781475940939, + -0.7821851736112869, + -0.7732518368763738, + -0.6904498759769209, + -0.6711264146838757, + -0.7785927374952162, + -0.7618368825335108, + -0.7103765598103176, + -0.7220878105638308, + -0.6854404520204773, + -0.6904189076681992, + -0.7766610744684207, + -0.7399529439411933, + -0.7356012791421104, + -0.700810473053583, + -0.7050525158012642, + -0.7032608957802895, + -0.7437790513277412, + -0.6914568961436078, + -0.7217904800986422, + -0.6725771763358225, + -0.7306627164037494, + -0.6812722151346441, + -0.6683545032285325, + -0.7183286286912239, + -0.7481858092118113, + -0.7102691168840504, + -0.7898211929386564, + -0.7635388311568645, + -0.6666718285455763, + -0.7091054285628722, + -0.7792445775024294, + -0.7430320623159582, + -0.6763039361112677, + -0.7344984847379595, + -0.6667710131954943, + -0.6864757237550765, + -0.6924781128037555, + -0.7677284894185472, + -0.7134826389356673, + -0.7214669015800427, + -0.7399963684907018, + -0.6681024619754498, + -0.7215485987791922, + -0.6634583140938237, + -0.7925123148176683, + -0.789652330149457, + -0.7213652877995306, + -0.7881401543789349, + -0.7197684594373567, + -0.7415948195524072, + -0.7573690425298277, + -0.7165573952131383, + -0.769836070166549, + -0.6876207770321183, + -0.737308891543659, + -0.7238513203090735, + -0.7023181359395316, + -0.7535752666435839, + -0.6908823716033664, + -0.7763536628934957, + -0.7721702941821543, + -0.7272649005473804, + -0.7012635736455374, + -0.6983767961999268, + -0.7694031063864708, + -0.7663641575237984, + -0.7351957110641543, + -0.7152792779898305, + -0.7453375803328576, + -0.6745106545678813, + -0.7386472886634508, + -0.7579671195758052, + -0.6891344811389071, + -0.7293323758022418, + -0.7808750500159024, + -0.7641360231517088, + -0.7719513312872205, + -0.7297687697178106, + -0.7546580336285239, + -0.6906714077727704, + -0.7180870566638446, + -0.6769163771733647, + -0.7332759856724878, + -0.782666356152172, + -0.7737716443589477, + -0.6671828070141143, + -0.7363093258641943, + -0.6635087708954657, + -0.6935384730729572, + -0.6764199707771283, + -0.6883038115213298, + -0.6671796988786235, + -0.7299968183222254, + -0.709520192824809, + -0.7290075687311519, + -0.6875380881858829, + -0.6838583960022817, + -0.791916748164993 + ], + "type": "scatter" + }, + { + "mode": "markers", + "name": "Expectation", + "x": [ + 0.5609335742540509 + ], + "y": [ + -0.7307572162679157 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines+markers", + "name": "Mode", + "x": [ + 0.44, + 0.4638206958770752, + 0.4638206958770752, + 0.44, + 0.44, + null, + 0.44, + 0.4638206958770752, + 0.4638206958770752, + 0.44, + 0.44, + null + ], + "y": [ + -0.7425735592842102, + -0.7425735592842102, + -0.66, + -0.66, + -0.7425735592842102, + null, + -0.7425735592842102, + -0.7425735592842102, + -0.66, + -0.66, + -0.7425735592842102, + null + ], + "type": "scatter" + } + ], + "layout": { + "title": { + "text": "DeterministicSumUnit" + }, + "xaxis": { + "title": { + "text": "relative_x" + }, + "range": [ + -1, + 1 + ] + }, + "yaxis": { + "title": { + "text": "relative_y" + }, + "range": [ + -1, + 1 + ] + }, + "template": { + "data": { + "histogram2dcontour": [ + { + "type": "histogram2dcontour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "choropleth": [ + { + "type": "choropleth", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "histogram2d": [ + { + "type": "histogram2d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmap": [ + { + "type": "heatmap", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmapgl": [ + { + "type": "heatmapgl", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "contourcarpet": [ + { + "type": "contourcarpet", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "contour": [ + { + "type": "contour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "surface": [ + { + "type": "surface", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "mesh3d": [ + { + "type": "mesh3d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "scatter": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scatter" + } + ], + "parcoords": [ + { + "type": "parcoords", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolargl": [ + { + "type": "scatterpolargl", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "bar": [ + { + "error_x": { + "color": "#f2f5fa" + }, + "error_y": { + "color": "#f2f5fa" + }, + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "scattergeo": [ + { + "type": "scattergeo", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolar": [ + { + "type": "scatterpolar", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "scattergl": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scattergl" + } + ], + "scatter3d": [ + { + "type": "scatter3d", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattermapbox": [ + { + "type": "scattermapbox", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterternary": [ + { + "type": "scatterternary", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattercarpet": [ + { + "type": "scattercarpet", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "baxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "type": "carpet" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#506784" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "header": { + "fill": { + "color": "#2a3f5f" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "type": "table" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ] + }, + "layout": { + "autotypenumbers": "strict", + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#f2f5fa" + }, + "hovermode": "closest", + "hoverlabel": { + "align": "left" + }, + "paper_bgcolor": "rgb(17,17,17)", + "plot_bgcolor": "rgb(17,17,17)", + "polar": { + "bgcolor": "rgb(17,17,17)", + "angularaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "radialaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "ternary": { + "bgcolor": "rgb(17,17,17)", + "aaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "baxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "caxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "sequential": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ] + }, + "xaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "yaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "scene": { + "xaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "yaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "zaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + } + }, + "shapedefaults": { + "line": { + "color": "#f2f5fa" + } + }, + "annotationdefaults": { + "arrowcolor": "#f2f5fa", + "arrowhead": 0, + "arrowwidth": 1 + }, + "geo": { + "bgcolor": "rgb(17,17,17)", + "landcolor": "rgb(17,17,17)", + "subunitcolor": "#506784", + "showland": true, + "showlakes": true, + "lakecolor": "rgb(17,17,17)" + }, + "title": { + "x": 0.05 + }, + "updatemenudefaults": { + "bgcolor": "#506784", + "borderwidth": 0 + }, + "sliderdefaults": { + "bgcolor": "#C8D4E3", + "borderwidth": 1, + "bordercolor": "rgb(17,17,17)", + "tickwidth": 0 + }, + "mapbox": { + "style": "dark" + } + } + } + }, + "config": { + "plotlyServerURL": "https://plot.ly" + } + }, + "text/html": "
" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "grounded_model = fpa.ground_model(fpa.policy, fpa.events_from_occupancy_costmap())\n", + "p_xy = grounded_model.marginal([relative_x, relative_y])\n", + "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", + "fig.update_xaxes(range=[-1, 1])\n", + "fig.update_yaxes(range=[-1, 1])\n", + "fig.show()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:15:49.278694Z", + "start_time": "2024-03-12T16:15:46.320651Z" + } + }, + "id": "a36ee203bb45f8b1", + "execution_count": 12 + }, + { + "cell_type": "code", + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n", + "navigate works\n", + "facing works\n", + "\n" + ] + }, + { + "ename": "KeyboardInterrupt", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mServiceException\u001B[0m Traceback (most recent call last)", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mcall_ik\u001B[0;34m(root_link, tip_link, target_pose, robot_object, joints)\u001B[0m\n\u001B[1;32m 95\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 96\u001B[0;31m \u001B[0mresp\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mreq\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 97\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mrospy\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mServiceException\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36m__call__\u001B[0;34m(self, *args, **kwds)\u001B[0m\n\u001B[1;32m 441\u001B[0m \"\"\"\n\u001B[0;32m--> 442\u001B[0;31m \u001B[0;32mreturn\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mcall\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwds\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 443\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36mcall\u001B[0;34m(self, *args, **kwds)\u001B[0m\n\u001B[1;32m 522\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 523\u001B[0;31m \u001B[0mresponses\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mtransport\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mreceive_once\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 524\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mlen\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mresponses\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;34m==\u001B[0m \u001B[0;36m0\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_base.py\u001B[0m in \u001B[0;36mreceive_once\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 741\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mb\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mtell\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;34m>=\u001B[0m \u001B[0;36m4\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 742\u001B[0;31m \u001B[0mp\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mread_messages\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0msock\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 743\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0;32mnot\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36mread_messages\u001B[0;34m(self, b, msg_queue, sock)\u001B[0m\n\u001B[1;32m 359\u001B[0m \"\"\"\n\u001B[0;32m--> 360\u001B[0;31m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_read_ok_byte\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0msock\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 361\u001B[0m \u001B[0mrospy\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mmsg\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdeserialize_messages\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mrecv_data_class\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mqueue_size\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mqueue_size\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmax_msgs\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mstart\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;31m#rospy.msg\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36m_read_ok_byte\u001B[0;34m(self, b, sock)\u001B[0m\n\u001B[1;32m 342\u001B[0m \u001B[0mb\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mtruncate\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;36m0\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 343\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0mServiceException\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"service [%s] responded with an error: %s\"\u001B[0m\u001B[0;34m%\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mresolved_name\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mstr\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 344\u001B[0m \u001B[0;32melse\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;31mServiceException\u001B[0m: service [/pr2_right_arm_kinematics/get_ik] responded with an error: b''", + "\nDuring handling of the above exception, another exception occurred:\n", + "\u001B[0;31mIKError\u001B[0m Traceback (most recent call last)", + "\u001B[0;32m\u001B[0m in \u001B[0;36m\u001B[0;34m\u001B[0m\n\u001B[1;32m 3\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m----> 4\u001B[0;31m \u001B[0msample\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 5\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mPlanFailure\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/resolver/location/jpt_location.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 298\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"facing works\"\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 299\u001B[0;31m \u001B[0mPickUpActionPerformable\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mobject_designator\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mgrasp\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 300\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"pickup works\"\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 256\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstatus\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mTaskStatus\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mFAILED\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 257\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 258\u001B[0m \u001B[0;32mfinally\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 244\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstart_time\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mnow\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 245\u001B[0;31m \u001B[0mresult\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mfun\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwargs\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 246\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/designators/actions/actions.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 296\u001B[0m \u001B[0mBulletWorld\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mcurrent_bullet_world\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0madd_vis_axis\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0madjusted_oTm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 297\u001B[0;31m \u001B[0mMoveTCPMotion\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0madjusted_oTm\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 298\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 256\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstatus\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mTaskStatus\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mFAILED\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 257\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 258\u001B[0m \u001B[0;32mfinally\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 244\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstart_time\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mnow\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 245\u001B[0;31m \u001B[0mresult\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mfun\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwargs\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 246\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/designators/motion_designator.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 142\u001B[0m \u001B[0mpm_manager\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mProcessModuleManager\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mget_manager\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 143\u001B[0;31m \u001B[0;32mreturn\u001B[0m \u001B[0mpm_manager\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mmove_tcp\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mexecute\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 144\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_module.py\u001B[0m in \u001B[0;36mexecute\u001B[0;34m(self, designator)\u001B[0m\n\u001B[1;32m 59\u001B[0m \u001B[0;32mwith\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_lock\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 60\u001B[0;31m \u001B[0mret\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_execute\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mdesignator\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 61\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mProcessModule\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mexecution_delay\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_modules/pr2_process_modules.py\u001B[0m in \u001B[0;36m_execute\u001B[0;34m(self, desig)\u001B[0m\n\u001B[1;32m 124\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 125\u001B[0;31m \u001B[0m_move_arm_tcp\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mdesig\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 126\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_modules/pr2_process_modules.py\u001B[0m in \u001B[0;36m_move_arm_tcp\u001B[0;34m(target, robot, arm)\u001B[0m\n\u001B[1;32m 206\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 207\u001B[0;31m \u001B[0minv\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mrequest_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mgripper\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 208\u001B[0m \u001B[0m_apply_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0minv\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mrequest_ik\u001B[0;34m(target_pose, robot, joints, gripper)\u001B[0m\n\u001B[1;32m 132\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 133\u001B[0;31m \u001B[0minv\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mcall_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mbase_link\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mend_effector\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mtarget_diff\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 134\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mcall_ik\u001B[0;34m(root_link, tip_link, target_pose, robot_object, joints)\u001B[0m\n\u001B[1;32m 98\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mrobot_description\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mname\u001B[0m \u001B[0;34m==\u001B[0m \u001B[0;34m\"pr2\"\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 99\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0mIKError\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget_pose\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mroot_link\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 100\u001B[0m \u001B[0;32melse\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;31mIKError\u001B[0m: Position header: \n seq: 0\n stamp: \n secs: 1710260163\n nsecs: 817859888\n frame_id: \"pr2_1/torso_lift_link\"\npose: \n position: \n x: 0.7127518608638204\n y: 0.10233092440219571\n z: 0.27932495587642475\n orientation: \n x: -1.5631567650027079e-07\n y: -2.969516120978674e-08\n z: -0.2977579729768291\n w: 0.9546413931569827 in frame 'torso_lift_link' is not reachable for end effector", + "\nDuring handling of the above exception, another exception occurred:\n", + "\u001B[0;31mKeyboardInterrupt\u001B[0m Traceback (most recent call last)", + "\u001B[0;32m\u001B[0m in \u001B[0;36m\u001B[0;34m\u001B[0m\n\u001B[1;32m 5\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mPlanFailure\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[1;32m 6\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtype\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0me\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m----> 7\u001B[0;31m \u001B[0mtime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0msleep\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 8\u001B[0m \u001B[0;32mcontinue\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[1;32m 9\u001B[0m \u001B[0;32mbreak\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", + "\u001B[0;31mKeyboardInterrupt\u001B[0m: " + ] + } + ], + "source": [ + "with simulated_robot:\n", + " for sample in fpa:\n", + " try:\n", + " sample.perform()\n", + " break\n", + " except PlanFailure as e:\n", + " print(type(e))\n", + " time.sleep(1)\n", + " continue" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-12T16:16:03.995962Z", + "start_time": "2024-03-12T16:15:49.279418Z" + } + }, + "id": "ea57ad24b398e28f", + "execution_count": 13 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "# world.exit()\n", + "# viz_marker_publisher._stop_publishing()" + ], + "metadata": { + "collapsed": false + }, + "id": "62728fa8ed6e55bd", + "execution_count": null + } + ], + "metadata": { + "kernelspec": { + "name": "pycram", + "language": "python", + "display_name": "pycram" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.6" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/src/pycram/orm/action_designator.py b/src/pycram/orm/action_designator.py index 48b4197a3..2f64be0ec 100644 --- a/src/pycram/orm/action_designator.py +++ b/src/pycram/orm/action_designator.py @@ -118,3 +118,8 @@ class GraspingAction(ObjectMixin, Action): id: Mapped[int] = mapped_column(ForeignKey(f'{Action.__tablename__}.id'), primary_key=True, init=False) arm: Mapped[str] + +class FaceAtAction(PoseMixin, Action): + """ORM Class of pycram.designators.action_designator.FaceAtAction.""" + + id: Mapped[int] = mapped_column(ForeignKey(f'{Action.__tablename__}.id'), primary_key=True, init=False) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 06717c76d..a85024e68 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -110,23 +110,21 @@ def __init__(self, target, reachable_for=None, reachable_arm=None): """ super().__init__(target, reachable_for, None, reachable_arm, None) - def create_occupancy_rectangles(self) -> List[Rectangle]: + @staticmethod + def create_occupancy_rectangles_from_map(ocm: OccupancyCostmap): """ + Create a list of rectangles that represent the occupied space of the target object from an OccupancyCostmap. + + :param ocm: The OccupancyCostmap :return: A list of rectangles that represent the occupied space of the target object. """ - # create Occupancy costmap for the target object - ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, - origin=self.target.pose) - - # working on a copy of the costmap, since found rectangles are deleted ocm_map = np.copy(ocm.map) - origin = np.array([ocm.height / 2, ocm.width / 2]) rectangles = [] # for every index pair (i, j) in the occupancy costmap - for i in range(0, ocm_map.shape[0]): - for j in range(0, ocm_map.shape[1]): + for i in range(0, ocm.map.shape[0]): + for j in range(0, ocm.map.shape[1]): # if this index has not been used yet if ocm_map[i][j] > 0: @@ -147,6 +145,15 @@ def create_occupancy_rectangles(self) -> List[Rectangle]: return rectangles + def create_occupancy_rectangles(self) -> List[Rectangle]: + """ + :return: A list of rectangles that represent the occupied space of the target object. + """ + # create Occupancy costmap for the target object + ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, + origin=self.target.pose) + return self.create_occupancy_rectangles_from_map(ocm) + class DatabaseCostmapLocation(AbstractCostmapLocation, RequiresDatabase): """ diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 250215127..98db73b22 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -1,39 +1,38 @@ -import dataclasses -import json -import time -from typing import Optional, List, Tuple +from dataclasses import dataclass +from typing import Optional, List +import numpy as np +import pandas as pd import portion -import sqlalchemy +import pybullet import sqlalchemy.orm - +import tqdm from probabilistic_model.learning.jpt.jpt import JPT from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe +from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution +from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit, \ + DecomposableProductUnit from random_events.events import Event -import numpy as np -import pybullet -import tf.transformations -from random_events.variables import Continuous +from random_events.variables import Continuous, Symbolic from sqlalchemy import select - -import pycram.designators.location_designator -import pycram.task -from ...costmaps import OccupancyCostmap, plot_grid -from ...plan_failures import PlanFailure -from ...pose import Pose -from pycram.bullet_world import BulletWorld, Object - -from ...orm.action_designator import PickUpAction +from tf import transformations + +from .database_location import Location, RequiresDatabase, AbstractCostmapLocation +from ...bullet_world import BulletWorld +from ...costmaps import OccupancyCostmap, plot_grid, VisibilityCostmap +from ...designator import ObjectDesignatorDescription, ActionDesignatorDescription +from ...designators.actions.actions import PickUpActionPerformable, NavigateActionPerformable, ActionAbstract, \ + LookAtActionPerformable +from ...enums import TaskStatus, Grasp, Arms +from ...local_transformer import LocalTransformer +from ...orm.action_designator import PickUpAction as ORMPickUpAction, FaceAtAction as ORMFaceAtAction +from ...orm.base import RobotState, Quaternion from ...orm.object_designator import Object -from ...orm.base import Position, RobotState, Pose as ORMPose, Quaternion from ...orm.task import TaskTreeNode -from .database_location import Location, RequiresDatabase, Rectangle, AbstractCostmapLocation -from ...enums import TaskStatus - -import pandas as pd - -from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit, DecomposableProductUnit -from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution +from ...plan_failures import PlanFailure +from ...pose import Pose +from ...robot_descriptions import robot_description +from ...task import with_tree class GaussianCostmapModel: @@ -54,6 +53,8 @@ class GaussianCostmapModel: relative_x = Continuous("relative_x") relative_y = Continuous("relative_y") + grasp = Symbolic("grasp", ["front", "left", "right"]) + arm = Symbolic("arm", ["left", "right"]) def __init__(self, distance_to_center: float = 0., variance: float = 0.5): self.distance_to_center = distance_to_center @@ -64,8 +65,8 @@ def create_model_with_center(self) -> ProbabilisticCircuit: Create a fully factorized gaussian at the center of the map. """ centered_model = DecomposableProductUnit() - centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., 0.5)) - centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., 0.5)) + centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., self.variance)) + centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., self.variance)) return centered_model.probabilistic_circuit def create_model(self) -> ProbabilisticCircuit: @@ -76,7 +77,7 @@ def create_model(self) -> ProbabilisticCircuit: """ centered_model = self.create_model_with_center() - model = DeterministicSumUnit() + region_model = DeterministicSumUnit() north_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), self.relative_y: portion.closed(self.distance_to_center, float("inf"))}) @@ -89,15 +90,22 @@ def create_model(self) -> ProbabilisticCircuit: for region in [north_region, south_region, east_region, west_region]: conditional, probability = centered_model.conditional(region) - model.add_subcircuit(conditional.root, probability) + region_model.add_subcircuit(conditional.root, probability) - return model.probabilistic_circuit + result = DecomposableProductUnit() + p_arms = SymbolicDistribution(self.arm, [1 / len(self.arm.domain) for _ in self.arm.domain]) + p_grasp = SymbolicDistribution(self.grasp, [1 / len(self.grasp.domain) for _ in self.grasp.domain]) + result.add_subcircuit(p_arms) + result.add_subcircuit(p_grasp) + result.add_subcircuit(region_model) + + return result.probabilistic_circuit class QueryBuilder(RequiresDatabase): def select_statement(self): - return (select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, + return (select(ORMPickUpAction.arm, ORMPickUpAction.grasp, RobotState.torso_height, self.relative_x, self.relative_y, Quaternion.x, Quaternion.y, Quaternion.z, TaskTreeNode.status)).distinct() @@ -157,7 +165,6 @@ def events_from_occupancy_costmap(self) -> List[Event]: :return: List of evidences describing the found boxes """ - events = [] for rectangle in self.create_occupancy_rectangles(): # get the occupancy costmap @@ -223,3 +230,186 @@ def close_visualization(self) -> None: for id in self.visual_ids: pybullet.removeBody(id) self.visual_ids = [] + + +@dataclass +class FaceAtPerformable(ActionAbstract): + """ + Turn the robot chassis such that is faces the ``pose`` and after that perform a look at action. + """ + + pose: Pose + """ + The pose to face + """ + + orm_class = ORMFaceAtAction + + @with_tree + def perform(self) -> None: + # get the robot position + robot_position = BulletWorld.robot.pose + + # calculate orientation for robot to face the object + angle = np.arctan2(robot_position.position.y - self.pose.position.y, + robot_position.position.x - self.pose.position.x) + np.pi + orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) + + # create new robot pose + new_robot_pose = Pose(robot_position.to_list()[0], orientation) + + # turn robot + NavigateActionPerformable(new_robot_pose).perform() + + # look at target + LookAtActionPerformable(self.pose).perform() + + +@dataclass +class FunkyPickUpActionPerformable(ActionAbstract): + """ + Navigate to `standing_position`, then turn towards the object + """ + + standing_position: Pose + """ + The pose to stand before trying to pick up the object + """ + + object_designator: ObjectDesignatorDescription.Object + """ + The object to pick up + """ + + arm: Arms + """ + The arm to use + """ + + grasp: Grasp + """ + The grasp to use + """ + + def perform(self): + NavigateActionPerformable(self.standing_position).perform() + FaceAtPerformable(self.object_designator.pose).perform() + PickUpActionPerformable(self.object_designator, self.arm, self.grasp).perform() + +class FunkyPickUpAction(ActionDesignatorDescription): + """ + Cooler PickUpAction + """ + + sample_amount: int = 20 + + @dataclass + class Variables: + arm: Symbolic + grasp: Symbolic + relative_x: Continuous + relative_y: Continuous + + def __init__(self, object_designator: ObjectDesignatorDescription.Object, arms: List[str], grasps: List[str], + policy: Optional[ProbabilisticCircuit] = None): + super().__init__(None) + + self.object_designator = object_designator + self.arms = arms + self.grasps = grasps + + if policy is None: + policy = self.create_initial_policy() + self.policy = policy + + self.variables = self.Variables(*self.policy.variables) + + @staticmethod + def create_initial_policy() -> ProbabilisticCircuit: + return GaussianCostmapModel(0.3, 0.5).create_model() + + def sample_to_action(self, sample: List) -> FunkyPickUpActionPerformable: + arm, grasp, relative_x, relative_y = sample + position = [relative_x, relative_y, 0.] + pose = Pose(position, frame=self.object_designator.bullet_world_object.tf_frame) + standing_position = LocalTransformer().transform_pose(pose, "map") + standing_position.position.z = 0 + action = FunkyPickUpActionPerformable(standing_position, self.object_designator, arm, grasp) + return action + + def events_from_occupancy_costmap(self) -> List[Event]: + # create Occupancy costmap for the target object + ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, + origin=self.object_designator.pose) + vcm = VisibilityCostmap(min_height=1.27, max_height=1.69, + size=200, resolution=0.02, origin=self.object_designator.pose) + mcm = ocm + vcm + rectangles = AbstractCostmapLocation.create_occupancy_rectangles_from_map(mcm) + + events = [] + + for rectangle in rectangles: + event = Event({self.variables.relative_x: portion.open(rectangle.x_lower, rectangle.x_upper), + self.variables.relative_y: portion.open(rectangle.y_lower, rectangle.y_upper)}) + events.append(event) + return events + + def ground_model(self, model: ProbabilisticCircuit, events: List[Event]) -> ProbabilisticCircuit: + """ + Ground the model to the current evidence. + """ + result = DeterministicSumUnit() + + for event in events: + conditional, probability = model.conditional(event) + if probability > 0: + result.add_subcircuit(conditional.root, probability) + + if len(result.subcircuits) == 0: + raise PlanFailure("No possible locations found") + + result.normalize() + return result.probabilistic_circuit + + def iterate_without_occupancy_costmap(self): + samples = self.policy.sample(self.sample_amount) + for sample in samples: + action = self.sample_to_action(sample) + yield action + + def __iter__(self): + model = self.ground_model(self.policy, self.events_from_occupancy_costmap()) + samples = model.sample(self.sample_amount) + likelihoods = [model.likelihood(sample) for sample in samples] + + # sort samples by likelihood + samples = [x for _, x in sorted(zip(likelihoods, samples), key=lambda pair: pair[0], reverse=True)] + + for sample in samples: + action = self.sample_to_action(sample) + yield action + + @staticmethod + def query_for_database(): + query_builder = RequiresDatabase() + query = select(ORMPickUpAction.arm, ORMPickUpAction.grasp, query_builder.relative_x, + query_builder.relative_y, ).distinct() + query = query_builder.join_statement(query).where(TaskTreeNode.status == TaskStatus.SUCCEEDED) + return query + + def try_out_policy(self): + successful_tries = 0 + total_tries = 0 + + pbar = tqdm.tqdm(self.iterate_without_occupancy_costmap(), total=self.sample_amount) + + for action in pbar: + total_tries += 1 + try: + action.perform() + successful_tries += 1 + except PlanFailure as p: + pass + + pbar.set_postfix({"Success Probability": successful_tries / total_tries}) + BulletWorld.current_bullet_world.reset_bullet_world() diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 65e3ff091..3ebe43d33 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -2,6 +2,12 @@ import time import unittest +import numpy as np +import pandas as pd +from anytree import RenderTree +from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit +from random_events.variables import Continuous + import pycram.plan_failures from pycram.bullet_world import BulletWorld, Object from pycram.designators import action_designator, object_designator @@ -10,25 +16,32 @@ from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description -from pycram.pose import Pose -from pycram.enums import ObjectType +from pycram.pose import Pose, Transform +from pycram.enums import ObjectType, Grasp, Arms import pycram.orm import pycram.task from pycram.task import with_tree from pycram.designators.object_designator import ObjectDesignatorDescription from pycram.ros.viz_marker_publisher import VizMarkerPublisher +from pycram.bullet_world_reasoning import visible +from bullet_world_testcase import BulletWorldTestCase import plotly.graph_objects as go import sqlalchemy import sqlalchemy.orm +from pycram.local_transformer import LocalTransformer +from pycram.resolver.location.jpt_location import JPTCostmapLocation, GaussianCostmapModel, FaceAtPerformable, \ + FunkyPickUpAction + # check if jpt is installed jpt_installed = True try: from probabilistic_model.learning.jpt.jpt import JPT from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe - from pycram.resolver.location.jpt_location import JPTCostmapLocation, GaussianCostmapModel -except ImportError: + +except ImportError as e: + print(e) jpt_installed = False pycrorm_uri = os.getenv('PYCRORM_URI') @@ -141,11 +154,100 @@ def test_object_at_different_location(self): raise p +class FacingTestCase(BulletWorldTestCase): + + def test_facing(self): + + with simulated_robot: + FaceAtPerformable(self.robot.pose, self.milk.pose).perform() + milk_in_robot_frame = LocalTransformer().transform_to_object_frame(self.milk.pose, self.robot) + self.assertAlmostEqual(milk_in_robot_frame.position.y, 0.) + + class TruncatedNormalTestCase(unittest.TestCase): def test_normal_costmap(self): - model = GaussianCostmapModel(0.1, 0.5).create_model() - go.Figure(model.root.plot()).show() + gaussian_model = GaussianCostmapModel(0.1, 0.5) + model = gaussian_model.create_model() + p_xy = model.marginal([gaussian_model.relative_x, gaussian_model.relative_y]) + fig = go.Figure(p_xy.root.plot(),p_xy.root.plotly_layout()) + # fig.show() + + +class FunkyPickUpTestCase(BulletWorldTestCase): + + def test_grounding(self): + fpa = FunkyPickUpAction(ObjectDesignatorDescription(types=[ObjectType.MILK]).ground(), arms=["left", "right"], + grasps=["front", "left", "right", "top"]) + model = fpa.ground_model() + self.assertIsInstance(model, ProbabilisticCircuit) + + +class RLTestCase(unittest.TestCase): + world: BulletWorld + milk: Object + robot: Object + viz_marker_publisher: VizMarkerPublisher + engine: sqlalchemy.engine.Engine + session: sqlalchemy.orm.Session + + @classmethod + def setUpClass(cls): + cls.world = BulletWorld("DIRECT") + cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.viz_marker_publisher = VizMarkerPublisher() + ProcessModule.execution_delay = False + cls.engine = sqlalchemy.create_engine(pycrorm_uri) + + def setUp(self): + self.world.reset_bullet_world() + pycram.orm.base.Base.metadata.create_all(self.engine) + self.session = sqlalchemy.orm.Session(bind=self.engine) + self.session.commit() + + def tearDown(self): + self.world.reset_bullet_world() + pycram.task.reset_tree() + pycram.orm.base.ProcessMetaData.reset() + self.session.rollback() + pycram.orm.base.Base.metadata.drop_all(self.engine) + self.session.close() + + @classmethod + def tearDownClass(cls): + cls.viz_marker_publisher._stop_publishing() + cls.world.exit() + + def test_funky_pick_up(self): + milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground() + fpa = FunkyPickUpAction(milk_description, + arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], + grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value]) + fpa.sample_amount = 1000 + relative_x = Continuous("relative_x") + relative_y = Continuous("relative_y") + p_xy = fpa.policy.marginal([relative_x, relative_y]) + fig = go.Figure(p_xy.root.plot(), p_xy.root.plotly_layout()) + # fig.show() + with simulated_robot: + fpa.try_out_policy() + + pycram.orm.base.ProcessMetaData().description = "costmap_no_obstacles_test" + + pycram.task.task_tree.root.insert(self.session) + samples = pd.read_sql_query(fpa.query_for_database(), self.engine) + samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) + + variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) + model = JPT(variables, min_samples_leaf=0.1) + model.fit(samples) + model = model.probabilistic_circuit + arm, grasp, relative_x, relative_y = model.variables + + p_xy = model.marginal([relative_x, relative_y]) + fig = go.Figure(p_xy.root.plot_2d(5000), p_xy.root.plotly_layout()) + fig.show() if __name__ == '__main__': From 9973778711d791b8f1a40f3e881a3c2fd8f9d30e Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Wed, 13 Mar 2024 14:25:31 +0100 Subject: [PATCH 112/195] [Resolver] Refactored Resolvers and wrote tutorial. --- doc/source/examples.rst | 2 +- examples/custom_resolver.ipynb | 486 - examples/improving_actions.ipynb | 141708 ++++++--------- src/pycram/costmaps.py | 47 + src/pycram/designators/actions/actions.py | 73 +- src/pycram/orm/queries/__init__.py | 0 src/pycram/orm/queries/queries.py | 51 + .../resolver/location/database_location.py | 145 +- src/pycram/resolver/location/jpt_location.py | 415 - src/pycram/resolver/probabilistic/__init__.py | 0 .../probabilistic/probabilistic_action.py | 315 + test/bullet_world_testcase.py | 13 +- test/test_action_designator.py | 9 +- test/test_costmaps.py | 5 + test/test_jpt_resolver.py | 254 - test/test_orm/__init__.py | 0 test/{ => test_orm}/test_orm.py | 2 +- test/test_probabilistic_actions/__init__.py | 0 .../test_database_resolver.py | 12 +- .../test_move_and_pick_up.py | 49 + 20 files changed, 61022 insertions(+), 82564 deletions(-) delete mode 100644 examples/custom_resolver.ipynb create mode 100644 src/pycram/orm/queries/__init__.py create mode 100644 src/pycram/orm/queries/queries.py delete mode 100644 src/pycram/resolver/location/jpt_location.py create mode 100644 src/pycram/resolver/probabilistic/__init__.py create mode 100644 src/pycram/resolver/probabilistic/probabilistic_action.py delete mode 100644 test/test_jpt_resolver.py create mode 100644 test/test_orm/__init__.py rename test/{ => test_orm}/test_orm.py (99%) create mode 100644 test/test_probabilistic_actions/__init__.py rename test/{ => test_probabilistic_actions}/test_database_resolver.py (93%) create mode 100644 test/test_probabilistic_actions/test_move_and_pick_up.py diff --git a/doc/source/examples.rst b/doc/source/examples.rst index 8810ec0a9..e7e567287 100644 --- a/doc/source/examples.rst +++ b/doc/source/examples.rst @@ -27,7 +27,7 @@ Misc notebooks/bullet_world notebooks/minimal_task_tree notebooks/pose - notebooks/custom_resolver + notebooks/improving_actions notebooks/language notebooks/local_transformer diff --git a/examples/custom_resolver.ipynb b/examples/custom_resolver.ipynb deleted file mode 100644 index 570c05a47..000000000 --- a/examples/custom_resolver.ipynb +++ /dev/null @@ -1,486 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Creating a custom Location Costmap\n", - "\n", - "In this tutorial we will walk through the creation of a costmap through probabilistic machine learning.\n", - "\n", - "After this tutorial you will know:\n", - "- Why probabilities are a useful thing in robot planning\n", - "- How to craft probabilistic models for your plan\n", - "\n", - "Lets start by installing the important package." - ] - }, - { - "cell_type": "markdown", - "source": [], - "metadata": { - "collapsed": false - } - }, - { - "cell_type": "code", - "metadata": { - "ExecuteTime": { - "end_time": "2024-03-07T14:18:35.388769Z", - "start_time": "2024-03-07T14:18:34.325541Z" - } - }, - "source": [ - "!pip install --upgrade probabilistic_model" - ], - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Requirement already satisfied: probabilistic_model in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (3.3.4)\r\n", - "Requirement already satisfied: random-events>=1.2.5 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.2.5)\r\n", - "Requirement already satisfied: networkx>=3.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (3.1)\r\n", - "Requirement already satisfied: portion>=2.4.2 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (2.4.2)\r\n", - "Requirement already satisfied: plotly>=5.19.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (5.19.0)\r\n", - "Requirement already satisfied: scipy>=1.10.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.10.1)\r\n", - "Requirement already satisfied: typing-extensions>=4.9.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (4.10.0)\r\n", - "Requirement already satisfied: numpy>=1.24.4 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from probabilistic_model) (1.24.4)\r\n", - "Requirement already satisfied: tenacity>=6.2.0 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from plotly>=5.19.0->probabilistic_model) (8.2.2)\r\n", - "Requirement already satisfied: packaging in /usr/lib/python3/dist-packages (from plotly>=5.19.0->probabilistic_model) (20.3)\r\n", - "Requirement already satisfied: sortedcontainers~=2.2 in /home/tom_sch/.virtualenvs/pycram/lib/python3.8/site-packages (from portion>=2.4.2->probabilistic_model) (2.4.0)\r\n" - ] - } - ], - "execution_count": 1 - }, - { - "cell_type": "markdown", - "source": [ - "Next, we need to gather a lot of data. For that we will write a randomized experiment for grasping a couple of objects.\n", - "In the experiment the robot will try to grasp a randomized object using random poses and torso heights." - ], - "metadata": { - "collapsed": false - } - }, - { - "cell_type": "code", - "metadata": { - "ExecuteTime": { - "end_time": "2024-03-07T14:18:36.577596Z", - "start_time": "2024-03-07T14:18:35.394399Z" - } - }, - "source": [ - "from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable\n", - "from tf import transformations\n", - "import itertools\n", - "from typing import Optional, List, Tuple\n", - "import numpy as np\n", - "import sqlalchemy.orm\n", - "import tqdm\n", - "import pycram.orm.base\n", - "import pycram.task\n", - "from pycram.bullet_world import BulletWorld, Object as BulletWorldObject\n", - "from pycram.designators.action_designator import PickUpAction, NavigateAction\n", - "from pycram.designators.object_designator import ObjectDesignatorDescription\n", - "import pycram.enums\n", - "from pycram.plan_failures import PlanFailure\n", - "from pycram.process_module import ProcessModule\n", - "from pycram.process_module import simulated_robot\n", - "import pycram.orm\n", - "\n", - "import sqlalchemy.sql\n", - "from pycram.pose import Pose\n", - "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", - " \n", - "\n", - "np.random.seed(420)\n", - "\n", - "ProcessModule.execution_delay = False\n", - "pycram.orm.base.ProcessMetaData().description = \"Tutorial for learning from experience in a Grasping action.\"\n", - "\n", - "\n", - "class GraspingExplorer:\n", - " \"\"\"Class to try randomized grasping plans.\"\"\"\n", - "\n", - " world: Optional[BulletWorld]\n", - "\n", - " def __init__(self, robots: Optional[List[Tuple[str, str]]] = None, objects: Optional[List[Tuple[str, str]]] = None,\n", - " arms: Optional[List[str]] = None, grasps: Optional[List[str]] = None,\n", - " samples_per_scenario: int = 1000):\n", - " \"\"\"\n", - " Create a GraspingExplorer.\n", - " :param robots: The robots to use\n", - " :param objects: The objects to try to grasp\n", - " :param arms: The arms of the robot to use\n", - " :param grasps: The grasp orientations to use\n", - " :param samples_per_scenario: The number of tries per scenario.\n", - " \"\"\"\n", - " # store exploration space\n", - " if not robots:\n", - " self.robots: List[Tuple[str, str]] = [(\"pr2\", \"pr2.urdf\")]\n", - "\n", - " if not objects:\n", - " self.objects: List[Tuple[str, pycram.enums.ObjectType, str]] = [(\"cereal\", pycram.enums.ObjectType.BREAKFAST_CEREAL, \"breakfast_cereal.stl\"), \n", - " (\"bowl\", pycram.enums.ObjectType.BOWL, \"bowl.stl\"),\n", - " (\"milk\", pycram.enums.ObjectType.MILK, \"milk.stl\"),\n", - " (\"spoon\", pycram.enums.ObjectType.SPOON, \"spoon.stl\")]\n", - "\n", - " if not arms:\n", - " self.arms: List[str] = [\"left\", \"right\"]\n", - "\n", - " if not grasps:\n", - " self.grasps: List[str] = [\"left\", \"right\", \"front\", \"top\"]\n", - "\n", - " # store trials per scenario\n", - " self.samples_per_scenario: int = samples_per_scenario\n", - "\n", - " # chain hyperparameters\n", - " self.hyper_parameters = [self.robots, self.objects, self.arms, self.grasps]\n", - "\n", - " self.total_tries = 0\n", - " self.total_failures = 0\n", - "\n", - " def perform(self, session: sqlalchemy.orm.Session):\n", - " \"\"\"\n", - " Perform all experiments.\n", - " :param session: The database-session to insert the samples in.\n", - " \"\"\"\n", - "\n", - " # create progress bar\n", - " progress_bar = tqdm.tqdm(\n", - " total=np.prod([len(p) for p in self.hyper_parameters]) * self.samples_per_scenario)\n", - "\n", - " self.world = BulletWorld(\"DIRECT\")\n", - " \n", - " v = VizMarkerPublisher()\n", - "\n", - "\n", - " # for every robot\n", - " for robot, robot_urdf in self.robots:\n", - "\n", - " # spawn it\n", - " robot = BulletWorldObject(robot, pycram.enums.ObjectType.ROBOT, robot_urdf)\n", - "\n", - " # for every obj\n", - " for obj, obj_type, obj_stl in self.objects:\n", - "\n", - " # spawn it\n", - " bw_object = BulletWorldObject(obj, obj_type, obj_stl, Pose([0, 0, 0.75], [0, 0, 0, 1]))\n", - "\n", - " # create object designator\n", - " object_designator = ObjectDesignatorDescription(names=[obj])\n", - "\n", - " # for every arm and grasp pose\n", - " for arm, grasp in itertools.product(self.arms, self.grasps):\n", - " # sample positions in 2D\n", - " positions = np.random.uniform([-2, -2], [2, 2], (self.samples_per_scenario, 2))\n", - "\n", - " # for every position\n", - " for position in positions:\n", - "\n", - " # set z axis to 0\n", - " position = [*position, 0]\n", - "\n", - " # calculate orientation for robot to face the object\n", - " angle = np.arctan2(position[1], position[0]) + np.pi\n", - " orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes=\"sxyz\"))\n", - "\n", - " # try to execute a grasping plan\n", - " with simulated_robot:\n", - "\n", - " ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform()\n", - " # navigate to sampled position\n", - " NavigateAction([Pose(position, orientation)]).resolve().perform()\n", - "\n", - " # move torso\n", - " height = np.random.uniform(0., 0.33, 1)[0]\n", - " MoveTorsoActionPerformable(height).perform()\n", - "\n", - " # try to pick it up\n", - " try:\n", - " PickUpAction(object_designator, [arm], [grasp]).resolve().perform()\n", - "\n", - " # if it fails\n", - " except PlanFailure:\n", - "\n", - " # update failure stats\n", - " self.total_failures += 1\n", - "\n", - " # reset BulletWorld\n", - " self.world.reset_bullet_world()\n", - "\n", - " # update progress bar\n", - " self.total_tries += 1\n", - "\n", - " # insert into database\n", - " pycram.task.task_tree.insert(session, use_progress_bar=False)\n", - " pycram.task.reset_tree()\n", - "\n", - " progress_bar.update()\n", - " progress_bar.set_postfix(success_rate=(self.total_tries - self.total_failures) /\n", - " self.total_tries)\n", - "\n", - " bw_object.remove()\n", - " robot.remove()\n", - "\n", - " self.world.exit()" - ], - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", - "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1709821116.366007]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" - ] - } - ], - "execution_count": 2 - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Next we have to establish a connection to a database and execute the experiment a couple of times. Note that the (few) number of samples we generate is only for demonstrations.\n", - "For robust and reliable machine learning millions of samples are required." - ] - }, - { - "cell_type": "code", - "metadata": { - "scrolled": false, - "ExecuteTime": { - "end_time": "2024-03-07T14:18:36.594199Z", - "start_time": "2024-03-07T14:18:36.578364Z" - } - }, - "source": [ - "engine = sqlalchemy.create_engine(\"sqlite+pysqlite:///:memory:\")\n", - "session = sqlalchemy.orm.Session(bind=engine)\n", - "pycram.orm.base.Base.metadata.create_all(bind=engine)\n", - "session.commit()\n", - "\n", - "explorer = GraspingExplorer(samples_per_scenario=30)" - ], - "outputs": [], - "execution_count": 3 - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Write the database to a file if wanted." - ] - }, - { - "cell_type": "code", - "metadata": { - "ExecuteTime": { - "end_time": "2024-03-07T14:20:14.842937Z", - "start_time": "2024-03-07T14:18:36.594881Z" - } - }, - "source": [ - "import os\n", - "explorer.perform(session)\n", - "con = engine.raw_connection()\n", - "\n", - "with open(os.path.join(os.path. expanduser('~'), \"Documents\", \"costmap.dump\"), 'w') as f:\n", - " for line in con.iterdump():\n", - " f.write('%s\\n' % line)" - ], - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - " 0%| | 0/960 [00:00
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" } ], "source": [ - "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", - "fpa = FunkyPickUpAction(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value])\n", - "relative_x = Continuous(\"relative_x\")\n", - "relative_y = Continuous(\"relative_y\")\n", - "p_xy = fpa.policy.marginal([relative_x, relative_y])\n", + "fpa = MoveAndPickUp(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value])\n", + "p_xy = fpa.policy.marginal([fpa.variables.relative_x, fpa.variables.relative_y])\n", "fig = go.Figure(p_xy.root.plot(), p_xy.root.plotly_layout())\n", - "fig.show()\n", - "\n", - "\n", - "samples = pd.read_sql_query(fpa.query_for_database(), engine)\n", - "samples = samples.rename(columns={\"anon_1\": \"relative_x\", \"anon_2\": \"relative_y\"})\n", - "\n", - "variables = infer_variables_from_dataframe(samples, scale_continuous_types=False)\n", - "model = JPT(variables, min_samples_leaf=0.05)\n", - "model.fit(samples)\n", - "model = model.probabilistic_circuit\n", - "arm, grasp, relative_x, relative_y = model.variables" + "fig.update_layout(title=\"Marginal View of relative x and y position of the robot with respect to the object.\")\n", + "fig.show()" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:15:42.335372Z", - "start_time": "2024-03-12T16:15:41.248751Z" + "end_time": "2024-03-13T13:13:38.569644Z", + "start_time": "2024-03-13T13:13:37.609252Z" } }, "id": "24bc79646157a9bf", "execution_count": 4 }, + { + "cell_type": "markdown", + "source": [ + "Next, we will perform pick up tasks using the default policy and observe the success rate.\n", + "The robot will now experiment with the behaviour specified by the default policy and observe his success rate in doing so.\n", + "After finishing the experiments, we insert the results into the database." + ], + "metadata": { + "collapsed": false + }, + "id": "b5cb56317f506b04" + }, + { + "cell_type": "code", + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "100%|██████████| 500/500 [00:32<00:00, 15.41it/s, Success Probability=0.336]\n" + ] + } + ], + "source": [ + "fpa.sample_amount = 500\n", + "with simulated_robot:\n", + " fpa.batch_rollout()\n" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-13T13:14:11.029579Z", + "start_time": "2024-03-13T13:13:38.570880Z" + } + }, + "id": "7461b696b899f603", + "execution_count": 5 + }, { "cell_type": "code", "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Inserting TaskTree into database: 100%|██████████| 5299/5299 [01:19<00:00, 66.58it/s] \n" + ] + }, { "data": { - "text/plain": "0.16896551724137923" + "text/plain": "TaskTreeNode(id=1, action_id=None, action=None, start_time=datetime.datetime(2024, 3, 13, 14, 13, 37, 62434), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" }, - "execution_count": 5, + "execution_count": 6, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "event = Event({arm:\"left\", grasp:\"front\"})\n", - "conditional_model, conditional_probability = model.conditional(event)\n", - "conditional_probability" + "pycram.orm.base.ProcessMetaData().description = \"Experimenting with Pick Up Actions\"\n", + "task_tree.insert(session)" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:15:42.343561Z", - "start_time": "2024-03-12T16:15:42.336652Z" + "end_time": "2024-03-13T13:15:30.631935Z", + "start_time": "2024-03-13T13:14:11.030250Z" } }, - "id": "825dceb35326faf7", - "execution_count": 5 + "id": "546851521d97359", + "execution_count": 6 + }, + { + "cell_type": "markdown", + "source": [ + "Let's query the data that is needed to learn a pick up action and have a look at it." + ], + "metadata": { + "collapsed": false + }, + "id": "2122db4e86143db9" + }, + { + "cell_type": "code", + "outputs": [ + { + "data": { + "text/plain": " arm grasp relative_x relative_y\n0 right right -0.034396 0.253821\n1 left right 0.027372 0.346807\n2 right right 0.051392 0.319307\n3 left right 0.074518 0.265504\n4 left left 0.174954 0.857668\n.. ... ... ... ...\n163 right front -0.721319 0.461749\n164 left front -0.407319 -0.462141\n165 right front -0.872285 0.151296\n166 right left -0.371555 0.522857\n167 right right -0.492056 -0.485929\n\n[168 rows x 4 columns]", + "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
armgrasprelative_xrelative_y
0rightright-0.0343960.253821
1leftright0.0273720.346807
2rightright0.0513920.319307
3leftright0.0745180.265504
4leftleft0.1749540.857668
...............
163rightfront-0.7213190.461749
164leftfront-0.407319-0.462141
165rightfront-0.8722850.151296
166rightleft-0.3715550.522857
167rightright-0.492056-0.485929
\n

168 rows × 4 columns

\n
" + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "samples = pd.read_sql_query(fpa.query_for_database(), engine)\n", + "samples" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-13T13:15:30.648040Z", + "start_time": "2024-03-13T13:15:30.632757Z" + } + }, + "id": "5d9cd8fe3195d669", + "execution_count": 7 + }, + { + "cell_type": "markdown", + "source": [ + "We can now learn a probabilistic model from the data. We will use the JPT algorithm to learn a model from the data." + ], + "metadata": { + "collapsed": false + }, + "id": "b51a7ee5d60ae120" + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "variables = infer_variables_from_dataframe(samples, scale_continuous_types=False)\n", + "model = JPT(variables, min_samples_leaf=25)\n", + "model.fit(samples)\n", + "model = model.probabilistic_circuit\n", + "arm, grasp, relative_x, relative_y = model.variables" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-13T13:17:05.078605Z", + "start_time": "2024-03-13T13:17:05.071510Z" + } + }, + "id": "8cfff78b3abd589b", + "execution_count": 21 + }, + { + "cell_type": "markdown", + "source": [ + "Let's have a look at how the model looks like. We will visualize the model density when we condition on grasping the object from the front with the left arm." + ], + "metadata": { + "collapsed": false + }, + "id": "9d6f0b2705e5ad5a" }, { "cell_type": "code", @@ -21170,20016 +21321,20016 @@ "data": [ { "hovertext": [ - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 1.0514755717245656", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.6866927513594758", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957", - "Likelihood: 0.8581162797598957" + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.6087440920448061", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748", + "Likelihood: 0.4763472330270748" ], "marker": { "color": [ - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 1.0514755717245656, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.6866927513594758, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957, - 0.8581162797598957 + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.6087440920448061, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748, + 0.4763472330270748 ] }, "mode": "markers", "name": "Samples", "x": [ - 0.41744723227877073, - 0.23213241679023017, - 0.3984301168903955, - 0.33732878887177614, - 0.3111569836217093, - 0.17568905342874647, - 0.16851756331741402, - 0.21688136567771754, - 0.2921736285404647, - 0.18070297417510778, - 0.3531694058956206, - 0.39366150820142737, - 0.11746473957442337, - 0.21689168925069374, - 0.427657545053645, - 0.4207527082830208, - 0.14455947883052828, - 0.13533906098393023, - 0.3414398822497842, - 0.2434932250293248, - 0.31782745394551226, - 0.1605637325424223, - 0.10732302942508813, - 0.2700243359234801, - 0.32886266618275645, - 0.25879223504916316, - 0.22027523802640786, - 0.3148862804086173, - 0.29011505974534724, - 0.2000717315400602, - 0.3900509569608099, - 0.1560551735624492, - 0.3096736064762478, - 0.16250650719146958, - 0.3069761251040846, - 0.36663485148167685, - 0.23232260224259998, - 0.16523355114490512, - 0.20130354179182933, - 0.24183624414545293, - 0.11884036650380625, - 0.15881128173534173, - 0.2648677195654897, - 0.33439283055423463, - 0.396716512522918, - 0.16534732997807827, - 0.1790122137626483, - 0.29106958312196984, - 0.2020292207164628, - 0.16997946479270643, - 0.22459443560846531, - 0.19356701598412546, - 0.2686034554037906, - 0.33202667237433525, - 0.21542716164939102, - 0.4272501933552264, - 0.33388478703609303, - 0.11667920405704175, - 0.16784789192673416, - 0.1751883061120198, - 0.2343143847867061, - 0.2956628842035833, - 0.23492304417305002, - 0.11097105097118706, - 0.4070197968642514, - 0.15490089054411918, - 0.19818653532438274, - 0.10496856662492285, - 0.16599190048342083, - 0.2048046122639664, - 0.17326470310676045, - 0.1691348037393077, - 0.41064708108294196, - 0.29428053172590796, - 0.2629698645788633, - 0.25028556470257696, - 0.14339590820778308, - 0.149791702778231, - 0.2586204161508881, - 0.27552400100801533, - 0.12522286012909067, - 0.4205857728305656, - 0.22793617010567768, - 0.10260479568819343, - 0.1375160364275951, - 0.2995164324095715, - 0.1365458179069641, - 0.11883654369477183, - 0.31400704368456256, - 0.17954995144093577, - 0.20543687206661554, - 0.1989887300492087, - 0.317730336348897, - 0.3538287578716448, - 0.10644417563035459, - 0.22761297412831255, - 0.22259724088965777, - 0.4220353962367303, - 0.2233770727141596, - 0.3622308202418298, - 0.2174656369709349, - 0.2367595548636201, - 0.40209305839327736, - 0.29331073268290675, - 0.2012100687004096, - 0.21311180464811352, - 0.20299224796648846, - 0.27865850068391096, - 0.33231837038272205, - 0.18041414183550655, - 0.31097982640242805, - 0.37553768066478704, - 0.18100382777785132, - 0.33748860400884984, - 0.36050070443612325, - 0.35415459186408893, - 0.22729956864277417, - 0.3683784676517707, - 0.3549333954343528, - 0.37305042828792107, - 0.4186077919072952, - 0.23659411527048096, - 0.29679428896278803, - 0.15168967453856466, - 0.10591084606582063, - 0.18899150993149383, - 0.27984036361552217, - 0.15611476400158553, - 0.2733484377511148, - 0.42036740885352414, - 0.20879860004775613, - 0.25757877678507113, - 0.12358873276290355, - 0.12423847809462489, - 0.42851852350642855, - 0.3778738966797693, - 0.2658249468324164, - 0.13906811981085854, - 0.3729714299529552, - 0.32311729605162715, - 0.2780341790787316, - 0.2949345294663914, - 0.20521992419462684, - 0.33536332616584563, - 0.25075053169958406, - 0.40606287165337684, - 0.38613749903239275, - 0.35140870003642677, - 0.2650104119389458, - 0.4002226778333782, - 0.3735529144615472, - 0.2174414876620535, - 0.42277610952607064, - 0.2664912305732733, - 0.21699632446243083, - 0.3932769534774596, - 0.12748177535127928, - 0.22259588925633697, - 0.13916730909102926, - 0.26440597530067866, - 0.23399445238014882, - 0.22372944043970006, - 0.24594290911408662, - 0.2727250786321572, - 0.10885068447211697, - 0.13914393374429554, - 0.29928724134886203, - 0.20499395909860776, - 0.1844117164016814, - 0.2936520520921924, - 0.17288777982415274, - 0.31973935103905127, - 0.12504647509055364, - 0.1381451451400751, - 0.33367519317280875, - 0.4006558747755889, - 0.265664598798815, - 0.40290649009299395, - 0.37636404207937624, - 0.3646261506659694, - 0.12281400114756955, - 0.21773246018555312, - 0.3628948844953884, - 0.16961330411900677, - 0.24430511095416915, - 0.32167749478837065, - 0.42827016126729334, - 0.1694557759595211, - 0.20047486304908557, - 0.251197591707743, - 0.2806610820344435, - 0.29738654625719074, - 0.25551264320804745, - 0.19879764497376534, - 0.3131501948880837, - 0.3259798128011095, - 0.2845334632662757, - 0.3559272371648311, - 0.2995765598126491, - 0.1227705736611866, - 0.13728780472747001, - 0.188720515947508, - 0.41429574183710893, - 0.12667372098548707, - 0.3741351076455084, - 0.16225425518241415, - 0.4095040295775199, - 0.3864307553983312, - 0.4264433144445654, - 0.40146994320582485, - 0.31862621198711, - 0.13632308754358388, - 0.387913042608469, - 0.11780590199886191, - 0.2697541865522548, - 0.30710136943308863, - 0.16828452321923423, - 0.42112612226237367, - 0.3753680885225615, - 0.3231012913527934, - 0.10281746255646682, - 0.24821071072379552, - 0.42810020002902177, - 0.3791710899839819, - 0.4283807989459727, - 0.21073238704040637, - 0.3260010904881271, - 0.3628451641695753, - 0.38797446984613027, - 0.2260050577494893, - 0.18874054126854056, - 0.3925698080032557, - 0.2577960892767853, - 0.42118768411770197, - 0.19853033646112483, - 0.33894219717841145, - 0.19214003392302076, - 0.3494358786719802, - 0.1578553799405086, - 0.2523240990112809, - 0.41657960978362335, - 0.2635514806704205, - 0.12814683531788906, - 0.10439794920051876, - 0.23124574943119708, - 0.4052153540022053, - 0.3856280549255634, - 0.22538779234312661, - 0.39637625834987256, - 0.41583635151656434, - 0.3309216624604924, - 0.3370222312517922, - 0.1581051913956418, - 0.3429701520417786, - 0.25889220662129875, - 0.1812721946437925, - 0.29969676052043154, - 0.35975012519387456, - 0.25089234631820706, - 0.2508239611372943, - 0.3916458897688029, - 0.13053943420558176, - 0.29463553378333784, - 0.3685500957612474, - 0.3501331703047733, - 0.31473748112480704, - 0.3038154522374473, - 0.39488230339665503, - 0.2688706115824474, - 0.3402273150008998, - 0.21174677274320508, - 0.3134535969344707, - 0.17893547231557289, - 0.29360209371993345, - 0.12841594278756974, - 0.16948370617846126, - 0.2864761095498157, - 0.2812549108510426, - 0.2538293396449668, - 0.1685541448373794, - 0.37901327455896994, - 0.3934731019623551, - 0.11544359836341198, - 0.3162199339280797, - 0.3366471157294083, - 0.2111425512419902, - 0.40419965953991677, - 0.3432356632113004, - 0.09889974852189307, - 0.22693692938941418, - 0.1563394570107817, - 0.32308607265109546, - 0.13425373486261571, - 0.3513436994235351, - 0.2584106977371875, - 0.147806591820903, - 0.3394582886640507, - 0.11236789019544875, - 0.3398242527910697, - 0.40188511089034573, - 0.24882754000868454, - 0.4124876140817718, - 0.23084283623483617, - 0.10797313683489479, - 0.14964877371461793, - 0.402397401248991, - 0.11770407034471059, - 0.2736902138661076, - 0.3778296677177699, - 0.29958733616218064, - 0.3230008204143872, - 0.10674986387076155, - 0.33905394570494374, - 0.26908497190581304, - 0.3005569044731663, - 0.16678092664908056, - 0.2906271301984962, - 0.428308395649697, - 0.26096013559409287, - 0.15304906278373728, - 0.12641865037245842, - 0.2018929182867472, - 0.1988243722944621, - 0.19246570287528497, - 0.13880272460599988, - 0.2672388013776057, - 0.39271741852607817, - 0.2455852059763256, - 0.2517653671859674, - 0.3585325177292023, - 0.3735963172184964, - 0.2913867890361105, - 0.3847812386653155, - 0.34880448878573966, - 0.3271840726971186, - 0.4028148535409611, - 0.2719428681014505, - 0.114094109751036, - 0.11149604281434917, - 0.26798098924701963, - 0.31334178400231283, - 0.32658518153692584, - 0.16413711024525687, - 0.3150233653043504, - 0.20802097990802415, - 0.24766967029461473, - 0.21964310127719947, - 0.18206591095823318, - 0.11974479068163355, - 0.41878069689212893, - 0.20648070285998307, - 0.37161459849345874, - 0.25557373617408097, - 0.2461638544577608, - 0.2749600547399827, - 0.26291767342265404, - 0.2130459269027662, - 0.3520011879909265, - 0.10941358293994227, - 0.24841699832773162, - 0.18722559849589668, - 0.11894941834450681, - 0.3934990329963456, - 0.12920992023536945, - 0.18575132652078305, - 0.40190033452819074, - 0.3907150312721053, - 0.22116529616781683, - 0.25263813850271954, - 0.3633897846158813, - 0.1947241222156323, - 0.3856172359377512, - 0.3110451786926528, - 0.25726958007644996, - 0.2922879463733003, - 0.26112493081312177, - 0.11941152471396228, - 0.22141398556821526, - 0.4002057366213337, - 0.24052270313711438, - 0.13951076573155635, - 0.18585411744094837, - 0.3881679426673186, - 0.2524589473804049, - 0.15198686716099236, - 0.1830565009418857, - 0.40583648957192975, - 0.30083168097121027, - 0.15390267199733543, - 0.3703104551549583, - 0.2428468851046927, - 0.3487644629630858, - 0.17953779951260823, - 0.2099902427959921, - 0.11667996680231266, - 0.2687096483107255, - 0.35669022157979524, - 0.2305284562298926, - 0.38212084303181093, - 0.2111205716525986, - 0.13990546963160966, - 0.11008688680361589, - 0.3083685843248434, - 0.16472888603120933, - 0.12664824334077657, - 0.424839408052584, - 0.173168555063542, - 0.21541706675498754, - 0.13458352456780043, - 0.2736207304411208, - 0.18836532344328194, - 0.11107410930144244, - 0.3264379159369793, - 0.33392930793506653, - 0.15004829443592077, - 0.4159959114543817, - 0.15038830381217355, - 0.3232713916986013, - 0.30939742165360495, - 0.23804564909208217, - 0.34869267866349196, - 0.413165137771016, - 0.21855018510738644, - 0.14662222918284282, - 0.25804532288191817, - 0.31900978492993987, - 0.32502297638281896, - 0.21597786592235163, - 0.11344205384964375, - 0.3955164539540007, - 0.21001979846065044, - 0.19229731416161192, - 0.31735574965400426, - 0.10179393987694962, - 0.2020740497487405, - 0.2322942543591911, - 0.29644397664068545, - 0.4044252928128523, - 0.31898200703264035, - 0.3072646947032501, - 0.2861708752502975, - 0.12680956791202957, - 0.3070068253889161, - 0.2046291226856996, - 0.34480593037079577, - 0.26340307467434326, - 0.37411912974967654, - 0.12383239392223654, - 0.3892949860183439, - 0.1580344865185015, - 0.35601824579443475, - 0.355042182035038, - 0.31814425999909324, - 0.32265378818769136, - 0.3179936697201482, - 0.2879759255787966, - 0.1502234374144242, - 0.4210993009639981, - 0.27235445518401635, - 0.21184332672511275, - 0.1094291186348138, - 0.27090697519751894, - 0.27095808737227667, - 0.37632897931753895, - 0.37296528437810594, - 0.10254719303605127, - 0.34017740043221234, - 0.29541703506260397, - 0.10045694359112667, - 0.23158368882463806, - 0.36598151580259186, - 0.10754222437252585, - 0.36167920775330226, - 0.1344510161080252, - 0.21886336596885125, - 0.1098465672406071, - 0.35005953750052254, - 0.40283570178989686, - 0.17433455037289736, - 0.2931752980790516, - 0.23188255440693686, - 0.39741109357118637, - 0.2978656298183605, - 0.3536774557705278, - 0.1565471089155846, - 0.28085988570402853, - 0.11401780166830851, - 0.318871493200042, - 0.3455459859584728, - 0.17317534796091638, - 0.41335265239266816, - 0.39458116159360174, - 0.382692553594718, - 0.31453868695684173, - 0.42145228888840763, - 0.25781143404443185, - 0.21644864648289963, - 0.4015108775652591, - 0.32541885970423956, - 0.11780521525084542, - 0.31771746986132343, - 0.31676094919061193, - 0.42256246659340807, - 0.3587908871719652, - 0.40095484693559125, - 0.4213293986168707, - 0.19224758841716205, - 0.2809006988182371, - 0.19761019477336073, - 0.3389956450586501, - 0.26540730142640157, - 0.25339596438447026, - 0.3612693651904746, - 0.2767876942580317, - 0.427852328938376, - 0.21657546138242104, - 0.2931293639484118, - 0.3197057239519082, - 0.192545177920166, - 0.24678631743267915, - 0.12468024620215276, - 0.15654951484919152, - 0.401018563461276, - 0.1266148074017086, - 0.2531158259219015, - 0.18483898397973356, - 0.3544576441589325, - 0.32187067708666856, - 0.41157721183300716, - 0.303469605814624, - 0.2699087589774055, - 0.24624346542837786, - 0.21826373028288293, - 0.399837489679775, - 0.15892668537692822, - 0.12521211528235188, - 0.36809365411301936, - 0.40949629241389074, - 0.327925299039819, - 0.1355294886894593, - 0.27874449911088994, - 0.2595646760402451, - 0.3248079359544661, - 0.19888793765572055, - 0.1275957370615913, - 0.42828121234387645, - 0.34029139056254853, - 0.416774112264047, - 0.10972141253167282, - 0.09870233632838657, - 0.3269693589139644, - 0.11153792490937797, - 0.3481907473399778, - 0.23605976672144566, - 0.1545789636200885, - 0.31366586644633654, - 0.3048516524468238, - 0.11870202583275008, - 0.34267612183086626, - 0.33615958492867926, - 0.30302694482404746, - 0.11329167136965959, - 0.2047899492532777, - 0.2262281802218787, - 0.20807510846645869, - 0.324195846094177, - 0.3953056879877715, - 0.3986099350861617, - 0.3229123255670094, - 0.20567148546764577, - 0.20530389211066558, - 0.23670370323277679, - 0.11047922740539884, - 0.2915660639678904, - 0.23413299289336645, - 0.2802539949457681, - 0.33405192975940257, - 0.12831821710956223, - 0.21513050869422956, - 0.1359987796136643, - 0.12285151901747755, - 0.36333390889798006, - 0.11441760857393454, - 0.40465410512813493, - 0.3493077248198267, - 0.41490349431675266, - 0.3785823446141775, - 0.3584808360577195, - 0.11340997985633941, - 0.2180760672992527, - 0.20056094560353682, - 0.37385423674078894, - 0.30293944324695865, - 0.2558228420029691, - 0.3210760498793451, - 0.1690185491706786, - 0.2559257603795686, - 0.27708117323683046, - 0.21929004557166942, - 0.2362615882202114, - 0.2230765256285033, - 0.3070942206087215, - 0.41600898660400887, - 0.1401061636182266, - 0.2970822300241619, - 0.3831415970714433, - 0.1872875547037921, - 0.19875947298179103, - 0.37251706433314663, - 0.14673221231124206, - 0.31565698469086656, - 0.1901598940292682, - 0.33420916322228333, - 0.1874686202800256, - 0.31154562301342165, - 0.19133142286412202, - 0.2675957627820217, - 0.3625348487937785, - 0.3748708014866189, - 0.1161120090412749, - 0.26365857913701835, - 0.15648907969411932, - 0.3749463642473593, - 0.31385720999317346, - 0.11020897186747548, - 0.2371360538701783, - 0.17278616233926053, - 0.29542387945730286, - 0.35854945619906203, - 0.1368812102573561, - 0.137979859953096, - 0.235563468629057, - 0.24754308182855808, - 0.22755571948091166, - 0.2872577456528981, - 0.38875990512499087, - 0.4283782234012334, - 0.18022082980604245, - 0.197907819734288, - 0.3873208983182626, - 0.37791625960921843, - 0.369020807341481, - 0.3068200732273403, - 0.18864307136579334, - 0.12867237808106421, - 0.11228435239250294, - 0.393088585850439, - 0.1853894832855982, - 0.38158088908487153, - 0.2695375734072408, - 0.22867120100518362, - 0.10364907627277221, - 0.4223414117502742, - 0.18379605643266622, - 0.39022833300293897, - 0.14256617159684098, - 0.36410225450868305, - 0.4020759156864393, - 0.3143981839917427, - 0.39840004462273115, - 0.2849672010194336, - 0.38801726902612427, - 0.3011567390406127, - 0.39080088538174795, - 0.3855367098946663, - 0.26154725518677224, - 0.31166708576982005, - 0.2535073591293773, - 0.3727942742152881, - 0.26547436901609556, - 0.34985355677347263, - 0.3081331162977572, - 0.1975037376292969, - 0.17648001578160166, - 0.2683407989784384, - 0.22206121491311576, - 0.20975561316561492, - 0.21534763010932043, - 0.22780549634519276, - 0.1530372070321257, - 0.2677171529295468, - 0.38002725299140866, - 0.2575635630341675, - 0.12343941949061493, - 0.3045465034705569, - 0.34996602906975943, - 0.40707035554482535, - 0.42978093362410436, - 0.2485562290451617, - 0.31506569217959307, - 0.33725516665277966, - 0.1646097097179063, - 0.20178477874301692, - 0.21170284980198123, - 0.13103086164249908, - 0.27289977336037957, - 0.42781921657499444, - 0.28586549844702547, - 0.40422122262757343, - 0.1449257065191809, - 0.38595117029244674, - 0.1865067128777484, - 0.24251751054263385, - 0.32470912428490656, - 0.1523093578795898, - 0.27089330710268444, - 0.13532364821261808, - 0.13825755557178446, - 0.3839080679033439, - 0.21258964908349226, - 0.11305575861244367, - 0.3632601704390946, - 0.3872621920454222, - 0.39687174219229016, - 0.12111210538707198, - 0.12794737614396676, - 0.137064433215538, - 0.29732063926513896, - 0.16252753708720385, - 0.1363311804286956, - 0.11604329260857227, - 0.30890304918433, - 0.35532672083131134, - 0.3124218750083089, - 0.18728890965225248, - 0.3926331491988323, - 0.18470212225995813, - 0.19248145283639295, - 0.2880786361156107, - 0.3047611539296913, - 0.417235991510573, - 0.39059097246598473, - 0.2431002443684911, - 0.33036436780332407, - 0.40416876275962027, - 0.35791119281884465, - 0.22842801284129297, - 0.3784543121014308, - 0.23234322271562965, - 0.35528519549299364, - 0.1978430192088355, - 0.2509678256008346, - 0.1492017547254672, - 0.21449270451841163, - 0.3660835275103999, - 0.1702723961309865, - 0.39503193012130294, - 0.234896245622019, - 0.30851227815173143, - 0.2863755631205608, - 0.30024074739004025, - 0.14897423535892892, - 0.3781093537895238, - 0.42345705429417557, - 0.3141198759227754, - 0.17900805281833299, - 0.11527418692006378, - 0.22599694336335646, - 0.1808570679875168, - 0.1525690726373632, - 0.15033511758777632, - 0.3022587136384396, - 0.2502001038194944, - 0.17481886510954603, - 0.19154609180554197, - 0.1589425903054936, - 0.3370434925772038, - 0.3244599087892668, - 0.23140322181663062, - 0.34536935220351744, - 0.1474666542590104, - 0.12191125818835988, - 0.10177505117062761, - 0.3394308110426607, - 0.40392575793970775, - 0.17568264608161382, - 0.41271387172421287, - 0.16792442033469163, - 0.17996436932209597, - 0.2817628156294836, - 0.276667842426792, - 0.10747711370522187, - 0.3449465409125452, - 0.3299049613514157, - 0.1837554274448753, - 0.42185726540380974, - 0.3296720856188142, - 0.23003763945496136, - 0.34843003695239033, - 0.12286213445233665, - 0.3807809285928901, - 0.3942991699347708, - 0.23042329803606054, - 0.3814504494609684, - 0.3023274215868633, - 0.17979405237793936, - 0.3911926340887006, - 0.3304336932167523, - 0.31407665759805725, - 0.3323063481143581, - 0.21234963514708655, - 0.32421058167316186, - 0.14248851960438869, - 0.17879093801381563, - 0.34127190162898, - 0.4109712878179507, - 0.2678320848193252, - 0.10985635851725933, - 0.13253335888766038, - 0.3874563815670088, - 0.2946421570280694, - 0.39107911930094447, - 0.36556493438422244, - 0.33479745707309305, - 0.13695013603817563, - 0.10998662722137509, - 0.17166779580183242, - 0.22087724061137776, - 0.40878021384137236, - 0.12055656056374642, - 0.3014483189535385, - 0.2623732162859929, - 0.31431075945873077, - 0.25702378296884465, - 0.2974577211904564, - 0.34524551850307134, - 0.3337033639381611, - 0.19099050934227402, - 0.19544888395849824, - 0.18077023412593463, - 0.32511585517048547, - 0.18739314271020435, - 0.37733311473393627, - 0.42915830253241616, - 0.1843173919056738, - 0.28398396384165164, - 0.4063113507612852, - 0.42671036494139575, - 0.1393195740303167, - 0.41239643127784276, - 0.39570898968358226, - 0.23382150470929422, - 0.16796220448532476, - 0.3365213764880585, - 0.2673944215877574, - 0.24829573470297467, - 0.3298894737933215, - 0.116828333891506, - 0.2003088587640823, - 0.23295703683991414, - 0.31130098498440056, - 0.19387334113865454, - 0.2080087944877108, - 0.23898287722073672, - 0.17204850773077027, - 0.31013886392565504, - 0.10084487773871345, - 0.1904530174400898, - 0.2711506688064088, - 0.11769657209722321, - 0.34174632909720415, - 0.308707612903522, - 0.38309066340850456, - 0.151592303498198, - 0.23471544981282247, - 0.22624550289438716, - 0.2939238744518584, - 0.2622915839371229, - 0.21729876206965537, - 0.28037068428421574, - 0.14104105249577953, - 0.37895073069346674, - 0.22097695339971563, - 0.34133246731458683, - 0.26287087919696706, - 0.385735732768566, - 0.276872606216889, - 0.12828112842464823, - 0.41697040013279596, - 0.3622116934466712, - 0.34473685777401597, - 0.28105041443986056, - 0.2905378202662565, - 0.15565772011397747, - 0.2709172956771992, - 0.24871908535062048, - 0.3966309862758353, - 0.3895023426293861, - 0.11672434350225339, - 0.19912189178911363, - 0.3885873577452961, - 0.4250510155857999, - 0.426997071524037, - 0.36631058935088734, - 0.26419239717298515, - 0.3518574205497663, - 0.11257659705209848, - 0.14346129909900326, - 0.412387601686004, - 0.3644797153665873, - 0.1067741866496056, - 0.2186575981281263, - 0.21371993524228644, - 0.15870006211059606, - 0.22127972423536352, - 0.17432648954656527, - 0.2642694470089064, - 0.10580989158385622, - 0.38906109507500414, - 0.3731199542153916, - 0.09993912095634606, - 0.3650642905598732, - 0.3370406449717155, - 0.30770606659462596, - 0.24552826724399715, - 0.2512373365185232, - 0.10204844887162481, - 0.3022592713902531, - 0.105361341741698, - 0.1978213171992671, - 0.12125415012371556, - 0.307325579576646, - 0.1937969183926374, - 0.26617735896599215, - 0.39129320904019244, - 0.16687264168894977, - 0.13121489111028017, - 0.14018771371148764, - 0.31278892418251814, - 0.1879516555503154, - 0.19709450169721301, - 0.3812614893143626, - 0.3571330137882415, - 0.26789232010617087, - 0.25670470552279134, - 0.18802990358909583, - 0.3692773627204558, - 0.17986523037237107, - 0.2030678722734233, - 0.35371114051008157, - 0.10186087339989908, - 0.3127899177466482, - 0.12443887110639766, - 0.40872370201650604, - 0.34536006200108504, - 0.320071993364345, - 0.10515699201093781, - 0.10186285823373922, - 0.1607735727531578, - 0.11281780066734487, - 0.1547062553060935, - 0.32794617731697673, - 0.24522333325463982, - 0.3294608597173964, - 0.16992247960307022, - 0.37239264096661634, - 0.20530479540493277, - 0.1550469672124911, - 0.18551369841951942, - 0.23941645420769145, - 0.3648056777415622, - 0.13898460370047355, - 0.36661960492390644, - 0.32210304346095386, - 0.3621993929308217, - 0.22401170925214495, - 0.3811796586845952, - 0.4260486057026653, - 0.19591470737323863, - 0.340495117889454, - 0.2687222196903377, - 0.40006209072273624, - 0.14631536547959623, - 0.3278611170801509, - 0.1951592949816328, - 0.2979985480692994, - 0.09897573292085601, - 0.34799680907784525, - 0.19776988369400997, - 0.33313889044679146, - 0.40083550809394164, - 0.28693979234797073, - 0.257122715395125, - 0.30773692001824154, - 0.19756621569542251, - 0.2235122903714905, - 0.21139055021254022, - 0.36822079770748023, - 0.38851015424213414, - 0.16132191296635057, - 0.157684048638499, - 0.3020824717292746, - 0.4158387283202257, - 0.10787384495988146, - 0.1766023709101065, - 0.3595244244937886, - 0.16628647122309986, - 0.11616093644878431, - 0.1423632620898573, - 0.31013628377768904, - 0.34763285736895544, - 0.2192337448930037, - 0.14588847967859478, - 0.38863212016282844, - 0.321745263593415, - 0.13611775872350904, - 0.27880334549126196, - 0.36621410781329294, - 0.13377983030995483, - 0.20136266174248324, - 0.14612208909588797, - 0.16146274848421965, - 0.20471438102977677, - 0.2568320942258709, - 0.17603675778879202, - 0.27886845167360397, - 0.11147043672933936, - 0.1806750542068608, - 0.12117547815424243, - 0.3786805794367242, - 0.23425738264486085, - 0.26743970927702365, - 0.19033775972681682, - 0.2659652645511245, - 0.17456321848242762, - 0.24111478992684177, - 0.41135481223476655, - 0.2895632099366868, - 0.427540821065612, - 0.35435597870908264, - 0.3354556752995498, - 0.2718477887273958, - 0.3886055543575918, - 0.2590661814398999, - 0.36880853021655624, - 0.22315308152656066, - 0.1330242284872749, - 0.20194133005061832, - 0.3306092204632235, - 0.25122862000648827, - 0.15317804041855257, - 0.2628943633964163, - 0.12530056645744558, - 0.28757633070022115, - 0.40129009767280516, - 0.21978111629883762, - 0.27174905019343076, - 0.36750785512618034, - 0.2394973317042752, - 0.2071293486430396, - 0.23011333739836115, - 0.17193439760674684, - 0.18999938116304052, - 0.11568120151038226, - 0.4043003360779576, - 0.1449739443585531, - 0.20046065645590505, - 0.11515235828578649, - 0.13060359665410531, - 0.4127435529293135, - 0.35986533936576925, - 0.17000545307302967, - 0.2886297440287784, - 0.3744061886081477, - 0.12300550366592566, - 0.12539867490779216, - 0.23549131594291453, - 0.350204112724882, - 0.3962679052131229, - 0.2056518810000009, - 0.1412373606946175, - 0.2957214305602084, - 0.4118989981112451, - 0.27901218569106573, - 0.23209727634310448, - 0.32223074242406774, - 0.1827615756588304, - 0.40219625517295715, - 0.28251601593158426, - 0.13649721509834686, - 0.38130065850439926, - 0.19492439337586537, - 0.29712279086980087, - 0.25541570028980676, - 0.12893805683842424, - 0.1420925168220867, - 0.21556839319419027, - 0.3565402251935201, - 0.13500101482602084, - 0.35319528972574027, - 0.18747599349764776, - 0.11678971575023979, - 0.2639709948420465, - 0.28869993944063754, - 0.31377330051826685, - 0.3083241848415335, - 0.143909153366649, - 0.2632837165163212, - 0.35422943226758064, - 0.33923995191334977, - 0.31238773493355354, - 0.23497643131310061, - 0.37642819572553476, - 0.21689990866435466, - 0.16069150858252784, - 0.42110355603617927, - 0.3349353639507615, - 0.38906971511511884, - 0.40770159351279883, - 0.21136515720526253, - 0.1605797023662666, - 0.3147299887112508, - 0.2340007613367144, - 0.36102055935980665, - 0.29285437198230146, - 0.3164045771525254, - 0.24334899032729512, - 0.3974142060967923, - 0.13680530145078673, - 0.3492001340938075, - 0.10965096858840695, - 0.13451204611630876, - 0.19000598466884627, - 0.11844697711847568, - 0.2552765569397325, - 0.11896134621948383, - 0.10115908460338162, - 0.24796060466780753, - 0.3877964936608319, - 0.1588794713820806, - 0.23788352905760596, - 0.2769046566872163, - 0.40316818646926267, - 0.22944471697335117, - 0.10591816452697143, - 0.36682719237431216, - 0.2905851769734655, - 0.20139497381627547, - 0.21658978014561567, - 0.23240427697451999, - 0.3961720798327488, - 0.22737306446435457, - 0.4024130868982765, - 0.2881138683111578, - 0.1645793245413487, - 0.15871316967408183, - 0.4206054527375133, - 0.27949442253332646, - 0.41107226792660484, - 0.3779408814423246, - 0.16767637785676814, - 0.26346809110185465, - 0.1360866739849988, - 0.1672430555490566, - 0.3670581975319115, - 0.3301891036844814, - 0.24854267659662144, - 0.15365531724732298, - 0.28016360187964273, - 0.2034713630385796, - 0.3042652208354848, - 0.3325920016238848, - 0.18838221834483768, - 0.34301154028154124, - 0.2854571187225807, - 0.297424245923416, - 0.39864566393933, - 0.3604484669905343, - 0.3607872067136694, - 0.21586707182126774, - 0.3639205240659639, - 0.3154881733971403, - 0.1372587510119173, - 0.3658039236531579, - 0.13104850692904355, - 0.41933119078588704, - 0.30457293957893516, - 0.28618871880318486, - 0.10620851432449464, - 0.25230416831419655, - 0.1292360409565615, - 0.2911800112241671, - 0.1029416977906903, - 0.2984226866341258, - 0.2364114471338638, - 0.1739562289750852, - 0.4226112662774253, - 0.3167447049469947, - 0.34867854930970055, - 0.2297860796308035, - 0.4156618020572685, - 0.2334793596560286, - 0.304650524033529, - 0.2877875213772723, - 0.289223855828581, - 0.2957279267314967, - 0.34798654818773356, - 0.24799242234663055, - 0.295647410615751, - 0.2327267168134993, - 0.11717477618505226, - 0.09926565613967764, - 0.2160419985489173, - 0.34092995996445696, - 0.15318611873228338, - 0.2694171571835632, - 0.1774893417237241, - 0.41709193562306895, - 0.25878707596830886, - 0.3142511046237021, - 0.1296202044611961, - 0.22200139473272346, - 0.39533906338815494, - 0.3102579792761897, - 0.16522970206697266, - 0.3244472452748285, - 0.23197321311158303, - 0.24809620645055236, - 0.42401341565084644, - 0.30767232693775126, - 0.34428184672280504, - 0.25959043789693315, - 0.27328649138351313, - 0.22899029647929334, - 0.30328314783602583, - 0.13641734235047942, - 0.33319903518523253, - 0.13707935288907355, - 0.3113575639352708, - 0.12821307565111306, - 0.10586260139902019, - 0.42287797922083536, - 0.31195425245861563, - 0.38910015585575664, - 0.22439988330718383, - 0.10800100360554363, - 0.18466097386249036, - 0.303039681547857, - 0.3176634088672594, - 0.32848615076087484, - 0.21048072908636112, - 0.1343403328602027, - 0.2428209886793674, - 0.2113401542513359, - 0.19984101777504468, - 0.3942866064018247, - 0.14198901857495813, - 0.3529338290188156, - 0.2851965480206943, - 0.4188774412706533, - 0.31950168275129576, - 0.2431852488172072, - 0.3760804505323179, - 0.19515798227404915, - 0.38142170147176147, - 0.29819587758617605, - 0.12143503978749098, - 0.35491723095505506, - 0.17267702474782964, - 0.3149515330025532, - 0.23780210403643587, - 0.29815334915736147, - 0.3732815881569289, - 0.292109958583029, - 0.11118645633457803, - 0.3796703951068473, - 0.16609153069164828, - 0.3614978369151487, - 0.38122594359495815, - 0.36891810080993487, - 0.1698186031902501, - 0.16831272553145885, - 0.11691358804502658, - 0.2800321213114977, - 0.24461508372588006, - 0.26173710667720773, - 0.19078758818146513, - 0.4017556633705134, - 0.3511962345834495, - 0.40572265934049734, - 0.1420534436182145, - 0.3933019159409373, - 0.3620772336068881, - 0.3749992369360854, - 0.4190640112191919, - 0.18245002932448456, - 0.3415841880136701, - 0.18122160846834118, - 0.40589204044579075, - 0.3904925174548626, - 0.1895301288940432, - 0.12350766972728881, - 0.198442501181195, - 0.1404627447171937, - 0.17819702454706565, - 0.23746255410793513, - 0.29594280442757537, - 0.24937398489125773, - 0.1358232908925549, - 0.18080681836656692, - 0.2141771981648154, - 0.3816210555099668, - 0.2842619616029195, - 0.2761607013433104, - 0.4203390763967362, - 0.39748819756541703, - 0.27396544043054827, - 0.4117822738843956, - 0.36843839793751615, - 0.14120627897439492, - 0.415219696427435, - 0.29563476701122343, - 0.38667475628873565, - 0.17812467086515177, - 0.12685540939655757, - 0.1192128441206246, - 0.3044388152735693, - 0.3509893283292217, - 0.23892486466539023, - 0.4038152894633718, - 0.18742383967630943, - 0.2936560818832553, - 0.19080947303891294, - 0.31728887533586136, - 0.39742595229621, - 0.2756553135015975, - 0.1383627128454346, - 0.2830770217867179, - 0.17478420141348916, - 0.3308282494126511, - 0.3776153840413772, - 0.12400318684625701, - 0.21531048565944488, - 0.15525761292235227, - 0.40623632040478996, - 0.11361264994317881, - 0.3477174954603666, - 0.1678169924613761, - 0.17545693129523604, - 0.40063548436063834, - 0.2855919855447918, - 0.3611670085859026, - 0.16164113795941143, - 0.2499203046038782, - 0.27390982916577566, - 0.22157130480428505, - 0.25145598072267256, - 0.23951607055530924, - 0.13998541866070635, - 0.22322428450331447, - 0.15969726480533858, - 0.24754922678959262, - 0.34701395506377386, - 0.2142442115949283, - 0.3981483719319317, - 0.14901908816898748, - 0.21492991988975643, - 0.31051992708774284, - 0.2763009888604768, - 0.4297875851739327, - 0.19700997254641675, - 0.1212165991460932, - 0.2546637777909912, - 0.3095275730826777, - 0.3884747596027634, - 0.3684821018314632, - 0.2033247093467146, - 0.35428020452780645, - 0.20724200456321257, - 0.2671248879985687, - 0.10811946225219572, - 0.11183179622598852, - 0.1824251387120338, - 0.18265238529080946, - 0.13105275466046354, - 0.3166003007714391, - 0.28793724078826244, - 0.21498429229884555, - 0.15223702272985498, - 0.16965754322966664, - 0.1687276411585783, - 0.18538754549202605, - 0.17492752301438386, - 0.3996497940469914, - 0.1271646280560017, - 0.4267843466165395, - 0.23550048100431212, - 0.38010315905200026, - 0.2055128248960563, - 0.38263817887370033, - 0.38742527759075013, - 0.38498646110735596, - 0.23022331908727456, - 0.2742072426639953, - 0.2565867019261133, - 0.3982357437769145, - 0.268430027127675, - 0.1358920607611211, - 0.26392646754416127, - 0.42318447967838224, - 0.24150784886432544, - 0.2492036057443122, - 0.3284517195968128, - 0.27692473422771813, - 0.33951284279598043, - 0.36784697762078367, - 0.2964599944162506, - 0.1911497885438156, - 0.11672664932751924, - 0.22419449577704825, - 0.32554708130951976, - 0.28040621351373163, - 0.3250241980980996, - 0.38850725623760174, - 0.24847082502622764, - 0.1904937808103267, - 0.11932189067402929, - 0.3268514276464647, - 0.1547739864980925, - 0.09899989936090518, - 0.3074390483271163, - 0.35319557107704547, - 0.17803535008135846, - 0.2136882856483336, - 0.2279476282582365, - 0.24922240947840893, - 0.39864446497864897, - 0.2117947858911814, - 0.19718360074566496, - 0.13816677499351873, - 0.4218311553345329, - 0.20118752714095606, - 0.17907787769195294, - 0.13336400865942336, - 0.11485556127191235, - 0.3571160700472151, - 0.10083448552900441, - 0.2607407017125238, - 0.22984072071200756, - 0.29663330069418736, - 0.276313401994555, - 0.14230875834430215, - 0.2962011828718204, - 0.2601580406105813, - 0.3944557158147862, - 0.2523326463247315, - 0.1420535888734656, - 0.22215638503670582, - 0.21731807440031592, - 0.3582145741305846, - 0.3653757451569741, - 0.14676217470558722, - 0.19073845201397704, - 0.3434380988185403, - 0.41916592875175956, - 0.14071807137820186, - 0.2341849866585199, - 0.2978095013279814, - 0.27405198338085013, - 0.14428355494700437, - 0.17183631690438517, - 0.32911041224745546, - 0.268913179232683, - 0.11281025378776798, - 0.10257248189418637, - 0.3721917135130975, - 0.26259046098213323, - 0.2110073925536395, - 0.33427565222800937, - 0.3072059186223791, - 0.16473327654420208, - 0.32691263665391035, - 0.3396058258680557, - 0.13096077103506212, - 0.1204917852218213, - 0.39114828944695434, - 0.37107313437015044, - 0.22920601667644203, - 0.14421165953236095, - 0.3333800903141788, - 0.16659923866769127, - 0.30296735772716676, - 0.41799800238955076, - 0.27805349346555686, - 0.37472490548802706, - 0.20520920859681607, - 0.32093404304882894, - 0.2603511216440024, - 0.20037841539097617, - 0.29071249599933435, - 0.206327138858686, - 0.2207325946274524, - 0.1747015990145373, - 0.40067022568874106, - 0.14852202333384829, - 0.19242303931717678, - 0.22303009495365567, - 0.26839821502418176, - 0.26237640415739083, - 0.22391368688453211, - 0.2392520534066842, - 0.30584454725936017, - 0.10037104881460049, - 0.3130023320936678, - 0.20979296624353674, - 0.32117007918368407, - 0.228864409808464, - 0.27659836901189194, - 0.1709217733155593, - 0.16891479182692784, - 0.1806965533004506, - 0.18524666527097822, - 0.319998747109961, - 0.31312750719092547, - 0.16045714987924603, - 0.31842137933262016, - 0.23130773881949174, - 0.39107156798169046, - 0.40330751138801124, - 0.23715972924376136, - 0.22419507777441935, - 0.1728488167057658, - 0.10911430731309314, - 0.24777035552834367, - 0.13100344531434824, - 0.158204234325099, - 0.11185598483620937, - 0.1850943002668826, - 0.38571056794212316, - 0.3630224103154799, - 0.24079304570574037, - 0.24965886293515818, - 0.1629685730511973, - 0.32141539139564923, - 0.17532388129194917, - 0.13919305494165926, - 0.17486845318347022, - 0.10279800838489377, - 0.1782151621362092, - 0.16967287192543645, - 0.31186561773700583, - 0.16535236763449856, - -0.6085351916502546, - -0.4534713526995688, - -0.5364468438205988, - -0.793186921668666, - -0.4963871929692635, - -0.2351558648597597, - -0.7402713558520848, - -0.6179963645290963, - -0.5864864675022867, - -0.4997483589853752, - -0.18709987738312894, - -0.6585544116079601, - -0.7985501298108431, - -0.3810617019836491, - -0.5506838584933718, - -0.1437672271379431, - -0.7529239610828299, - -0.20662285261601, - -0.19851977622644712, - -0.6175827326249789, - -0.3820278980192747, - -0.7230007679739977, - -0.48459157922839796, - -0.48833241827283047, - -0.3939698290847586, - -0.6448458980940712, - -0.44678578277513353, - -0.45289284259340473, - -0.5478564219742315, - -0.6013212116572688, - -0.7166572626930239, - -0.7623333125422446, - -0.2003823598416945, - -0.7389758530804491, - -0.22815769623955418, - -0.6437047738918245, - -0.6857183900192345, - -0.34053284022371794, - -0.1516477076833319, - -0.66385324243893, - -0.4544900952844484, - -0.47809894362162814, - -0.45829498384016765, - -0.3666495086738576, - -0.44366658577630275, - -0.3650604866282936, - -0.4825165983602309, - -0.7187019153959397, - -0.3297410196736136, - -0.12095915544045577, - -0.1255624561863744, - -0.1057960893079446, - -0.633475112789538, - -0.3408679733862799, - -0.18732924404898432, - -0.6353579346887662, - -0.4006757153565659, - -0.1603298764025285, - -0.13601822343208758, - -0.4027329662264841, - -0.5758966504476031, - -0.7122742165058038, - -0.7269977138751839, - -0.1256798589161362, - -0.3294985673126664, - -0.5234223475571453, - -0.762057735721429, - -0.7221846412146564, - -0.09690429407419754, - -0.7784047817665974, - -0.7098232146548087, - -0.2212488423632829, - -0.18904531029389238, - -0.5665434811189427, - -0.7523977188018495, - -0.27414544476110114, - -0.31588693711071386, - -0.4286701971120516, - -0.10937742558942032, - -0.6181373817511423, - -0.712287768974202, - -0.4204216657696721, - -0.14224485576569146, - -0.6171755140522357, - -0.29007511560247323, - -0.5221003891421967, - -0.10348655611706792, - -0.4565305046803286, - -0.5222071118179687, - -0.5802593970917223, - -0.6535954571245174, - -0.6100149557071751, - -0.634979746991576, - -0.11308025548277567, - -0.5930815404314207, - -0.35887178510539364, - -0.3399248869559814, - -0.38438049469935476, - -0.5174325471803054, - -0.33431229151638225, - -0.7183359224684762, - -0.7011414664425359, - -0.25478109924275416, - -0.3407446550517252, - -0.0930298315748932, - -0.32169274310199464, - -0.5881103040555693, - -0.15549368268209252, - -0.1489717618609231, - -0.14697435799320635, - -0.4825667402884856, - -0.5963966307155077, - -0.21676134507498934, - -0.2333979486759521, - -0.7577836053948446, - -0.3481875739973763, - -0.34639220455906844, - -0.5796728725918795, - -0.3855767359861388, - -0.4132708200849922, - -0.7589012543608877, - -0.18096455102729536, - -0.1359212685413982, - -0.5884147421417598, - -0.36825145376686613, - -0.1700421993586818, - -0.5304433312635739, - -0.6310183592346432, - -0.322441949242111, - -0.15667356048497494, - -0.19011132039508172, - -0.7341792876996639, - -0.10603349177595434, - -0.3323984970206733, - -0.47032823859929285, - -0.3763375764559204, - -0.11751975183909036, - -0.3101075453542754, - -0.7729200208085096, - -0.5214214312982124, - -0.23204133825837092, - -0.7397585929908713, - -0.35810555192677407, - -0.34069942751146864, - -0.7550105721199484, - -0.25516812368345876, - -0.19529804622076485, - -0.09242229915111011, - -0.11372540699075395, - -0.32171275277355593, - -0.3052865037840513, - -0.7291471952615898, - -0.17912899987833664, - -0.13474134660537118, - -0.49779836957692947, - -0.5612260640485112, - -0.7741163003201172, - -0.10569318002109085, - -0.32557072833777584, - -0.3366617457056094, - -0.29645222022407125, - -0.4264131068899221, - -0.5693226521747676, - -0.7221651019640203, - -0.7505826607842722, - -0.5072685886909565, - -0.4514268011848177, - -0.5045003550965237, - -0.604432983622436, - -0.6416834007522707, - -0.1836703169892926, - -0.252245151105679, - -0.4227061232760515, - -0.6015036969512865, - -0.5822839820764248, - -0.3078070920044231, - -0.7472483734995929, - -0.24271813472200043, - -0.23717800717021886, - -0.42948684084455313, - -0.3368086456473459, - -0.7913857658001071, - -0.3772947258267371, - -0.5090484419809416, - -0.6988221809761425, - -0.6206602486377899, - -0.5721745362450186, - -0.7930258956506555, - -0.36000829783086685, - -0.3532217449042171, - -0.16340462129785716, - -0.31414427188489924, - -0.22339785335965145, - -0.629702172575573, - -0.42752491671495724, - -0.6014115565839417, - -0.7753078092040525, - -0.731989875605601, - -0.17923392518755543, - -0.656326448391567, - -0.3116945430960046, - -0.7253876267185816, - -0.651969021419032, - -0.3692545864026298, - -0.34752206335309693, - -0.12025487726356421, - -0.6816637212178216, - -0.1544145494640362, - -0.4666106095246712, - -0.44352913445158554, - -0.2889648813182124, - -0.28640621964518975, - -0.5328709004020438, - -0.21293102054888113, - -0.5022363961667615, - -0.2527565269305593, - -0.5824792547681779, - -0.5339851793941885, - -0.45570060244568433, - -0.6308656696457425, - -0.4622427736769257, - -0.28764567494609217, - -0.3675179762711833, - -0.17838873407240918, - -0.3069405186210808, - -0.09072600933063946, - -0.20229003819301938, - -0.6972857556229716, - -0.08721725035010697, - -0.543907087215489, - -0.18063065822252566, - -0.758820957118962, - -0.420129268056298, - -0.4558432400545988, - -0.2914164647226214, - -0.5389497049922014, - -0.12743994589416874, - -0.2469297109324724, - -0.460510172325023, - -0.10081726731225416, - -0.2595476521264679, - -0.37526368329921567, - -0.09512258110635563, - -0.6333105595414369, - -0.10276914751252719, - -0.6576236872728133, - -0.2954398502737341, - -0.36725812338428826, - -0.6482439044873467, - -0.39828576077624295, - -0.544673642395358, - -0.6603994315473953, - -0.5323930317617473, - -0.41214117440051057, - -0.41536675313152943, - -0.20164687530550396, - -0.18859731177448436, - -0.6586019657804364, - -0.2965466336861421, - -0.5628362558344764, - -0.29258433128391503, - -0.5164352477718619, - -0.3951678459372906, - -0.6122325076788256, - -0.27640615655102285, - -0.7468716848066453, - -0.3233378971392864, - -0.6573555228515571, - -0.2867700164316964, - -0.631357314950372, - -0.12066233226842138, - -0.6500059280572169, - -0.3824099246113974, - -0.10550214348520814, - -0.5623494723303732, - -0.6438929922623371, - -0.47379425007660286, - -0.35281433876927865, - -0.5974509796002809, - -0.20389615479173606, - -0.541549782790768, - -0.5672443084133199, - -0.20153917003225352, - -0.32847540275497694, - -0.605022949736354, - -0.4232479064191625, - -0.5034945818769674, - -0.547257211050681, - -0.7577129981564157, - -0.7931959416007439, - -0.7883677961002385, - -0.4886445194358259, - -0.25545364025860884, - -0.405876572848583, - -0.7711284477701987, - -0.22504208150819882, - -0.7848569382941031, - -0.6404871454924528, - -0.7198364057201909, - -0.6776237154469636, - -0.2215704755749337, - -0.7025394537627686, - -0.5811759893001291, - -0.7149306236558857, - -0.5837983118425899, - -0.6896552659674238, - -0.29830194183365155, - -0.11966340123531438, - -0.3545995863257699, - -0.4812597150516569, - -0.25874235874414675, - -0.5461273402592441, - -0.4385853730665787, - -0.3183057704001628, - -0.20965310797716896, - -0.08714577237384802, - -0.4551125712933774, - -0.173927283320907, - -0.5142739623738715, - -0.5361706032661812, - -0.45634611690752735, - -0.5966335839415083, - -0.4525254246799064, - -0.6962259334216804, - -0.18983087879115068, - -0.5452023967986366, - -0.7322272570810155, - -0.31668069230115736, - -0.08328640370560514, - -0.25487505506354835, - -0.401485394853011, - -0.7168212436543471, - -0.4873787134992148, - -0.31153163179495924, - -0.11761390998445753, - -0.14250877539718054, - -0.16790993824241085, - -0.5090804387423848, - -0.653890834320382, - -0.5110194757425526, - -0.5302245380437036, - -0.1586966208891708, - -0.35395486997185216, - -0.6611864700719848, - -0.5172397436201676, - -0.518549036681407, - -0.1225876325683577, - -0.355415403071279, - -0.568114071098023, - -0.38227060828306275, - -0.19445085023560715, - -0.0875013387236131, - -0.47763571752605793, - -0.6954453816333059, - -0.1914070538749233, - -0.6911859529179856, - -0.769457972373803, - -0.5322703268055229, - -0.4628321163441318, - -0.6505566519429754, - -0.3016736873322337, - -0.7549523433264376, - -0.17973221396830885, - -0.3771581554605596, - -0.6658398481365159, - -0.12934991610033386, - -0.18292051223575234, - -0.3590464414066933, - -0.4144493086288245, - -0.384504262203564, - -0.12023776955818899, - -0.49800080743267516, - -0.6887839345169521, - -0.5833469041579763, - -0.5082611610637071, - -0.7344571705995057, - -0.629121415937667, - -0.517261473964286, - -0.14743567289785353, - -0.47917147071718186, - -0.413997530050827, - -0.26515163537687414, - -0.42388472976595465, - -0.22268045303821982, - -0.628375395035557, - -0.5934853576068937, - -0.5905511557615533, - -0.1338497231874356, - -0.15153738788637205, - -0.5776991564633909, - -0.5090885641429452, - -0.7552407372649924, - -0.268709852350708, - -0.3757715121337437, - -0.24488958527051174, - -0.7130276075798886, - -0.7466981353519284, - -0.6625322177129145, - -0.230533529600348, - -0.4084030767081878, - -0.4567656715185556, - -0.37147614421633235, - -0.3589596351512008, - -0.6758261698551509, - -0.6204761305643056, - -0.5018583185347634, - -0.2687015489430956, - -0.10299684798609965, - -0.5685036162308248, - -0.09507310622520904, - -0.41009934464403, - -0.24004965419650526, - -0.14022999694720917, - -0.44079898476420254, - -0.46972485790904056, - -0.7013232375568017, - -0.38595131031964097, - -0.16114065450568615, - -0.2771342423408474, - -0.41186107772496017, - -0.4996031740684015, - -0.3312901849513773, - -0.6860931926398864, - -0.12487183114097644, - -0.7211862387683785, - -0.1943583327832552, - -0.4523983298908485, - -0.4703566077456144, - -0.47411677685521614, - -0.7564952429042398, - -0.5065982548135745, - -0.5631064707222864, - -0.3674234450570997, - -0.39574605516728895, - -0.5563205652016161, - -0.3537178011413451, - -0.43180232046324113, - -0.3417675834436557, - -0.4961493392438717, - -0.3447590428761452, - -0.7646003028156131, - -0.3341887185051965, - -0.1894107269480727, - -0.6927249403340313, - -0.08674131868713819, - -0.48260642629908923, - -0.3742756432317222, - -0.58251124335773, - -0.13094216947370563, - -0.12113638496381096, - -0.4678093133438751, - -0.2903610935222749, - -0.4475053316643175, - -0.21070044457445225, - -0.18806389874228258, - -0.4163925304748745, - -0.4431417480084269, - -0.7307983184898582, - -0.25660784319482965, - -0.7127214297143493, - -0.31226879940467994, - -0.4065388241778085, - -0.7776390219715588, - -0.6918494181691769, - -0.17014059006443172, - -0.16301029416138557, - -0.7849471823761607, - -0.5259111285433719, - -0.3095907377807696, - -0.45497991597882564, - -0.6298337125070399, - -0.13972390210996444, - -0.46241417181269295, - -0.11092000747121877, - -0.5162045362028029, - -0.7342116862512006, - -0.7847815184779344, - -0.3689993604901128, - -0.22027914774919743, - -0.21791060200450363, - -0.7616273232638723, - -0.534461629866918, - -0.4618371670950945, - -0.327410663386637, - -0.5566856824613038, - -0.4002285686014181, - -0.5186393462362449, - -0.4673741701945013, - -0.6362332242289289, - -0.3463554027819274, - -0.5172465046885177, - -0.2147963101556586, - -0.31021981269776944, - -0.08772854828084375, - -0.17844235915773765, - -0.5046948659206141, - -0.5840092152437003, - -0.6674333504730066, - -0.558188442744873, - -0.17390084198140388, - -0.6729531524940164, - -0.39736845019877637, - -0.4564936606654865, - -0.638562039692766, - -0.6889211500575501, - -0.6836534941682845, - -0.414441009535277, - -0.7686466403189088, - -0.2056644752691984, - -0.3843853749529518, - -0.43333090897409904, - -0.10283307753188542, - -0.45742938883850365, - -0.2514064336920965, - -0.16225516049976085, - -0.08310308915261644, - -0.6854801254188113, - -0.17151784170135242, - -0.2425786281085346, - -0.23336438767996892, - -0.2696829050273345, - -0.7169973955274009, - -0.740771254197044, - -0.3626334640709428, - -0.21416486760035758, - -0.7104147462817543, - -0.7221111793324888, - -0.2784750401498779, - -0.2923856603556467, - -0.3135325174227641, - -0.10173263115678166, - -0.6727146491202131, - -0.1415015965795734, - -0.4260518629219641, - -0.4442628050364041, - -0.11996698753618928, - -0.799128817597992, - -0.3985042610610896, - -0.15136542309670775, - -0.4244759258688911, - -0.5180374442428207, - -0.6148068385661356, - -0.43256450070761965, - -0.3692514430029943, - -0.7806335916934246, - -0.6775217881059356, - -0.17462750516063863, - -0.346437185543518, - -0.596974155237633, - -0.3222481617443928, - -0.35944059042135645, - -0.47446546086686386, - -0.44264070596988503, - -0.4548375179154901, - -0.5679055171297939, - -0.6631288759453227, - -0.2595279013483306, - -0.682307522515138, - -0.3807304875102639, - -0.26667635413329704, - -0.6322833640733463, - -0.34913111035087563, - -0.30637582309321826, - -0.13102032759467086, - -0.6040564330509313, - -0.08997367430640657, - -0.7402772679424331, - -0.4361509548033033, - -0.40787806669937743, - -0.7116570987085888, - -0.4901826058388175, - -0.10832076272360314, - -0.10365108791448818, - -0.09022696552900367, - -0.41829691077846815, - -0.3380626469998706, - -0.767468415306309, - -0.19528962968826902, - -0.7966639424833689, - -0.728755062995928, - -0.4528452097245375, - -0.4679280197522147, - -0.5564036206835486, - -0.3617487292179839, - -0.7987335609488413, - -0.14096373608763269, - -0.40509976406884235, - -0.09730998075426789, - -0.25963518443425904, - -0.16809644804957813, - -0.39692276231817125, - -0.12390973065878874, - -0.09778386156111196, - -0.607626659171192, - -0.21093492197073083, - -0.41018838566792937, - -0.6265355871204477, - -0.16710283379732405, - -0.4288178075427081, - -0.4005971156534551, - -0.6501134734110616, - -0.18199850627064562, - -0.5173490815532075, - -0.2661906870331242, - -0.4204732578150415, - -0.3084136205889827, - -0.11680415111711684, - -0.703935913977833, - -0.7460005755389697, - -0.16597310728371384, - -0.4557178124316127, - -0.5316906144230458, - -0.7109654875263346, - -0.38564645416526017, - -0.38336439908267766, - -0.7538178185482021, - -0.18785688565947578, - -0.7156067196858215, - -0.31504837648056655, - -0.7290129771371742, - -0.29311530611372727, - -0.23339846584656765, - -0.6496122189760334, - -0.11258095971295456, - -0.657016329571009, - -0.7700007989394301, - -0.13419123893961693, - -0.2344829311427611, - -0.7992049814079959, - -0.3370456795565154, - -0.4954329932103491, - -0.1002640652819301, - -0.38447992772328643, - -0.727660386948209, - -0.13368738935905766, - -0.4019594976165771, - -0.0911505955728481, - -0.17293097746903663, - -0.3627171655880487, - -0.34611878170792887, - -0.7643476705177993, - -0.7543165635943676, - -0.1805880584204378, - -0.39261187123703006, - -0.33173851866265835, - -0.5478208932278117, - -0.20125173285779918, - -0.5235608295709335, - -0.7712293679419892, - -0.5259773000116807, - -0.42070513979970964, - -0.7547090185392135, - -0.693488073091883, - -0.1934972519056437, - -0.6758729558309158, - -0.3483793348449903, - -0.789014377015334, - -0.1762836252669412, - -0.5107424399476301, - -0.5781538452951681, - -0.7218623147922872, - -0.796575883247079, - -0.5460847339479824, - -0.09439529417962511, - -0.4636987226333378, - -0.7988394002608332, - -0.4852274859125316, - -0.08338302098362527, - -0.42921676986172935, - -0.5325436257894134, - -0.7793437543552139, - -0.47386743694061273, - -0.26749714040739725, - -0.642345252679334, - -0.5005992740198429, - -0.30852902706500634, - -0.6867156490607442, - -0.4596443422877545, - -0.27189421165282446, - -0.27130849918586963, - -0.2598516940024409, - -0.09089202389769069, - -0.23245177897908387, - -0.3067678537361091, - -0.4544454555337352, - -0.7520596827631935, - -0.644504459356493, - -0.7582095087104088, - -0.33862779343422544, - -0.6116850895081594, - -0.44853472643252357, - -0.2613195240235622, - -0.5655623338706602, - -0.7554824621312357, - -0.6645514063624804, - -0.36419784278232714, - -0.10170382505162456, - -0.6188148244474532, - -0.5234448694230057, - -0.6585936139066135, - -0.5020508418046392, - -0.32133317490077423, - -0.33365799878540514, - -0.5644652611706944, - -0.7572142100412361, - -0.3144770844372168, - -0.46075139593941195, - -0.3463847263137057, - -0.44047354733342786, - -0.32129552976409886, - -0.42020624741039053, - -0.38519016411691726, - -0.12910365225965736, - -0.6759080896934927, - -0.4628851966965444, - -0.4778535191971686, - -0.5181780519508147, - -0.11409246133360085, - -0.14456771435252402, - -0.20197058335156715, - -0.406516482519049, - -0.30766174705957805, - -0.5151176150826206, - -0.4424196835839895, - -0.10537421780085698, - -0.25686950381526563, - -0.09846373435215128, - -0.607500345023942, - -0.41169858643515894, - -0.3386694314529072, - -0.6185416285689627, - -0.18939499780462843, - -0.6663850381745817, - -0.6067219125722387, - -0.599159110280749, - -0.7183700033913668, - -0.17197818151778266, - -0.5633334723523596, - -0.7125766214775388, - -0.2785236775218928, - -0.7498402330141763, - -0.24627013693750277, - -0.4584451665009222, - -0.5498662360780326, - -0.5357228105853347, - -0.4858344786948245, - -0.40525818739199143, - -0.7203529440055443, - -0.7519528985626106, - -0.6137637674017835, - -0.6634754027707027, - -0.5230603867883616, - -0.22764576983258922, - -0.7524202691224511, - -0.3730805559974848, - -0.32528122886773503, - -0.6057638815488342, - -0.29999955683463553, - -0.6860347022811644, - -0.3144349580092956, - -0.7648350641749221, - -0.40387146504566157, - -0.504317256494983, - -0.1819605432023157, - -0.3683451562841461, - -0.1487398823241236, - -0.4457138102385767, - -0.2898338649845258, - -0.35440023998383474, - -0.22762086014724614, - -0.23704765047702103, - -0.29655558956803574, - -0.29537688457167754, - -0.25387160888477467, - -0.5435266028918454, - -0.14119120239551652, - -0.5947557852348291, - -0.26283399916139527, - -0.28442739041460163, - -0.7229371664813248, - -0.4278766775804382, - -0.7898098752915985, - -0.37027123359591346, - -0.7151138405341851, - -0.7501175194457681, - -0.39912043801074715, - -0.7300101325867504, - -0.7630248072445482, - -0.355692087875602, - -0.258525094539517, - -0.5581422132816063, - -0.1006389766318897, - -0.7406958770560305, - -0.3411536358476248, - -0.438233153472205, - -0.7552705923778663, - -0.46293698139815415, - -0.5390746440938624, - -0.08452094196232818, - -0.3483451796052788, - -0.33415241864541545, - -0.33083805039007347, - -0.3471644335969035, - -0.44604948709325803, - -0.7887988749796876, - -0.297683805361062, - -0.48950674757124657, - -0.6291848227751228, - -0.5084002730506109, - -0.746916869108862, - -0.40682986986082825, - -0.43293544125796735, - -0.4292061908439538, - -0.7330415095940561, - -0.3440830644808564, - -0.22058570416478507, - -0.46893181323915345, - -0.33470538811191963, - -0.7900834377720152, - -0.29682560958842996, - -0.7658155552200016, - -0.14241528006596893, - -0.44653918777598384, - -0.7296831698743313, - -0.6332865273844404, - -0.7658366632624626, - -0.3739467909590795, - -0.7875094227472825, - -0.1899097899402109, - -0.1709310787497511, - -0.2427995241266212, - -0.7510118835552769, - -0.6009151971975283, - -0.7312988822658367, - -0.6797733417122772, - -0.6437528767310507, - -0.5940424518941385, - -0.641970315703042, - -0.2584896122358369, - -0.09153606575730688, - -0.3732811950010894, - -0.23633183670843316, - -0.6774482211929537, - -0.18465800735452986, - -0.3201979044292014, - -0.35364694014346654, - -0.3979843329470003, - -0.1346714814932386, - -0.6065936453016807, - -0.2792611889078127, - -0.19100965377393775, - -0.0936206757983663, - -0.514777306264116, - -0.6503874493099155, - -0.27685947801035504, - -0.40032846451114035, - -0.11746191533194017, - -0.30704459242852433, - -0.6582310085090683, - -0.7176865441545762, - -0.525986634053655, - -0.6604769957786485, - -0.5374251312808644, - -0.6576426540600415, - -0.3287018615371444, - -0.31700458741923715, - -0.1132865387113523, - -0.41609666804621825, - -0.27456382368412835, - -0.08867451572222929, - -0.3997360636556127, - -0.414453425029192, - -0.7808650558073191, - -0.2579309594721422, - -0.6088114952972713, - -0.6287072870784206, - -0.5828794180180125, - -0.09969758810232499, - -0.6738079585698074, - -0.09623719237033224, - -0.7676130130929842, - -0.7737103398472509, - -0.34597348295063324, - -0.45790129036088084, - -0.44993123802216034, - -0.2835116895999775, - -0.19213635534784734, - -0.6072785311857705, - -0.2679804434713392, - -0.6329486466164147, - -0.6264475401930454, - -0.19378422398548356, - -0.17337637794118999, - -0.17624738502991755, - -0.6762522867632866, - -0.6787389783141333, - -0.45240172010496876, - -0.16684808093797288, - -0.19107407853528202, - -0.7707616894544028, - -0.29638882877620343, - -0.5299615200040471, - -0.17959039842850655, - -0.2407820367055461, - -0.5117299087610387, - -0.38553717967313333, - -0.16554637110423676, - -0.3878745556960095, - -0.49865513173884257, - -0.12104688766395588, - -0.1312755695845873, - -0.19237677355818916, - -0.39072031199794577, - -0.20192812247633463, - -0.5188832550802616, - -0.5197515973213503, - -0.6653564554556404, - -0.7942194425306023, - -0.4132123870794429, - -0.7755905895321701, - -0.5921098104690499, - -0.5453493032353529, - -0.3187343405017762, - -0.40440785193092693, - -0.26713783718538253, - -0.7377911926946938, - -0.6366462665408158, - -0.5175690652576461, - -0.7594923178376508, - -0.7465752003287397, - -0.19093299180818335, - -0.25572990680834695, - -0.17726829810092715, - -0.48230327947813634, - -0.7324081715680475, - -0.4995741778267182, - -0.10284066544669213, - -0.7901512102610031, - -0.34783063828506944, - -0.10504035495188258, - -0.7148736652233464, - -0.6219014969443846, - -0.6043140188613227, - -0.11330684299892269, - -0.3265718189864549, - -0.7796967439908321, - -0.44009496946780097, - -0.09714281109482947, - -0.44388921580330615, - -0.19166495998942756, - -0.6000928005618062, - -0.29964856376666593, - -0.3293333629637959, - -0.5558831544658642, - -0.3698504858951949, - -0.7292166691684722, - -0.6436244660728715, - -0.2720947557099157, - -0.14924653899049967, - -0.2045659656298935, - -0.41511957159952606, - -0.42700524345583496, - -0.552172891871198, - -0.2307817360885991, - -0.1963611477133056, - -0.705128630568199, - -0.3599497155145975, - -0.1708711199458247, - -0.2481806464956514, - -0.44242218430696245, - -0.7437108468890983, - -0.17521630406522593, - -0.4372836771285445, - -0.6087516750208806, - -0.7034848685128136, - -0.6815304772179598, - -0.2374832899849204, - -0.6565768451743462, - -0.4574606505624607, - -0.3413027909132777, - -0.7484420962137638, - -0.46806339258254803, - -0.7665017051404595, - -0.4144676641474874, - -0.45221698619526735, - -0.28417554664393974, - -0.44587152271983715, - -0.20254636940511228, - -0.1197938553146145, - -0.3648611602360423, - -0.10418648053245227, - -0.6349348730951019, - -0.4941956320381143, - -0.576717994459745, - -0.45285750344997694, - -0.45164169950713295, - -0.22831534888178795, - -0.2033536959163985, - -0.6520870435278008, - -0.38023521666925975, - -0.5974438544558769, - -0.3597689765556962, - -0.4407080673153558, - -0.4073245140640598, - -0.6382409926899664, - -0.27812556072638006, - -0.6589726118414029, - -0.7493822769351899, - -0.33720545109303895, - -0.30040371246375114, - -0.4482217694887043, - -0.43354703569459896, - -0.6318046036806373, - -0.36470028789325354, - -0.7262526192648854, - -0.6475390626550305, - -0.16997723852582958, - -0.5672577514811791, - -0.38469627667510453, - -0.7599831597981399, - -0.1761593422984945, - -0.14807549538859466, - -0.5968645808169767, - -0.4713993074160562, - -0.49986536897115985, - -0.7292217752695588, - -0.20947967676639279, - -0.6804554539367296, - -0.6999871664707953, - -0.5370704822256942, - -0.17386824626548125, - -0.5589404393047411, - -0.1615763308312146, - -0.6614583504194871, - -0.6726412738327159, - -0.6106065527998852, - -0.15242125090314795, - -0.42862677567009405, - -0.4745486987324791, - -0.3404286078033285, - -0.7783900187462052, - -0.45789203422212793, - -0.3263011402690722, - -0.7758583687763119, - -0.1509876708579574, - -0.7373521243097911, - -0.512898874576157, - -0.09422120181707339, - -0.691624227529603, - -0.7577368823171444, - -0.6611563460677792, - -0.20516343787113167, - -0.22838072856088953, - -0.2477817531589669, - -0.1120636010610786, - -0.41730223997016025, - -0.5332949425288778, - -0.5580401336891949, - -0.5179660427102086, - -0.6697925560618818, - -0.791895491300042, - -0.14748076711066604, - -0.4326403236215553, - -0.7077643769679852, - -0.6013105263123165, - -0.4365937725149072, - -0.3777746003929892, - -0.34065875346889235, - -0.08786767127512929, - -0.23177739033153677, - -0.7817354712786639, - -0.4249859680934804, - -0.14597906322547316, - -0.46732869093150603, - -0.5301574759190408, - -0.21736883665305695, - -0.7571060531651631, - -0.7284710081200838, - -0.1354415600247707, - -0.19616989876734248, - -0.3137966997375952, - -0.395932241581999, - -0.3391040628056412, - -0.49909559336164444, - -0.6970869911471712, - -0.653067899174696, - -0.2048181412818325, - -0.5029541869924375, - -0.6244569281417812, - -0.49214181780311017, - -0.7046560831526325, - -0.383829858812327, - -0.19136428585703025, - -0.1516800401520838, - -0.39824787457373606, - -0.38465628799538015, - -0.17714635453907712, - -0.6836835656571069, - -0.4632155106366406, - -0.36456666474419225, - -0.46004508891769064, - -0.24484331095180567, - -0.5323456832265863, - -0.5878295150691782, - -0.6975204303122303, - -0.6755020656924225, - -0.22675037272964982, - -0.6020951669067455, - -0.3433733557683691, - -0.7934987841958766, - -0.5209788839806492, - -0.36964961476241687, - -0.163092817503387, - -0.4073833932809953, - -0.21999740217003383, - -0.34325315286640934, - -0.5837108690629155, - -0.7630034925509945, - -0.5276378630688006, - -0.6977035016904816, - -0.6724066084645162, - -0.5505167593442408, - -0.30345885951636614, - -0.4484286791703807, - -0.5033461771046164, - -0.17002663816497499, - -0.3998493379994792, - -0.19957427293938634, - -0.37527611983767584, - -0.22792332814911154, - -0.3912135622515793, - -0.32047578419543665, - -0.758128871089109, - -0.4060384176976609, - -0.25522913883027076, - -0.13973183314288218, - -0.742966331565037, - -0.40658299571049766, - -0.5094231538855394, - -0.6357474795630408, - -0.4955313604815909, - -0.14908287291695133, - -0.703277241640773, - -0.7372869161084357, - -0.698622110954852, - -0.4065220589230452, - -0.2392215537011948, - -0.34380831943155976, - -0.11926633786569052, - -0.795827259388717, - -0.7999144666848168, - -0.08961523796115389, - -0.3127623290315469, - -0.6465416248598892, - -0.43192319258107237, - -0.47184180025145833, - -0.6551532476769204, - -0.20945366528076204, - -0.413068591013324, - -0.4172662903811182, - -0.7523010759034812, - -0.3046091465637908, - -0.623552944631834, - -0.515927238648364, - -0.23850242098264463, - -0.6891858921072268, - -0.16346562514612806, - -0.49025770952347747, - -0.19550508346127893, - -0.5665666492538851, - -0.26857295517212465, - -0.6146367966741575, - -0.2575251170244649, - -0.5470095084095647, - -0.09701505177322789, - -0.17533210794510024, - -0.11313739038915027, - -0.27163456529996544, - -0.24136156524384023, - -0.7325457896674233, - -0.2434748591145185, - -0.7401938420007976, - -0.5266891117500785, - -0.16104248022154333, - -0.08684192508629318, - -0.17131946965867528, - -0.5051545761916645, - -0.6306697760004305, - -0.5709404945992502, - -0.2746988361499709, - -0.6431538787190181, - -0.4758500971512931, - -0.4074764820003953, - -0.23745144481652436, - -0.32410635706362484, - -0.7083145437122669, - -0.5378600427698097, - -0.6319106821290118, - -0.12334622592484534, - -0.5466200886995689, - -0.10738678596513962, - -0.36901040784614575, - -0.5606032311482206, - -0.7056094346060241, - -0.6464691028207331, - -0.383385198811361, - -0.2700879307997802, - -0.629189642925148, - -0.0934495648428817, - -0.08510517515048988, - -0.7566120389920123, - -0.6345344558475887, - -0.499047308367454, - -0.7002943103561624, - -0.6469489375314812, - -0.7247890352351309, - -0.17643984111083488, - -0.6661204432669164, - -0.09304553259696191, - -0.7153091323862433, - -0.08286052731253568, - -0.4082273222392614, - -0.4988839358906468, - -0.12545837686571792, - -0.3188190355016568, - -0.4958050126941469, - -0.780572158824997, - -0.5103520384520999, - -0.15372822350128734, - -0.28842388149383136, - -0.22342392901976116, - -0.3875731946576387, - -0.1423244820419426, - -0.6744514940178366, - -0.5963784750015421, - -0.18217324337986318, - -0.25492323514104, - -0.5047070201949306, - -0.1351818399070539, - -0.6672765315915195, - -0.22240761131904796, - -0.4410405334806564, - -0.11295165788580419, - -0.1980340295734433, - -0.7035088144238597, - -0.6781922595125325, - -0.284893402177371, - -0.5946113689400991, - -0.7758687994675332, - -0.576249309795152, - -0.1949675034048418, - -0.49423232701253555, - -0.30627059142400925, - -0.3775488254200271, - -0.6094002042477555, - -0.12086579942513165, - -0.133075632403858, - -0.09976774375338682, - -0.46645898627321647, - -0.47575649707476786, - -0.31442377743395367, - -0.2552398354277162, - -0.498216810994683, - -0.20519615727250262, - -0.24258810564873545, - -0.7456917725738518, - -0.24023121264663228, - -0.1518958954394357, - -0.617799186111555, - -0.5400432446053466, - -0.2471578649192795, - -0.29609586449909087, - -0.4683708012850416, - -0.3828878923967083, - -0.45822072460714247, - -0.5889136791757511, - -0.3720994210448573, - -0.2364274690407333, - -0.4764350061960863, - -0.6327297627938813, - -0.635793464173389, - -0.4019013138174164, - -0.19946682879845623, - -0.49341530564019137, - -0.7225602134825617, - -0.5976382624177604, - -0.3123412637981403, - -0.48706648854054513, - -0.17929052082684105, - -0.6330595043394575, - -0.6669962581341908, - -0.30492703146066547, - -0.16921594917237626, - -0.15963520729337266, - -0.5838841565047594, - -0.09373125976142327, - -0.6013567585450005, - -0.4344006184695035, - -0.37237830210682993, - -0.684002221213197, - -0.20752511920725158, - -0.1454609496173772, - -0.5395072544147776, - -0.355301867057297, - -0.2759952922996999, - -0.5714084772824986, - -0.20718787531223648, - -0.33069786259772627, - -0.19965667565599043, - -0.4285638905584309, - -0.3807567113287514, - -0.3501531965764775, - -0.6992574680165832, - -0.5618896096743076, - -0.4652824289762144, - -0.1716378325320106, - -0.7962018499174927, - -0.6191206257779621, - -0.12786025767008036, - -0.24426879692132952, - -0.570272508263572, - -0.2612779538112051, - -0.3289023437981394, - -0.48724961887349, - -0.5134014550731499, - -0.5247191668986786, - -0.3658683894634728, - -0.17416984128976765, - -0.6796457910781535, - -0.7182303378036454, - -0.13962958799126968, - -0.4831674009996435, - -0.6861824706929484, - -0.3708712376215427, - -0.5338796277586279, - -0.6782982140421708, - -0.7439380798553357, - -0.1754157223805829, - -0.7271362574787373, - -0.5464141234065625, - -0.08669959807595351, - -0.6436261141488336, - -0.7210865978863977, - -0.3357104014590779, - -0.4026561967949146, - -0.48220336347719667, - -0.2434330162865439, - -0.1967099582700701, - -0.5107287395740885, - -0.32298182945702736, - -0.11223739165728275, - -0.6984417009268691, - -0.11599304674106614, - -0.19418575895174472, - -0.5147496477932276, - -0.7192983754119646, - -0.6512961176773646, - -0.73298918210822, - -0.5308735985303137, - -0.16561707037022255, - -0.7560644124827675, - -0.326099938948567, - -0.3381296047892128, - -0.39868671450616705, - -0.693327603666582, - -0.44663330659687966, - -0.2596440930636673, - -0.7419478292434556, - -0.31350512358809324, - -0.4574871068518621, - -0.41260205291379304, - -0.5826909090681253, - -0.35176501338297644, - -0.7468870363728654, - -0.37451930860772165, - -0.31151725920963463, - -0.20482354333055597, - -0.4682695800645062, - -0.32638904839382055, - -0.5413060643709253, - -0.6501492409303982, - -0.21661775057000143, - -0.14992679704665302, - -0.4626931391806582, - -0.6168950817048018, - -0.38776011326860343, - -0.26380361241555983, - -0.6870850138470607, - -0.5800281447031428, - -0.3022780351751406, - -0.7882915420146859, - -0.4098869297486037, - -0.3291522904943834, - -0.7415310711082508, - -0.14472433104031523, - -0.42889853651558874, - -0.3253493951557222, - -0.34366356509912066, - -0.3529210156348367, - -0.43337457249714506, - -0.5899987078620634, - -0.58622327999086, - -0.49210556264925986, - -0.11033180569164946, - -0.10249803671603219, - -0.5393167614731296, - -0.38690594243875315, - -0.3033183923336662, - -0.42781639937222304, - -0.3912110713998188, - -0.1425333789566815, - -0.6705196026441934, - -0.2289410401319797, - -0.41767508970377365, - -0.26168986570595787, - -0.32090405395886, - -0.4626552799497554, - -0.5889779475799972, - -0.30346552010444716, - -0.4535533819907084, - -0.5388267845473902, - -0.6916004556850894, - -0.6362634052609557, - -0.7912030749138426, - -0.642849800670243, - -0.11254791362046201, - -0.611109751010339, - -0.7369404571237048, - -0.6987042321355255, - -0.26155794779754604, - -0.7787015936231552, - -0.5163106487887021, - -0.6500752426078973, - -0.6980546217721177, - -0.25060158852171743, - -0.29897562154733437, - -0.7530526989991013, - -0.19535276211305708, - -0.16024759833920543, - -0.31034656405355937, - -0.2541600464776266, - -0.14462666208787622, - -0.3638224359612768, - -0.5622443299738988, - -0.4189896339411016, - -0.2676859829826236, - -0.10043937120788071, - -0.3552942013858431, - -0.4036634144525731, - -0.17580912247529046, - -0.38119807440655923, - -0.3910720519323437, - -0.4570912106258756, - -0.6134421077211618, - -0.4715861124910955, - -0.3772127898841234, - -0.36187039929893555, - -0.2664363380406438, - -0.6018202924504018, - -0.5241050150227081, - -0.43647648331695293, - -0.6074572498015256, - -0.7808903827056961, - -0.2753899553247787, - -0.6258042900451712, - -0.7931112659043473, - -0.455661894624806, - -0.5799714400679494, - -0.12265024916080935, - -0.2301396379122872, - -0.6837264872013813, - -0.5355551595989578, - -0.4030095139593444, - -0.4395574399252403, - -0.14423707370883943, - -0.6199335177031936, - -0.40828854553350746, - -0.7077283388930417, - -0.49922093389796834, - -0.39921871025863803, - -0.23627389493765028, - -0.4301340809749206, - -0.13715367758518737, - -0.22117751723236068, - -0.17100263206484245, - -0.5131179155068875, - -0.5913742799360792, - -0.7160537223812331, - -0.2466403114596064, - -0.48239748259443044, - -0.7673414993885352, - -0.5925328031880006, - -0.13320985771410276, - -0.36024953854175934, - -0.35307587730594714, - -0.1053251037553472, - -0.3676451118217507, - -0.36569750864225453, - -0.26965478058344206, - -0.6494420464602072, - -0.5353740356516703, - -0.3522812204826816, - -0.746511143953328, - -0.12725116316553198, - -0.41335570489436724, - -0.6941260853744902, - -0.48636398845456563, - -0.23950676440220253, - -0.1663471691082018, - -0.6648216395591364, - -0.6373791801266523, - -0.711103712355324, - -0.5261845759326929, - -0.4574864640074604, - -0.7869345077143913, - -0.6845907225184475, - -0.26946031209899823, - -0.42842501394644333, - -0.6385503076175482, - -0.541224186617698, - -0.6066906757938157, - -0.3860968825397, - -0.4472209437673175, - -0.3242159753044714, - -0.5867477361245715, - -0.5335390181474818, - -0.24899537714155395, - -0.7761782188566722, - -0.3227838630165448, - -0.41033508956039894, - -0.6390333119357671, - -0.2702015596972741, - -0.286385739900777, - -0.4788132499354045, - -0.5923145433249595, - -0.3843887439454244, - -0.5635529005528672, - -0.4066617429882232, - -0.6766307952678066, - -0.18175802071874303, - -0.4263744531232733, - -0.5824159678643865, - -0.15102712487154746, - -0.7794045933360308, - -0.3080448410219481, - -0.19996356294920514, - -0.18639670370465855, - -0.8000738785830445, - -0.16780874126458822, - -0.31996968360963174, - -0.3355429380238856, - -0.684889990367853, - -0.4649330465428007, - -0.09022829403462262, - -0.08482893361295607, - -0.11969021991758788, - -0.21477484421354365, - -0.19827684729634454, - -0.6489970614991425, - -0.17119575539597753, - -0.4663400122526376, - -0.7094446817969429, - -0.27803551297154117, - -0.4887757357619509, - -0.7754764352853616, - -0.1389629303626404, - -0.764862826982245, - -0.5635723925970655, - -0.45391663122140274, - -0.4521514530007663, - -0.6176582416065881, - -0.6633968531098474, - -0.26089026987292363, - -0.39923376064984906, - -0.2528737038501413, - -0.4776214646972339, - -0.7669386675695304, - -0.42967705951624724, - -0.34216793060755923, - -0.6976889205569852, - -0.31036305273118114, - -0.7614416889113327, - -0.15386502734501106, - -0.219385898750736, - -0.1974563334593621, - -0.14146004383177513, - -0.16848003583748106, - -0.39600064451249894, - -0.7342421061567382, - -0.34468496967353623, - -0.7610667096404304, - -0.13743553338300074, - -0.1767023527572018, - -0.32360142715592916, - -0.5368974580645022, - -0.24543896425861655, - -0.14392116748046302, - -0.7659452570232232, - -0.09559618090600785, - -0.32359162634103733, - -0.22216958221961836, - -0.573658194163092, - -0.24727567164045838, - -0.44351084893245685, - -0.1233491254422916, - -0.30050384312004197, - -0.6211412954725984, - -0.4971244259513559, - -0.6238381191001369, - -0.11247930614083201, - -0.5294020363535721, - -0.4321026916052286, - -0.7076309758751673, - -0.25650408604382335, - -0.11103306834200688, - -0.5794156500760158, - -0.19690861873342425, - -0.5151781721280362, - -0.25109887147060483, - -0.7802176781097133, - -0.615666441415472, - -0.20100342257900528, - -0.40915133094186384, - -0.3026147473129941, - -0.7913906233648397, - -0.39821023892300733, - -0.6502042995486487, - -0.3669393134853677, - -0.22172659283229534, - -0.24499884051697007, - -0.3916866687844012, - -0.392905979543251, - -0.346911982372515, - -0.800250944121166, - -0.1253210300403501, - -0.3272784727516094, - -0.41761442598731635, - -0.7352351391599029, - -0.6117146722221538, - -0.1429383403174399, - -0.2642147344287673, - -0.5856083374695769, - -0.26072111696555866, - -0.7945057309548055, - -0.6533275650035527, - -0.150460600278718, - -0.16377878342825458, - -0.5494817871090364, - -0.4330138713229226, - -0.7918558419932781, - -0.24585923704383028, - -0.7627772341347785, - -0.5489175659223864, - -0.1536528775446212, - -0.7793319607452506, - -0.6909444866762877, - -0.7948486520894311, - -0.46455163131022925, - -0.46846895487843926, - -0.5713184562137086, - -0.31941155712786273, - -0.410790830371373, - -0.3705397757637784, - -0.2837296563708881, - -0.08462730905466809, - -0.5953809192119098, - -0.752431355151125, - -0.38254406377286304, - -0.6310313133183707, - -0.2287580010391127, - -0.7181406522478964, - -0.20176160146376754, - -0.3072883965912449, - -0.697134205440133, - -0.11113265923805749, - -0.22745524369853398, - -0.38835346552213645, - -0.5565770014911928, - -0.37860239175045246, - -0.7563460540066596, - -0.10862735043135296, - -0.4836829578356807, - -0.46477719453383576, - -0.5231845581290065, - -0.24255157181531484, - -0.5947675664410612, - -0.6758559776789529, - -0.16048516116244893, - -0.5820975850891517, - -0.209783938311638, - -0.5124779308359526, - -0.4730916127481676, - -0.3745004783022733, - -0.17644639240748905, - -0.434123665095636, - -0.7665236904756383, - -0.47021277315835197, - -0.5535434755238146, - -0.48414083311735673, - -0.387539128566767, - -0.3209220094710326, - -0.6717782338182545, - -0.29062351262974895, - -0.31606398808255626, - -0.4830701018236165, - -0.437197566078656, - -0.6653987321218131, - -0.49075059288665174, - -0.7499301044593171, - -0.19576783163454603, - -0.46354583850254133, - -0.14676590354063734, - -0.6290807343748398, - -0.7236124681783012, - -0.7276658865560551, - -0.5212603175672923, - -0.6397874458278698, - -0.6905127188928222, - -0.3123370378835586, - -0.14314335054517724, - -0.7595429774772623, - -0.5234473306438339, - -0.5166387461325392, - -0.23128585169837979, - -0.33965997285596794, - -0.6376913739930195, - -0.22760649944878897, - -0.1420696371420448, - -0.40427879881718964, - -0.3137900879085634, - -0.5199922379471393, - -0.6025176423027883, - -0.4829598704530101, - -0.24778872329894475, - -0.5379206544931877, - -0.588126025007241, - -0.5707787283046785, - -0.12228789031393339, - -0.7296201486421786, - -0.4642648574187249, - -0.09346374777627076, - -0.4739052833700804, - -0.6405841200382205, - -0.12713892614102096, - -0.1283807490351434, - -0.1655430057914936, - -0.1639199604870769, - -0.20680532301866228, - -0.7748933319317606, - -0.19454761941910814, - -0.3589623618351943, - -0.6691411381216061, - -0.6114434733778147, - -0.4976569413790858, - -0.43312179234551584, - -0.32674057473081564, - -0.6861955387955881, - -0.5847395488221622, - -0.3692012261909586, - -0.4438658045895635, - -0.4659241886283738, - -0.14361815726810057, - -0.6569973748115695, - -0.6248363778727819, - -0.42396905406979685, - -0.18388177489336943, - -0.14016030739700147, - -0.7202524015573655, - -0.567962328999499, - -0.4277470613971229, - -0.20519180132564496, - -0.17296121479123072, - -0.5720104624995628, - -0.5427463025910934, - -0.7024598693895463, - -0.5257045577088066, - -0.6010175718298862, - -0.7413152098369795, - -0.20669903374092358, - -0.1425286330161366, - -0.3108506372549392, - -0.5377946433720664, - -0.707884553011443, - -0.3951925942920407, - -0.7287667777811875, - -0.30624358057450835, - -0.728475644431766, - -0.657198940236599, - -0.21996736086095847, - -0.7904695662950147, - -0.683338458043161, - -0.5763862327877658, - -0.1452187637191864, - -0.2514834708030791, - -0.3859357194144821, - -0.739141419315079, - -0.2592687165374482, - -0.24645453610766654, - -0.25513443576984063, - -0.7222833304133486, - -0.3590873575383169, - -0.6394718290368249, - -0.36114984637771624, - -0.5058933695098569, - -0.5928323247430954, - -0.4735720230626949, - -0.7110212855882431, - -0.2664630539098459, - -0.4366759919270297, - -0.286202648493766, - -0.5891807652069525, - -0.7368516869582906, - -0.6728451372007997, - -0.3516066288399121, - -0.6979495651097387, - -0.40997614797162657, - -0.2758881324705833, - -0.4280018811597031, - -0.31109791647262314, - -0.7865310928254463, - -0.15928153979847537, - -0.5860736067385106, - -0.527395205048963, - -0.600843498989499, - -0.2310452295540253, - -0.21254385977851864, - -0.5168569141812089, - -0.5070973849338128, - -0.32410740223014467, - -0.22493034613449847, - -0.28431951493623775, - -0.39119331209697505, - -0.13200364712052937, - -0.7143188720826544, - -0.3104917086078942, - -0.6196439187428268, - -0.6818087080085242, - -0.7763049034175691, - -0.21937086579779952, - -0.6815088296201317, - -0.1857375200073954, - -0.5645558191383732, - -0.7913215727276101, - -0.48115346454592495, - -0.19328802701248382, - -0.7164219950849436, - -0.7404754687693023, - -0.26132899192622006, - -0.6803105215936648, - -0.1546982530169242, - -0.0910655101624761, - -0.6910321154383521, - -0.7767761144657133, - -0.21724978329935796, - -0.611333077721238, - -0.20869538480975924, - -0.4439947884746872, - -0.20220313884920826, - -0.17074097421181167, - -0.47390196510080757, - -0.10505044527939855, - -0.3778712708090126, - -0.5025453784011005, - -0.44246638421654105, - -0.6977702363845788, - -0.5886258816490869, - -0.5215482243975829, - -0.37451001310959714, - -0.1617412746377228, - -0.4128595244425113, - -0.36844450908177634, - -0.17951174651873913, - -0.2628113068980771, - -0.5002369110096617, - -0.3476556234433606, - -0.2167152879790295, - -0.1230977645431729, - -0.5851636162675155, - -0.2732144067804225, - -0.7507680632057, - -0.23998250663552168, - -0.6081745272772247, - -0.5305305596836667, - -0.29346751598273046, - -0.5907680221280646, - -0.6650393792199791, - -0.5824203297744049, - -0.12892254522695357, - -0.767434730505811, - -0.34149631962322546, - -0.10571470870554822, - -0.4087179134419463, - -0.13677613936435873, - -0.5644814120856376, - -0.16903421401592822, - -0.6282705200384541, - -0.5280756842010228, - -0.7323546828070098, - -0.6109002566043935, - -0.47562595074826614, - -0.44161164028610156, - -0.6774101776443479, - -0.5881595101363171, - -0.44725564273029017, - -0.33361685380897843, - -0.6927513690408285, - -0.7472941058790271, - -0.2887009563038748, - -0.6445689118238047, - -0.18462404463996307, - -0.7118690491850058, - -0.028644436652831007, - -0.5682213006487901, - -0.6761455082238639, - -0.7003957845987544, - -0.30961203475365756, - -0.20623057177949677, - -0.3273935249206563, - -0.4032066598340096, - -0.3739556110157591, - -0.048505620904187974, - -0.6143557833771102, - -0.0034200841974143525, - -0.5446935886239564, - -0.24065317607590675, - -0.6181052453815119, - -0.45526548090616376, - -0.10945783990114921, - -0.28901501939481933, - -0.34033382267912793, - -0.1454832982009434, - 0.012897850363320473, - -0.6678582430210497, - -0.7850026998568009, - -0.7852278665419362, - -0.030556862254371375, - -0.6646340451448222, - -0.5726298468923214, - -0.4284284197961865, - -0.5436936367462497, - -0.4614212869037729, - -0.004799908953896148, - -0.7435909949194295, - -0.24612666817161566, - -0.6349580147073742, - -0.20004930889233274, - -0.6671581323153982, - -0.2845637584366414, - -0.033020424186114394, - -0.06968246509644904, - -0.3090867243991956, - -0.152423765587263, - -0.5652696296847189, - -0.568238228585626, - -0.1357651541524343, - -0.3543794614987937, - -0.14576374663857883, - -0.17984947437792098, - -0.022041597390107137, - -0.4123831774304446, - -0.6904124058368837, - -0.19707330349128083, - -0.32844467817671436, - -0.5255600177061701, - -0.2401551633468133, - -0.49730269014768974, - -0.5140029235684116, - -0.6427336183515416, - -0.583688828455233, - -0.7463995801345831, - -0.5314727403868991, - -0.7760832592575109, - -0.12106765545725462, - -0.6668961583831643, - -0.6918027771714741, - -0.7198097782297318, - -0.18619947760387257, - -0.5621390328431375, - -0.2731014847118969, - -0.21294833598853335, - -0.002661342332841099, - 0.0031716726548818297, - -0.3799537688383251, - -0.06830770149848542, - -0.5059256303047455, - -0.04857167339145774, - -0.4892303373727485, - 0.012225884826685185, - 0.0056307664183246064, - -0.332873174368265, - -0.209776962211084, - -0.08229534097028346, - -0.04048656746044199, - -0.7399131428242549, - -0.4388587387286096, - -0.6230182975078828, - -0.3003055968623449, - -0.6705299766690708, - -0.13802266641944783, - 0.002044381906342263, - 0.018918961055593875, - -0.27888213177451204, - -0.48463299877864546, - -0.3401154840910416, - -0.27710366368685035, - -0.6387493498620576, - -0.38551642806522507, - -0.17940987789800178, - -0.2524818971633992, - -0.48763190105543663, - -0.6222336471890448, - -0.17109825426774894, - -0.6835414124776183, - -0.772525301468476, - -0.6766934027237923, - -0.1076950317128833, - -0.2128081183234014, - -0.21791689372387402, - -0.5579305187666843, - -0.05135308827756613, - -0.023460168514662927, - -0.3149885289523897, - -0.5178573764843226, - -0.46634522056928124, - -0.34535650649826083, - -0.005577310243458644, - -0.05853409242996421, - -0.31739667962050716, - -0.023571032480717236, - -0.24547580189029894, - -0.23194484547769556, - -0.6557189324027477, - -0.006354114953748158, - 0.02857010456534237, - -0.1994003819967507, - -0.7141180236559873, - -0.31180971979843003, - -0.7427163700246756, - -0.08877440956658855, - -0.16605997092133673, - -0.15332693550905208, - -0.6296013609431108, - -0.37145316362603964, - -0.04388301730170052, - -0.36693004702360366, - -0.7433893912425946, - -0.16896388366056792, - -0.7316175215805563, - -0.5148972188223215, - -0.3959099441367876, - -0.0177045752340369, - -0.08594261758278987, - -0.23284462507091497, - -0.11679476762823493, - -0.01210191830476981, - -0.31951713949030813, - -0.7427116127736441, - -0.35071996154453466, - -0.06462277846440778, - -0.2955683319808774, - -0.36523402275562544, - -0.733385324703893, - -0.06310247150668546, - -0.6623004160714272, - -0.1939839253158271, - -0.028844364080795604, - -0.13654579718631066, - -0.35877482231772134, - -0.5626299015888594, - -0.08541630481228202, - -0.17881778727763797, - -0.015351181521610857, - -0.2010133316677445, - -0.1069770101891716, - -0.3726844039212457, - -0.4049397081170551, - -0.7417485823134328, - -0.6802794650798121, - -0.02130852272063022, - -0.6400836989009979, - -0.3678876623947573, - -0.7610433491098076, - -0.0694886312211308, - -0.252982224111188, - -0.2825075679647888, - -0.7927326588947858, - -0.26352733599070677, - -0.24422570823760736, - -0.32304360819023226, - -0.3390189540645605, - -0.32399021557821556, - -0.14469914673706485, - -0.2817646070207982, - -0.5103712701967662, - -0.4285893730046574, - -0.401203350166824, - -0.6771111804185244, - -0.7104216740149053, - -0.3192284316874434, - 0.017786541757378926, - -0.03201783529176372, - -0.2826019319558072, - -0.7764561334259938, - -0.7833816275309494, - -0.15264816282142157, - -0.6499788975909858, - -0.188629997834727, - -0.5433002672934204, - -0.03008504505782139, - -0.568786381614895, - -0.2440275158012516, - -0.009473770859637853, - -0.46947217102460737, - -0.24019826502769526, - -0.6372902904471724, - -0.5218485919158382, - -0.6842749684192738, - -0.2935006487647196, - -0.37483948961838537, - -0.38770625831187566, - -0.08768741132242885, - -0.3486766344442988, - -0.37456364415500965, - -0.2042292917660612, - -0.21920718851305454, - -0.057898135215270985, - -0.4380378113327816, - -0.26066875024215697, - -0.7473097849691618, - -0.5475786233099075, - -0.1574278769931493, - -0.6108684237310923, - -0.4349474357542298, - -0.5606028801472006, - -0.4964135483072312, - -0.43336374662003935, - -0.5652635542386734, - -0.3636620699801873, - -0.21871063766098764, - -0.020631759257782267, - -0.7160331741984897, - -0.031558931746257235, - -0.20614928192312865, - -0.1737798038093039, - -0.08751380883167503, - -0.3083121351305639, - -0.3877389966231362, - -0.5115295705663062, - -0.5827043388296944, - -0.7090319178181832, - -0.26073502478377586, - -0.5739663376550358, - -0.39496315886852373, - -0.6575210688138703, - -0.2692209183342398, - -0.664616955155737, - -0.6794305728761255, - -0.7137792938848052, - -0.22301432647531072, - -0.2567319358771605, - -0.26548471304625454, - -0.7246339843782515, - -0.4033902132682898, - -0.27656735708417135, - -0.6392732101891146, - -0.4954179835736905, - 0.002975274858330601, - 0.014477149180258109, - -0.6646730750130856, - -0.24591246816394197, - -0.6868564597886957, - -0.04334715687516977, - 0.020431097420084865, - -0.5374419578935599, - -0.07017306341050689, - -0.3139960152481467, - -0.3769172691233961, - -0.08247553124809515, - -0.4445322149533635, - -0.7497248661059652, - -0.29528361013229565, - -0.3587957494920995, - -0.552912238526478, - -0.09453094549574192, - -0.7661358241452023, - 0.014503487658766856, - -0.6485973623072108, - -0.4032302098645176, - -0.12891785646368026, - -0.35196480654687107, - -0.7386233981317014, - -0.2056061223731268, - -0.7368199169420901, - -0.4533385497429416, - -0.35466743904685366, - -0.6714945670218072, - -0.6687201938265028, - -0.5915987370350417, - -0.31273541856994325, - -0.5201962848083782, - -0.4994916047453349, - -0.7542317400100009, - 0.012349411146361011, - -0.7486225593437275, - -0.36950863795194155, - -0.5925850040948341, - -0.2792402504767182, - -0.6408625805503269, - -0.09388905995983732, - -0.6543473676900937, - -0.14477367930955898, - -0.5251651090526217, - -0.5466530391133149, - -0.15812657478318348, - -0.6161614455440395, - -0.4963654079458288, - -0.21033425101648384, - -0.05425923114475917, - -0.5657110359117172, - -0.5164183520541652, - -0.7733228926445131, - -0.7438621299718542, - -0.6725311075242977, - -0.7124447317689679, - -0.05544480394914453, - -0.6059856142726605, - -0.2396824048017303, - -0.40947247031252865, - 8.28653487226827E-4, - -0.09015678248253256, - -0.6121167451063412, - -0.31169492162324597, - -0.19521252303029002, - -0.11056480029494387, - -0.6727445013217316, - -0.23316131213334645, - -0.17022966947591, - -0.12757895818566622, - 0.022671854384848644, - -0.2694250592182065, - -0.7598085900285642, - -0.6454473747564246, - -0.02683876023419951, - -0.3439670622131043, - -0.47069235525497055, - -0.5819910368011265, - -0.23133573798427043, - 0.011458731832515001, - -0.57118784757535, - -0.0018145853919742105, - -0.35652211245349097, - -0.5530380729712387, - -0.6193999580966358, - -0.1893079786395705, - 0.024957218616917687, - -0.2173836769080001, - -0.17066547252886133, - -0.05060238982586773, - -0.7867706646779886, - -0.10168554721500855, - 0.0011147825232927788, - -0.19017701361940564, - -0.7181685143572314, - -0.1129451938753614, - -0.7146387669912889, - -0.0784207089556147, - -0.45591076452989, - -0.4172748427428094, - -0.6039295766652144, - -0.03185438324595691, - -0.17980909909657272, - -0.36944864614072875, - -0.38416933307491336, - -0.7706989493506609, - -0.0658501479802216, - -0.5764435940838147, - -0.14189907312740868, - -0.013422462719137385, - -0.6222453065970618, - -0.5259733607281458, - -0.2310878328693836, - -0.40291401742280114, - -0.07106973779853265, - -0.47043175124731434, - -0.7273444314211993, - -0.08087869990696672, - -0.3204767136982867, - -0.2585946646721726, - -0.6057498828989125, - -0.5905434508301268, - -0.7928344995379331, - -0.7248512606136377, - -0.34250218135957566, - -0.010363589996780553, - -0.27416628514225216, - -0.7651383433710999, - -0.6298385586469244, - -0.13582485423970347, - -0.18288015968938032, - -0.1732340130327007, - -0.2656632648902896, - -0.7697560015861669, - -0.7223572497125923, - -0.5822413284805388, - -0.22021654979663208, - -0.4730215008907269, - -0.2631864639552025, - -0.14052292274361888, - -0.563243279324239, - -0.47252000708722186, - -0.27982176036006123, - -0.25941358184032426, - -0.5029363225967856, - -0.4288107677190784, - -0.7835735943611504, - -0.4089508126522304, - -0.42676754675753203, - -0.46108953156007204, - -0.4248841356215185, - -0.11288109473906172, - -0.2211061003484276, - -0.4150572663536512, - 0.030656896715989812, - 0.009133695764402816, - -0.667006805809373, - -0.7557082419596406, - -0.3291178758199489, - -0.17805700026721483, - -0.0871829094003469, - -0.711765326594408, - -0.27685834607945614, - -0.18110053812623084, - -0.4690174878926864, - -0.45003982694885347, - -0.6113757205779646, - -0.26071468186049607, - -0.23438814623526794, - -0.4978693341836642, - -0.14653549139058653, - -0.4982195755520266, - -0.025575660730456473, - -0.454448022289329, - -0.12622311508218176, - -0.748848055905728, - -0.7476313187018037, - 0.0018038960917283742, - -0.7415838329702403, - -0.5677466171217503, - -0.25663908048026374, - -0.6800504639381837, - -0.47671137891350923, - -0.5610727418111003, - -0.7723747973828496, - -0.2537128833719168, - -0.7847893087788816, - -0.12957214951440366, - -0.10489070439695891, - -0.16113521780433837, - -0.30372131005173375, - -0.2384752396954145, - -0.4181247289117847, - 0.009703748589484973, - -0.022895333117143313, - -0.6128646059555032, - -0.14465444499403624, - -0.6853462301712031, - -0.0078026569664998435, - -0.10536741440162134, - -0.059307699191376906, - -0.17953429858312764, - -0.26786236900891824, - -0.4535908401193144, - -0.2538687709834475, - -0.7125516562196998, - -0.36660982163193545, - -0.2454898166514844, - -0.12254012214796639, - -0.7517480399835548, - -0.7295155466411832, - -0.05978689878887722, - -0.23097878529678972, - -0.6342399832496994, - 0.03217876691197008, - -0.5139233967284, - -0.3701739407086189, - -0.6674158735079075, - -0.7917770787569359, - -0.40161129732928263, - -0.6970068511778603, - -0.5050140308570752, - -0.7246925860571658, - -0.7200235268262727, - -0.07124378601780434, - -0.5494437995093958, - -0.20904149138621575, - -0.45452387220910323, - -0.6132484370059039, - -0.45724382078310144, - -0.5333297419443971, - -0.6491166444197426, - -0.1344794885671422, - 0.024308734580423597, - -0.51809124702873, - -0.6822588833174883, - -0.590516185062501, - -0.6868662610651999, - -0.5943128580154429, - -0.4767653875726424, - -0.22600813491235427, - -0.16472684741535004, - -0.17292294186209511, - -0.321454692424985, - -0.588731742014493, - -0.1066485381364537, - -0.5714593833056831, - -0.6653087025106876, - -0.3049450553218727, - -0.14503695017078788, - -0.11620517402539599, - -0.022408716013234464, - -0.5701076444217026, - -0.6112383983482428, - -0.4863692937265071, - -0.4502291455469535, - -0.19764294369954793, - -0.4299971124701484, - -0.1675036256007001, - -0.3488828793152377, - -0.1090276424175034, - -0.6846792195180742, - -0.12686881623383373, - -0.19724460530558052, - -0.4513643184078011, - -0.007808535971994046, - 0.03191818547447789, - -0.09563028865079037, - -0.7016096095466148, - 0.022473777632734615, - -0.462346845773728, - -0.30328995926547536, - -0.26007309937241285, - -0.09196557162667507, - -0.32802133947452966, - -0.7925413107287014, - -0.5008871340753411, - -0.008416861998349012, - 0.02606685745844728, - -0.054987839142220274, - -0.49588503022438785, - -0.03308022536048305, - -0.702756442516447, - -0.47107916583746207, - -0.6830205495795528, - -0.11328308749724636, - -0.3008272996219197, - -0.7503706656593389, - -0.7370198647241777, - -0.4069329281707632, - -0.3125007266682357, - -0.43570015190262434, - -0.11732726371044455, - -0.4339642046773194, - -0.5164417438608457, - -0.24467923591843044, - -0.11871571642590495, - -0.7080734369008009, - -0.13296392770583743, - -0.4292120905627611, - -0.5432359464556052, - -0.6423766534311552, - -0.036189056981117074, - -0.5157453051622938, - -0.5060239160700146, - -0.6362832052848465, - -0.715573937698591, - -0.04143410846770745, - -0.24322895835935443, - -0.6392634252532154, - -0.10894386845758308, - -0.16488187359178585, - -0.28943631390143854, - -0.2764858716395975, - -0.059676145046893, - -0.07378463732049878, - -0.1729525334272789, - -0.7858504776949403, - -0.6406401734105314, - -0.6515775422144823, - -0.6375900463451535, - 0.02511702588218323, - -0.653392679049351, - -0.3185126800958841, - -0.7584164385118924, - -0.518492079517992, - -0.1482650911624781, - -0.29991022887974683, - -0.6559018260653308, - -0.6870272550867548, - -0.43629500357611695, - -0.3765365936885969, - -0.5653873937152796, - -0.168956300130365, - -0.7336499008805688, - -0.12861170943410993, - -0.135730724080094, - -0.37187220714752695, - -0.38779318208542873, - -0.629635315763273, - 0.009704494820207743, - -0.23669629738712328, - -0.326227595971116, - -0.5031554893072568, - -0.2661685424917246, - -0.045897324659389005, - -0.6115561678510802, - -0.3419880151973794, - -0.44294460913539774, - -0.06863517244242356, - -0.4994614951158129, - -0.1477894358275781, - -0.41934105691046847, - -0.2206872436428179, - -0.03320131217989131, - -0.5723403986441075, - -0.027445480842139824, - -0.6418786473313005, - -0.476083376392335, - -0.5018593574710868, - -0.5663171600560113, - -0.2804869080806267, - -0.42536032175022054, - -0.6941794092924961, - -0.24453573132534234, - -0.1984690762195882, - -0.5064358389889363, - -0.01738635964380575, - -0.07546576824310114, - -0.6658307514069565, - -0.5523773053452022, - -0.25454402581871094, - -0.2624578501605319, - -0.06837127835728718, - -0.28932274534507263, - 0.01327586175050599, - -0.23938050611103112, - -0.2364658768109239, - -0.5762722034209132, - -0.15248134555732895, - -0.11622941219574101, - -0.7075884420902977, - -0.18826023293349048, - 0.01019056088285808, - -0.6847940087390453, - -0.4122153944663661, - -0.6937746549153775, - -0.06418901631993368, - -0.4509793467577941, - -0.7806309842238376, - -0.6013465070207337, - -0.16055697289709037, - -0.6661737911470489, - -0.42333742278009806, - 0.006247782506570543, - -0.49986828157360613, - -0.11442943928544036, - -0.6513957624077014, - -0.1774368600260361, - -0.4234205919468303, - -0.3703282073658169, - -0.7135778141064897, - -0.7495614875577817, - -0.36819022361301457, - -0.6711765037578539, - -0.49190609559545634, - -0.4536586479998692, - -0.23251036848860596, - -0.5391828550342428, - -0.13231009069676902, - -0.35776185320336745, - -0.16928211934050896, - -0.17433533833256487, - -0.24775968631069079, - -0.2989511406850551, - -0.25384400408191754, - -0.10713974094945355, - -0.7804718436429406, - -0.5682743258981755, - -0.29373307725895204, - -0.5340469496437472, - 0.032851467201501894, - -0.6174891648347074, - -0.4050249608096046, - -0.7711156790914869, - -0.1817552760790635, - -0.07448804152441257, - -0.7599178794709691, - -0.5995717080408052, - 0.02195675914346895, - -0.6308333927585608, - -0.14428816447122972, - -0.0797344199099016, - -0.7211739510414674, - -0.3937556877016114, - -0.033824734891451436, - -0.5354470394207049, - -0.1439634913668083, - -0.5972027926764891, - -0.5332527723867185, - -0.6800020303903413, - -0.23885445921266768, - -0.07745033155248848, - 0.005083267940292235, - -0.19443702839364652, - -0.49157957970164573, - -0.3573816051268854, - -0.27941842256498217, - -0.6284994269458148, - -0.3165700761289172, - -0.19813239793806203, - -0.1118939796717231, - -0.13274027020549473, - -0.09002628499522936, - -0.6901981995331077, - -0.22365941001963563, - -0.5614782045779492, - -0.13344635650108017, - -0.756273555825669, - -0.5930927594569813, - -0.6233102522317505, - -0.5954138152055675, - -0.1668798137263593, - -0.4788009200566102, - -0.12734941605905936, - -0.31448104003597543, - -0.05738440338888284, - -0.33084068445309867, - -0.4057543607382148, - -0.34855282732203585, - -0.6403024534345169, - -0.09433315500796535, - -0.7002402844477739, - -0.5044847860214987, - -0.6727906763659818, - -0.43802560828675324, - -0.5804536746272644, - -0.7347803862073712, - -0.6049945090274944, - -0.15990698597071318, - -0.633563377673354, - -0.33281024787536256, - -0.1230356661818417, - -0.7097071743969986, - -0.2558899352240095, - -0.10530123603714425, - -0.6710831818466573, - -0.3298602963595659, - -0.615003479923401, - -0.6723535635519909, - -0.16826753287717866, - -0.16491631875031965, - -0.47404256448074783, - -0.2992547750836425, - -0.6690893687190003, - -0.7759093448001242, - -0.34508746535289075, - -0.25324874213531434, - -0.7232722216664452, - -0.3147685355483583, - -0.6599358639101516, - -0.7917420033839161, - -0.6411380096627898, - -0.14975940791938191, - -0.11845984978836721, - -0.41889814608628945, - -0.5173352439397632, - -0.29752673030804205, - -0.6935028273248652, - -0.16399473745784043, - -0.47592842536818847, - -0.34837091226119066, - -0.32406730880304563, - 0.03061157584484775, - -0.09253230475111895, - -0.26230108761483517, - -0.5686043306638882, - -0.3962422024665556, - -0.53180526461415, - 0.012531154231611774, - -0.770795590733425, - -0.7264506855848256, - -0.6567552899617026, - -0.13235223291232412, - -0.6285306033326522, - -0.7445887978070114, - -0.6319617730308145, - -0.20505357190559093, - -0.2805857707060062, - -0.22093192391569905, - -0.0372319226370349, - -0.12467507583784088, - -0.30969653086279914, - -0.13151215013283413, - -0.4168785570360154, - -0.03951862316367849, - -0.7360886380008581, - -0.7032514696725986, - -0.11969263097826777, - -0.4226259961785681, - -0.5956260619885615, - -0.6710374705794984, - -0.10299303841211771, - -0.1736606745418282, - -0.07389847186391829, - -0.1382959642822601, - -0.299231907557821, - -0.04169891320977204, - -0.1791789614101229, - -0.49584832658918027, - 0.0020492784236193495, - -0.7373071629917763, - -0.13733636291991058, - -0.7000526267989857, - -0.06013413443224358, - -0.6535704528178649, - -0.7089010572948997, - -0.19937621079787649, - -0.7553625497544202, - -0.48918682041044614, - 0.029638310973938653, - -0.16492087908058595, - -0.5566226852830378, - -0.6551575971863272, - -0.25011257245761964, - -0.5261323089719867, - -0.2892777013783566, - -0.7878240528331778, - -0.7272720291810205, - -0.5482982427003854, - -0.13222952045641312, - -0.0838503158711057, - -0.043498968284120254, - -0.1147631170783785, - -0.20526718239017006, - -0.09351482732584149, - -0.049552647058247024, - -0.1732079080468003, - -0.5160700601045064, - -0.1439395185200446, - -0.06981173516433059, - -0.1386370192586318, - -0.5717515484508299, - -0.17181420625894306, - -0.473392191624673, - -0.25357836485194163, - -0.2921541187687975, - -0.05319825148229873, - -0.6208897655211428, - -0.0450901699223345, - -0.39030154815804846, - -0.055019525797222135, - -0.4261499232737379, - -0.32934690002443523, - -0.3501454241263356, - -0.5045088018683648, - -0.2881636413500156, - -0.7692402335612436, - -0.06510713029066173, - -0.41090394175677064, - -0.5053239860024024, - -0.7762770719975131, - -0.041718341550800564, - -0.5460507297404152, - -0.2939058052478915, - -0.4320077759050138, - -0.5073052337840216, - 0.03324105828674084, - -0.4953678759980301, - -0.5857807681761021, - -0.6704001358916081, - -0.4132135492932214, - -0.45441787702966424, - -0.21044514119714353, - -0.22007829013920444, - -0.3608291017080544, - -0.18671619419080254, - -0.41709494554843285, - -0.35341058807110415, - -0.3273201853607853, - -0.6897638167010467, - -0.5384939952426475, - -0.3958607776765772, - -0.23753570080058128, - -0.769871172912403, - -0.33082468045987684, - -0.7511379555946688, - -0.6766726445632939, - -0.6541435878544906, - -0.5266526105863001, - -0.10207483570508802, - -0.05080273929851675, - -0.24394861223335418, - -0.6723590854017463, - -0.5307764828291411, - -0.6319420732729679, - -0.6022875788769844, - -0.39677247115746217, - -0.1953344678928478, - -0.534534692581148, - -0.2943917754951315, - -0.27062619167118784, - -0.20824002209824688, - -0.15133988067648485, - -0.05219304486442333, - -0.4659042504344871, - 0.020327344736411734, - -0.19447650767111158, - -0.4323948824096013, - -0.5828601629452616, - -0.18646635172105586, - -0.34280642493418034, - -0.46091062247655673, - -0.2787870942049011, - -0.4579989932638007, - -0.78824303407088, - -0.1197835322207007, - -0.4175410412863832, - 0.0012088558675816818, - -0.2731890255492838, - -0.35535525742185037, - -0.7252128134135282, - -0.11633263527683357, - -0.27866621312609086, - -0.52382599880742, - -0.33391964411623093, - -0.6479053097890342, - -0.08975268924960889, - -0.6209052190911855, - 0.023083007768978536, - -0.5557851082969456, - -0.16157604469015796, - -0.0724372490209455, - -0.0495505886133254, - -0.3878311270118106, - -0.48949318075416254, - -0.09494326557947497, - -0.23335239048031764, - -0.48228391277761096, - -0.22631866218560925, - -0.5929139920573763, - -0.3430749156218318, - -0.33892174861708213, - -0.4688443744834029, - -0.5363649064759884, - -0.3107185459234752, - 0.007708516941042132, - -0.4730589663282211, - -0.6788548247135193, - -0.6200511717657662, - -0.288722645026553, - -0.700903493361996, - -0.40082943236509844, - -0.7489412824263818, - 0.03461416170656395, - -0.29825890808179956, - -0.39864720135976456, - -0.5930256034892631, - -0.263513301083934, - -0.6324474616555595, - -0.49242672385667846, - -0.48560990486872924, - 0.02362935827714996, - -0.6298072696596222, - -0.25147374867640615, - -0.07848359554520845, - -0.24674058077408578, - -0.012263158293670307, - -0.23229672978557558, - -0.7657972098089191, - -0.7352639502799808, - -0.6775460570805267, - -0.7487240066023368, - -0.05126552568252429, - 0.032464270018653485, - 0.017851133983904477, - -0.4198503582127633, - -0.6558810261424987, - -0.5271945871856112, - -0.14895827726115185, - -0.028454114764777105, - -0.2649289282068955, - -0.20592658188438895, - -0.35763150148647826, - 0.0013282018878705282, - -0.4531603371219599, - -0.07630574606987939, - -0.724139537693219, - -0.06412121603739185, - -0.7817453448229755, - -0.4286575837165389, - -0.6408899411994583, - -0.1313461322792463, - -0.6632360495403837, - -0.6730193767246124, - -0.40864217613118614, - -0.7749333290536907, - -0.5130815871761524, - -0.6418378939535541, - -0.3708966929106333, - -0.5749134250717003, - -0.010975663664617885, - -0.5164676982916647, - -0.7370143303618245, - -0.6695795014673463, - 0.031360834456165, - -0.49959664682233684, - -0.6859985675017239, - -0.009995526768192708, - -0.13943660582285533, - -0.4885171216093596, - -0.7705775480389246, - 0.022501846499317857, - -0.5078197589119802, - -0.40211302878096195, - -0.060063783729691345, - -0.029308956698123945, - -0.37841050771067564, - -0.5456342057207966, - -0.12686628542386047, - -0.6179546906371615, - -0.6790803793026624, - -0.28253835989204856, - -0.0015717097796272839, - -0.6077186275896374, - -0.049314444294704995, - -0.7860311475543592, - -0.5325774264564678, - -0.5703936079189501, - -0.5863316499804672, - -0.6454407730197068, - -0.5900448376631369, - 0.006848844370682672, - -0.7376895301996448, - -0.7097383075263907, - -0.6835983332762877, - -0.1276412712616175, - -0.4587664759227373, - -0.4392971776287275, - -0.3328834107129518, - -0.35977579514984, - -0.27043604477845296, - -0.2519278702362727, - -0.08218311029922998, - -0.7014912198706068, - -0.23195044319469282, - -0.4958431995451776, - -0.5544965015864766, - -0.4679780035553173, - -0.5132822749924224, - -0.7641568213420822, - -0.5321976135803256, - -0.5837004359953905, - -0.4798238904195544, - -0.5674297310202601, - -0.14483959211031439, - -0.2529227414690758, - -0.3443041507888581, - -0.6006372726855345, - -0.6589135185270847, - -0.44098291835490666, - -0.6205306467857522, - -0.016870528210274127, - -0.5177143975683843, - -0.14768830873200933, - -0.1992104309359234, - -0.12424087565482633, - -0.2035508485320957, - -0.4820014822260369, - -0.27534124184567077, - -0.6800447188063323, - -0.7755147492107645, - -0.5756176180234372, - -0.24207282902907168, - -0.72040582481972, - 0.004527871391003302, - -0.3322920328093088, - -0.18100592629454815, - -0.4184191339335987, - -0.32261597778520223, - -0.3545792698062639, - -0.006672792324399435, - -0.06835047566511554, - -0.6607644001787514, - -0.4786183667118361, - -0.03513521199400116, - -0.40876297307936993, - -0.14368112964412438, - -0.46282693545017284, - -0.16930222407871076, - -0.5812293118911955, - -0.4647539395974092, - -0.21773903836985276, - -0.693862109708601, - -0.05126696029797739, - -0.6688561518758832, - -0.7451329275053756, - -0.7802456545318212, - -0.283923273352121, - -0.4899849209506357, - -0.785732019694183, - -0.3481142760079432, - -0.5713732928793567, - -0.5000767483545112, - -0.3908693462836726, - -0.022462597925433703, - -0.7334478215199934, - 0.024689967452817152, - -0.18634674853911415, - -0.665961945769949, - -0.22000840070825267, - -0.45856532488638513, - -0.29625295650180355, - -0.09730318987146991, - -0.5778402095246735, - -0.7447787435755028, - -0.49180008313911794, - -0.5977440453875981, - -0.6003133173126101, - -0.7148131162429346, - -0.7349557896843418, - -0.24159760922192186, - -0.6954401226391085, - -0.19479291921335573, - -0.7815422393258987, - -0.4043197716632178, - -0.13991067136829438, - -0.1336454293909708, - -0.6720913458368037, - -0.18271668005339825, - -0.1162631769920972, - 0.005967038037478889, - -0.04102274848402199, - -0.5671162206575208, - -0.7239103515244917, - -0.5042719144152783, - -0.6230716563181128, - -0.12777398300806964, - -0.3968498941037569, - -0.6545673458609336, - -0.650645597869091, - -0.22196353189215112, - -0.24212689855855263, - 1.047971213463672E-5, - -0.36123327420627516, - -0.39018413029942006, - -0.2710562491274652, - -0.21187451053403217, - -0.43716305358115304, - -0.16013909592837805, - -0.25455842163805453, - -0.5360524988902435, - -0.7080782298925345, - -0.5824516856801322, - -0.6736469397318823, - -0.7209300913011292, - -0.33604010902358905, - -0.5313295674132731, - -0.16815340070274465, - -0.17356661866041345, - -0.4414964768146462, - -0.054174514239599625, - 0.005887372470019803, - -0.09730178545570489, - -0.5791500200865971, - -0.22312506599622517, - -0.7009483649079742, - -0.4064721687351931, - -0.6880695490767827, - -0.4689145779368606, - -0.6696618945511532, - -0.23169366666778135, - -0.007569278381555189, - -0.39497858973412164, - -0.7608867333063412, - -0.052752787894636666, - -0.2521360157443392, - -0.7677555119277779, - -0.7088390598829266, - -0.3104160421784301, - -0.04003191133160866, - -0.12207293583229817, - -0.2557707118904188, - -0.11129149100859548, - -0.7012500169206597, - -0.6521051494587826, - -0.461597004183464, - 0.03016072677321735, - -0.44848779640440317, - -0.08969026310028372, - -0.7309717292420966, - -0.10318408582471972, - -0.5599121663892537, - -0.42452872113947565, - -0.5599015655184201, - -0.5967250017634745, - -0.3538847557062413, - -0.6696418952226448, - -0.33418490143747953, - -0.4336558567165822, - -0.04636198824000004, - -0.11271875448859103, - 0.031119921384286764, - -0.1905954551556054, - -0.1407491865850049, - -0.4556528013247818, - -0.018140271470337366, - -0.3096806076771443, - -0.41373052426358037, - -0.6925155100797322, - 0.021188309158246765, - -0.2990608598945399, - -0.48274549654961213, - 0.007472395021256295, - 0.02672062995085045, - -0.5296690942174976, - -0.3782361662259277, - -0.033104729197459104, - -0.44026049713536075, - -0.5605687583168468, - -0.19833389541875124, - -0.5199461018365696, - -0.4475843490803444, - -0.36789631548032037, - -0.6724953999051304, - -0.13831409636539038, - -0.20068323667551347, - -0.6298187180300431, - -0.690383460781715, - -0.04951074565908864, - -0.1319807016604252, - -0.3590947802350185, - -0.11066575752023822, - -0.2810377419496828, - -0.7708462941796744, - -0.20878270542354027, - -0.7330902421485962, - -0.05341173456782988, - -0.6166532213736374, - -0.25680252134693493, - -0.35700061819269513, - 0.006046714115483409, - -0.7404232325878498, - -0.3697598891270426, - -0.5880911504560362, - -0.37422118825414524, - -0.2307171433420051, - -0.2282093218281931, - -0.20942001959356293, - -0.2523110425627427, - -0.68292474144442, - -0.037361598692412734, - -0.6447522446759045, - -0.4873021852174014, - -0.43048443237865675, - -0.5396959599179465, - -0.23069634477201661, - -0.2573879403154069, - -0.36249536900036716, - -0.4510409319738745, - -0.07724294726495295, - -0.28802105189408733, - -0.6330361788810356, - -0.16714932100800728, - -0.34534339199508096, - -0.0013499281240251237, - -0.716573748920715, - 0.016688447514834892, - -0.7700374673118641, - -0.3868346841521628, - -0.7439282421239203, - -0.7225364830778199, - -0.467472891805536, - -0.661099697740121, - -0.7535168255681416, - -0.6486368055368054, - -0.2929268934035172, - -0.5697512103987582, - -0.18232113482445755, - -0.2734826768490518, - -0.05579007557276172, - -0.548795993816951, - -0.016223258465786095, - -0.02148078128924069, - -0.2595444355585401, - -0.6190249693560921, - -0.10505363176553817, - -1.5679007702606995E-4, - -0.27915350711387177, - -0.5555887329042855, - -0.6588509013016333, - -0.3953638980075538, - -0.06301188393415624, - -0.23344535246867837, - -0.028875716007441654, - -0.05827578726058291, - -0.7895483906997106, - -0.20610947865808282, - -0.18094119346623005, - -0.6598192066294442, - -0.13942236297752797, - -0.36529200263803624, - -0.009176061001677338, - -0.5634344969342666, - -0.6876672360135442, - -0.014511012382622313, - -0.4854908913869333, - -0.2048359105042502, - -0.21434581996574187, - -0.5791219920420355, - -0.6780287504941361, - -0.7038769487642423, - -0.73899573722431, - -0.23040283066415668, - -0.37467977089347526, - -0.7550496501913383, - -0.6331192054037552, - -0.49866305336643935, - -0.781201082791045, - -0.7209453392218887, - -0.20021135174949622, - -0.5770606608165492, - -0.6433394584256065, - -0.5114345149450683, - -0.5745157326607716, - -0.2638769874148519, - -0.7876743118600503, - -0.48944018963662594, - -0.09943467699290343, - -0.6114368020134766, - -0.2966629079701761, - -0.7798856465653339, - -0.7159261310284725, - -0.3543849702770864, - -0.5015310113767302, - 0.03132329542969858, - -0.07525567904077757, - 6.752111767593938E-4, - -0.03641013028761175, - -0.5038261294089754, - -0.24021404054623297, - -0.43239254517716774, - -0.4608124415524506, - -0.26046611398175556, - -0.048639345028680614, - -0.24564618247513348, - -0.6816916196710536, - -0.7693318794137107, - -0.08151907913049616, - -0.30766187548280444, - -0.5033891252453877, - -0.09461227878388889, - -0.6464693052576798, - -0.7638492088752294, - 0.004797179154370279, - -0.1833806732785429, - -0.3985593461439495, - -0.19515577506074833, - -0.46128152421686014, - -0.03212520162538979, - -0.7396630004525394, - -0.6625254633169643, - -0.538267546975146, - -0.7849396114143096, - -0.05034377884670893, - -0.09609427397546721, - -0.7108682981075108, - -0.1815516064866065, - -0.7566815185112952, - -0.671501358001361, - -0.2543991863431265, - -0.7856521835388227, - -0.39871699078002915, - -0.30812763235417656, - -0.20426302631486914, - -0.3347136447176435, - -0.3640324352178688, - -0.2982642602804499, - -0.6154933626910952, - -0.711808140977203, - -0.18882096228612044, - -0.6142308234925228, - -0.5367969027988494, - -0.2734885702681732, - -0.2590439470836743, - -0.10631094467224023, - -0.015299417838801288, - -0.7207050227437684, - -0.3325661260626656, - -0.10019405486872401, - -0.6592776451415353, - -0.34236203391008624, - -0.5351430243213142, - -0.2849028388075697, - -0.4018786440437122, - -0.5749030156608457, - -0.7377769467045292, - -0.2697745523712054, - -0.6160189815672794, - -0.1787188194328564, - -0.024342677011031655, - -0.23853037315239112, - -0.30155936384684456, - -0.6331446449786193, - -0.4706423478051226, - -0.22528415025078985, - -0.2775397185523719, - -0.09041439029104648, - -0.6277903403193613, - -0.46997569028928715, - -0.7849048234629199, - -0.5863555670105787, - -0.10774981390483185, - -0.32983029743287473, - 0.018379660398119113, - -0.7338696537858592, - -7.59824959258526E-4, - -0.33879339106152395, - -0.10464274984744393, - -0.6164338152110451, - -0.7735187177726851, - -0.6541638793315199, - -0.3273368457443866, - -0.44407260906349405, - -0.15658370631532315, - -0.6613276094415184, - -0.1438837402515587, - -0.5576813839426419, - -0.7668589163395308, - -0.29763315370014914, - -0.28573154080607166, - -0.6037151274025617, - -0.1264286945964943, - -0.29818139376591785, - -0.7188429079178189, - -0.3884527169211098, - -0.4985607378012302, - -0.7044699501754836, - -0.30049996520450184, - -0.23542270680337474, - -0.6420296435093625, - -0.2957263382527379, - -0.1498276669936609, - -0.35308472102954774, - -0.15162553436103787, - -0.3750250300503019, - -0.2264994589135072, - -0.6205060859947452, - -0.1119505963354126, - -0.04102762787081149, - -0.02469382563772482, - -0.15529859590199657, - -0.6238214928874387, - -0.43508762229231207, - -0.5670375026769051, - -0.41499885698269673, - -0.36777294757537554, - -0.12604268563956456, - -0.6151136211449588, - -0.4839522439615772, - -0.26743837622242506, - -0.5698486678417666, - -0.16374665356839357, - -0.4070596964865238, - -0.15852580911630032, - -0.5223769480201474, - -0.5466021850575631, - -0.592795935563423, - -0.19210856882377958, - -0.6210764473413306, - -0.6410143314420444, - -0.43703018984818437, - -0.4709393579483418, - -0.12781031745495186, - -0.3223622464405789, - -0.7215272966143049, - -0.2042849872852024, - -0.160007557929563, - -0.03898928542451163, - -0.3266708011316816, - -0.06181466200794594, - -0.34448422726312716, - -0.6185098881365586, - -0.6922469362834338, - -0.7897487034892247, - -0.027495403778915684, - -0.08502542992558071, - -0.0174506952887874, - -0.3223909431908251, - -0.1462026421105178, - -0.6157342683771422, - -0.30601865356611635, - -0.1890958063447098, - -0.10102456695104234, - -0.6078419905411091, - -0.3486939763113935, - 0.030781007654438364, - -0.3715716671085146, - -0.4529244673698536, - -0.05850838928761504, - -0.1713692090756611, - -0.43112812287620966, - -0.2411702398741008, - -0.015752681838542837, - -0.07401715419280464, - -0.15199979099954808, - -0.14244648427433082, - -0.591810506075059, - -0.3771805606979448, - -0.39498540628369266, - -0.24248417762100072, - -0.2292126751750162, - -0.5962490218843289, - -0.6199007361181618, - -0.18180986268357602, - -0.1284741523517925, - -0.2558673772604999, - -0.5010815082085773, - -0.6628070902129439, - -0.05094706726682241, - -0.3383828515482358, - -0.2839747183029544, - -0.19588620497203046, - -0.21478544858648985, - -0.053773279241218996, - -0.3018992884717704, - -0.15726887295152858, - -0.036851232024717184, - -0.39922687518081135, - -0.7088015525076107, - -0.16854188888293242, - -0.6003053891148977, - -0.5278105662661734, - -0.03687426869393595, - -0.27627083380855355, - -0.2923950263581463, - -0.2820966545416772, - -0.5057872264477339, - -0.38572891651245705, - -0.48637743095270203, - -0.3087564579016277, - -0.04323214459695057, - -0.23566975151400604, - -0.24312415372667384, - -0.351974495920043, - -0.29004960941275937, - -0.44333470349889015, - -0.6240821236965928, - -0.31148642460932024, - -0.14872640805071546 + 0.4454473561983937, + -0.11089104000282013, + 0.5710393656759419, + -0.14941327254291925, + -0.2343010285350915, + -0.7064425950849652, + -0.4160717850731219, + -0.18899651957578145, + -0.24596804097165492, + 0.18196996886087424, + -0.21480242251832027, + -0.1531833304888266, + -0.037910297560927564, + -0.3613340342820306, + 0.2052353637234855, + -0.3328546807527252, + -0.19687224885880483, + -0.36197566515233925, + 0.5878302280032505, + -0.5369143872020734, + 0.2939919892381174, + -0.34051140638968386, + 0.3360232898700187, + -0.0514376397574795, + -0.25518848291088725, + -0.5016364980833922, + 0.0926896529838881, + -0.3917062214162105, + -0.5452430449116754, + -0.15342472035295984, + 0.022307171465376863, + 0.3727631759585074, + -0.6038972220319024, + -0.4125467312085292, + -0.4792189492273889, + -0.057668958594455755, + 0.19795037334856347, + -0.6119788879657624, + 0.39645623244559125, + 0.09077338834370385, + 0.19031569338785714, + -0.09286913770279304, + 0.2920901260889549, + 0.2544883545811677, + 0.1755033886815417, + 0.254342881598585, + 0.260064186859709, + -0.31946837557973273, + -0.4242086071497505, + -0.6083466187073574, + -0.44053732916181915, + -0.29918588039491434, + -0.4530847742256059, + 0.2712215520216418, + 0.44062569886432323, + -0.6762141742147593, + -0.09050006370943464, + 0.2746959833286259, + -0.5014160631466476, + 0.40196266798407565, + -0.6761542958848055, + 0.4209920678986031, + -0.7310488554882372, + 0.018931774908213517, + 0.6586608923032021, + -0.5778200340152329, + 0.1419540669601156, + -0.4796335851482425, + -0.3491291964353084, + -0.15971562688358232, + 0.47726886709147387, + 0.026747279552132297, + -0.39042250420619257, + 0.6353631054037182, + 0.34396651208376416, + -0.5457213960065672, + -0.18350937613701634, + 0.4145631392183281, + 0.08447456410897558, + 0.37718689042050435, + 0.4916723362526768, + -0.49287876454944884, + -0.4056174788424846, + -0.7078208781012341, + 0.5202264066337418, + 0.3199281650627229, + -0.2463919001552719, + 0.6056244705125414, + -0.27311203654258753, + -0.5033378923790488, + 0.49528165368911437, + -0.16585222832314472, + -0.6340662761126755, + -0.11434479827354549, + 0.5770408512693802, + -0.7251095320455188, + -0.10342784749299783, + -0.3101571093425869, + 0.5885193413577393, + -0.6457164555129192, + -0.7163295890084154, + 0.5327871833143311, + -0.6736464430689871, + 0.12019680121471743, + 0.2161231785343598, + 0.5365266425018008, + 0.25511315704874915, + 0.2980016937243134, + 0.10382408341614591, + 0.40130274440103986, + -0.5073820996034815, + 0.24962273439069282, + 0.27917529109147876, + 0.4438146926878145, + 0.06485110618531653, + -0.13705044744440043, + 0.14491586031211745, + -0.24043279144210505, + 0.11801545473424979, + 0.6052405723611004, + 0.23980591595745848, + 0.15206745288828438, + -0.6396294043009085, + 0.4329059418361224, + -0.02577503338713394, + -0.634843448088235, + -0.16755406067282996, + 0.1933862507825146, + -0.45282498370350455, + -0.4790792057209454, + -0.19806287448234716, + -0.5286828954058319, + 0.13922384348464079, + 0.0038429164225874946, + -0.6261502673990162, + 0.2700742964187667, + 0.36499176228053487, + 0.5618008462948151, + 0.5111525241773826, + 0.04113869506300183, + 0.13586592846289947, + 0.12478823553902596, + 0.20114095463350345, + -0.26945451278215127, + -0.13529106075861863, + -0.06243906067320293, + 0.15205570197985618, + 0.1795577892646375, + 0.06121462123879562, + 0.08057325412355443, + 0.07251019459850838, + 0.08941433477860516, + 0.5718029020486283, + -0.5141395438875778, + -0.38703237610081104, + -0.367497801569079, + -0.2992123215235272, + 0.06434460673374753, + -0.6392979685480753, + 0.2497979183947806, + 0.5208411618552454, + -0.24722311460322677, + -0.21771361560124258, + -0.619369201577475, + -0.5634006676828716, + -0.6136543848114238, + -0.27594865208188907, + -0.5357492000780432, + -0.488203400757565, + -0.3386784372126736, + 0.6100685999306946, + 0.6113964164570117, + 0.029999335047808606, + 0.3523266288981487, + 0.3089307094334036, + 0.5919613466883388, + -0.6385544979206305, + 0.23443226577135723, + -0.4094202986794217, + 0.4698963656276499, + 0.0026904757563149806, + 0.23499803871256086, + -0.5624944032182047, + -0.011093422485949134, + 0.3871925936976316, + 0.5241319636548026, + 0.034103050277218716, + 0.44382959317230386, + 0.5677019769564974, + -0.5058378296806741, + 0.02245062963453015, + 0.3812929480342552, + -0.19574067498531966, + 0.01629567545638122, + -0.07912271969116069, + -0.03425684556446307, + -0.2219077079913223, + 0.4940946790988169, + -0.7637178368160429, + 0.104909697543912, + -0.6874922707615666, + 0.04226433607847213, + 0.13095618794841812, + 0.44112843275643543, + -0.47714058249628677, + 0.45795306090913324, + -0.5027491995418384, + -0.2397162254251486, + -0.3189337392426345, + -0.2517467537850969, + 0.16122426536539913, + 0.412898953178677, + -0.14219088129616975, + -0.6684198730891455, + 0.13799144913620187, + 0.1967816040235213, + 0.5087855559844631, + -0.02780088259620439, + 0.3536029904545913, + 0.03937070277148225, + 0.593282925379199, + -0.05845702019210253, + -0.7608676820604792, + -0.1470772359020115, + -0.18311203447066493, + 0.396125534090089, + -0.3030989152827623, + -0.02906968731474402, + -0.11157891531967601, + -0.6653668697796462, + 0.646071074786735, + -0.7379637073476591, + 0.11078061158213992, + -0.4089957356936407, + -0.23680304101850058, + -0.7632491255517249, + 0.07173636066607891, + -0.4853024994660538, + 0.31775194308858234, + 0.47883272687866996, + -0.3619938171960608, + -0.5561588230998792, + -0.27504126091445974, + -0.5913563257180976, + 0.4619484789467808, + -0.4119386865876118, + -0.3176786617054978, + -0.1950615374141328, + 0.4751653297694053, + -0.6921517778243618, + 0.5301408835033486, + -0.0712180081562136, + -0.7450987127906832, + 0.0739454070547142, + 0.6043413456552228, + 0.18367023297933116, + 0.24267166191307454, + -0.38221791213921896, + -0.16014788203907337, + 0.21206927088093763, + 0.0940033745998119, + 0.23441359947803597, + 0.43136566388279174, + -0.740585551229173, + 0.6495145526600815, + -0.28617025762275033, + -0.47496829613500813, + -0.667009087379127, + -0.6642066603207792, + -0.512797083938951, + -0.39695089493176405, + -0.5965904458097978, + -0.43427492194153877, + -0.17120614531406952, + -0.22084142536748985, + -0.5196186074555198, + -0.35045541102004396, + 0.08806876335433245, + -0.3169996793997466, + -0.5400173170896891, + -0.7467051027910236, + -0.035279233856880476, + 0.5902214108846479, + 0.41010542964489505, + -0.22295481801700867, + -0.07610912771727718, + 0.4775996907726042, + 0.38173979032697736, + 0.5752087888290028, + -0.25185706678523934, + -0.20964873301744935, + 0.22323511202445767, + 0.21387250692121995, + 0.5035292880769077, + 0.28284832540660865, + -0.5384342673749117, + 0.09291721525068042, + 0.043840509213700085, + 0.5002092829661112, + -0.6508800611475185, + -0.08970985322255376, + 0.4670688743282684, + 0.1462599962618253, + 0.5879358115262902, + -0.049208816557356316, + -0.05714529006423752, + -0.6339161179657641, + -0.6630736868097262, + -0.6236633750572222, + 0.0622556676365984, + -0.23251952391653763, + -0.4271831850989639, + -0.29488763562405107, + 0.12636302661318488, + 0.08035345291713825, + -0.509263236072613, + 0.6131732277722931, + -0.023284234205435017, + -0.28342510325707343, + 0.4459998380090652, + -0.5155213036642088, + 0.1716912352870521, + 0.0975835432896589, + 0.1494410395441661, + -0.467053039443657, + -0.21196315849859126, + -0.6511785018685088, + 0.44925291945540213, + 0.34858085064833155, + -0.18873863106499877, + -0.6215564015476869, + 0.0375708297657964, + 0.585457305232855, + 0.04382419662490278, + 0.3354127405423021, + -0.435170121501985, + 0.5166266981899604, + -0.49089765148857006, + -0.2661189209654916, + 0.17312562466800963, + -0.6333366980503783, + -0.16861723200694934, + -0.07992530286640331, + 0.17091145296780663, + 0.5421165344069155, + -0.46852745746794483, + 0.18847954971923764, + -0.5461082018986758, + 0.02329059738810768, + -0.2321561655274743, + -0.4358176069167477, + 0.3313102982998889, + 0.03829364240359001, + -0.006706330774077673, + -0.7586669958016808, + -0.15712552828550896, + -0.692188506707252, + -0.6104156091526033, + -0.33167091735879484, + -0.25582187493649844, + 0.016789983508893713, + 0.5989359487354332, + -0.670628275408617, + -0.05835361096985536, + -0.5238973575318513, + -0.5881507271089405, + 0.3530955766140439, + 0.2062236935275218, + -0.3604348039355122, + 0.6347501308019078, + -0.5366631019083749, + 0.3931919788983286, + -0.4451802200770916, + -0.30046721292730394, + -0.3919875947583116, + -0.33859109506627355, + 0.4547614709269606, + 0.4881145908642305, + -0.3534570210690383, + -0.1860699714751617, + 0.5408336321716661, + -0.0693814365803963, + 0.515080681222582, + -0.2798175715713648, + -0.09122990594535485, + 0.07634033299789289, + 0.27422580412035347, + -0.3052427541490926, + 0.5574588840156159, + -0.3703679346003914, + -0.2997844539978946, + -0.6511525380603933, + 0.39095424488965, + -0.24216284451533387, + -0.5815825625845307, + 0.19485449168291835, + -0.6862639551223708, + -0.3799121530912541, + -0.6323439189294723, + 0.2875379790547853, + -0.350366894251929, + -0.1322078948049621, + -0.5062752128595371, + 0.5254376323037123, + 0.3884202595078051, + -0.3304884330307577, + -0.6667657864712184, + 0.15316024242915272, + 0.027744060821661476, + 0.2501203304356333, + -0.4639123267938478, + -0.3904244259136192, + -0.06597562080696906, + -0.26713156616262945, + 0.0062716455520841485, + -0.1520201247229267, + 0.5178080836165736, + -0.1906109884957603, + -0.6932576285423548, + 0.028856454236943496, + 0.49262180261020816, + 0.24123266164836166, + 0.4547329365849285, + -0.13321977059659051, + 0.46281042300921305, + 0.10595641279550028, + -0.2609588971932921, + -0.7182663124838602, + 0.19718790075320347, + 0.0010658669747334315, + -0.07131034610165266, + -0.21284208446774766, + -0.6913279096649312, + -0.15779075294318234, + -0.7638537467182946, + -0.618504671119156, + 0.5183725000298197, + 0.11495014200161535, + 0.5816704327262628, + -0.5977191211404708, + 0.30503296521116974, + 0.05360302602485345, + 0.08035245632534949, + -0.37272186399807894, + 0.07576571022307232, + -0.31998854618406913, + 0.5126926876653469, + 0.173992662133163, + -0.3442985417998398, + 0.2648927562666278, + 0.15296343765733555, + -0.6996653795055099, + 0.638044459580959, + 0.5355685261523561, + 0.1277276025658296, + 0.17664556065213455, + 0.006471631068764139, + -0.02130004581481637, + -0.46327785324886656, + 0.1907251219784427, + -0.15139081261131482, + -0.42209810635930695, + 0.28377765667615484, + -0.1269234652177479, + 0.46262505860245395, + -0.5666974434649671, + 0.6074308252740873, + 0.21021234909626174, + -0.6720909139642199, + -0.3539325376688002, + 0.5852422813550989, + -0.6720592245249544, + 0.021712705485522954, + 0.6038798819959942, + -0.4925080406239542, + -0.6623576349821093, + -0.2284514233705448, + -0.7390400391873496, + 0.6521284577670151, + 0.12444373266282582, + -0.04492727941953811, + 0.5491418282548167, + 0.5607219959558, + -0.7407689607533896, + -0.4143625297552815, + -0.7268494932628078, + 0.632518084641133, + -0.09078246197503348, + -0.28990377496786746, + -0.275949732726062, + 0.44631757341676426, + -0.027081649349994907, + -0.7450529791684767, + -0.7396780962079007, + -0.5423999933318188, + -0.08973838583615568, + -0.19824649680546857, + -0.6574091224605235, + 0.3637273111269378, + -0.49446698989081106, + 0.4708963546587145, + 0.2952170656286289, + 0.1187733780813085, + -0.3726546410291769, + 0.3878409953876135, + -0.5276457237342735, + 0.655436310592275, + 0.49631414893407866, + -0.7237397523633081, + -0.3327356771386858, + -0.2966723271323164, + 0.5610227932439006, + -0.3303973272360154, + 0.09539393697049126, + 0.26268163523968735, + 0.3995537749902177, + -0.49634084819803115, + 0.4869024334024138, + 0.25198167668147453, + -0.6418655159722053, + -0.05859807260904759, + 0.19034352974914992, + -0.028418279884116382, + -0.3197631856197805, + 0.41272534610492906, + -0.2539973332916965, + -0.08855529440328724, + -0.47122421117634317, + -0.37317323408430175, + -0.06236681970689417, + -0.6799379146557003, + 0.4561177766737602, + 0.234167316562213, + -0.5325268921929643, + 0.10910042387965424, + 0.32712526810059284, + 0.40069271560806763, + 0.42017793387510494, + 0.47779751195049125, + -0.7400423425623481, + 0.16764078237729862, + 0.207528846092498, + -0.37548467635139804, + -0.6612539485966953, + 0.5974618488759452, + 0.35348041606966796, + -0.12962942320605042, + -0.6139077053476943, + -0.13973605823265933, + 0.2058272029962941, + -0.2685567856973311, + -0.6861960801848073, + 0.33485058534877254, + 0.012302191940470886, + -0.464429676628864, + -0.6492438263057351, + -0.0186483312899266, + -0.3034344109110076, + -0.5753403737020971, + 0.3003606640987554, + 0.3738842535932009, + 0.3317222475015743, + 0.44077683159658665, + 0.42413783605579203, + -0.6799459394268741, + -0.2219445495837109, + 0.06572273452160615, + 0.323626056102151, + 0.10267389282155759, + -0.4821655135606116, + -0.3914517175969564, + -0.3637173277634637, + 0.6458602961337548, + -0.7299382027233633, + 0.5217938818268343, + 0.5751188644637223, + 0.47558825118566805, + -0.07104619594219086, + 0.5453804600973761, + 0.4520430083064383, + -0.6928781421017636, + -0.578549875339917, + -0.12918653367064492, + 0.6599652547352374, + 0.14127566386149726, + -0.29777245482695874, + -0.014450132344048128, + -0.3986156390495676, + -0.4935599717690233, + -0.1713895736367117, + -0.5440025780084298, + -0.660931180526871, + -0.5755296432620881, + -0.12006310476740045, + -0.4035378669957121, + -0.7282914742201707, + -0.11484126668617745, + 0.2233905148630454, + 0.009778565125774796, + -0.04322408804548927, + -0.2371440334263658, + -0.08460330279343697, + -0.518574054386634, + -0.5439202143814637, + -0.7266271084217321, + -0.5407201773557909, + 0.0568236414313773, + -0.5075969396304099, + -0.08597234963689104, + 0.13595270527235448, + 0.6507991187027932, + -0.41707429803211715, + -0.23265742324287053, + 0.2979060808711512, + -0.5725908930351131, + -0.12499795449448736, + 0.04879030177963861, + 0.2566040301414688, + -0.16360511469847783, + -0.10560251040753599, + 0.5460976364373579, + -0.3509915573845642, + -0.3315045548765893, + 0.1507572059984129, + 0.03190857722362361, + 0.46071345086087045, + 0.5051607796222896, + 0.5398185493527571, + 0.23780616594375437, + -0.615758263991746, + 0.31426244514781854, + -0.6723791868089266, + -0.24911796072647907, + -0.6649957224105575, + 0.5191901898549162, + -0.4428763638080709, + 0.30430986713474606, + -0.5958926684654666, + -0.2666460320944308, + -0.1220343900217945, + -0.23928373593625252, + 0.5550839666511328, + 0.646215361075316, + -0.21608378445286258, + -0.6642591472450751, + 0.5882991865117982, + -0.5546529522988672, + 0.25686514904074154, + -0.25169467778841415, + -0.6960175915026101, + 0.5408680960411237, + -0.03637887690681063, + 0.24827869445046502, + 0.48068841844208066, + -0.26861123913672647, + -0.35459059089325107, + -0.5824177589508487, + -0.38756478906344327, + -0.726212399410795, + 0.09730739037058955, + 0.5272987474151604, + -0.13009095506662016, + -0.31651358459512957, + 0.1444534162099187, + -0.6536066188314298, + 0.6196452890624212, + 0.14167467658799937, + -0.4065028888815495, + -0.1373783537470744, + -0.16455856693389903, + -0.7533191156474927, + -0.27525900938890613, + 0.2417824065530022, + -0.5482263597408826, + -0.09858566599689833, + -0.21228250720116104, + -0.18170899043537247, + -0.5667835579865961, + -0.48772774768923904, + 0.3181063866208472, + -0.6644781580050712, + -0.39495671173529734, + -0.5464351296259431, + 0.18166294050964904, + 0.015334581652788337, + -0.6331457497589267, + -0.20054735322816775, + -0.0656922960785149, + -0.1274671098553115, + -0.08247269815229252, + 0.31600827485772764, + -0.17872954074202785, + 0.10692108883807017, + -0.20112397026657258, + -0.7027652846057418, + -0.18849680150127768, + -0.3767936412144454, + -0.7117901339326531, + 0.6183102342042873, + 0.6153265660462529, + 0.5248112681878664, + 0.5679261790421025, + -0.5105721902201814, + -0.7259571130058946, + 0.47640907218925543, + -0.1432947759181078, + -0.24223385804294006, + 0.3630502073428986, + 0.21891573186827007, + 0.07578612403593965, + 0.5467677614750187, + -0.5623975078156378, + -0.018070012085878995, + -0.08860814382975879, + -0.13271457992111024, + 0.35262083308143766, + -0.5337631816531428, + -0.25236514367006535, + -0.018784804672243416, + -0.035294995785998706, + -0.23236229429039057, + 0.650399746411931, + -0.17800977781299954, + -0.719266033779226, + -0.09481671757913246, + 0.381615585099942, + -0.465857561420301, + -0.018604257957573478, + -0.6987903116773482, + 0.49046854109526594, + 0.6496744479740552, + -0.25177658206196407, + 0.24971840204541118, + 0.4476883892551017, + 0.1953134824390711, + 0.4840410826958418, + -0.13784493525811725, + -0.1373050037025637, + 0.1914783004912407, + -0.25877123196272933, + -0.2847999813229375, + -0.4618210854443179, + -0.5846882435138421, + -0.6480948143622676, + 0.35413951334678806, + -0.46533804105819493, + 0.07185115379740237, + -0.06897396982735271, + -0.16845402084397376, + -0.21796573216998627, + 0.3154797277461626, + 0.27541106748997246, + 0.5577951137842837, + -0.23971965553027352, + -0.484117093499168, + -0.5457885297271188, + -0.4183443961594414, + 0.5757166787127813, + -0.41079083279683226, + -0.3346332286545001, + -0.14243589548227664, + 0.39680647972323635, + 0.4391351554255295, + -0.5379486044438373, + 0.2907897525727988, + 0.043403324540364996, + 0.18152726668713737, + -0.27999270874055976, + -0.5900733419366777, + 0.12452162186914562, + 0.12999720548476212, + -0.20203897764848722, + 0.13375850222082641, + -0.5265971883880036, + 0.23343084490322863, + -0.20871759709971605, + 0.09862606866286416, + 0.17670901598085886, + 0.3069259983823184, + 0.39636890136521397, + 0.06006022140240286, + 0.07818468764010233, + 0.2559376260322884, + -0.44747442705888574, + 0.15727463150230503, + 0.3961277463651781, + -0.2518820151609825, + -0.1738453982828655, + 0.4245647766050963, + 0.5158322980546229, + -0.7319016760051386, + -0.052645090465298416, + 0.1382767032115364, + -0.1935751953409266, + -0.21867055004005687, + -0.12179021704730109, + -0.30702801335588353, + -0.532946579172977, + 0.3967257740808715, + 0.6619354085807173, + 0.4647882015839456, + 0.6308118110693396, + 0.22889346893265772, + 0.5019203694542579, + 0.0020636231182711295, + 0.17711252914996778, + -0.6253756150040396, + 0.21931753337675575, + 0.508025617543652, + 0.6170349439200241, + -0.5387170005830038, + 0.4948599227784459, + 0.018213150465743455, + 0.6165755876016944, + 0.30882618317028177, + -0.6557577325025716, + -0.5427022346805149, + -0.0756643420028068, + 0.08369855677171845, + -0.13167490274449334, + -0.544110732704644, + -0.2674397611365089, + -0.046825315658290734, + -0.7255157814166103, + 0.10918735830399184, + 0.07242167537168342, + -0.3015176205448372, + -0.1967621300258392, + -0.7201352121332484, + -0.41849225252372624, + -0.4146241568443396, + 0.11291303436102595, + 0.060385535656026335, + 0.1319417380867116, + 0.3191757536745842, + 0.06424574520681225, + -0.4306635644497059, + 0.5097487570126379, + -0.3557763992137541, + 0.5871641186898092, + -0.26477478113319175, + 0.5145137416832487, + -0.39198061071862617, + 0.010148426324029569, + -0.3477086924580039, + 0.34724681373163657, + 0.08307740690794707, + 0.26363352775588467, + 0.1644386396200651, + 0.36680632113026757, + -0.38401326132903496, + -0.3857137573627872, + -0.5279846937813912, + -0.5764858615286849, + 0.41999996119928495, + -0.49232605420471026, + 0.6086723462992875, + -0.20728926293212047, + 0.5903532214507684, + 0.5308086154652784, + 0.4911173966094703, + 0.1061865920319891, + 0.23746811308751703, + 0.28965743422058166, + 0.08902257008503578, + -0.07027803570937197, + 0.6198421334618379, + 0.5526174973186812, + 0.38047188370946794, + -0.5471641050375228, + -0.004035357924602634, + -0.5643212992061846, + -0.4574325907988678, + -0.20510920188248116, + 0.4930864679694854, + 0.43692524045196357, + 0.43975396052531723, + -0.5776661208070235, + 0.168308034413018, + -0.1297261490268915, + 0.057683987994021635, + -0.6999299919819586, + -0.08253893825638192, + -0.24212448951001508, + -0.7286085516030413, + 0.6629293731986564, + -0.3647386107272755, + 0.6094579643083639, + 0.5185893645254934, + 0.20638013794241383, + 0.4891526684672073, + -0.4944956477065197, + -0.38174585687265306, + 0.5025626484939486, + 0.6325974499663686, + 0.27470255884635686, + 0.3221312768956214, + 0.5453349265286155, + -0.2502050949034961, + 0.2432811855485001, + -0.5939923384697904, + -0.4036855776157719, + -0.1545761475846339, + -0.45585535909813113, + -0.3303404103174817, + 0.6093479801960603, + 0.5058677116487827, + 0.2991133312422899, + -0.5128604405728006, + 0.4184440239143389, + 0.4181284403070519, + -0.2356864990444102, + -0.1733364024444337, + -0.042314421662120516, + -0.4897324684591845, + 0.3644873355971091, + -0.353942461477021, + 0.17922121972080718, + 0.5110496126159777, + 0.5285160823947995, + 0.2690818131285849, + 0.33458942728620744, + 0.4439023936062504, + -0.49737622571923074, + 0.29938823109106216, + 0.5077578926343033, + 0.17893819952232237, + 0.10293898548278135, + -0.10399872419384948, + -0.19878926933359287, + -0.4471399804834539, + 0.6009856245070112, + -0.7251064642192446, + -0.5401545926592977, + -0.39600973044682675, + -0.233733876200243, + 0.629282324277686, + -0.6114877349684389, + 0.17198491385208559, + -0.7241841646995839, + -0.49239556762106984, + -0.24543860341030976, + -0.0020143332466923125, + -0.19927539671956696, + -0.5407710095263225, + 0.08049920333337157, + 0.014323414696309489, + 0.5139418317538588, + -0.3344135046299313, + -0.3693643341079451, + 0.3353680841161165, + -0.244921684832904, + -0.5396368901456556, + -0.5346956281164634, + -0.283939026281719, + -0.34861658248677135, + -0.20142876023435818, + -0.2209124525970677, + 0.36792677954325803, + 0.04413751512319419, + -0.3346086674963509, + 0.09966726418365224, + 0.5774907282758232, + -0.10217082116856069, + -0.7201988104703897, + -0.017159209956906007, + 0.05112133844694722, + 0.47908221351829716, + 0.07564829287326325, + 0.08582472966626298, + -0.3106519738106511, + 0.5484273646269066, + -0.09419425748937638, + -0.18227055128525815, + -0.5866069160463128, + 0.45160413406413513, + 0.025321496397673338, + -0.6301165642697986, + -0.295096908969683, + 0.35724896995774025, + 0.06710339897658746, + -0.18472358155124124, + -0.09836757463093126, + -0.6793673735986294, + 0.29012886853654984, + 0.4661803371881238, + 0.09926821815690723, + -0.3693858204877357, + -0.0805089366079994, + 0.14781786993220636, + -0.4467966795525286, + 0.4116263553130425, + -0.5988157637066414, + -0.1999167688685516, + -0.012836820490482626, + -0.08924794159367389, + 0.5065620714569589, + -0.5016061614589856, + 0.6461962730940166, + 0.1844330514225878, + 0.15496597225513242, + -0.5984869896974043, + -0.5040095744636994, + 0.3860262963265163, + 0.6212440008130425, + 0.21654078131525178, + -0.627630874274039, + -0.1921334027202588, + 0.0301399150296503, + 0.32008411886012345, + -0.7641279047060564, + 0.16384575618060626, + 0.04217931850589873, + -0.5769910840266457, + 0.0519096129679647, + -0.15104683985610035, + 0.3495271224166586, + -0.17459511768033886, + -0.3011279777345308, + -0.614746913079838, + -0.5220028737233989, + -0.3300862511150607, + 0.6039567322219374, + 0.3324184398076536, + 0.4981899680741416, + 0.42160656204251945, + -0.314017911513589, + 0.1814092028624057, + -0.422855972566006, + 0.22122647796856887, + 0.2346575244626029, + -0.4053076112409958, + 0.1732227756359752, + -0.27094607570671164, + -0.22670726325072021, + -0.1495344600392441, + -0.285721743925414, + -0.6960736928001995, + -0.307049900326417, + 0.3275776912342968, + 0.5269185796796808, + 0.22512831680844536, + 0.605007185595894, + 0.2705511596396003, + -0.09187118584261544, + -0.047872443912226226, + 0.36184894545690593, + -0.6676701684342297, + -0.2810181686079917, + 0.3681518383030583, + -0.5344973025963247, + 0.1375857821257488, + 0.0901315783524611, + -0.3096013114661354, + -0.45296581640202344, + 0.35244999845825287, + -0.5193024702220221, + 0.5827995922164148, + -0.25140774936269716, + -0.30115130428621406, + 0.045110756031254584, + 0.49291608391809183, + -0.5184223381518098, + -0.16369637782783175, + 0.12938186049066758, + 0.44649787444638356, + 0.5917546588794088, + 0.03994616722280986, + 0.5475446330406964, + -0.6604224577074518, + -0.14636845101607987, + 0.23984025244872587, + -0.048958320694745816, + 0.10831981909701494, + 0.6225738043450159, + 0.6589939647511843, + 0.46979188550277773, + -8.818194935741319E-4, + -0.15033426753243873, + -0.3527962311052352, + -9.362360717892759E-4, + 0.052569055611696336, + -0.39636990488399315, + -0.3256306652209891, + 0.03435267243991946, + -0.5023007964177431, + 0.46050905522261154, + -0.640741944038244, + 0.6227910332022367, + -0.5871922370677398, + 0.28729303375285065, + -0.15470813894370206, + -0.3587685722397697, + -0.2842136870801877, + 0.37571810685288776, + -0.5978175446083611, + -0.04630380090247255, + -0.7225427695566795, + 0.5365085585641499, + -0.003031906061449985, + 0.4974517262097825, + -0.6238507255374959, + -0.6107627110992793, + 0.03726388307865969, + 0.6485006529237901, + -0.11823626098028939, + -0.5001422739627053, + 0.2451732692010281, + -0.35217681171982124, + -0.17782632469550486, + -0.18693700534743507, + 0.33171326727914263, + -0.5892353169689322, + 0.39586752388272084, + -0.3779324643193454, + 0.4687001622099737, + -0.48842821078757376, + -0.74563703864726, + -0.6499411166686864, + -0.559350300668757, + -0.5566341357216479, + -0.5919244503109357, + -0.3063897300029512, + -0.10664058026628265, + -0.37957564491914214, + -0.043955713831441146, + 0.6302406005053917, + -0.20055175455952867, + 0.1951764438894913, + 0.534910152768859, + 0.22242384977816654, + -0.6757203005397632, + 0.4561337080040998, + -0.7097194666606957, + 0.03871627876630135, + -0.6252897632770051, + -0.7524435180478044, + -0.29228663668973964, + -0.21384402526638469, + -0.5719788516320157, + 0.2498954225338147, + 0.5478151673788089, + 0.43688653824911705, + -0.1134652569083704, + 0.6251549296587272, + 0.5772050008498261, + 0.3246125706529367, + 0.576478233048679, + -0.44696853699266637, + -0.36082359743435516, + -0.5722592790960125, + -0.12332002969450873, + 0.31753588381967435, + 0.1894413230429819, + 0.4527105652305229, + -0.08764749676435002, + -0.7603754305156462, + -0.5935291468150039, + -0.6995416781087648, + 0.34580546687505354, + 0.45322413200919887, + 0.6543843906819719, + -0.4495157296046501, + -0.4653979535380195, + -0.2682040111341707, + 0.41100936891707096, + 0.4116814649257269, + 0.6625227680579563, + 0.4049222848792625, + 0.30755664642245295, + -0.037166305405933464, + 0.35586231010025304, + 0.2427677395172555, + 0.05575871016348577, + 0.6048939048123126, + -0.020366992845705645, + -0.05695072300799442, + 0.06043799503053038, + -0.31306225894745093, + -0.05991040459300889, + -0.7424275958581105, + -0.6183850032235647, + 0.2884217266811794, + -0.4381078537321331, + 0.024570302952876544, + -0.6527492212542356, + 0.36565731309988847, + 0.30077812867101505, + 0.3673450029086339, + 0.1586277949607705, + -0.19067124587170325, + -0.37102280011105865, + 0.028940606976860628, + -0.3001647687192018, + 0.6078052747082877, + -0.48402593581217446, + -0.3978314744516266, + 0.6235542596207421, + -0.6774244025942846, + 0.3147714162371217, + -0.25342508511680095, + -0.5784582215254848, + -0.4491583821771359, + -0.09407705708406766, + -0.5882029645634469, + -0.6889070212982475, + -0.17793701634265424, + -0.5609096421496804, + 0.5427255201472708, + -0.35340714572183624, + -0.5392693271972594, + -0.7051624527486002, + -0.6205630960185342, + -0.7524888164772489, + -0.5968531741886746, + -0.3621176046618017, + -0.4676686327251963, + 0.2435558209729788, + -0.3994134147757806, + -0.5257498305260155, + -0.4273682668451701, + 0.16544337620944483, + -0.34667820343367595, + 0.1513930259994588, + 0.6529841416904142, + -0.2439762052369847, + -0.5078108435374106, + -0.3931695119513511, + -0.7597790134700139, + 0.2815044323875008, + 0.14916078179395797, + -0.726124015706409, + 0.024533833280849016, + -0.3612581465677304, + -0.7630393463085405, + 0.06679320752639462, + 0.22875642687509423, + -0.05946236676530514, + 0.24604845169906742, + 0.1742510842555678, + 0.01642816095414723, + -0.3594057209970389, + 0.3010053527570874, + -0.6934075278695504, + 0.34024731004111, + 0.3076058324549068, + -0.24131474432848166, + 0.5025387834470009, + 0.6376591877857624, + -0.35021394234837705, + 0.23436561174207438, + 0.4739198991936401, + 0.10926511571422448, + -0.517642502745002, + 0.34493796965922907, + 0.33019913425644376, + 0.019782680970543143, + 0.10919984546173134, + -0.3679492545772583, + 0.559931973641138, + 0.4051203152892878, + -0.44623279490740936, + 0.0814547028540028, + 0.045101742342410156, + 0.10051244402290471, + -0.6767937515294473, + 0.018457225652000586, + -0.29833167897317864, + -0.5767916028045526, + 0.20653918056896303, + 0.6076141551642339, + 0.6384748862322028, + 0.6344496380600865, + 0.3825654838276956, + -0.27288016834282414, + -0.5707631773874572, + 0.6270482024729519, + 0.569963398141908, + 0.3968387503416996, + -0.3436172376665723, + 0.398561376982001, + -0.746703660518641, + 0.5865584870802801, + -0.6933702950464723, + -0.7214648929046372, + 0.556408835347587, + 0.16300634792551727, + -0.3628587759699842, + 0.3740259221665744, + -0.300889686863034, + 0.48157705891971514, + -0.0962114401716696, + -0.1410898748305336, + -0.6754620354192252, + -0.39222328874248186, + 0.25787969057288673, + 0.6530590762961789, + 0.6442686160873753, + 0.005657077142275702, + -0.5315437343495297, + -0.6510710147919749, + -0.21102348854321618, + -0.6942177134120445, + 0.17789669062637137, + -0.07763449982235382, + -0.2054268230973325, + -0.26723973962220376, + -0.6496940058331719, + 0.595136113630749, + 0.31329727372173266, + -0.019137459775872556, + -0.6943498616730939, + 0.6592461255997651, + -0.10582521450500537, + -0.2125252031923759, + -0.6525397224589529, + 0.6227911950399444, + -0.7626298873551415, + 0.14896927055169207, + -0.1908068876487623, + -0.09281002903515179, + -0.6736604698969415, + -0.6253186507799158, + -0.04592336707711686, + -0.34186283377306875, + 0.5715419211866414, + 0.4999734078838657, + 0.13289049638979045, + -0.26118649872323874, + -0.16741050896379217, + -0.0844545048352614, + -0.6190999428378166, + -0.15287098812653444, + 0.46185306789203884, + 0.37239568880351837, + -0.25556609439957845, + 0.6624725086263455, + -0.14366090605513115, + -0.12327359647994007, + 0.015163873920581605, + -0.18808052795689167, + 0.1367170596272682, + -0.5982060022537283, + -0.05542125082857774, + -0.2241583990753071, + -0.2194984087879136, + -0.7402784596504098, + 0.1729921855527562, + -0.7090882407621556, + 0.4900150524774668, + 0.046937756795113694, + -0.7392289516288809, + 0.5662545185103814, + 0.5433856698594067, + -0.7284569903351779, + 0.5849546430414404, + -0.2242745811574245, + 0.0597056235765453, + 0.44722500089546313, + 0.3517238315244008, + -0.5029397455508533, + 0.6312926617168367, + 0.12460941960462502, + 0.13704327649856995, + 0.5039896373179652, + 0.24390143319322333, + 0.19149476837264723, + -0.5128823666914949, + 0.2647750424471641, + -0.3680611500494898, + -0.3877659201859463, + -0.08745799296309098, + -0.010918963738974052, + 0.11759932907751836, + -0.3549189407957777, + -0.3106979670701851, + -0.6311292816625387, + 0.5644052941943708, + -0.2835660917509549, + 0.35728039660841626, + -0.6365531691110633, + -0.04021901488599566, + -0.2969474192395863, + -0.5807621884390967, + -0.45655953319652354, + 0.27116701290613554, + 0.3327571098528247, + 0.05803543585105242, + 0.2562338076694751, + -0.5930939577819212, + -0.06503210584004959, + -0.5914807178864929, + -0.6107034874429883, + 0.1662709175832361, + -0.6317932727975925, + -0.04579067004309956, + -0.3405567537492535, + 0.5387461959661682, + -0.6939908489414627, + 0.05011615181184481, + -0.4266576649431623, + 0.36012893779381583, + -0.755043763434499, + 0.14867896304366746, + -0.2879646572605367, + -0.39208137179145947, + 0.4112568276705927, + -0.41076787311074064, + -0.6361352977967946, + -0.5235173701929665, + -0.14492607929403745, + 0.5151870778314745, + -0.7264239270645486, + -0.3387617194082069, + -0.009880847101307655, + -0.3110546259429949, + 0.4748778253472056, + 0.41429707857181775, + 0.46680296976386393, + 0.3357818340469786, + -0.5859626881646985, + 0.13256479004114807, + 0.33617224630379694, + -0.5549880672760404, + 0.28397077084360756, + 0.23777860272259332, + -0.08395837795507866, + -0.19647804765133092, + 0.2761081337452146, + -0.4898539487256357, + 0.4719317575464407, + -0.27419685617389994, + -0.3965249493069466, + -0.5895185426991184, + 0.2241746519485195, + 0.2878424189723955, + -0.09111455326275453, + -0.5383401465606218, + -0.172279074628364, + -0.02502154229012754, + 0.2380407934351051, + 0.3819371865508333, + 0.3588242740506137, + -0.19077276388585918, + -0.12089108279356775, + -0.33980485417897005, + 0.5166882785783077, + 0.12551868839129932, + -0.5212700342915406, + -0.15282263516079875, + -0.47605798404851846, + -0.41377308911519967, + -0.3543474967718771, + -0.3405805239065341, + -0.5858315718608847, + 0.20189480053598508, + -0.4842427173463679, + 0.03298416272108484, + -0.15678251560371614, + -0.6145454140422693, + -0.1723936611804633, + -0.302192136435797, + 0.2993893078463633, + -0.6384288020081698, + 0.3855856439991677, + -0.1120536132245542, + 0.5942777892581695, + -0.7624131415260572, + -0.5704291511309472, + 0.46380159428266354, + -0.09613517967037288, + 0.5671229326906985, + -0.12498937726827175, + 0.522145399606123, + 0.3903118428438691, + -0.209389200754597, + 0.20728848410383005, + -0.03776033853891847, + -0.7264212824644174, + -0.32327474180160115, + -0.1361725045519897, + 0.40613238499479565, + 0.47451818295344383, + 0.16089503089547608, + -0.019596125570276013, + 0.45724551158668236, + 0.4005784594013052, + 0.3408269618812029, + 0.15262373344309188, + -0.2916714823070263, + -0.6742343464956603, + 0.19656949186229744, + -0.5111788826915104, + -0.5919619805759616, + 0.5627448964462743, + -0.3727647530388363, + 0.22899350572726884, + -0.17661994619617838, + -0.3183784376194394, + 0.4985497410187151, + -0.048980978547962795, + -0.5320377783735929, + 0.02690259478667234, + 0.007165511726275553, + 0.2545178033072423, + -0.09254433425941755, + 0.5245336051197876, + -0.7085690692899164, + -0.4288427484944969, + 0.49580101642111096, + -0.13009580759948725, + 0.6587022953880161, + -0.5340439932077895, + -0.6171656909310699, + 0.21075094095861446, + -0.13388232536685762, + 0.43065127180799034, + -0.4037407696707578, + -0.6257240945109172, + 0.18276340082217157, + -0.31454035853182366, + -0.6283737491493212, + 0.016790606151071197, + -0.17359943906500042, + 0.2978542194295971, + -0.7559922801212275, + -0.3287643288193839, + -0.286614811514763, + -0.7164412056950442, + 0.6433045730574051, + -0.7507702233500977, + -0.7619105609973188, + -0.5100803077549615, + 0.38076859293449183, + 0.21505190998396762, + -0.6946669014887279, + 0.4428637974466255, + -0.7075667731033559, + -0.6470041985076034, + -0.06744519313389474, + -0.30168885809749785, + -0.6221798864595838, + 0.5114923124983345, + -0.7625905879845126, + 0.04251312531845253, + 0.2410836648557041, + 0.602758154832986, + -0.25777756489474113, + 0.33016803925634874, + -0.27442139381764624, + -0.6263079167041392, + 0.5410647351347372, + 0.21175746141441432, + -0.3939228843627196, + 0.544025096322167, + -0.6111689965692524, + -0.3277522771387663, + -0.032262441959112764, + 0.5968813727399692, + 0.11788952800158414, + 0.2906506807748229, + -0.5391163376552274, + -0.4156337451984087, + -0.28310014329522337, + 0.03358280118520607, + 0.2270453494359873, + 0.47984388119105625, + 0.6081633280283217, + 0.6586534654632857, + 0.03834041102447083, + -0.4509177829886213, + -0.34458407821559184, + 0.2350144808813467, + -0.24483660699835352, + 0.25582634248855507, + -0.4090153293818653, + 0.6311354901199046, + 0.31586079239154985, + 0.4198703253051831, + 0.20874406200862727, + 0.1363594554951978, + -0.003300423354864357, + -0.33303067640824313, + -0.716873708603178, + 0.5858673659439616, + -0.021851421216508515, + -0.17491228279972793, + 0.4093101453154885, + 0.015452312982516037, + -0.14290764405904288, + -0.09102895715608128, + -0.1673373329537976, + -0.41502011234700836, + -0.7037694702856487, + 0.1335840223169904, + -0.6298148824178755, + 0.19187903770895864, + 0.6317007442346528, + 0.007427434771815955, + 0.4716537853787687, + -0.6232688831589885, + 0.6294894047011467, + -0.7190662140514184, + 0.14357405236704268, + 0.2341710332629453, + 0.221677017804205, + 0.015848538101831067, + 0.4242650878050803, + 0.5795772112869134, + 0.0023819813014011038, + 0.17315257431547082, + -0.2942258123444146, + 0.05130901638233165, + -0.39854447098660367, + 0.43093852299348756, + -0.5523643192832345, + -0.5038144991574374, + -0.5991388515451257, + 0.19147778273300153, + 0.08994963774600506, + 0.49008218334825815, + -0.4275072136872958, + -0.35666666303729483, + -0.6991666877055732, + -0.5759002958418156, + -0.27549359728980466, + -0.5692269187114077, + 0.3162256916143492, + 0.004448404638537795, + -0.20479278129969325, + -0.3056934049594838, + 0.5589105525918444, + 0.09402371063490422, + -0.336647958761039, + -0.4234750228615038, + -0.22654557407478937, + -0.7455107446592906, + 0.15824529656329167, + -0.3665038158692616, + 0.6620153700389978, + 0.28157126327642346, + 0.5827621025770634, + 0.16563465260808452, + 0.30022260496549136, + 0.48766983659495444, + -0.16449889577467958, + -0.2511387670541849, + 0.4824483657052968, + -0.23431952307995074, + -0.21133012217583835, + 0.5066925245622252, + 0.16593000305115424, + 0.49246602218563773, + -0.526279195137921, + 0.6517174925222623, + 0.36356665312659253, + 0.6472289771486307, + 0.08550480052650544, + -0.6898301541456526, + -0.1678464117697559, + 0.6062761763975705, + 0.04428454475668597, + -0.4742631388410521, + 0.359353600604594, + 0.4478107562145811, + -0.15455664911442946, + -0.7626417911258428, + -0.17176991646232398, + -0.6733366115520428, + 0.538935701150569, + 0.07020134171744552, + -0.20119791165333922, + 0.5545863721287995, + 0.42571837017103953, + 0.6250829615661716, + 0.3072189607094641, + -0.052097952467348274, + 0.4510640550642392, + 0.2719051339070725, + 0.07080390704721706, + -0.08946287975297051, + -0.4847111719000606, + 0.2546907602981644, + 0.3684112059370833, + 0.12881550277047926, + -0.2838657506668141, + -0.20472073619664433, + -0.5090734699934125, + 0.5252021292231214, + -0.02823469275043211, + -0.1749659481409659, + -0.4436652041598651, + -0.41991413826624274, + -0.264577512632841, + -0.022587258071060545, + 0.312729278982952, + -0.11598258761557079, + -0.4322589459746922, + -0.4920414657241903, + -0.19981180920719244, + 0.48184959510956815, + -0.2618808605425983, + 0.5526990203770802, + -0.6742877080513883, + -0.2555243325948139, + -0.28435740490112354, + -0.5604940899721215, + -0.6987179283649345, + -0.08449551018875745, + 0.6067957789093003, + 0.10443700486915453, + -0.5267517176608622, + -0.5931698269315537, + 0.6060543617510187, + 0.6306772700438853, + -0.5482039084910377, + -0.4900799244651708, + -0.5729304163501201, + -0.4885144379896632, + 0.6449745906017516, + 0.16742658976876879, + 0.1288791469515851, + -0.2867352447352268, + -0.7045674418295503, + -0.13839894798727126, + 0.6396042382125849, + -0.6694724737379091, + -0.0312896691050818, + 0.30106465894184875, + 0.5623817907867424, + 0.1490755509294477, + 0.6580328611867085, + -0.7628907308545967, + -0.4381546223019964, + 0.13117197015201087, + 0.6165648898324013, + -0.6828497059170577, + 0.06678251218809883, + -0.2496848100227692, + 0.1862433427314797, + -0.7204760286605324, + -0.36480806995537945, + -0.3939679992939423, + -0.6526210170894378, + 0.5301319359260187, + 0.5568846748501964, + 0.15338102571992784, + 0.06296750912000593, + -0.4218504572839842, + 0.39501712621557583, + -0.1988508594026871, + 0.5314076647536675, + 0.4575696268781356, + 0.0304993765224868, + -0.03967159467993109, + -0.7300384633645136, + -0.3137121399667934, + 0.076773988300736, + -0.07043468666886876, + -0.7411103128942058, + -0.6606757787882339, + -0.5567913013456361, + -0.398495582892433, + 0.01530055736856728, + -0.5830750037030168, + 0.2972959948181023, + 0.42321769902460826, + -0.6416174255570856, + 0.0345224803640769, + 0.30453484425853705, + 0.11631414400355555, + 0.08715988030954192, + -0.18894690375918644, + -0.2602449998036829, + -0.6953571327348718, + -0.15955488162293052, + 0.6165161254026047, + 0.4844639890079775, + 0.6494051389329344, + 0.4407561989999912, + -0.36296548660298444, + -0.1416708487122309, + -0.031119572538864215, + 0.33246843160846196, + -0.22754969447451912, + -0.08751753394516948, + -0.22834979175244918, + -0.3729452186886337, + 0.6181476686892938, + 0.05320518403374597, + -0.6547171905212146, + -0.6467158424639652, + 0.00684038057857117, + 0.08731176920482264, + -0.7608267722626788, + -0.26210097783790653, + 0.5700409436492763, + -0.17621061608006494, + -0.634992954884855, + -0.5563112376793904, + -0.19910554818645443, + -0.6856566636475372, + -0.3371252522380489, + 0.549962080703308, + 0.2488690159667909, + -0.016178187499937047, + -0.40724029678151286, + -0.6715479332237013, + -0.4839098067716601, + -0.5358904094398551, + -0.7232867703174244, + -0.6775678282757995, + -0.3463296641412934, + 0.11278992164984503, + 0.19402727895686434, + -0.495714296222076, + 0.6556668667031759, + -0.39114136957533147, + -0.35198761994067485, + -0.6145240779243334, + -0.5799023830095942, + -0.24674894416865079, + -0.6167831795787374, + -0.054703924408976534, + 0.6243002154539831, + -0.20141154150155538, + -0.5460967605179384, + 0.5596095270816831, + -0.6312509658945377, + -0.593096869583137, + -0.05743607292841646, + -0.29685284224061476, + 0.011136656649245014, + 0.17770284266505376, + -0.047631205882770034, + -0.06456790222480613, + 0.20003968799197736, + 0.047001525887113704, + -0.7177236605274305, + -0.5830254550894531, + -0.4347195109318642, + 0.25418826454403554, + 0.5382054282591239, + 0.043524407647468344, + 0.04225788063640101, + -0.11121484130854775, + -0.6197477032142316, + -0.07769433519022662, + -0.06575380340942849, + 0.27973498047972944, + 0.2606723298384631, + 0.27221689610338917, + -0.5205776841795785, + -0.5202666271913218, + 0.2168496729652284, + -0.40868478499654387, + -0.17569757900423355, + 0.3782769591334313, + -0.7395277716501539, + -0.721016618123802, + 0.6619616555064346, + 0.5790684057011141, + 0.11230642416225656, + -0.14413732602808016, + -0.7577422646827519, + -0.581650000914853, + 0.11103849818175282, + 0.6114845524154428, + 0.6150246685048274, + 0.43857876728552714, + 0.12360194890655407, + -0.18221508572643796, + 0.021869007093694548, + -0.2424522437994734, + -0.6401433722777707, + 0.4229545167883656, + 0.4297830981196563, + -0.2750819500994322, + -0.6446401318147011, + -0.14271443272287443, + -0.24154758873895865, + -0.6859805898245431, + -0.32517338632714315, + 0.15361958833699585, + -0.2209959545069866, + -0.1296025121224097, + -0.5881579205705467, + -0.6559671338878557, + 0.46565899357555407, + -0.40107107076265425, + -0.4164316373559324, + -0.44497738273756376, + 0.16465835466822742, + -0.15877090520131998, + -0.2581874702070269, + -0.6602976416354241, + 0.007567106068037566, + 0.2954830826941962, + -0.12478141604510207, + 0.6165798678157682, + -0.46984261124445814, + 0.6085274134780628, + 0.13036245649927714, + 0.46743143460874326, + 0.27884686562277905, + -0.062320369253876184, + 0.5547742036695843, + -0.028612689268972535, + 0.29438440314814407, + 0.42690460439044375, + -0.10657349880034661, + -0.48379689103198137, + 0.1425077404913594, + -0.013597872607968298, + 0.01569002944441089, + -0.4159156132397436, + -0.6855899614587532, + 0.26621151589521597, + 0.053630451050860284, + 0.2954196737735487, + -0.6485096694135426, + -0.5609421163095643, + 0.4829317819432396, + 0.5476258668349739, + 0.1479630564768908, + 0.5694779052352236, + -0.5266388827858001, + -0.6283734419807878, + -0.7277462487773867, + -0.06428982491505353, + -0.2917418282665535, + 0.3642168660931796, + -0.6100216558992744, + 0.027756338311083595, + 0.30104984255646994, + 0.37357866620877755, + -0.6029926481302216, + 0.3490859310716167, + -0.2044706295387173, + 0.029688630285913176, + -0.20375452195436272, + 0.17986663130361058, + -0.02371636485639883, + -0.30254637263591755, + 0.46611080291898854, + 0.6146324527112569, + -0.2681382922204793, + -0.4391350788783636, + -0.5096989041282072, + -0.24985625807518508, + 0.5670775314829427, + -0.6339718154933047, + 0.6132337870334815, + 0.6293020928023209, + -0.16134100354175052, + -0.6601851790867649, + 0.005647503344351934, + -0.4420156754533061, + -0.11830953412420298, + 0.2969042558946823, + -0.4850224985370228, + -0.1752525105055226, + -0.5779190677048087, + 0.24840065828618763, + 0.16973398060707434, + 0.20947323424417785, + 0.651452432302, + 0.2079673916416891, + -0.40240300215485586, + -0.08704175759307331, + -0.38899993431573004, + -0.6557034538833235, + 0.07245099187308157, + -0.5065494715482497, + -0.7432607897526862, + -0.19353353448679056, + 0.47284317282402377, + -0.24308719110220978, + -0.05594266188868002, + 0.40853516210812335, + 0.039147063028111106, + 0.3430015362949833, + 0.2038335007037606, + -0.6873403871105402, + -0.07564670086896241, + 0.6010659517078619, + -0.4091900386262156, + 0.2743909275613189, + -0.6256670739698689, + 0.16239625163992877, + 0.058599179829225134, + -0.01107505148136223, + 0.19602975762417785, + -0.4524809523964616, + 0.0626683471567484, + -0.44464895344205274, + 0.5788121268573033, + 0.4689694733873474, + -0.5169921774179487, + -0.5549365611816774, + 0.41058659081322524, + -0.13980825723988943, + -0.25049343266713153, + -0.4431626570545929, + 0.3567809535711196, + 0.4961978377070634, + -0.7510411227246861, + -0.6279146094417822, + 0.40031954728839103, + -0.3303717826866608, + 0.4452879030312843, + -0.5381724690700783, + 0.3860062175001092, + 0.5852173409938072, + -0.6059231996502911, + -0.6942194374967876, + -0.3341315303701659, + -0.5492353422400551, + 0.13660737711241921, + -0.6160630933171314, + -0.6193146364945608, + 0.5069781731171378, + -0.2362186018863507, + -0.6111137325010285, + -0.6000425466985262, + -0.6881979195571591, + 0.10213013462066012, + 0.42298859476430517, + -0.23612042085563678, + 0.019564514876270644, + 0.3045220493093904, + -0.6047442322990123, + -0.16142879939230914, + -0.12199797126062017, + -0.09189046682124968, + -0.3600245134812375, + -0.20265012640716495, + 0.4852963373118201, + 0.4459406530738318, + 0.3684761682540588, + -0.519540024039166, + 0.4466304916459888, + 0.44358952852527767, + 0.19240768197971025, + 0.2951543245414011, + -0.003583666660804119, + 0.2372998012245523, + 0.14513685474634108, + -0.6937502881322933, + 0.11834087446814145, + 0.11192874297174749, + 0.388574729897336, + -0.25724537176992024, + 0.3232712401170569, + -0.6535731515244705, + -0.5414140454453734, + -0.49860044845256757, + -0.34545173763293024, + -0.24522914490335934, + -0.34762235610074826, + 0.3761005096939599, + 0.3165821535007248, + -0.3831842293592118, + -0.3140356681985823, + -0.5217241831196332, + 0.09111614121644529, + 0.2987590743042571, + 0.30346490744219745, + 0.36137588178714986, + 0.09877086450637629, + -0.001727159559440139, + -0.4572276484171078, + 0.10029472721560817, + 0.36358138128782713, + -0.1978793639019828, + -0.6808658433131461, + -0.6479137435005982, + -0.012788357799573102, + 0.2548131809986406, + 0.4093885246049055, + -0.5680841405783403, + 0.6034441909762319, + 0.31835942431766673, + 0.6407535734579889, + 0.26183000057129135, + -0.12187565506209319, + 0.1232235386591416, + -0.4793026636539617, + 0.13120806975642918, + 0.10225836757813933, + -0.413633063901347, + 0.4837084496231122, + -0.4874147141392305, + -0.2247179016845121, + 0.3135453553228026, + -0.4281259067695525, + -0.41176812111826244, + -0.39047228120408284, + 0.051087907854351466, + 0.05617201398781091, + 0.3551546786087426, + -0.5188140738078725, + 0.6037269952067538, + 0.6140481001321566, + -0.16040632604227778, + -0.6869330759797218, + -0.3122820296797271, + 0.6051215289138817, + -0.057156481366258394, + -0.45362055086183295, + -0.06102615287016122, + -0.13070622507331786, + -0.3375438798339792, + -0.03673697995105962, + -0.22354407382728814, + 0.19075339254549029, + 0.11612715552766972, + -0.7023767611917623, + 0.4127533085133447, + 0.20239974435784736, + -0.5275004583312355, + -0.4973257219261071, + 0.17970807649635212, + 0.42732596653629973, + -0.7258259011896722, + -0.7066848007964828, + -0.33266829268216025, + 0.2843589790510336, + -0.7495876593750447, + -0.07846923354240343, + 0.48054533998696003, + -0.05378250481226521, + 0.33624119335353997, + -0.4494080985945933, + 0.014872345528222697, + 0.5074608038167557, + 0.11976001478845921, + 0.23727519015866083, + -0.7508983511818221, + -0.14686689439792167, + -0.5144324178039333, + -0.6189778882812349, + 0.31722209185979466, + -0.13487946784728322, + -0.6052014221687714, + -0.30650806510855716, + -0.015241699646542761, + 0.2540517919126092, + -0.16869888441032543, + 0.09775661450293771, + 0.4441987363436958, + -0.3742311515727382, + -0.5658431594949489, + -0.7259137281592494, + -0.3542243759861796, + 0.1706580920630475, + 0.12477418435497112, + 0.20762976050906612, + -0.3083070675087068, + -0.7290025522585131, + 0.5917103756010452, + -0.08562853336500575, + -0.27715482256061197, + -0.41122320595733897, + 0.6223429001974562, + -0.2885050365859732, + -0.37841345922643516, + -0.19031272925070408, + -0.6537079735199535, + -0.17979219720708017, + -0.5475815732669543, + -0.35553132644379265, + -0.6843580780215366, + -0.04671404229931009, + -0.7110156146596188, + -0.5630039271079648, + -0.4522907220064117, + -0.6208648868024852, + 0.15564915465304419, + 0.04471929397853913, + -0.4270927801306462, + 0.2482375986539379, + -0.4786736709214616, + -0.6532248376733828, + -0.1472516135142451, + 0.30815201192731234, + -0.3093339875708195, + 0.2994936805758134, + 0.3194491943941252, + -0.05462494734790213, + 0.07211814780544379, + 0.610109089914317, + -0.24193042436308587, + 0.568125648517596, + -0.576556356611323, + -0.5836797463610257, + 0.27177612782238925, + 0.12607042853895667, + 0.3377091239457187, + 0.2617476619124802, + -0.06877183919933527, + -0.693564186708677, + -0.26672258268085913, + -0.6195625792531544, + 0.3664780266048647, + 0.2058470323845074, + 0.12856865301700893, + 0.013486196132596717, + -0.4482366399454, + 0.14855247523789195, + 0.3122808471376307, + 0.3492038097120328, + -0.7171117411874807, + -0.13910738370340792, + -0.33298121865038727, + 0.28222746569921686, + -0.19991913897313118, + -0.4878214509985586, + -0.6060715167895847, + 0.5828461454361266, + -0.6361983400178586, + 0.32441564762229824, + 0.208391093598289, + -0.330151015383208, + 0.13173228350703492, + -0.3153376391862849, + -0.5898061052376881, + -0.14171508302024327, + -0.1120608598017988, + -0.45964106015521206, + 0.30633787377408217, + -0.7263316271938302, + -0.3666508602618164, + 0.540490800996282, + 0.3693508193199434, + -0.2071130096748829, + 0.1100047791341705, + -0.08333012415789331, + -0.7225182205379367, + -0.044121204456633256, + 0.023680223017011004, + -0.2804509336919006, + -0.754010827174768, + -0.5808608125455037, + -0.4332602524892016, + 0.623741149126093, + -0.3720899586229709, + -0.12660409650655735, + 0.1706681423420493, + 0.5180081645014708, + -0.5028606614739608, + 0.44403310302442256, + 0.5893262378308025, + -0.19371150410091342, + 0.18692726352915134, + 0.2087357181402718, + -0.6854242408131991, + 0.12076642430959372, + -0.3350374377608796, + -0.20102618595471378, + -0.7029876340565926, + 0.6599189339178132, + -0.7502207706761215, + -0.23904914889892703, + -0.26364510267508234, + 0.6522508759548836, + -0.2752930996470513, + -0.5796887798748465, + 0.36826755959133795, + 0.036592494737797465, + -0.023624535011383396, + -0.42134863957835683, + 0.2331849025122592, + -0.2218962530562495, + 0.03772448056530331, + 0.6618427251950866, + 0.5050858412112335, + -0.5058076773458247, + -0.6462666805433973, + 0.19624583466640888, + -0.6797305433616194, + 0.36753883336845317, + -0.31088044572961476, + -0.5380437230946474, + -0.26441202335382985, + -0.09476977973508771, + 0.1211299411644372, + 0.4817217359690761, + 0.5613854321083968, + -0.5585483557448119, + -0.17858676501295656, + -0.3176093327883313, + -0.039642236025249744, + -0.09671318192789458, + -0.31290684605323593, + 0.3808475162058679, + -0.6391673573772423, + 0.3453611778396749, + -0.4385482938643188, + -0.7529620610014068, + 0.20091429294222507, + 0.17705290194207657, + -0.23965221247957724, + 0.032868039541271155, + -0.6775718430778613, + -0.3817424794205966, + 0.11629240306942001, + 0.19066322752235743, + -0.11208866406312179, + -0.2590965023550008, + -0.31714581087906496, + -0.30108436424131785, + -0.04316602237196232, + -0.766522987146709, + -0.24671875174373614, + -0.7224227556614055, + 0.1283643231152427, + -0.4698280557544534, + -0.06843339710561103, + -0.4041243889210961, + -0.4453550724191725, + 0.22474773136370052, + 0.49079844265605665, + -0.5981905589064379, + -0.2969973562852295, + 0.04676597572086161, + 0.14968630846148223, + -0.7231933319762865, + -0.07123257573639086, + 0.35810002341511693, + 0.07290085956822101, + -0.11855514710512316, + -0.7093688408175439, + -0.26574393868177637, + 0.0034958539364337016, + 0.6313602151030543, + -0.3041060707966816, + 0.19626310853165563, + -0.5098963663018229, + -0.29544369424555816, + 0.5539241666130822, + 0.5085267615245549, + 0.6316032350623361, + 0.40785135463494415, + 0.5498865438927515, + 0.6568861436687458, + 0.09955517217246346, + -0.7031253768947868, + 0.29877090746768353, + -0.0034393800322517487, + -0.48429428974494476, + 0.39773815742221375, + -0.325093969127755, + -0.619659652353058, + -0.4351362502521054, + -0.6244833221602306, + 0.3709650158279053, + -0.16440697879693467, + -0.2827792095188531, + 0.09021651093738514, + 0.17556005858960655, + -0.25118176356132815, + 0.036828772211130345, + -0.5751529767096863, + 0.541286224618522, + 0.6141932691787021, + 0.5311578835841363, + -0.26768888462645046, + 0.48481123370949464, + 0.6172197868428227, + -0.5025651491857155, + -0.23133769194995246, + 0.4285224850128152, + 0.19362710296795294, + 0.5984750889672724, + -0.5839174541195489, + -0.3921886713458141, + -0.40597695231079944, + -0.45464364048610734, + -0.6494642326909911, + 0.4459811745234611, + -0.13411476575527825, + -0.18442687604903196, + -0.4012230577108948, + 0.41492789770614247, + -0.17804051490341077, + 0.49266378743474004, + 0.6207442665425972, + 0.37052835167001963, + -0.7223073677387857, + -0.5811548534302843, + -0.10417040316493853, + -0.7288272307862701, + 0.14906598753798772, + -0.6482771540843674, + 0.44320351273345604, + 0.12531992270445003, + 0.16678215703592025, + 0.6273081806043489, + 0.5910547488703713, + -0.17396087365377388, + 0.6501356907363899, + -0.3079314905377853, + 0.5489641060352238, + -0.7021192456228238, + -0.6080071861794056, + 0.38929846174008464, + -0.26815911475827264, + -0.6772819443009973, + -0.4381133920620594, + -0.27382116128972356, + -0.5452243385703373, + -0.5378011708011309, + -0.6896750720573193, + 0.3594529568705661, + -0.3411802342337974, + 0.38820102408398827, + -0.08106446455860972, + -0.12719011244309297, + -0.6762472325142596, + -0.5684236215664435, + 0.16695928389379033, + -0.5432037972909585, + 0.15367790996842856, + -0.6560587737208035, + -0.736152907029002, + -0.47785244288349515, + -0.4276162644567797, + 0.2164318544654369, + -0.5392742751049694, + -0.21833663812926907, + 0.07389157077654229, + 0.12375324253894426, + 0.020099927354505276, + 0.5813967903863694, + 0.35383832587165986, + -0.2477268055505779, + -0.11900899382717123, + 0.06408422505147493, + 0.4942930667398552, + -0.18132834812961107, + -0.09708151366671802, + -0.4700937860207572, + 0.005535517631253595, + 0.5547503469615928, + -0.05376865210635429, + -0.16782695489167454, + 0.08923426046418104, + 0.19255295750457713, + 0.3760044336493552, + -0.10649023636659138, + 0.5855505089126877, + -0.24470274198556685, + 0.14196452476715415, + 0.49260046475671226, + -0.5626921458513341, + -0.6426884793796654, + -0.014289782042527954, + 0.5520490162793347, + -0.23690085776665892, + -0.5803558267079201, + -0.7294451773457725, + -0.4846970891883623, + -0.1848253060275361, + -0.479040974438224, + 0.1776908933845076, + 0.5072996210326858, + -0.10662944678450448, + -0.10681743985296122, + 0.49880580457014945, + 0.5301473336787826, + -0.24936914477368932, + -0.5141780264213314, + -0.44751623904524174, + -0.334622816124719, + -0.2673148117559813, + -0.503664319787505, + -0.7396285447760504, + -0.07130553335736645, + -0.3687836664681851, + 0.6319011373416917, + -0.2709377024787806, + 0.6097847707439196, + 0.355746263119083, + -0.41158869863375314, + -0.4311621437298894, + 0.25618485475125563, + -0.03352834681431871, + 0.21289655507270377, + -0.6775403121648869, + 0.1562762837433026, + -0.3839599129186803, + -0.7219661754366384, + -0.058458924385966116, + 0.37953389872756127, + -0.4430483410524779, + 0.6544517419340713, + -0.622318291509161, + 0.43517796476866366, + 0.5744183701546951, + -0.14830784892325388, + 0.26059807087108655, + 0.2401089875122292, + 0.07547640288651492, + 0.1698435686696712, + -0.5287222811456984, + -0.5470429936874179, + 0.6055494017243642, + 0.45564032341136074, + -0.7533499559059014, + -0.5394633917382917, + -0.1597604939325723, + 0.027365980608062723, + 0.015178442398115943, + -0.3293833782758871, + 0.4860506439970945, + -0.43259202085700255, + 0.3948140194989761, + 0.49944897199741745, + -0.14023079865675925, + -0.1940529714922653, + 0.304898240684242, + 0.2905760205644763, + -0.12127890763647708, + -0.09541013165667578, + -0.5917250164837924, + -0.2382505402261036, + -0.7191766848559619, + 0.15086742226694816, + 0.09245666526319418, + 0.5288185939990975, + 0.0554950735344919, + -0.20457810496102335, + -6.233852019705832E-4, + -0.31476383848305267, + -0.514762336775307, + 0.15347255788376657, + -0.824790370187182, + -0.6603612502639212, + -0.8439867325237941, + 0.374616007183844, + -0.2122661027003796, + 0.12124805210084888, + 0.06356529202782135, + 0.34669384301861106, + -0.8119762406470217, + 0.21086754969103993, + -0.7203698834890493, + 0.18507059823566774, + -0.4585292351823371, + 0.10759488435867648, + 0.14471153202603793, + -0.06189830826011733, + -0.2757256930447084, + -0.09822946217025785, + -0.39204303483978903, + -0.25961681571452744, + -0.23002573393326353, + 0.5614121312685032, + -0.24339332018855275, + -0.10284710486068416, + 0.21423960976071, + -0.6380278079620122, + 0.28162050241263437, + -0.6218905321273346, + 0.5339285784278471, + 0.44796228382137526, + -0.36894586625380127, + 0.5681988161516696, + -0.2326624608597081, + -0.1920324693663742, + 0.5264555426592312, + -0.37881567491696744, + -0.031203347098210044, + -0.4290563803968437, + -0.6629196585221641, + 0.08962769865965514, + -0.17615538798614538, + -0.7179495771177363, + 0.5124175348631108, + -0.5226773888070322, + -0.5841752984072472, + 0.08857007463148503, + 0.24391761295829273, + 0.096790116734493, + 0.06269788865935566, + 0.4691273192037124, + 0.009535184993131773, + 0.3198510904726082, + -0.8178818196963906, + -0.249643638790625, + -0.75148504306464, + -0.0048486025622652695, + -0.8006502992196561, + -0.409998617770215, + -0.6175708419830134, + -0.08353280655847051, + -0.7475084262349976, + 0.49342176290522044, + -0.25537814952813165, + 0.282921464507337, + -0.6497840894799911, + 0.3147523864222752, + 0.31213488277564205, + 0.38380844120081203, + -0.5690400764022097, + 0.18642414181926092, + 0.2806879341726072, + 0.16118326532381144, + -0.15319576576501792, + 0.4157997958005617, + 0.30321184155812997, + -0.2099403440370744, + -0.5281366541621764, + 0.01726316059532851, + 0.5321591864097879, + -0.10880678175705549, + -0.8562259554912758, + -0.07884185246366526, + 0.4316426497178718, + 0.06955246964723183, + 0.002014602554886613, + 0.2144855045482552, + -0.2084937761425515, + -0.5393937090888308, + -0.047454833027659626, + -0.1825052837335981, + 0.5319053855767659, + -0.4117237538259926, + 0.00921085422930723, + -0.142196875912586, + -0.24263388214974368, + -0.2513620032578111, + -0.21210257317022363, + 0.3187923311343903, + 0.4118307475599392, + 0.4269034779316996, + -0.7171306535557964, + 0.0716151869589029, + -0.5299446531400099, + 0.5465385634295152, + -0.1368613597682944, + 0.4465065742918537, + -0.5755893353425889, + -0.4424423111410085, + -0.6145585623583245, + -0.7137796601853177, + -0.6007549988996526, + 0.31121149065294396, + -0.034678470228454605, + 0.4547542468368668, + -0.0800495652650497, + -0.8577695890572146, + -0.8649032818885145, + -0.01558972979756268, + -0.12197471473310972, + -0.5127099408810252, + 0.094099895056026, + -0.025646016213168643, + 0.44073127926735167, + -0.7340745928134773, + -0.11112187260450967, + 0.3415193084309158, + 0.4969254022355636, + 0.39411403009360124, + -0.21868854928042825, + -0.03451272227627822, + 0.5078185491974212, + -0.8574122746490691, + -0.5965627325031317, + -0.534086147592677, + -0.03229926993855925, + -0.6147472091105046, + -0.0484747074696934, + -0.006795429549605103, + -0.6724457066840949, + -0.10311472462126015, + 0.12953061955799172, + -0.5299484021681798, + 0.3384221304318553, + 0.3906547044098101, + -0.5684453298908109, + -0.2616133558279662, + -0.4827556858529786, + 0.3858741163241861, + 0.27968632821899275, + 0.20119757114631298, + -0.6496693192132249, + -0.2148957611329888, + 0.027300407255205772, + -0.08929940244039491, + -0.44489841728088964, + 0.11465006952295254, + 0.37545232564655007, + -0.7828346854355837, + -0.8355271867686669, + -0.4027302802697345, + 0.15596888101675765, + 0.47320204031629687, + 0.4965761727867617, + -0.7906735898432456, + -0.3161936919507844, + 0.2291381380173647, + -0.7884841085811362, + -0.6808198899839839, + 0.3063183220993011, + 0.24806431111367222, + 0.0341848093576429, + -0.03349627552635159, + -0.5712349331251796, + 0.46528470137152245, + -0.5014205700622552, + -0.5001031931547097, + -0.2289359392418585, + -0.33367382917500765, + -0.022405703948518818, + -0.46193652937621715, + -0.18912990084229053, + -0.8400781323921843, + 0.1683845302627056, + -0.7966889801804031, + 0.2322987424762173, + -0.588893357017187, + -0.4262742182799753, + 0.5073492156927439, + -0.04479866710935998, + 0.1582206368421779, + 0.47990484208735773, + 0.4191550491424325, + 0.06780089335071338, + -0.6158369334326628, + 0.5656013110560705, + -0.3174692820393029, + -0.24857194422351614, + -0.42393207763017393, + -0.5764847464798737, + -0.6325494501302161, + -0.7378961264309627, + -0.7396713702858912, + 0.29194201040659395, + -0.4670815247846071, + 0.5441329534594739, + 0.38893256277072674, + 0.031788821945932355, + -0.054034490831131765, + 0.315040197536852, + -0.06939325740508218, + -0.21224083477555533, + -0.7805954395234711, + -0.5220556360111718, + -0.01569544306636461, + 0.29035985499113015, + 0.5037530466859315, + 0.5210925807322326, + -0.8409269898772953, + 0.5558278811219541, + -0.11251490306755674, + -0.7338553434271025, + -0.7412117770104789, + 0.15783016344046752, + -0.2214822715915824, + 0.446557904578335, + -0.6408520010698787, + -0.7599051457718988, + 0.5013046364614704, + 0.1026885043339485, + -0.7269589422996791, + -0.25793193787132085, + -0.03935030533049688, + -0.8514126698294248, + -0.36290029241809096, + 0.3513057615200528, + -0.05245204916151891, + -0.20063194301230003, + -0.39248402589150405, + 0.5440437946711596, + -0.8383876390818458, + -0.0946608215995075, + 0.1881765189303688, + -0.5328848701373274, + -0.434804289188884, + 0.40991022991026993, + 0.09055508935349321, + -0.17942135958391914, + -0.07723440566747364, + -0.7649319525494993, + 0.46790701888973363, + -0.40407738318346925, + -0.0072717656903154015, + 0.3121978841051587, + -0.42839082586246124, + -0.20774703062765165, + -0.285716377300687, + -0.12871690219017562, + 0.32552204609454427, + 0.46261245905064285, + -0.5756342348597254, + 0.34678946464274385, + -0.6088234162319979, + 0.3703144511494172, + 0.3317009018269603, + 0.4492145694688243, + -0.5143646174877878, + 0.029394092975071118, + -0.44724180169400707, + -0.35805917143588994, + 0.5289571595682316, + -0.49482209970685503, + 0.2620269774884503, + 0.4350504838633975, + -0.1602118518817568, + 0.20081598066513262, + -0.13826436703666134, + 0.40057536676021743, + 0.2538231974941709, + -0.05118815956805556, + -0.6078249956138948, + -0.30505893883306556, + -0.670427762110797, + 0.006243930065205738, + 0.24533833852394782, + -0.6996832150601122, + -0.06727870846870543, + -0.5568681719670704, + 0.016580367115645256, + 0.3323438350955008, + -0.15531542137698928, + 0.2208793364261341, + -0.2085627186390172, + 0.028177563237665515, + -0.16273604739168068, + -0.23083121217004987, + 0.4718754984079012, + 0.016410437754938778, + -0.6806876761966563, + -0.8507320123466507, + 0.15132766413889764, + 0.5391490349239716, + -0.47366104144604254, + -0.7483740988890837, + 0.03575078628490369, + 0.048236997337214094, + -0.3488139321991949, + -0.8565410470948713, + -0.44090617762239304, + 0.43620799193688353, + 0.05645671760360205, + 0.5192793071982513, + 0.1503144936362597, + 0.3041470787920415, + 0.4830168799628627, + 0.0759225538565157, + 0.23739863077966317, + 0.179057236411172, + 0.1733056521325247, + 0.28424564497034566, + 0.5605541612196294, + 0.09263165903170256, + 0.2754550849838835, + -0.3838241531760817, + 0.05667947155009134, + 0.45692281381549504, + -0.7147954215310331, + 0.4660639773672175, + -0.663320482855327, + -0.20301110528470667, + -0.5680608614788459, + -0.5182156301713601, + 0.11839130076986926, + -0.06290148538577811, + 0.07347788747786355, + 0.4198270718255588, + 0.31030886007789316, + -0.004483510580180261, + -0.7390706554968345, + -0.25473018188852004, + -0.6208399227947098, + -0.44517076536548766, + 0.20001180261209694, + -0.10525293670637237, + -0.4108488105507192, + -0.4749793245299859, + -0.7141347119311063, + -0.16578247675085844, + -0.12965632501927304, + -0.32378983253535865, + -0.05576225565107917, + -0.05821355913759774, + -0.20664282948630064, + -0.7788707482239364, + -0.6863292070379448, + -0.6879305808918867, + 0.08579259855481736, + 0.1860865684075741, + -0.5629486969409012, + -0.059895622367331924, + -0.6715743079933197, + -0.7482505678465471, + -0.6356396915163044, + -0.34874040439314036, + 0.058348508198604265, + 0.2315699067640784, + -0.050124488726073446, + -0.1732296614559764, + 0.30854851396069516, + 0.17266164152523222, + -0.26437902351799036, + 0.2824452963595292, + 0.0032204766068074653, + -0.057275475269848775, + -0.4007273534076439, + -0.0357667993146088, + -0.027800311817403056, + 7.01602968140036E-4, + -0.2877221333554525, + 0.2622305484685876, + -0.4557026168653967, + -0.1647907254356158, + 0.17634727586121612, + 0.37196744803405335, + 0.14825937099880715, + -0.8102823307622364, + -0.46964297580563363, + -0.06446033458484157, + 0.4022987080392213, + -0.5318114637715431, + -0.5364334778289647, + -0.05125624929436101, + 0.04071251619681138, + 0.11955611810793543, + -0.173020150148671, + -0.37928774944100674, + -0.27812732458144673, + -0.16747969873353608, + -0.24177291778991616, + 0.4200093655319477, + 0.35522827160021087, + 0.1310530907864792, + -0.727717025421091, + -0.692829496928937, + -0.21388955809521937, + -0.7972284803479865, + 0.1407831983513841, + -0.689326553395478, + -0.07827626080604033, + -0.192198485745403, + -0.08700701589026671, + 0.03976352971525243, + 0.45141386552009655, + 0.15422128102804833, + -0.3710017634086661, + 0.3865461641005665, + -0.44576708732159465, + -0.08641315202893718, + -0.5367746940434531, + 0.31032634796704817, + -0.32650217335958576, + 0.5407248174318948, + -0.6328345447812502, + 0.009754753258556792, + -0.11014378407078418, + -0.04317902752804792, + -0.7651567762006174, + -0.3080261290789803, + -0.13651181947086288, + -0.009068456922996182, + 0.11457513047419043, + -0.34184355285294765, + 0.10968523825727072, + 0.036314112656835595, + 0.40776821973510535, + -0.5319789659564945, + 0.021338633284716524, + -0.2437616537683619, + -0.6950510511234288, + 0.06629237507924146, + -0.4740083457406461, + -0.39861215594823585, + -0.10575616779158759, + -0.6758903688543212, + -0.6309834608542364, + -0.4061907140455842, + 0.13021249880055075, + -0.717391896090114, + 0.5072578107541357, + -0.818042348440045, + -0.05991745186028574, + 0.43766137293034824, + -0.3789233918089672, + 0.4031929447139311, + 0.5495317253936978, + -0.04618253937223704, + 0.5126505102087504, + -0.03928991128148818, + -0.6960834835252644, + -0.8279662878497888, + -0.5452726497506994, + 0.5402240394935307, + 0.008808223377965052, + 0.43239334738009316, + -0.5554853521712213, + -0.7362845899756932, + 0.3760090572300161, + -0.6471417826847002, + 0.5577038929153761, + 0.24171773893217718, + 0.5507994082881174, + 0.02747846553967792, + -0.191381930478573, + 0.20021878576965335, + -0.3195080229762759, + -0.6091663359513408, + 0.07572494795422968, + 0.5598133686491733, + -0.6356091054619364, + -0.1634705586228684, + 0.5439497493173309, + -0.4384803495393443, + 0.4466559907514924, + -0.09222991196862074, + -0.5840169797674009, + -0.8415047705133795, + -0.8517943165721304, + 0.45027465869578975, + -0.7277762600774709, + -0.6395959722845003, + -0.623068709903789, + -0.7949514812911215, + 0.28197781481646134, + -0.20774780558047212, + -0.8518237061845072, + -0.6947908526992299, + 0.5251174468911481, + -0.4078187023110212, + 0.3249199488120462, + -0.6850357078341452, + 0.4669330423805982, + 0.43448662355279843, + -0.07763640898389135, + -0.013196806964642649, + 0.018892850754874457, + -0.6758908589509383, + -0.24111485344321804, + -0.5377530876495873, + -0.11155032788347052, + 0.3519434100509826, + -0.37150871202988917, + 0.18590158591767603, + 0.5470375577073829, + 0.466550323693947, + -0.5199041643340641, + -0.2794156537271256, + -0.31309437280182095, + 0.05136772690773295, + -0.3124434032726281, + -0.7326459677518763, + -0.8114325604658542, + -0.1588949087406364, + -0.007099599037325155, + -0.63413548109464, + -0.18473698674722405, + -0.7855995251460426, + 0.31797656531617746, + -0.5511538277486376, + -0.18483985111448376, + -0.49282481457737204, + 0.37005554525158724, + -0.6576051100354118, + 0.37955125932174827, + -0.48211962146436643, + -0.6830168316638403, + 0.44975560403504655, + -0.17553972799844286, + 0.0752702828788886, + 0.4344892398175737, + 0.0017981072598352021, + 0.4249717974182792, + -0.3167487434502647, + 0.007194352438750218, + 0.4147450319431665, + 0.03870489098645635, + 0.43923664058837364, + -0.41410190555579074, + -0.5507562642642059, + -0.6002242494682576, + -0.10889498890575233, + -0.8211364250177392, + -0.05216695685383055, + -0.813435505687969, + -0.6406626215087391, + -0.8559721363598547, + -0.15171672614348708, + -0.45867492586058906, + -0.14565712992480384, + -0.1564171547689166, + -0.06328246972896578, + 0.43101608898524013, + -0.03778188962600604, + 0.10901000941306593, + -0.009638636199291839, + -0.37616334727358613, + -0.740900829544233, + 0.3599456294264247, + -0.7542439796216813, + -0.39732116522473215, + 0.04594369661437181, + -0.044118080137605986, + 0.5087345091062618, + -0.19611724639460215, + 0.4951832614567946, + -0.5016177379458797, + 0.49955609511961185, + 0.01876790277387408, + -0.8634371628892029, + 0.44313346139197973, + 0.23381745363397255, + 0.12391542479982032, + -0.19483092984335237, + -0.03115651222434801, + -0.0748923963326582, + -0.2909875517339614, + -0.8120242592617036, + 0.39125943606114544, + 0.3197149340035288, + 0.5037365780160594, + -0.7865169701103724, + -0.07842911778423156, + 0.5159106792120756, + 0.3787140268000646, + -0.6547044160307728, + -0.7764388745810463, + -0.5641987441097946, + 0.5459753927929198, + -0.7312173538202661, + 0.06377122475776886, + 0.36161889591916085, + -0.2011928652932965, + -0.02452917369304275, + -0.6623163571566645, + 0.19318402075496643, + -0.7680107225383619, + 0.5293349705021955, + 0.21250897512490563, + 0.02319244159671796, + 0.3329803930375561, + -0.26606297088924136, + -0.7211882188708287, + 0.5390969737854723, + -0.21079993924061557, + -0.864605342272505, + -0.38837941348160765, + 0.41823597843668536, + -0.2552342590944848, + 0.47685912562011135, + 0.1985543466987243, + -0.765263413888327, + 0.361471382404994, + -0.634890228910368, + -0.5502515879482714, + -0.7358340527613334, + -0.03290562162866595, + -0.6310675073706142, + 0.04800385316724831, + 0.13375379003360566, + -0.8652846394001897, + -0.2793727216909806, + -0.3937958094480469, + 0.3310692396487487, + -0.052468258565638526, + 0.3771169872589444, + 0.5637009912118205, + -0.8518855805981844, + 0.0015315422389104993, + -0.5926570510789044, + -0.6173962716125588, + -0.749087791410619, + 0.5210527522597037, + -0.5956184368946456, + 0.5369012082013984, + -0.11429498626221712, + -0.3056524866330588, + 0.4495692488647667, + 0.4503964372073588, + -0.7635852121326956, + -0.7198688334415346, + -0.07813682854911252, + -0.7253477646339248, + -0.7173358299905993, + 0.4435781861402128, + 0.5418804812575939, + 0.37541179008047276, + 0.367793648712466, + -0.4647432655410691, + 0.5225078456357366, + 0.192889566648901, + 0.12026637433267062, + -0.7157410791653203, + 0.1378599933829372, + -0.5887552907661215, + -0.2957678214516416, + 0.5632351071766402, + -0.6369362230310561, + -0.38698062283174695, + -0.18683594741251452, + -0.5594493911635658, + 0.2842042894066805, + 0.16058962227785867, + 0.04432197487432976, + -0.05770550757308479, + -0.6796031812773596, + 0.2674603432153968, + 0.16758932031493412, + -0.818725660312715, + 0.3504954759943526, + 0.44791000914801327, + 0.04598237220491208, + -0.03704179361504989, + -0.2309030030525301, + -0.0836164693584035, + -0.6796808305829967, + -0.40784190086486993, + -0.6066137203898629, + -0.07805674649748462, + -0.29385442236408976, + -0.11562649826440707, + -0.026921161793954873, + 0.2405436575349862, + -0.8355938382810748, + -0.32692775789958584, + 0.1499520575686153, + -0.017869928634047128, + -0.045928806531637334, + -0.5800190816865176, + -0.15883186816506134, + -0.36896359121993577, + 0.4862642781207913, + -0.6777043588550468, + -0.2622408658763954, + -0.2948227422362716, + 0.3806231540359224, + -0.6050025715190228, + -0.7564738508905979, + -0.2607694147142795, + -0.32665129689793715, + 0.4802266512899871, + 0.5514534603766414, + -0.32357829660776183, + -0.10966331648303418, + -0.18474308356253255, + -0.8282230594740453, + -0.059921587527557385, + -0.12601453819306552, + -0.04396626419907057, + 0.5139518760107307, + -0.2152452973364769, + -0.28785782734667664, + 0.5094144642382072, + -0.024440315940866486, + 0.20807240106587388, + -0.8315414195186976, + 0.21025281855639055, + -0.2701943176777376, + -0.7654364486815748, + -0.3215723566265446, + -0.7535751361087384, + -0.6392278810591489, + -0.6452437646269187, + -0.8431004263812488, + -0.3799961063253469, + -0.5825428212683781, + -0.8320893359579377, + -0.1697417912596364, + 0.5348883250576608, + -0.5398588655172005, + 0.033431877076000704, + -0.5936697758384981, + -0.5226161055642864, + -0.8005560044809275, + -0.7965105168861248, + 0.3691242412648177, + -0.6937862250976627, + 0.35040605694472116, + -0.17837693648816766, + -0.244417601573369, + -0.61445180314855, + 0.5285543882052453, + -0.3523988989368124, + -0.3929565690842258, + -0.25350446893161704, + 0.5494745589974974, + -0.784542909073046, + -0.026281905101789516, + 0.22426126289453552, + -0.48173770881949635, + 0.3657409224673236, + 0.22231997975545004, + -0.533008653233666, + 0.20366288727084259, + 0.5221387828568655, + -0.46873357382996406, + 0.25501152040421027, + -0.696628596467591, + -0.20655848053545944, + -0.5872283749478526, + 0.09218788896682362, + -0.3923477529963874, + -0.1315133296675458, + -0.340391297729581, + -0.49835602820474256, + -0.6831693073719277, + -0.6504985539682296, + -0.4464016029583402, + 0.3083473534329655, + 0.02955822240011019, + 0.1063968560492704, + -0.3854928272752617, + -0.540142312781615, + 0.4576868194109005, + 0.5334145898100575, + -0.0783177351659271, + 0.19813312007249162, + 0.008691486862014042, + 0.15814388878615793, + -0.817023886091732, + -0.4287405988809998, + -0.5299198482675674, + 0.18443690919759081, + -0.47348635773960435, + -0.029509244909436738, + -0.7253918341258397, + -0.05981434753028225, + 0.07553154012871244, + -0.6487033184681834, + 0.15544192300755477, + -0.5526306676535154, + 0.2975907768675785, + 0.15859166967871352, + -0.6899725342441001, + -0.25493758769107966, + 0.5089181953505029, + -0.12794362933392378, + 0.493937820145141, + -0.8216215855692749, + -0.2825159738467733, + 0.2008234845723289, + -0.13975043678519639, + -0.5203618613600492, + -0.44912390297532134, + -0.37013003121980265, + 0.3691974469982584, + 0.0805086096736567, + 0.17742568480365284, + -0.4895806193565768, + -0.4544061923636817, + 0.22068108536059627, + 0.12406554753917809, + -0.3706282436926665, + -0.806838857155417, + -0.515167385407844, + 0.28050884845879653, + -0.3635706768830289, + 0.23335914662882473, + -0.14422600712656497, + 0.3689729392521601, + 0.5679998549181433, + 0.5493094502722031, + -0.5837931163262116, + -0.5674625253155892, + -0.34442801379799737, + -0.6471531649982707, + -0.7507870983282026, + -0.6944123931368477, + 0.18044808988204997, + 0.24515893886268603, + 0.4210809629463417, + -0.32074006225673923, + 0.43770313780987213, + -0.08497637931289148, + -0.18821017236137638, + 0.35835074123863, + 0.4956150067880143, + -0.3514560599728854, + -0.8137668322032384, + -0.3758968042507638, + -0.13829848628368346, + -0.07520154368788323, + 0.11363502815012783, + -0.18416468255804352, + -0.6719914398681339, + -0.028741315801634082, + -0.8464461227217549, + 0.4468618451977715, + -0.5641194642674763, + -0.7845925640604738, + 0.1866804611778774, + -0.0782595327421759, + 0.004736717244885891, + -0.7248991953322157, + 0.0251440840829813, + -0.36125459080621347, + 0.1255743954403532, + -0.7830034669784431, + -0.4004280737190602, + 0.24042534826844375, + 0.1979768712552028, + -0.4971212024310576, + 0.12845008046197504, + 0.12906935510861617, + -0.07786114099226804, + 0.07613821286741562, + 0.38901439772730284, + 0.1924930486684493, + 0.5295942862003784, + -0.3355837376907339, + 0.013925460825616187, + -0.6732898797620178, + 0.19504827614124998, + -0.7398764086102974, + 0.01217470396702336, + 0.37511663833189957, + 0.14625413708500568, + 0.44743138184511233, + -0.6794539534138169, + 0.40631697652087584, + -0.44905709304703023, + 0.15724873243300475, + -0.5681133120449617, + 0.033024748357831646, + -0.33575436287438276, + 0.14243800229746184, + -0.27636035634004286, + -0.05226496569474026, + 0.23552971216041585, + 0.3800550089255532, + 0.22897184041625063, + -0.13122234458848692, + -0.4574266914753337, + 0.24521590428678386, + 0.49249512101795667, + -0.47678803189545765, + -0.8007984017689251, + -0.3083228062660127, + -0.5353439109907986, + -0.7218025206253171, + 0.4191604917731975, + -0.6975416090395639, + -0.3631013593262977, + 0.5352073909910875, + -0.7219811416690617, + -0.5539255072599483, + -0.6652274743309413, + -0.09919264590404286, + -0.6145302225191196, + 0.5276271932206136, + -0.6330568613761108, + 0.18913693557305256, + 0.4534704854495153, + 0.20373650512234165, + -0.5601386149996802, + 0.2802157176280955, + -0.8476046805121642, + -0.5075965674736702, + -0.3490687223262272, + 0.5570572791276351, + -0.7361946483728283, + -0.6852966525928147, + 0.027590744124519007, + 0.4259739665301643, + -0.7830952533086055, + -0.5355883104702968, + -0.7904282123555648, + -0.06736429362501939, + 0.540708371477671, + 0.5286358945430008, + -0.48263580169732195, + -0.7514243827223145, + 0.14286897210924732, + -0.16727085630210603, + -0.6070124151603566, + -0.13225482227463747, + -0.3314468164448152, + 0.2920115541570891, + -0.04575628085651473, + -0.018340822193554596, + -0.4182319253454998, + -0.6136847253541307, + -0.4301168921319787, + -0.01425078252921208, + -0.474368878550999, + 0.17293140248056504, + 0.4633194977124544, + -0.746684978621531, + -0.3919462569706351, + 0.5448759520751094, + -0.30548167992349995, + -0.40944603024368287, + -0.3047406673934483, + -0.332090196934439, + 0.03703479241840557, + -0.7727216710972382, + 0.33926568118023703, + -0.34395832657260383, + -0.18648553344840557, + 0.02687876592970695, + -0.7105134586242587, + 0.41325269902866024, + 0.3616897103275931, + -0.06421028504374637, + -0.6808524095612685, + 0.447597420481769, + -0.5491614182991906, + 0.1806061678375337, + -0.37473445105322895, + -0.664269864649377, + 0.46498704789542655, + -0.7555192592273756, + -0.5184121482221482, + -0.3626449182219448, + -0.47422205624506136, + -0.7751084049009909, + 0.08411480753090272, + 0.29719690626218664, + -0.5990086808572148, + -0.5553807339737875, + 0.21923756822552343, + 0.12030820760343441, + 0.5336754075185344, + 0.4019439775044771, + 0.23756253073395128, + 0.30259758668707937, + -0.3518200864697858, + -0.6758651062471108, + 0.3636108280246584, + -0.16509674238273864, + 0.5313374889795586, + -0.050060500679253384, + 0.3480436246076828, + -0.6932424322034467, + 0.4929567564859634, + -0.3566872783523307, + -0.22164540812772737, + 0.5229521382866256, + -0.012903842103757945, + 0.5577309796431029, + 0.550791623341123, + -0.516773962198853, + 0.5627772585576305, + 0.38989156888232945, + -0.5465594956888004, + -0.8111085789678508, + 0.4701006519748343, + 0.09823875501868484, + -0.3786097735868933, + 0.2797295557344053, + 0.5559322374639588, + -0.41665729240888427, + 0.06120996467200901, + -0.1671270305508512, + -0.43873272003944697, + 0.2985890140981238, + -0.6428538441707263, + -0.3686309715489465, + -0.09638444792369705, + 0.1659940333326515, + 0.09392284939313622, + -0.3045803736172664, + 0.26291525866111853, + -0.4824656301190116, + -0.36003908627023284, + -0.06944390122434396, + 0.21185959663048193, + -0.4188620110985345, + 0.1182208778250724, + 0.45103041119474097, + -0.13648572034979456, + -0.04840907213165002, + -0.24696817849099806, + -0.823396311110811, + 0.08887734837776506, + 0.2766553673182288, + -0.6161808381262777, + -0.03697671775790867, + 0.2870041617214436, + -0.2996751661607626, + -0.8545475731186042, + 0.2706173304917767, + -0.39957920065608715, + 0.172572874208633, + -0.33257787177256604, + -0.4271707014307076, + 0.08036805338013786, + -0.1585277273580744, + 0.2596625999053561, + -0.39554963137702914, + -0.0128343292869868, + -0.01859758486512253, + 0.1938838135686618, + 0.48347605551116146, + -0.1693997386974797, + 0.2538998612920156, + -0.22969455487795176, + 0.14825636759761118, + -0.19819041736481535, + -0.8511785371799444, + -0.30260234458372526, + -0.5838237605660784, + 0.5085614052921608, + -0.2558387996679009, + -0.7216271783255273, + -0.6473913134082507, + -0.03415364319750491, + -0.7705942702878886, + -0.7844789686820394, + -0.5172871281937925, + 0.2459992201187562, + -0.4140016875732543, + -0.7832431655223205, + 0.3354824702069743, + 0.08757387879491008, + 0.4887112463509873, + 0.4133873775805481, + 0.3986125462632737, + -0.020433470974657086, + 0.3759817453675589, + -0.16429306634824525, + -0.4496409485445045, + -0.2973903246058859, + -0.5531764752657968, + 0.02857891767457643, + -0.7656945087541976, + -0.3069412487621199, + -2.9339139748341125E-5, + 0.16444930287693982, + 0.08004641602338569, + 0.018552940207674284, + 0.24501962344892236, + -0.23693789984144986, + -0.18055276095596196, + 0.4700878128469139, + 0.13214753265969514, + -0.08809511495770528, + -0.008818773640919986, + 0.48663583734873694, + 0.27508381480623134, + -0.07125509785243445, + 0.24543873929169413, + -0.1555568462876854, + -0.04935969641120286, + 0.27797731140294935, + -0.5747905108081299, + -0.8039722740802748, + 0.19103319710078503, + 0.35951799447899035, + -0.12010778169832714, + -0.09080351213108129, + 0.03783202233067362, + -0.8270052965058172, + 0.40588328191117484, + -0.7468294832368908, + 0.19767561663869349, + 0.2663034101427002, + -0.11039115789620713, + 0.15080319839882406, + 0.30032685306330276, + -0.5866128667210395, + 0.49383716672175604, + 0.2208391157595888, + 0.3938260255309656, + -0.4087280171348672, + -0.6071583790195882, + -0.028408286992154252, + 0.2593256238532795, + -0.5221113248323748, + -0.7317739223555245, + 0.39585041620945005, + -0.7884772425522276, + -0.23462844103017788, + -0.10025489690330625, + -0.24932613374921453, + 0.2817420554898513, + -0.48417441650819015, + 0.5481741536989442, + -0.14588893822197735, + 0.373852427523496, + -0.8320621280084265, + 0.13929853702497663, + 0.10468847406626347, + 0.4573592304862921, + -0.0535902843239231, + -0.7721984427612633, + 0.1382930407234162, + -0.3546603011272409, + -0.6837331876032878, + -0.11391708911653375, + -0.43097924476130006, + 0.3254245428636089, + 0.28567450598869026, + -0.8368223096970313, + 0.28869060159296156, + -0.7047111878447386, + -0.4976193970939526, + 0.35772509427784316, + -0.16190107624252104, + 0.40865729875918433, + -0.22989843209421323, + 0.1838368764351348, + -0.13629426166655456, + -0.20564758737898436, + -0.08269713678006851, + -0.257389830597784, + -0.43797606688110186, + 0.26538446684887984, + 0.16591528586889925, + -0.22132367099498396, + 0.10246674854636917, + 0.22083527556054072, + 0.31270540736397767, + -0.8216713205459993, + -0.7399504979132201, + -0.5731282254729952, + 0.023249030412974325, + -0.142465486095666, + -0.5623512699184494, + 0.2849410996754693, + 0.4830821294376031, + -0.6378312895761763, + 0.1586643503401013, + -0.22838340861821327, + -0.12805649537705333, + -0.10076051685375909, + -0.7190836079097105, + 0.4686196454272311, + -0.24665761492293914, + -0.14356227206882244, + -0.386191159041871, + -0.519839893711838, + 0.4587390349146263, + -0.10966180747460641, + 0.15910901917446663, + 0.14465206081426896, + -0.651183917312661, + -0.5885570665902868, + -0.5162752337099163, + -0.19359279328204937, + 0.5072090265355209, + -0.6620416124274751, + -0.7241313026985603, + -0.6125636845098084, + 0.14390347023935224, + -0.15437367931826051, + -0.1274462406757968, + -0.5838669898686242, + -0.46174459102933435, + -0.3839577785790684, + 0.5119642595303484, + 0.24210914320392862, + 0.3583804875047085, + -0.826622755646466, + -0.09855911333253631, + -0.7118323520607587, + -0.24392228007965033, + -0.8146022151926732, + -0.6198078575303817, + 0.0784755487413098, + 0.41373113459009647, + 0.4619981795187489, + 0.21952352609328596, + -0.2472848319156683, + 0.19799427730591868, + -0.28374447051875806, + 0.007079231997767721, + 0.43656003856262715, + -0.6265632623887375, + 0.1798657805957018, + -0.7253869708671647, + 0.08171098632782792, + -0.2978513474041514, + -0.7120214557510672, + 0.19173830079081222, + 0.5027988288311183, + -0.8399318528498452, + 0.5003464865865319, + -0.4347200431393139, + -0.09691277873750304, + -0.30983848110079404, + 0.4075423126435229, + 0.2268882093482274, + 0.5561368910170614, + -0.39763361469738173, + 0.5241433313888846, + -0.4876121250561742, + 0.19096491820930317, + 0.3973743776691687, + -0.43088356571934217, + -0.4467982891687077, + 0.23255884136364857, + 0.34080635476806975, + 0.27220675098269864, + 0.4376670065845245, + -0.13769899481403924, + 0.17293374713489018, + -0.5667623705084973, + -0.7671770897427748, + -0.7760246435550455, + -0.29423808307869626, + -0.4803511497292016, + 0.3327034825386641, + -0.0032852746689013834, + -0.33628361798728335, + -0.8543778606917724, + 0.21653294331211237, + -0.44803110826274967, + -0.34815287082111934, + -0.32693329918356395, + -0.5838993082449155, + 0.5161453011066388, + -0.27214583517160174, + 0.478371069395362, + -0.5427008666329363, + -0.7472496823484759, + -0.7296097445817937, + 0.5379479738103774, + -0.7936348016395954, + 0.521937780632026, + 0.43269553441647846, + -0.4798156267542926, + -0.529941352807741, + 0.28936274065344425, + -0.05679734623287258, + -0.671970489788579, + 0.294671417884117, + -0.0926632726825114, + -0.04802166690918275, + 0.4380939642888164, + -0.820917202292079, + -0.530810740166737, + 0.4622882885797399, + 0.08179517691970761, + -0.5910279920730246, + -0.6283849573071685, + 0.2612493657671422, + -0.28379863953514284, + -0.7682602814727183, + -0.6901483195020461, + -0.32740911799000816, + -0.8122182029059006, + -0.8161978615964067, + -0.22173108398322028, + -0.21484511275796903, + 0.4351698751057522, + -0.49943780329045806, + 0.37373865864795563, + -0.2517712235348587, + 0.11441652508985456, + 0.45690846059522916, + -0.7262882339825423, + 0.22285950545990563, + -0.5572043367991169, + 0.3297195492682663, + -0.21997088771655604, + -0.8121951365899825, + -0.002949199893468313, + 0.47266610472493586, + -0.05059437563122282, + 0.01915827871697251, + 0.09990920329697817, + 0.11487142245890547, + -0.16640518488892087, + -0.3169480318327149, + -0.8196253007049188, + -0.6538643045828882, + 0.003833951857836193, + -0.6969470332941766, + 0.07553515316562964, + -0.36341782621793994, + -0.5082098575995855, + -0.3384125574616901, + -0.607746445005714, + -0.4848689353030491, + -0.27393683586370465, + 0.3795896630639908, + 0.32620422461386234, + -0.845121513988865, + -0.5251402005630181, + -0.14646010877621385, + -0.4320596768152289, + -0.5960265998816162, + -0.2053456245648213, + 0.29348158845873096, + -0.6655289275881517, + -0.804343236284128, + 0.001136767618878043, + 0.3903302551369001, + -0.1849599684513371, + -0.7975778199357929, + -0.02167356467200854, + 0.4646266254411038, + -0.036883737586110854, + 0.5126285582007566, + 0.45800724100259216, + 0.5300016641379626, + -0.51597633109618, + -0.6797595205355415, + 0.3838815017418995, + -0.4501081259041149, + -0.2201960030187895, + -0.5461491647945129, + 0.2548774838782506, + -0.730891958011938, + -0.3507750202651898, + -0.8136623947018764, + 0.26544231833408194, + -0.816149882898108, + -0.31084478813670613, + 0.43462556803397256, + -0.5336575174641115, + -0.1732820789621412, + 0.5056613742441027, + -0.04685607036013206, + 0.11509181199195473, + -0.494604929958633, + 0.4691410036633321, + -0.36908012431961995, + 0.16312148379471525, + -0.09141715004138995, + -0.4216367851055951, + -0.6234522698188647, + -0.3504034643138709, + -0.2322746526015016, + -0.6087751912905788, + -0.8223242087842576, + 0.09987350950193108, + -0.693795889554921, + 0.331716232575507, + -0.6473949468693431, + -0.8157628035462844, + 0.24673242826391295, + 0.39773546937337323, + -0.7726837690594588, + 0.5550201567397097, + 0.5397588664207988, + -0.01356568797047153, + -0.010355709694870763, + 0.09665648189374032, + 0.09643163252503828, + 0.5525956213096603, + 0.3201125854557003, + 0.5060481819807015, + -0.5138841650821728, + -0.729518438499001, + -0.8178923071380538, + -0.11953778471490684, + 0.27680521975370587, + 0.39763507537354736, + 0.01498941393026576, + -0.005087826377151106, + 0.3519816661558932, + -0.5552846674815681, + -0.12971691688895193, + 0.29656049862699096, + 0.20501047797864458, + -0.5263090487200806, + -0.043723700310382085, + -0.8323272505457582, + -0.11773278305854129, + -0.22354600991525675, + -0.7650617700026286, + -0.6740806203927537, + -0.13613636608620305, + -0.4935048748694338, + -0.03957734725089557, + -0.7820716239101202, + -0.23020456153102653, + -0.476976460986373, + 0.20721883680499142, + -0.21965638539782006, + 0.1732024966356258, + 0.34984900061228563, + 0.4628162707583343, + 0.18738010056399523, + -0.22638364389464916, + 0.3626736596607718, + 0.5584504553167955, + 0.03724852908205678, + -0.29268339110066854, + -0.7920714374751618, + -0.4206109851436813, + 0.4342110383730997, + -0.6161671399547839, + -0.789177316716601, + -0.8084048150789597, + 0.06928281617144794, + -0.0409907921804481, + 0.24701733680320292, + -0.4451454685808498, + 0.08929206142020374, + -0.15379070579359577, + 0.2764571107708369, + -0.3418804412705879, + 0.5278587379665842, + 0.487628766633702, + -0.40729223799899683, + 0.312296519832451, + -0.7518696551711974, + -0.3702391113126663, + -0.6778418998982564, + 0.2085760553257403, + -0.6159868274102152, + 0.02571529820832863, + -0.4615756031471907, + 0.09332926868048097, + -0.6669793065979778, + -0.551862119674617, + -0.3133654058636931, + 0.028255769822494337, + 0.2924729514617528, + 0.22517756121073917, + -0.5598195481392986, + -0.5775291178916446, + -0.21952995393780617, + -0.21665796071969445, + -0.5465625158839718, + -0.14279608207044647, + 0.394463518970976, + 0.2435030813984571, + -0.06760751415706057, + -0.6665881454912341, + -0.8282668824095777, + -0.5929707019752315, + -0.4073289837915071, + 0.33352339448083446, + -0.16146564136139163, + -0.02319098788081375, + 0.217785911817866, + -0.6652006040727956, + -0.7883822890982588, + 0.4599139604852436, + 0.29724459595651864, + -0.2925745394246635, + -0.493645556015376, + -0.6824403914651176, + -0.7463371866438291, + 0.4490323558684626, + 0.05791319027763586, + -0.2529956888612439, + -0.575803535095631, + 0.3954853773592475, + 0.5215011501210798, + 0.1963368870545683, + -0.5099219469631673, + -0.25665719260177433, + -0.5020263462070649, + -0.8347655085339043, + -0.7677215423738174, + 0.26410856899686186, + -0.39465277184458997, + -0.4505357584144548, + -0.8375777761969063, + 0.2878626341167063, + -0.6446236416734189, + -0.5338686187671586, + 0.014180661060455235, + 0.22426434092601188, + -0.36129848039186974, + 0.06136683205716642, + -0.2716065840234496, + -0.7644320987027596, + -0.7743964806259123, + -0.1524720300281288, + 0.4665351307447283, + -0.06097687183654232, + 0.5301934129930508, + -0.8437712167570767, + -0.5761843084814394, + 0.06674639747749189, + -0.3036514935020488, + -0.6135187444255745, + -0.8228758391998791, + 0.41298542900686064, + -0.3541270687857979, + -0.7024802209412726, + -0.08879579218636913, + 0.27594729223383907, + 0.5071080798514214, + 0.3189827859041001, + -0.6818899934015686, + -0.7137364786431868, + 0.38642558110904845, + -0.02891876228563728, + 0.2685057475664563, + -0.43013493354849464, + 0.27157265702743216, + -0.4380243751911918, + -0.5818923412800383, + -0.8281250757754761, + -0.10278284712326813, + 0.07098228054060907, + -0.745591555863228, + -0.01504730400134513, + -0.7153839507424147, + -0.5127424791200245, + 5.166171587234203E-4, + -0.06869248504969949, + -0.4740873726450752, + -0.7755807674593386, + -0.3961718453956403, + -0.12089187225779063, + -0.26945875958923904, + -0.5584126986264645, + -0.6412848981221669, + 0.03429907117993114, + -0.68212728151403, + -0.6398165094660291, + 0.3720557687715773, + -0.14270751741560728, + -0.7613728152649898, + 0.2232286867592843, + 0.10590663468450934, + -0.32196945446722103, + 0.16451053113784653, + 0.09795610880774408, + 0.06438009458199578, + 0.44590659422398105, + 0.43249074910783203, + -0.5105712978909234, + -0.14940623961537935, + 0.4751454793301697, + -0.7358790488907359, + -0.6679473691023871, + -0.09741553436029249, + 0.43012964449739766, + -0.7794358875942838, + -0.6554510498462447, + -0.5175693595531318, + -0.7444870038395576, + 0.564103375923138, + -0.43348787885316653, + -0.5956878597466553, + -0.2308333487988833, + -0.4953817042788792, + -0.36100597325944295, + -0.5545316836829939, + -0.08851129223895027, + -0.7793471938656209, + -0.26633352819861866, + -0.6140490129328349, + 0.5509510500120509, + 0.43900929996604976, + -0.003860333386092041, + -0.441056532701872, + -0.00581923059886158, + 0.18965817365625726, + -0.3568043833507657, + 0.1797892622635613, + 0.30266231017158396, + -0.8218046320525598, + -0.14972415268530515, + -0.37391870477099465, + -0.8049922693975204, + -0.28943990871793956, + -0.8591015370497347, + 0.3041503168018307, + 0.2968973726674409, + -0.5432936796671808, + 0.03910061120992603, + 0.14338285954623764, + 0.4573884792851506, + -0.7573608233414376, + -0.2355902125520427, + 0.09703410089697484, + -0.5897871294478001, + 0.257506352268311, + 0.00864968341769079, + -0.8260828474439624, + -0.4018902615880149, + -0.6264914226829033, + -0.3797456384037127, + -0.6622959445298957, + 0.4933275603326901, + -0.12994649602989194, + -0.28500531438516785, + -0.04515009407231707, + -0.22054077887130696, + -0.4811180922765364, + -0.8499027584130903, + -0.1466434037280332, + -0.23983496474791188, + 0.2582678125519946, + 0.4701630584072165, + -0.2461546968393935, + 0.10918250119934625, + -0.7557573902240986, + -0.7190456687665141, + 0.06541888813545371, + 0.03131404330099663, + 0.37532871648995103, + 0.22133708333819557, + 0.31284384457817693, + 0.29147372048995157, + 0.24556680095461858, + -0.7590794675231979, + -0.3557201865490648, + 0.557462757063351, + -0.5447793440644553, + -0.4820346850989318, + -0.5062957012308271, + -0.3719450801016303, + -0.6499193134937375, + -0.4055568071183105, + -0.5722790613430715, + -0.7567724826953643, + 0.3261423234576628, + 0.03803089004330362, + 0.4034514646690348, + -0.3502019219407666, + -0.7754054097391467, + -4.102516282837865E-4, + -0.31999109889843613, + -0.8419806815004366, + -0.44185083574541123, + 0.4695784786992938, + 0.20731201925556864, + 0.03079154930574657, + -0.6183765586812033, + 0.44900648946932553, + -0.6671793310563453, + -0.7042106927204742, + 0.2964843555521879, + 0.49821673793486543, + -0.6303171232727922, + -0.232922340492967, + -0.7679093976485243, + -0.01633565027112127, + 0.23064496848270322, + -0.2997482955042827, + -0.856058474912956, + 0.4661993388575747, + -0.15981589353011028, + -0.394061167078383, + 0.4067673953314317, + -0.24196522480687577, + 0.5563076697858429, + 0.2020917371841544, + -0.2641537304011262, + -0.13507007456295184, + 0.4190789112249662, + 0.21494976110222774, + 0.519319104237457, + 0.18263923550341077, + -0.6269684664621246, + 0.047195666074336895, + 0.03970602332429063, + -0.13407013995052453, + -0.371656793121971, + -0.02541464099509283, + -0.037373211916411964, + 0.1897585344555497, + -0.4653442037210913, + -0.8455771743986048, + -0.563420124738415, + 0.24016029118031068, + 0.09742361214212547, + -0.19901855216134523, + -0.48021073717877283, + 0.14676220795651318, + -0.3040210336965664, + -0.24226999004452165, + 0.19148390190898046, + -0.7046344097109309, + -0.7303125352820306, + -0.3490629757185213, + -0.1092297646073841, + -0.70170041324674, + -0.19197915171410007, + 0.14774304343586708, + 0.01584082447873958, + -0.49107873527290924, + 0.19796496313536327, + -0.6941026633607958, + -0.30993266214678283, + 0.10882444639857924, + 0.5635319671980363, + -0.48640068240705164, + -0.8025294710841302, + -0.27318043760721167, + -0.19601047258645776, + 0.18526558259972137, + 0.2018933873818629, + -0.7426793437673028, + -0.47935946992896034, + -0.4332091529209003, + 0.13377289307995732, + -0.5655513396574596, + -0.13619901846588767, + -0.7262581591677021, + 0.10599947488778727, + 0.351358708699002, + -0.4581710635553554, + -0.7099209613267268, + -0.23148794100046644, + -0.329103276299073, + -0.5584831073048581, + 0.5101647895325225, + -0.3526381411679522, + -0.005376570162258232, + -0.7637513834383449, + -0.4412261968333257, + 0.14959756894957565, + -0.5947039880399436, + 0.26357742891585456, + 0.3888577230124677, + -0.687350248381749, + -0.6977833385470689, + 0.1075640635352485, + -0.30196625521025267, + -0.6863618491057621, + 0.019003938341827564, + -0.6606320975937646, + -0.577554649286286, + -0.7987483633406931, + -0.014773010152043797, + 0.09384164407224638, + -0.4131303225673762, + -0.6063189317899118, + -0.8447397126355957, + -0.11228294561986563, + -0.8038011949381104, + -0.20096842607771503, + -0.24723660971366856, + -0.8038788334948839, + -0.7820399263198698, + 0.4571479074353091, + -0.7022847187472436, + -0.5079643064492989, + -0.8355930438036645, + -0.09134856163138383, + 0.45907980464373477, + 0.14436210023069918, + 0.44232742213617726, + 0.32911508793129407, + 0.013092312627932423, + -0.13983904317498153, + -0.24644998236332338, + 0.41798437316665904, + 0.32854665566834473, + 0.21660182119321525, + 0.3693794637818437, + 0.04803043763945092, + -0.8421015640790477, + -0.3494560618246747, + -0.42866861161020414, + 0.5706512209998398, + 0.5227151684933011, + 0.5404970339910813, + 0.2435249415991112, + -0.29896408874000513, + -0.47780190750091805, + 0.0041339929518200424, + 0.4338433887533544, + -0.13322790582038913, + 0.5125801980520999, + 0.050982400509599346, + 0.30648042961042155, + 0.4583194362785541, + -0.6473893764786641, + -0.0865642491387778, + 0.21233302980613056, + -0.03682270393084064, + 0.4710933174748182, + -0.7060194359633954, + -0.8361744706733536, + 0.19065540575204842, + -0.15198805830977102, + -0.16072590847917745, + 0.4954628439320681, + -0.33456536438609286, + 0.3523506268185266, + -0.38270513835537173, + -0.5605287987010588, + -0.598217458534931, + 0.42386616455225123, + -0.019934836908555575, + -0.8414222192812735, + 0.4083799126540959, + -0.7392800819457873, + -0.2961280870492181, + -0.08336964821704385, + 0.08279275222655791, + 0.5447767212308445, + -0.6775872741529938, + 0.2592159084456991, + -0.5821397467350549, + -0.8473613748331217, + -0.09914283241057953, + -0.7173849631973392, + -0.49055480832762877, + -0.6306798893997886, + -0.771872494593313, + 0.1860392007975218, + -0.4014380205990101, + -0.29425713081566696, + -0.31578185765298694, + 0.5353191303344871, + -0.363902878461711, + 0.23335467874254845, + -0.5402299877244316, + 0.04086475578084903, + 0.4445459048419582, + -0.1005782729601542, + -0.45388228946477005, + -0.3981207949219989, + 0.4233047222915767, + -0.5612772907821049, + -0.7249984227062962, + 0.292762579180865, + -0.3719521362592318, + 0.5728811799626004, + -0.8349791978604912, + -0.8393779201348534, + -0.10749833180330415, + -0.7534156164732724, + 0.29399993698654625, + -0.004699751408409059, + -0.6426471821326155, + -0.7418905515980931, + -0.3452685691327342, + -0.8340773208626224, + -0.44546462669263714, + 0.021299272116080736, + -0.09762399621991147, + -0.758097378942503, + 0.31649289729440677, + -0.6616885284773324, + -0.23189073492579348, + -0.7927868125862797, + 0.4536841035842283, + -0.6827385729724927, + -0.31049661739213386, + 0.1625371613620541, + -0.040848837164327634, + -0.7146485837546255, + 0.027379914217576795, + -0.5862451133367712, + 0.2774469423877528, + 0.47288682028554274, + -0.23127321740334383, + -0.19974458024039754, + -0.03627764878204209, + 0.06855182819409711, + -0.2769129354057822, + -0.7062550134215166, + 0.040709189645647514, + -0.1089695838659771, + 0.09189329847720251, + 0.3701151345036324, + -0.49839153720825563, + -0.23833332573410637, + 0.43532063094805196, + -0.13580450463739557, + -0.3107306055092083, + -0.10796789591487843, + -0.1129356744297374, + 0.04414333516864366, + -0.41535544002929703, + -0.0933015987091178, + -0.3628522633989384, + 0.11890020240483257, + 0.5209085085838263, + 0.39316619023254007, + 0.03647340574137581, + 0.14226698544693694, + -0.8006458107507269, + -0.119340650374407, + 0.07566420639994298, + 0.15928105854543695, + -0.2028089646032385, + -0.6041512843273265, + -0.2879573324504805, + -0.25765352693465793, + 0.4842749248734868, + -0.3629703668721579, + 0.09182527158670672, + -0.07117364396367998, + 0.38833424349242507, + 0.06075462259142761, + -0.37417015852735575, + -0.6858179512099302, + -0.407887497520941, + 0.021544409626290784, + 0.08678728227994925, + -0.2876838244909722, + -0.7737183222968134, + -0.49904155899093666, + -0.007529344728048337, + -0.20963427296309756, + -0.533604179969527, + -0.22863883306251742, + -0.46263203894561333, + -0.63042125808265, + 0.004450412048307206, + -0.27765390088873954, + -0.04169215734499232, + -0.5994180624575065, + 0.19565350964925954, + 0.4949863487128501, + -0.4727930355759016, + 0.47283280361127766, + 0.5693562819291889, + 0.13918734025945723, + 0.5127119710669328, + -0.00101023984999693, + 0.29596298497107565, + 0.4859467756430176, + 0.0944555685581463, + -0.5255955884913852, + -0.6633058534381584, + -0.020174028925330822, + -0.8345138662398128, + -0.26679228713768965, + 0.2649806186848267, + -0.5892787354192339, + -0.09904943547536038, + -0.2586155082498185, + 0.514999892165394, + 0.3772831836668722, + -0.5812464522426297, + -0.0055661197824189435, + -0.7585320930065418, + -0.42338894178707476, + -0.21324792137003945, + 0.09199814774719461, + -0.4233613612308073, + -0.3206860803591778, + -0.3448886868025909, + 0.23047131496098427, + 0.2845783607555119, + -0.24813832351420895, + 0.4878956651215016, + -0.5643743264169245, + -0.4356166709247325, + -0.4656796680587568, + -0.20145171119569882, + 0.45619263791077214, + -0.34678388889367806, + 0.3721550000917502, + 0.39947399350976687, + -0.43771748488133677, + 0.3815729848106064, + 0.48723092218744646, + 0.2764240095515502, + -0.15311412402176083, + -0.31827189408160095, + 0.46160799841518485, + 0.05602678907844594, + -0.7578481016495894, + -0.8136069926895493, + -0.3690540710077418, + 0.30753801300031935, + 0.39472361922957355, + 0.3635170630049116, + 0.5616253884247226, + -0.030103093605118314, + 0.10474345465618395, + -0.577578238222473, + 0.287569334821246, + 0.22393122248620134, + 0.08485310403960566, + 0.44761355675023085, + -0.04737165745440508, + 0.5494005906990325, + 0.1552231963127495, + 0.5386547486728392, + 0.2724478530148109, + -0.23297594833138957, + 0.14586346111885917, + -0.1381639038726422, + -0.6686556017942662, + 0.4415387029418185, + 0.4411483533329623, + 0.2854946921678645, + 0.30833432957405416, + -0.43145089700544376, + -0.3635346576418008, + 0.4111284595288862, + -0.5132017239166828, + 0.5035665923774908, + -0.299952442388995, + -0.3158712090127075, + 0.04575094395196888, + 0.2604773753994747, + -0.5475816470889181, + -0.2244989468959907, + -0.022246921386472773, + -0.28620977396509306, + -0.5838950140003534, + -0.6025022615460167, + 0.4779541770773261, + -0.7840128341448419, + -0.766778933957962, + 0.48958346814736675, + -0.2232867949770555, + -0.20211986737900023, + 0.45216180356497504, + 0.1972119576750997, + -0.003953787849516166, + 0.12426850696859337, + 0.5147599887682364, + -0.3521636253648526, + 0.3710559609743007, + -0.6956308449981345, + -0.3144053248674943, + -0.5302709381788782, + -0.8631466446298643, + -0.5254339096258754, + 0.18397739699082538, + -0.4146437654326068, + -0.13943477624903866, + 0.22292928692988534, + 0.3731414460369247, + -0.5924376212166305, + -0.670654130853, + 0.20339235104752063, + -0.5171121900065381, + -0.6475020017660061, + -0.7338829381800058, + -0.45630071974873454, + -0.50617842707646, + -0.6911233384886499, + -0.6393660733997515, + -0.7536547519170652, + -0.8394481213722493, + -0.8205846403345407, + 0.11309771742193908, + 0.35968499819740374, + -0.5601889237354443, + -0.3585604879673412, + 0.5029126837244855, + -0.18208066047830718, + -0.24456184264709835, + -0.5284968960535116, + -0.7838317556978269, + -0.4200331321205793, + 0.1361601071515237, + -0.7482036697792729, + -0.11247775520185921, + 0.1305622375996205, + -0.846454219948884, + 0.3057395776314229, + 0.35380788385744033, + 0.4977074096243046, + -0.4433327640485504, + 0.21594900649164184, + -0.14092464337069022, + -0.041291436636792245, + 0.49666830454059174, + 0.22273892329142853, + 0.020456381694762715, + -0.31316008101875104, + -0.3291585740141877, + 0.2348118025238679, + 0.09142166475314584, + 0.06530565418586531, + -0.10958439882470394, + -0.8457844565000228, + 0.24942669157600794, + -0.10548668091929603, + 0.09343214123431254, + -0.23546295252189287, + 0.546860394896858, + -0.6219395430569923, + -0.35836052557115816, + -0.31757315503816064, + 0.3767079264784172, + 0.37496532468736077, + -0.8458814517481306, + -0.762301500498061, + -0.02468502225597846, + -0.4709725730662154, + 0.4069867609210409, + -0.05176701007517126, + -0.6387367270858044, + -0.77179196461427, + 0.1844054493794811, + 0.4919813581907855, + -0.4911303107312647, + 0.5708464386559269, + -0.6022689004257256, + -0.7243333388942447, + -0.8570346701795286, + -0.3066904940910319, + -0.44667182997044397, + 0.004202003938535093, + -0.8019513478066388, + 0.2882247226545418, + -0.6452976245473137, + -0.28693734554979833, + 0.40974526324202243, + -0.499435481992257, + -0.5916332295879848, + -0.17581134975829404, + 0.1056053570488793, + 0.07441719249617096, + -0.8343770008451341, + 0.31792731418010445, + -0.6975894826707351, + -0.010582066100678356, + 0.38149590941843536, + -0.6895837900434507, + 0.5704488413693254, + -0.12345607380513268, + 0.4384739285572061, + 0.18131652186561031, + 0.08845470269074085, + 0.5213583908783384, + -0.2589663083102437, + -0.4392398753421862, + -0.16838911852892435, + -0.4905882091737129, + 0.062881703705427, + -0.021717688616054498, + -0.39412704022204037, + 0.17967681888394993, + -0.7646150453742456, + -0.2737471849990327, + 0.38549612703243197, + -0.3661050931451345, + 0.5238673733781103, + 0.45818262160689827, + 0.1378740998271144, + -0.18852184972011032, + 0.034099540973499654, + 0.1793190463160519, + -0.7328935225618745, + 0.4024423412172313, + -0.5724573457290482, + -0.07403465121995512, + -0.801585933191058, + -0.8033196728724308, + -0.2738422961858832, + -0.5323445644233806, + -0.8272132469354051, + 0.4498596461473885, + 0.5600466808703315, + 0.08460286768826675, + -0.10755658855067818, + -0.5806281151714756, + -0.7704424597510359, + 0.5062386676843127, + -0.5087712615598743, + -0.5311128435489452, + -0.5829941055381648, + 0.28979057415291587, + -0.820065151433655, + 0.5322089364117064, + -0.18761216072557563, + -0.1478977060834903, + -0.5981385172862348, + 0.2281972009327098, + 0.14019977177875442, + -0.7467477188381, + 0.23275936976178047, + -0.11321638964366643, + -0.250916453068045, + 0.14563791022800743, + -0.5122534135852332, + 0.08029737705703544, + -0.6177375076151895, + 0.4151527002026121, + 0.42713403792364857, + -0.5872000572556563, + -0.543015861445334, + -0.806996995989619, + -0.330269172923325, + -0.31927426990957064, + -0.8119198472961915, + 0.3534120666455447, + -0.6400297465578833, + -0.18547279939595473, + -0.09185626394271473, + -0.611429075951019, + -0.4636764065212946, + -0.36621085726517355, + 0.030722575876298563, + 0.17313923539013487, + -0.1117067083070391, + 0.47254724331108866, + 0.5288745386516029, + 0.45370733003651065, + -0.6823382950925105, + -0.5676855978425266, + -0.6139829383861428, + -0.6335854349684381, + 0.192811034899405, + -0.0024453584742725187, + 0.13287259354590053, + -0.08062337077732673, + 0.5430940797944368, + -0.16019653872928086, + -0.04386951397957106, + -0.6112084357525731, + 0.2615406621712406, + 0.1794387541782203, + -0.706724959686797, + -0.2677211110518841, + -0.16199289169964037, + -0.33918984898290705, + -0.43641297292400744, + 0.05313659266685378, + 0.4580781419627835, + -0.8007308149604145, + -0.6680551380161386, + -0.7537190028860564, + -0.08799855854286487, + 0.11084016799577345, + -0.37778740895354623, + -0.36332966410878076, + -0.07204611408079242, + -0.01529493553594452, + 0.5686046653543277, + -0.8395527796541046, + -0.016633495227694528, + 0.41205346144486255, + 0.2752146247224694, + -0.6728098557208293, + 0.3506942723278246, + -0.39524019014273126, + -0.3602045914124562, + 0.17252616559275502, + 0.5356794359277264, + 0.46050730721223476, + -0.642029403981299, + 0.4873610268111299, + -0.3226698330479385, + 0.1488254624966301, + 0.5398046846420335, + 0.16137235848981235, + 0.03957863452474464, + -0.6516271346629332, + -0.8463017858656255, + -0.7500415300996814, + 0.24999973380065366, + -0.6091414456980548, + -0.2864706525165953, + -0.5220705253484916, + 0.20521312304915962, + 0.1009401523536847, + -0.7274559675831669, + -0.36441437118022557, + 0.28764763954130745, + 0.10742469891767503, + -0.5460294289483456, + 0.4287826302972768, + 0.07280793256788543, + -0.3276652730581565, + -0.38552369474257353, + 0.15802279734002433, + 0.08170886447126591, + 0.0650523324289014, + -0.06012111545839571, + 0.4324843405930532, + -0.25825048147317387, + -0.4939002470337223, + 0.25484557003325303, + 0.34084108765516685, + 0.26097213713120504, + -0.05648978372583646, + -0.06647125935545584, + 0.2044151921154389, + 0.256030143676673, + -0.04229651909270171, + -0.11748387432538265, + -0.616180469564086, + 0.3449824361595424, + 0.3260382192583291, + 0.010464906529598417, + -0.8229935367077977, + -0.2520398365023133, + -0.8594459532099404, + 0.30599239877832685, + 0.09768198847719511, + -0.4573017708452276, + -0.17431084502802496, + -0.43057324468802394, + -0.09688258623184454, + -0.6211495625842187, + -0.7376756580000732, + -0.8010848891173104, + -0.17903467355950153, + -0.8608733954627402, + -0.2798176312469044, + -0.1745746651282204, + 0.43611588116351596, + 0.1979975468167614, + -0.4441290706589586, + -0.18150565301774246, + -0.5210464983211207, + 0.3562592108329494, + -0.21062571607352953, + 0.3123978061280488, + 0.011506478388027652, + 0.07795211593124018, + 0.06201783129639549, + -0.49456782283009737, + -0.4347485229601763, + -0.04859838861856258, + -0.7862496764436054, + -0.6765280005142229, + 0.10293472266127746, + -0.7987252139224961, + -0.45607156316864883, + -0.43227468621815457, + 0.5722411421385696, + -0.028401713094380998, + 0.41889620625055635, + 0.5051827108494422, + 0.12405763293684013, + 0.042888029323559285, + 0.4491948458333106, + -0.6711402458754786, + 0.21752050528299072, + 0.250672089315253, + 0.48804589378734375, + 0.48223358278711403, + -0.6896316707600407, + -0.8539399501747809, + -0.12157760624004177, + -0.36710488127882224, + -0.39271147490916924, + 0.2530016160029278, + 0.24660690951248743, + -0.36184035582751395, + -0.49414793878643093, + -0.11954415794111473, + 0.5112356181472113, + -0.8299896561651939, + -0.45531445116486347, + -0.31935873872526, + -0.23016687933675617, + -0.7477634602213625, + -0.5591401914743588, + -0.1971980767189182, + 0.4079030125358256, + 0.3449214255172506, + -0.8210374439075871, + -0.23402507231214764, + -0.40225341081975124, + 0.44772221986171434, + 0.19162965132609244, + -0.38417204418316475, + 0.27227511190322917, + 0.3021246679510372, + -0.4658214051793032, + -0.07879930020149961, + -0.07592510272171815, + 0.4264786993709573, + 0.17951503615006126, + 0.48513796816710375, + -0.06567131934352122, + -0.40146871009059387, + -0.7458729985800804, + 0.3806399532677296, + -0.25239470570092837, + -0.0030890730980135395, + -0.5552973917448436, + -0.5221980397724795, + -0.7222152811028232, + 0.5032009772484396, + -0.29945881332695956, + 0.09372621100139189, + -0.8031998810761245, + -0.012457078570529578, + -0.6262815753898228, + -0.21806505554406153, + -0.5600397023516299, + -0.2918344343451239, + -0.22105673651730473, + -0.41528659949327995, + -0.06546904655114316, + 0.20146720492658932, + -0.37917696152951214, + 0.23087909622096392, + 0.1633270169607064, + -0.29234460674042295, + -0.5686398740577376, + 0.03421441271894132, + -0.10935673009987035, + 0.45691895140658434, + -0.6687211478507818, + -0.1158754010601587, + -0.23461113115846421, + -0.8344722262888639, + 0.44401555327044084, + 0.34048450221485216, + -0.15292940628081186, + 0.4702370977532997, + 0.5027496769575219, + -0.4238032428820775, + -0.37895676352466307, + -0.24140186828921073, + 0.4261777098003119 ], "y": [ - -0.4096477562911808, - 0.18749260441031212, - 0.06829721654937981, - -0.3420770384581052, - -0.002400526314887297, - -0.05280192308722964, - -0.0992651736968383, - 0.1350288547749806, - 0.22223964534114926, - -0.4706655183556956, - -0.17309649352630002, - 0.23150911877578784, - -0.01681238732072965, - -0.03741269378568901, - -0.1357618925817779, - -0.30092878538489304, - -0.534378459885241, - -0.19578006790418684, - 0.2912924564325504, - -0.5042385029352286, - -0.4300259583824423, - -0.2843904054179383, - -0.36787548974181916, - -0.2815098363746651, - -0.5470363113358362, - -0.34183338847426625, - 0.10370262481784498, - -0.3303356043380446, - -0.4819041436045123, - 0.02413515722133497, - -0.21093833729345496, - -0.07189540845992548, - -0.3776257357436176, - -0.16607875787817772, - -0.4755955212029108, - -0.49937691563929976, - 0.17497179033984134, - -0.3008125483153798, - 0.22965872215767458, - -0.15241834880517663, - -0.43622307731856613, - 0.13107917178441653, - -0.10043417541075805, - 0.2809663127286971, - -0.16803302314056062, - 0.2167759088996507, - -0.4538862624938166, - -0.15790516285907408, - -0.4844709448122107, - -0.07471141390157993, - 0.23459579767799432, - -0.2177809651298453, - 0.288896347384631, - -0.09852973632948048, - -0.3691256816979681, - 0.15534627817949254, - -0.1567868675557162, - -0.1415032947417753, - -0.4287672296100807, - -0.18730172288779912, - 0.14786019783589144, - -0.4604451487561816, - -0.3811482078659205, - 0.30988643815922323, - -0.2018690807606835, - 0.009947937293745768, - -0.03722892312233361, - -0.3482463629119634, - -0.3776719436609959, - 0.11907682583117662, - -0.4543594626125251, - -0.4566799355197617, - -0.48007945622655745, - -0.5139412176639372, - -0.12412218054533158, - 0.12447079305069164, - -0.3540823887703475, - -0.47860294772907414, - -0.10065601479392805, - -0.06579725855633045, - -0.03449143386077347, - -0.522768469250392, - 0.04277082478599248, - -0.378580523965034, - -0.07323143034227658, - -0.043336743606666395, - -0.33099872312009976, - -0.06719310636716885, - 0.043939139859997534, - 0.03521474082317433, - -0.03128157786440522, - -0.29307288854455854, - -0.26420320912087125, - -0.3810574805260642, - 0.10723144115009675, - -0.4858761172648171, - -0.47631139545712226, - 0.04552026933345299, - -0.36674988939918873, - -0.019450623568658787, - -0.09284322458482419, - -0.06077347774939995, - -0.2720366953536244, - 0.01574960021650984, - -0.48398315201884723, - 0.06365061368764646, - 0.06968275583492789, - -0.21067748780044532, - 0.21437618658262791, - -0.18136823116214262, - 0.10343687839243332, - 0.2956970833389184, - -0.49811647263109743, - 0.27288833805709944, - -0.5298248949772498, - -0.4436123361250707, - 0.08428324525514297, - -0.07583795668622778, - 0.29652835507161235, - -0.2323767840246433, - 0.029623762462827274, - -0.2782061754764153, - -0.252948003578585, - 0.026303905632580893, - -0.21577424776700965, - -0.03569026950251819, - -0.3934251623883752, - 0.30491666221671776, - -0.22293765877228922, - -0.3724701911062412, - -0.4494030396391027, - -0.5464826242001161, - -0.2788584560349018, - -0.28679290724342066, - -0.4746578372595468, - -0.256510178752399, - 0.21917952208294877, - 0.1634220526861615, - -0.11983126387745563, - -0.26018342476324186, - 0.1820106017847264, - -0.023552911188141956, - 0.19053973989112105, - -0.45132358086662266, - 0.06057494915558459, - -0.13281248096027948, - -0.4058347975526494, - -0.41638979488482336, - -0.246323288181795, - -0.048016881982824944, - -0.3303848040036139, - -0.011305029394976684, - -0.19172571112105458, - -0.5371107805580042, - -0.21497445248041486, - 0.28197046475198606, - -0.3755380212720577, - 0.17895383386143715, - -0.19931777263875056, - -0.2736119508625021, - 0.20351225683758756, - -0.29811658912611044, - -0.015383153783681047, - 0.18960668964597227, - -0.23584114884816065, - -0.5291082965015353, - -0.08656319800975848, - -0.2981745945222676, - -0.1875046959248418, - -0.5455446415006664, - -0.14622960099223686, - -0.12713376378642277, - -0.5154318849832105, - 0.21287309844467595, - 0.12629053484440456, - -0.20546332277187807, - -0.33330258384891737, - -0.19726606799756652, - -0.4287557708661356, - -0.13213310689100777, - 0.30174874831122633, - -0.03393559635834398, - -0.4220681947027398, - -0.2304380990681562, - 0.20854895893169134, - -0.2740811139360852, - 0.05876329463192398, - 0.013104171264562536, - -0.49095868166957746, - -0.0808379625323774, - 0.005699473366230445, - 0.21267490869504924, - -0.3724056930901842, - -0.16525599158197096, - -0.316683435062162, - -0.5155331207288915, - 0.1691658432762685, - 0.21073270416511536, - 0.023823423880988126, - 0.051547603663334884, - -0.03411507765507915, - -0.18092827913417414, - 0.19188483180791327, - 0.1634412058536533, - -0.1902693765153199, - -0.30844501867108576, - -0.4219294497645971, - -0.1924043319509125, - 0.025941450969686697, - -0.1085583324763334, - -0.15765536529062296, - 0.09721951147183361, - 0.18311643662899446, - -0.3643491764410336, - -0.18357417291795797, - 0.021216659216295897, - 0.0725345364940061, - -0.05047025285839801, - -0.4086619793593543, - -0.02013073741302074, - -0.43324759023663667, - -0.40587833985199984, - 0.18024155642538653, - -0.519493876559641, - -0.1387111447796216, - -0.47704755004043786, - 0.08582702543122422, - -0.35584622026431123, - -0.019798673948430157, - 0.29304112105765023, - 0.24373260742879588, - -0.4263250672167551, - 0.20030949252025443, - -0.047068262086094714, - 0.2406359467365814, - 0.14769852468105837, - -0.10546554517557344, - -0.3678499095170185, - -0.06185531500055763, - -0.14159554005623065, - -0.4072577666899947, - 0.21127728614730779, - -0.47046047692040055, - 0.24291901037548025, - -0.48760854270152754, - -0.5515672349781173, - -0.2772567153785384, - -0.46847134217597647, - -0.12317757958612163, - -0.10207462903133202, - -0.05273414279414523, - -0.0944709322472903, - 0.25173090046763846, - -0.5515814591701362, - -0.36162589456332606, - -0.13146989407969217, - -0.4336283984269591, - 0.2896663276084872, - -0.30982376906639336, - 0.15933535680410615, - -0.2990450312121093, - -0.0011885257555734885, - 0.14009974858874497, - 0.0955374583336005, - 0.12308048214799472, - -0.19255692236465488, - 0.04176497767861187, - 0.3025108928655137, - -0.5508920363778388, - 0.12167884091247472, - -0.1057413214198118, - -0.45980875238857577, - -0.3873986201181665, - 0.15678971786856488, - -0.23623589133506023, - -0.49021686953945814, - -0.38526224316472474, - -0.3772081162910297, - -0.09265524706894557, - -0.4660649211869279, - 0.017622918888313688, - -0.022438942755905855, - -0.32594918517516736, - 0.0983662184772891, - -0.15280332751256037, - 0.009731097802525124, - 0.0035530359513963328, - -0.3850144040568292, - -0.49480498332730644, - -0.18608371863558448, - -0.44576299994494134, - -0.05455849003142432, - -0.0054815558146680265, - -0.45349625031911667, - -0.5063780664579527, - 0.19625200804653176, - 0.25277991250567944, - 0.005947382356229158, - -0.3381939092491292, - 0.19484569857135547, - -0.4353378899997517, - -0.0850732386086066, - -0.3123778896159747, - -0.5481334933918249, - 0.014403622371416458, - 0.26338003733112436, - 0.18520924957382523, - -0.2789866870771953, - 0.23075438978026697, - 0.016061717899407135, - -0.5399518764654597, - -0.10202806369968481, - -0.005720177376899671, - -0.4966143526716611, - 0.04558511720508274, - -0.055881112266447874, - 0.18070858379008947, - -0.243120740376576, - -0.46654758141543634, - -0.3809026892658526, - 0.2681128577143159, - 0.12971376387259692, - -0.22035497866395015, - 0.21628491645474435, - -0.3937140388602313, - 0.29340143854925116, - 0.13001545792038482, - -0.33415002786798087, - -0.3545271911374706, - -0.2208566641085732, - 0.09518341922383633, - -0.14430127827648742, - 0.2777870006677967, - 0.07614207580049792, - -0.009788980288426674, - -0.21925183786189512, - 0.16433288006393898, - -0.02505427552186623, - -0.5173642588734564, - -0.43804556303287623, - 0.27447220443936127, - 0.16579095741446803, - -0.14627345239694767, - 0.25966335121654716, - 0.31103217672015404, - -0.11562931269828464, - -0.17374225953323902, - 0.16017644163373057, - -0.29386012422462554, - -0.04700882942485274, - -0.475406045575919, - -0.0861991064731159, - 0.2127571850365203, - -0.385003096650097, - 0.07972027323172792, - -0.12871254249913427, - -0.0026398035897032823, - 0.26462737985230256, - 0.2004682106944684, - -0.027020926878708162, - -0.5411359490672385, - -0.042537380717559414, - -0.5442059869688534, - -0.11000561260979408, - -0.2939729597641183, - 0.03526598141500148, - 0.09203645473376776, - 0.062436560434793176, - 0.14340481948356543, - -0.3327265619839293, - 0.0746318301225698, - -0.505481323851333, - 0.13237508350789495, - -0.2460483070284767, - 0.20099637415894744, - -0.23386247365548868, - -0.5317693293725291, - -0.11205751879714593, - 0.11227759765243384, - -0.20218325600231363, - -0.4567042392100063, - -0.3585676598146613, - -0.4826928022929059, - -0.1360469443810038, - -0.3936112045852943, - 0.24824635736024936, - -0.35180182801363635, - -0.24194404513123396, - -0.5458986256924425, - 0.2821303415730876, - -0.03721938497299593, - -0.08193849334935055, - 0.25899508333447374, - -0.5400401428053989, - -0.4332625180349224, - -0.28176212600665046, - 0.15555560192592366, - 0.044945075597131456, - 0.16545822973992197, - -0.2172629097654708, - 0.12468062962878157, - 0.08981734231925986, - 0.28550414527712753, - -0.009592977511525103, - -0.08215520203768217, - -0.19839283128439217, - -0.03813441536829787, - 0.2174680922075497, - -0.08655061996891172, - 0.04542487674841866, - -0.42488847466329455, - 0.12890112402350506, - -0.5483009206496554, - -0.021141416250266443, - -0.007020842361695201, - -0.3212729978544658, - -0.22734750333906512, - -0.13618846644762983, - -0.19494629657903634, - -0.1823040985174465, - -0.4047021614930527, - -0.03401530168412459, - -0.00948769585115039, - 0.11374138675404344, - 0.044410175278078445, - -0.3738309926147075, - -0.23382525750421268, - 0.30507554595916775, - -0.28834271905485237, - -0.4857062000556884, - -0.4562432521537243, - 0.22479210234688507, - -0.4707214226617907, - -0.3283549301761604, - 0.20306216047996628, - -0.20792144180268174, - 0.30018503795933715, - -0.26808993583057444, - 0.22940142969472233, - 0.2624421684789373, - 0.19850414020886764, - 0.015060620364561683, - 0.11289653276404255, - 0.06100597027636345, - 0.3172093907888661, - -0.2745566800782283, - -0.03660710049742655, - -0.04303313515987106, - -0.004755992505385276, - -0.22470992810382268, - 0.21414279827248728, - -0.23549478598058005, - 0.11511885960775414, - -0.15549324354004668, - 0.11442399128462954, - -0.4091471069484407, - 0.2843532172002835, - 0.008519357599662492, - -0.41844628752710517, - 0.16762005174261707, - -0.011954661252641552, - 0.13780231971300672, - -0.29108703933355157, - -0.5406882005591049, - -0.46580207828460873, - -0.20188703006036762, - 0.14192529524586162, - -0.3354371968365327, - 0.008357788321777804, - -0.06826565247455235, - -0.557152758068432, - 0.14163430867836158, - -0.5514136140294529, - -0.430709151421826, - -0.27451347784487523, - -0.12658546103840423, - -0.06798722612198171, - -0.4124242778142451, - -0.36604567202236815, - -0.3242592425174513, - -0.12489686501251529, - -0.22148081567431882, - 0.04673149372828167, - 0.12922687154503332, - -0.2635798127599651, - -0.480184954429308, - 0.3193054079869049, - 0.0434145682328303, - -0.2626138494640247, - -0.47212362391415924, - -0.2951687597310474, - 0.18764404055377604, - -0.10673539918534075, - 0.11989622621213591, - -0.45686553990877155, - -0.2845638949208605, - -0.519516414760641, - 0.14411700385038673, - -0.5207154667758737, - -0.14021950773265507, - -0.21618502232016945, - -0.48932031225504213, - -0.14490535353911677, - -0.3035421158391066, - -0.3188792972821039, - 0.11785127038344123, - 0.22997368516284655, - -0.11672092936347384, - -0.25086765276884054, - -0.4667531985418675, - 0.16745573593747087, - -0.3968779912682585, - 0.20022562759132045, - -0.05591436964747465, - -0.42266822739705634, - -0.3109207941298007, - 0.06370911519146616, - -0.2897798896288354, - 0.013742416542256719, - -0.42695527699600894, - -0.26857667869798835, - -0.13883166676665154, - -0.22653344304557, - -0.3719974335972732, - -0.15268839736616074, - 0.2969615148129232, - -0.2682802351886277, - -0.26692260832646486, - -0.2647624266768782, - -0.5437371353025393, - 0.025021180727972103, - -0.5538839787670344, - -0.12353979037941559, - -0.5491801536006361, - 0.1475579983818076, - -0.004520415491028995, - -0.08822855704291627, - 0.044579700001466716, - -0.28692367702351457, - -0.15260058120800685, - 0.191765551964987, - -0.022541499169476564, - -0.0968180044650499, - -0.28781918866867284, - -0.01006085980521787, - 0.11393637925860722, - -0.4725685230043419, - 0.3009305877064792, - -0.15159544119370139, - -0.5438583484875015, - -0.492462795571676, - -0.4470274656553325, - -0.4864479707701822, - -0.2656698599189881, - 0.28973935751684277, - -0.26837804878742993, - -0.3689055802277702, - -0.09238808850329416, - 0.03291251343006085, - -0.11862348774038928, - -0.2473101403678052, - 0.19386110709602866, - 0.13578073667636636, - -0.15315254865201078, - -0.14513409931843835, - 0.29105775865502825, - -0.45767627138123046, - 0.05784643780644294, - -0.028587376897697303, - -0.3499831721532928, - -0.25770519444144946, - -0.2360765093180925, - 0.07072891298986017, - -0.19302053470504765, - 0.11177570778729629, - 0.2818378934274144, - 0.21719938824581897, - 0.19496652877177434, - -0.29135957443975496, - -0.27211385929491716, - 0.20579847252463956, - 0.014435383093822307, - -0.4915601122553409, - -0.20738695800919216, - 0.030356988760285475, - 0.3024541996169716, - 0.24747342598033117, - -0.516738753580773, - 0.20344079984388408, - 0.14043924722143397, - -0.20507031108672746, - -0.26290936961878764, - -0.43694786457582874, - 0.1771094532420261, - -0.1722170453949784, - -0.41288159137285496, - 0.1402239295073594, - -0.38489495872999857, - 0.20517822769999772, - -0.1899740581322551, - -0.3988279269139593, - -0.2750535145061923, - 0.20491538210823457, - -0.314944361731795, - -0.17912654632134983, - 0.09867849284714325, - 0.1026241313456483, - -0.25325623526996793, - 0.25146605198169103, - -0.35494075614055465, - -0.16370442022524995, - -0.5438875272713599, - -0.38769583469914937, - -0.33640240933116855, - 0.30331275858715334, - 0.08051971608895758, - 0.23950853388194615, - 0.2785242585836596, - -0.033996737717092995, - -0.4992048284995884, - -0.4771554590341583, - 0.05358164916147001, - -0.3725357622562069, - -0.29128183120885953, - 0.07769423128295239, - -0.5578757233621233, - -0.06664487453668566, - 0.08951406634768955, - 0.11846662772042738, - -0.3219189502741451, - -0.3533428174391513, - 0.2841598580843534, - 0.09454768928967272, - -0.07220086540353993, - 0.1840549903355172, - 0.23866100760983655, - -0.044854509413939425, - -0.24093519277414832, - -0.47806788911538445, - 0.05437397278302847, - 0.11014176755739169, - 0.06901952960548952, - -0.07172180278979445, - 0.3165863664855433, - -0.08385107971302852, - 0.19040201602574502, - 0.16958002744206147, - -0.20281321355038961, - 0.15961758492688516, - -0.2723300887092337, - -0.4185323893625071, - 0.11537952214553548, - 0.10483934048384758, - -0.47393461907250445, - -0.4830203080593717, - -0.017442373236849718, - -0.5416632237627897, - -0.20943462510591637, - -0.2972005916998788, - -0.3134014507329055, - -0.13780229166819674, - 0.27261178915039974, - -0.3422605139278926, - 0.02023370167520866, - -0.33457861290372126, - 0.23783689344515735, - 0.2283784762497213, - -0.2324929486587159, - 0.2880656010654161, - -0.44014504178420355, - -0.2354645202042932, - -0.14800159541875862, - 0.30437255311922917, - 0.2039398175047411, - -0.21820503180283213, - -0.2808497718941932, - -0.09513645797608827, - -0.5459315170894545, - 0.21511128064621998, - -0.28780680573487444, - -0.5329112085163217, - 0.073249464212081, - -0.04017634336050402, - 0.1128448612860633, - 0.1660210110698438, - -0.31195543000108583, - 0.23166304564985574, - -0.5470908109983984, - 0.28270734319574786, - -0.517657089676595, - -0.2024080402608811, - 0.09697199820985836, - -0.1474179876627803, - -0.417560054510556, - -0.13621152331401343, - -0.1841887353906877, - -0.26239821482412673, - -0.15147954745023007, - -0.12011521197568792, - -0.4348291816046552, - 0.29123330322662444, - -0.48394620719381654, - -0.2883380067455289, - 0.29255965848160803, - 0.15625855787969145, - 0.2631154248619264, - -0.35764878768177943, - 0.31697923052756627, - 0.15993747859423646, - -0.3866643185220987, - 0.17847064390552414, - -0.18899920192296032, - -0.5016911539032664, - -0.3521003389009735, - -0.15340830118974352, - 0.14254902705373862, - 0.14894459296567908, - 0.03127042399932789, - -0.3596824521325828, - -0.204013399031452, - -0.26507141720398464, - 0.25588026092716853, - -0.08101976563593627, - -0.3416435403550287, - -0.23937150083555553, - -0.18603595722157046, - 0.023728245470781784, - -0.3291717741875467, - 0.2761978879446485, - -0.1377958333536834, - -0.39979160979012973, - -0.34574324159565806, - -0.41634446704242295, - -0.4592943009017524, - -0.11616796617901343, - -0.21679832184434727, - -0.5496491697354352, - 0.28972961169608624, - -0.5006208336067144, - -0.10366597081712559, - -0.40077605156499574, - 0.10797176487172433, - 0.2477924306988193, - -0.1959128641173239, - -0.09493030501784472, - -0.060964648209367256, - -0.15164439338259872, - 0.2850900721769909, - 0.05480580097464882, - -0.1986870983077192, - 0.23847452751595066, - -0.08708210892849011, - -0.45371675830094804, - -0.317850943677945, - -0.20340273156194533, - 0.09293215937466093, - -0.21653557611129753, - -0.2928184306007654, - -0.12815953629627058, - -0.07877302899032396, - 0.0060151165036965715, - -0.42226179969174515, - 0.2722197678340541, - 0.23633157325846543, - -0.2230021283122558, - -0.28425854032954445, - 0.2991198580826564, - 0.3181038909485122, - -0.20032446954259098, - 0.0949724573466385, - -0.19624269935795324, - 0.2592835427762822, - -0.37871012001497373, - 0.10555516137109144, - 0.2827624037575446, - 0.2078504791381156, - 0.1606807148426389, - 0.05895967876665542, - -0.0031680945545921047, - -0.19534966135946225, - -0.33996046844257133, - -0.4967688160788958, - -0.48158769396821466, - -0.45977442048832173, - 0.2599887313737368, - -0.05307484254270234, - -0.07990703804237809, - -0.28806424453704543, - -0.43398397713990217, - -0.038538010703897396, - 0.10941025748696187, - -0.045524254403607634, - 0.10620521344238898, - 0.23888853782960673, - -0.26189942725702686, - -0.44369631246449137, - 0.04204427921226117, - 0.25828716533488316, - 0.02344180521782857, - 0.30232232971084927, - 0.2714657569873258, - 0.25885854738420155, - -0.4317746429647147, - -0.5214566197328206, - -0.18383759630899882, - -0.49811004451822266, - -0.1527194780179429, - -0.5453850010787856, - -0.5374280044067732, - 0.08943832773579075, - 0.17706977803253798, - 0.12078859084704507, - 0.18071825003297093, - 0.09336061678087182, - -0.5093260966743246, - 4.531129047635751E-5, - -0.30082556017034834, - 0.23418719000749033, - -0.18366293387879168, - 0.3049332045298332, - -0.1517564413048928, - 0.12089449019887755, - -0.25485032662401436, - -0.4815285451540234, - -0.005827436795668772, - -0.3601711868682415, - 0.15832536155635657, - -0.19225413849072254, - 0.11928379325021266, - -0.2557618288584662, - -0.47895226935054036, - 0.12079317874657869, - -0.5486077324279779, - 0.14911293723439978, - 0.18050375987201928, - -0.2585795237761485, - -0.2928372692377276, - -0.1949500360155476, - -0.2315845638658695, - 0.21966842734607572, - 0.3125415973214539, - -0.48918639273942965, - -0.2438605803194177, - -0.5373574557268785, - -0.42096304098113035, - -0.48162694584234883, - -0.06778580671970647, - -0.019339121269753012, - -0.07655596283892313, - -0.5570380149935515, - -0.5177431141409524, - 0.0032080101446406717, - -0.04013310585640906, - -0.3682997310632157, - -0.09766981254469137, - -0.04471968969214124, - -0.08017754019318457, - 0.27268598010471956, - -0.48243065168627774, - 0.29484705352378215, - -0.43988919913522234, - 6.000334468049262E-4, - -0.01026899230157341, - -0.2047681682644369, - -0.5054968467559465, - -0.13026673696357766, - -0.17680185192164832, - -0.5240299659979628, - 0.04534400970533692, - -0.48214841481854326, - 0.29203703933422465, - 0.19054157313386488, - -0.31384877766020824, - 0.2742522465071242, - -0.26072695615783087, - -0.3570199069972172, - -0.16403730868809296, - -0.15120345777078958, - -0.16577696586921964, - -0.12249185036402449, - -0.24332843375832164, - 0.19955754370163137, - 0.20565232230375696, - -0.09378626207452362, - 0.32006729585760296, - -0.02132624838770769, - 0.27705066565918424, - -0.27395915396186704, - -0.025470271261353372, - -0.10363813088123319, - -0.029749597639713632, - -0.4639491885005627, - 0.29245344364266024, - 0.05502318584006982, - -0.4858309044953764, - 0.0725679788734146, - -0.030704499681003194, - 0.176058268903865, - 0.18230468590068227, - -0.05514955695356405, - -0.1451112879600565, - -0.3817541871489202, - 0.09913955235277228, - -0.4997591409208556, - 0.11861076022680106, - -0.39693728233799974, - -0.08164227704695015, - -0.0036543187811445277, - 0.06136879626189129, - -0.04463237371661921, - 0.20343140840940555, - -0.13675960206733956, - -0.29314145550000975, - -0.2623547698301337, - 0.3158908323755706, - 0.29602808309240847, - -0.19106818168821044, - 0.11386680571344376, - -0.016712935165135168, - -0.48276504632907746, - -0.04902842232108273, - -0.5192936855397541, - -0.35618657208493176, - -0.3949613725753207, - 0.24594150820639749, - 0.11081724618045374, - -0.2666641337853787, - -0.030819038143866218, - 0.13047380994704005, - -0.2757307439738276, - 0.14732241345141694, - -0.048428228095589776, - -0.2666512434631738, - -0.503297087471769, - -0.02746680080545949, - 0.1211426505770562, - 0.14616458461612136, - -0.5302501677641891, - -0.043297025791848576, - 0.021351907140995885, - -0.4465624566695596, - -0.4910254359894402, - -0.33706632442310086, - -0.2388526663244398, - -0.4711238772657089, - -0.37821727066796174, - -0.5529759216494881, - -0.25762633698941495, - -0.23596645501141378, - 0.2173086411795977, - -0.34962594108310074, - 0.15747274388186294, - 0.10189250031026775, - -0.12020483368600082, - -0.16619691133207098, - -0.2563227051654043, - -0.44289179179441107, - -0.11359852735849774, - 0.283916825414509, - 0.2971010832003399, - -0.4930625768733345, - -0.2891350870644755, - 0.1355754532245943, - -0.20360307079791023, - -0.21896873890393692, - 0.24670516199440684, - -0.4976836696548668, - 0.07876630142935048, - -0.3459380639010389, - -0.25497656010829883, - 0.09508415009098792, - 0.2843311318057804, - -0.24350642065140293, - 0.14497348583284797, - -0.3063938846356634, - -0.029569094802013973, - 0.2580083224287718, - -0.5040161816255984, - -0.41505451629923784, - -0.35530817142738447, - -0.39247556231301606, - -0.2958626262681478, - 0.031490667092864744, - -0.18615757920389864, - 0.18054547971469725, - 0.15606903853915388, - -0.38613585489970403, - -0.23026702204172222, - 0.26793015361603323, - -0.45336757470079236, - 0.20975590512417486, - -0.5377727893523405, - -0.24994075430432366, - 0.11487021050625867, - -0.29196370582056075, - -0.537415452398828, - -0.09449970134288377, - -0.2468896570937661, - -0.05157105436127507, - -0.1552267591658752, - 0.23343770254661333, - -0.3009769976034521, - 0.23314580301254206, - 0.316943957816597, - -0.3677223555508472, - -0.41407666018693057, - 0.2510288347445676, - 0.2803553598345032, - 0.2981272817132997, - 0.04084744667433293, - -0.48267224986507196, - -0.0533843215088623, - 0.2627491752173198, - -0.422372762233439, - -0.27119261432626784, - -0.5432490513713819, - 0.15424408410523882, - -0.011694763832993949, - -0.13488499363868994, - 0.04500628939326745, - 0.1565143971674815, - 0.02234772992488876, - 0.2479493861414005, - -0.3952467151229049, - -0.050546682487293104, - -0.5391935061717593, - -0.35600965085032393, - -0.3391543977918434, - -0.18108390386891315, - -0.09138449311024932, - -0.08372562565227604, - -0.5033301094499862, - -0.4007512878706162, - -0.43275342333485284, - 0.13223923098993207, - -0.09012232594169095, - -0.469151398843462, - -0.1930620731063754, - 0.25734912100963425, - -0.11718500700836487, - -0.17056854996576715, - -0.39130689247268213, - -0.39440474782059076, - -0.48099945388667137, - -0.1770930582107058, - -0.2411583560490605, - 0.3104963956343929, - 0.047960504794115066, - -0.49885464052887263, - 0.18782467718291407, - 0.2294953160129528, - -0.4054042326724141, - 0.02289557040109169, - -0.21362843603214637, - -0.3157376644106723, - -0.028094683357883787, - -0.1742732092303661, - -0.386052678039825, - -0.11626050375370206, - -0.09078939299588568, - 0.2498752181863182, - -0.34714229620169107, - 0.2005998567865206, - 0.13800702252295594, - 0.14971877624161067, - -0.1191620429806532, - 0.016479993689645367, - 0.11507270356732147, - -0.1822450800698031, - -0.36030089453010883, - -0.057400304690092274, - 0.06351385433966139, - -0.41802460839968575, - -0.551346971750351, - -0.05212209706446369, - -0.19979234411016406, - 0.26542233831288264, - -0.4682894520847779, - 0.22516937216307653, - -0.18205529921892033, - -0.36055318924197416, - -0.3243549481376561, - -0.20066356524744638, - -0.337129648848759, - -0.35736135537167424, - 0.05206019690915242, - 0.1770801077563745, - 0.1989153091627026, - -0.10977803645863132, - -0.2904041206170612, - 0.14563451385305248, - -0.5232186339360484, - 0.02629344724257998, - 0.2356336869483845, - -0.49168177439946303, - 0.011895400303228776, - 0.2351965572225555, - -0.5179810126792017, - -0.3585953517629589, - 0.053320168301218995, - -0.4579543903254919, - 0.020455016743346488, - -0.07686016224171249, - 0.21446838325102213, - 0.07621736191710049, - 0.02903203706257651, - -0.39833768977737016, - -0.1002643552610587, - 0.07757562216824432, - 0.31094916590080235, - -0.18262162268238252, - -0.404193555470137, - 0.09977703716157638, - 0.07201525200407088, - -0.014943945912369916, - 0.20137669475929576, - -0.06787296437128298, - -0.05703231926132846, - -0.5355502902389487, - -0.47143938777897587, - -0.08122066803902989, - 0.2647576899589199, - 0.17574879722838876, - 0.08415742018133676, - -0.41576841116579233, - -0.439537861381035, - 0.18526994204414737, - -0.052557625646117434, - -0.12961739650612836, - 0.09278835820580056, - 0.31985331522515204, - -0.5281938208269424, - 0.061062032970773394, - -0.5113993789134934, - 0.28909857447004705, - -0.03197992852962461, - 0.15344817445286796, - -0.03293440189684582, - 0.18057177568208516, - -0.04902511978107382, - -0.37614308016567893, - -0.15003571268334404, - 0.15125068847156542, - -0.1570340239033765, - -0.037737195397582246, - -0.23842986364473845, - -0.430244584541121, - -0.46597344263940166, - -0.29688859352720676, - -0.31294384949129644, - 0.060128936108451936, - -0.2806557842849447, - -0.19052070170342772, - 0.17418504636329468, - -0.33533793819506785, - 0.1569961115427334, - -0.16061290427196562, - -0.4031953471906732, - -0.10241949013441604, - 0.11937672882351147, - 0.2833172889013511, - -0.3842790066611216, - 0.16213538321065668, - -0.17995356029696902, - -0.01889155165988321, - 0.13437374633512988, - -0.47996284418772006, - 0.05059056751871949, - 0.2819807250749362, - 0.14842825713891072, - -0.2535557660615947, - 0.2074881328572803, - -0.09936381704749314, - -0.4312148071439521, - -0.30692795975738946, - 0.12379833142427998, - -0.08495670428917473, - 0.04675831630645233, - -0.05785868387879922, - 0.20358276961875776, - -0.14128867773803833, - -0.36439807597330065, - 0.1446230022745243, - -0.26097947625214446, - 0.2097303716116491, - -0.29580461162628097, - 0.09736983788288234, - -0.2258167394888746, - -0.07952760233261114, - -0.13434059423899047, - 0.047610886685918063, - -0.2927322657310315, - 0.16466489522897576, - -0.19894414175956077, - -0.230286421800097, - 0.07864110057790397, - -0.1034423727257453, - -0.3749111308591566, - 0.11849986473313179, - -0.06686980665934239, - -0.24326866050193485, - 0.18304595636036503, - 0.26203261108481346, - -0.15286873171306026, - -0.45816915472097663, - -0.11852224352000734, - -0.5219819577000515, - 0.17379229761241466, - -0.31908554535176603, - -0.09928118570213612, - -0.009359403979378955, - -0.42141766594215607, - 0.15290528038509854, - -0.25618268062675137, - -0.513272429599717, - -0.1114732733895395, - -0.2759135670885761, - -0.10727939474369996, - -0.35429576106376737, - -0.42782410180161534, - -0.3705079014944683, - -0.480638555389997, - 0.017557041008003704, - -0.23171366141994043, - 0.20742763359165017, - -0.16616679251213906, - -0.30248687040301364, - -0.13606437796052206, - 0.11738949300988433, - -0.21174525358909613, - 0.04747006548605881, - 0.035948873169356355, - -0.017354461127040977, - 0.047497251446131594, - 0.06315915027957508, - 0.14785157426997864, - -0.501936730933181, - 0.1283599014620207, - 0.1157778198143401, - 0.1057547451267461, - -0.48781539360131576, - -0.14680745886161212, - -0.2835319061670345, - -0.43500704878922264, - -0.40003901531606767, - -0.2060987731425643, - -0.05635982195855138, - 0.31194232808568956, - -0.38892696350001177, - 0.17274228281819226, - 0.17291257836808038, - 0.2091961855910327, - -0.3803693474626942, - -0.32543397908313887, - 0.17355068195314716, - -0.42019386201154985, - -0.21423844680209897, - -0.18710650004580848, - -0.3029925118516206, - 0.07368415934503403, - -0.5498019492214257, - 0.13921248052882906, - -0.11457494805267687, - -0.336798479975004, - 0.09110349449626431, - -0.09201355678890272, - 0.2747450642515368, - -0.16576357010471676, - -0.036895911685465355, - -0.40159579310215404, - -0.42547800126126223, - -0.22652485957204543, - -0.03270053367809156, - -0.41379011088457074, - 0.08085498068587593, - -0.21654133632102163, - -0.3143823157632485, - -0.3891672884912538, - -0.015897135120746864, - -0.02725497500116736, - -0.4439764135033165, - -0.17214680854601921, - 0.06388450203426699, - 0.21490667584232115, - -0.09957370680854338, - -0.4066876483705281, - -0.5318945592914471, - 0.12978526956976666, - 0.09579970938203153, - 0.2815921384824841, - -0.11578421581061682, - -0.1111034105280741, - -0.02115080194449237, - 0.06276541632389188, - -0.4762688046364132, - -0.38552880103939213, - 0.14178963543620937, - -0.023919083220879767, - -0.3706757919132241, - -0.06879297614023394, - -0.411350589221101, - -0.4890681157511164, - -0.07096634168667981, - 0.1285372506779452, - -0.29256442455044074, - -0.23329122179282635, - -0.3533655240870843, - 0.15113461954371932, - 0.033566352792570586, - -0.28047023518270137, - -0.3837878847941978, - 0.18197858594142402, - -0.5298419442778023, - -0.45301760549897896, - 0.20685979536486032, - 0.03297519521833414, - 0.2689705725387449, - -0.3730605976273741, - -0.5196595916502829, - -0.26354608839254173, - -0.25663306449003437, - 0.018199634383289198, - -0.3730087240067243, - 0.18669701418488227, - -0.29732450723988285, - -0.05099635358665, - 0.06954224990364866, - -0.5556991882993212, - -0.17313956062245278, - -0.1272025915980805, - 0.025200007519529444, - 0.10771085869651875, - -0.3884694236594309, - -0.48871752622568804, - -0.1686166546321582, - 0.08493539859192856, - -0.5201525555637331, - 0.2544668794551499, - 0.3036784515058889, - 0.012495378768293763, - 0.23195558274961514, - -0.030704783871677965, - -0.39073612926298096, - 0.14594506633457638, - -0.058251099740406764, - 0.12840556761165967, - -0.03234804756391496, - 0.1812073597886663, - -0.37800629036521616, - 0.2027589274305024, - 0.16657263886899465, - -0.28506841368990504, - -0.1664428698109119, - 0.14051945011192324, - 0.19894256187728554, - -0.14617664831594918, - -0.23664079071336025, - 0.25943691956295356, - -0.318823119010449, - -0.008797070079808345, - -0.510049933206354, - -0.4479448139513439, - 0.19458261389063947, - 0.2284140754884456, - -0.45725717051589176, - 0.0606640695642352, - -0.4205377014006062, - 0.04063390732566485, - -0.04527291393313959, - -0.2736419939966379, - -0.2356419192807086, - -0.09296237797393109, - -0.07858954577371186, - -0.15703101899888544, - -0.33406335808285137, - -0.4242302236223642, - -0.04834099067028719, - 0.3023714103878723, - 0.11048217840549024, - 0.24095439057196832, - -0.33602201436790713, - -0.19592024289144128, - -0.34997502353468224, - -0.14726123111038653, - 0.31872388916844885, - 0.2733406274953356, - 0.11357598035529137, - -0.35843898454499157, - -0.40412624303531985, - -0.43956186465342806, - -0.35397528479247325, - -0.4955809891484949, - 0.23525361841504133, - -0.5336764143382922, - -0.32110433447626907, - 0.25463886847148876, - 0.21856591886781107, - -0.03864468979384894, - 0.2681936650844653, - 0.235704305010091, - 0.26714442079052614, - 0.0888933052371601, - -0.030642824494499843, - -0.34743491788583547, - -0.18902206315681458, - -0.5311441986931759, - 0.04042860212169541, - 0.11541541770529706, - -0.04382886137058839, - 0.054217494621499385, - -0.4554897988176617, - -0.18257785381736374, - 0.09318475730581344, - 0.016937232178351858, - 0.19778178538323032, - 0.14991477928531394, - 0.06810597379092787, - -0.3564148451495994, - 0.10254118749553331, - 0.05929319439614722, - 0.13049339576201613, - -0.39119135206213007, - -0.23553542259662769, - 0.2034172785268774, - -0.4655398507681707, - 0.20778459726852916, - 0.28893028532248777, - -0.10512237846112171, - -0.3952679783821944, - -0.45896628385974125, - 0.060094649583873894, - 0.16112523720967808, - -0.16707717751373186, - -0.2489914420694691, - -0.22877984491579623, - -0.10525949019295516, - -0.08952715744297307, - 0.03162017253628868, - -0.5340263350614788, - 0.008109163497973193, - 0.1845737387447839, - -0.4284131563114456, - 0.28899504314322777, - -0.15340794007941272, - -0.1549228744892896, - -0.48479188306761445, - 0.017515839494207652, - 0.18473372523414044, - -0.17817560180800113, - 0.06699524097045617, - -0.14942308452019692, - -0.1103261791297992, - 0.031990319690550995, - -0.5490529685875273, - -0.1117411461617479, - -0.49577578198696115, - -0.5268055516829402, - 0.21560429651336954, - -0.1096202339188781, - -0.1337320687603566, - -0.09710235324002259, - -0.29092193608874806, - -0.03601864222713658, - -0.34115258923073366, - 0.12380783514108151, - -0.4223029127622213, - 0.06746506985552458, - 0.10696516064398787, - -0.15058052885537582, - -0.3631992429910472, - 0.002908843876274325, - -0.5035298352347428, - -0.5318065555196861, - -0.3847458117389193, - -0.25073699064778593, - -0.07605950975058229, - 0.08305211571775384, - 0.29053082765730187, - -0.12423588311180411, - 0.2828816610546734, - -0.266817916070154, - -0.0070430781601512615, - 0.14933386886713929, - -0.4129944551273053, - -0.3079391257554661, - 0.3068417991662826, - -0.3991534959927291, - -0.03612655665383102, - -0.46075957260188966, - -0.29043516093527655, - -0.23545901325547736, - -0.030505536737911343, - -0.36477776401707906, - -0.4861019220220133, - 0.2186033324801383, - -0.5206847253666874, - -0.2729487345477392, - -0.4119210671976738, - 0.21812620545866712, - -0.018616275901243262, - -0.208232203697162, - 0.11778584237346645, - 0.3163121075535067, - 0.02108950448364877, - -0.4445132844262737, - 0.2381478647598424, - -0.10604013991524858, - -0.4099322188947626, - -0.11941791767135912, - -0.19685913552357837, - -0.4943092114359048, - -0.09958410749112778, - -0.11039944170985072, - -0.5058395738764752, - 0.09792311489011529, - -0.33064679388133367, - -0.045970200285772034, - 0.013761762268814537, - -0.40113778615837414, - -0.26916167648367983, - -0.2714356769804465, - 0.03315678092145913, - -0.46288007497961503, - 0.03307920615645754, - 0.19308757103288854, - -0.023721849149378027, - -0.181192695494379, - -0.5086460382019501, - 0.16798215705469566, - -0.08385912396355971, - 0.17958030426313065, - -0.20560929198982747, - 0.08163033880673098, - 0.02773473766518053, - -0.2199216246447374, - 0.11017193325523311, - 0.2522998984538556, - 0.0651373214386527, - -0.43437276550137216, - -0.005111266017855054, - -0.334448307737201, - -0.2308088300963615, - -0.6026924268590017, - -0.005190706138323953, - -0.3227036494401482, - 0.11580678299223923, - -0.4256699047746152, - -0.36249113340203415, - -0.4789682910855698, - -0.023360972273397507, - -0.4028887542163954, - -0.1664409052027368, - -0.44090256160067076, - -0.44412643785867995, - -0.12179709860599586, - 0.03003684741681234, - -0.5895901997857975, - -0.2881291089293445, - -0.5144229256800246, - -0.3447170557340809, - -0.4213171989080437, - -0.5424058278104219, - -0.585116059246504, - 0.08720577253477257, - -0.13196250613492033, - -0.5720761474503353, - 0.013615324566599862, - -0.3086947929251241, - 0.03245373668863216, - 0.07357258551379386, - -0.0023836450763556893, - -0.4441251901838268, - 0.0768129119465647, - -0.43170514206451926, - -0.6419466438543554, - -0.2812082389009253, - -0.04574898438435071, - 0.06793054617128391, - -0.178574681660931, - -0.1507011318478214, - -0.33938055930181527, - -0.17739377977190202, - -0.02101099019285635, - -0.3535531715694571, - -0.6453286299732565, - -0.20042696241894642, - -0.4556524040962303, - -0.40706202452023243, - -0.38430416975663767, - -0.6372269055838472, - -0.07599275815899875, - -0.08075411927746745, - -0.5743606631466995, - -0.6164319877108126, - -0.05560753633274684, - -0.2037742155046532, - -0.3130169853129591, - -0.08894235205385637, - -0.22189975594619898, - -0.6107627208151849, - -0.13130386639303604, - -0.49240200706428405, - -0.3213136545253284, - -0.6047536998214852, - -0.5287860869564337, - -0.31488365966611703, - -0.10958570268042822, - -0.37905494122538247, - -0.4291928344641174, - -0.16502871053085605, - -0.08854899022514162, - -0.19660867788489111, - -0.5808593039530027, - -0.5896625206317714, - -0.10590349944984456, - -0.5419989901020837, - -0.18368265911492088, - -0.40205661112748464, - -0.28466117827623083, - -0.29826142833269037, - -0.23197440254480806, - -0.10500168136223986, - -0.5902087278486788, - -0.015255124865682146, - -0.48263776127848856, - -0.32593021456969695, - 0.06318393533902422, - -0.038711863900311005, - -0.44080064194061214, - -0.14435008662447935, - -0.17188190420074534, - -0.5526408303589537, - -0.16375708740144196, - -0.09093103624959387, - 0.09830211114661436, - -0.6039250037437699, - 0.08937852654649314, - -0.3964794523940304, - -0.6542600383201331, - -0.6425572837139588, - 0.003628074046863383, - -0.30729117600188494, - -0.0730344972743463, - -0.5005461004155785, - -0.43202594830094954, - -0.46280367255028904, - -0.5556490103810665, - -0.4813752499946051, - -0.10373134087785219, - -0.2210490803018233, - -0.5473660096116677, - -0.12339470610810266, - -0.5780987206875765, - -0.32940392400001195, - -0.24744685303288216, - -0.6276279654335989, - -0.577546006149786, - -0.6311519808148525, - -0.37805667537286597, - -0.39915943203112386, - -0.40485284205237304, - -0.37534730317900494, - -0.46083512851964503, - -0.57997896445252, - -0.18811471379219058, - -0.2612036131845849, - -0.013308321577108151, - -0.5306075420297673, - -0.49003915543801013, - -0.33365334776615685, - -0.2479358782168442, - 0.07768803870697705, - -0.03172221171929235, - -0.44962579604670927, - -0.23604858668114542, - -0.06773885257760781, - -0.6042959417597175, - -0.009923611801429422, - 0.06658949348997434, - 0.10413715433919102, - -0.31674050033735435, - -0.3283028810007334, - -0.6525263779573796, - -0.27624703202258283, - -0.06049949979946978, - -0.32551134738445897, - -0.28407472156957725, - -0.11380456051415477, - -0.4024008148915694, - -0.24198876065972613, - 0.08265621705240223, - 0.1202676952415096, - -0.3216134023349307, - -0.6388364101119921, - -0.2700119827500489, - -0.645982765748083, - -0.04845845032389873, - -0.5859298028543722, - -0.3959645437197545, - -0.43914215731860917, - -0.5023541765706173, - -0.028800520316338063, - -0.024118144328933222, - -0.07064156766499918, - -0.00872092316414863, - -0.5585188405249814, - 0.11349893510914366, - -0.5411253119822217, - -0.23198940874220153, - -0.3556382789022766, - -0.14574650430598202, - -0.1222102752105867, - -0.1305604960556329, - 0.07220059599464212, - -0.45784743423361307, - -0.06668307995330913, - -0.16090623846858298, - -0.16777226040906934, - -0.05526002733437996, - -0.3974311111363549, - -0.036593548817030364, - 0.03099674676648878, - -0.3678308860052181, - 0.0816212381533874, - -0.41755825039968997, - -0.4551889521983238, - -0.015506065397983382, - -0.5686462178807695, - 0.046650487796379925, - -0.00841742918647781, - 0.012574528517236838, - -0.16527418615600808, - -0.2096262868786034, - -0.42532794084033865, - -0.32670060766309317, - -0.11889502136762142, - -0.05740353877564863, - -0.18919393896076725, - -0.38790950854079315, - 0.11681548150533538, - 0.015607440371495529, - -0.5496871411408674, - -0.43169128243446864, - -0.4935692073657829, - -0.3677128680108731, - 0.04431017404968185, - -0.3061609001543733, - 0.1045265506473394, - 0.08358534091025782, - -0.18602149500186688, - -0.43251056738798627, - -0.6538446967601559, - 0.11023904106862448, - -0.36328898205364896, - -0.26500777905509426, - -0.05826681463655925, - -0.060036719856821796, - 0.10474737934713474, - -0.3482676581060117, - -0.22940474934462457, - -0.15427899469698503, - -0.20065990328436778, - -0.24502387107263973, - -0.5650371026595785, - 0.04659879101791575, - -0.12512415549793032, - -0.17045944401341379, - -0.43776823511016105, - -0.6228399737232229, - -0.44460045145337657, - -0.1174455592195578, - -0.5778880247793677, - 0.07260197359892528, - -0.08781497288045437, - 0.008492115270013034, - -0.17386280038915308, - -0.004599999612647898, - 0.03395433039769491, - -0.37170611904400586, - -0.526140110520721, - 0.06166299039541778, - -0.3718382639470537, - 0.09197375237717909, - -0.42557210223187236, - -0.5401628329147738, - -0.6030359011541634, - -0.47829203280734844, - -0.051398958644517045, - -0.3070277489140675, - -0.37250099022813876, - 0.07954863269139356, - -0.6635402232342693, - 0.11791388796733049, - -0.5028237494472932, - -0.3957577829435543, - -0.10242874040106331, - -0.3115857809579027, - 0.11309380436295724, - -0.030266066231571465, - -0.5043894833641986, - 0.043480282033169115, - -0.11324368702784693, - -0.3332570677147316, - -0.5056059757288387, - 0.08947184127155239, - -0.12038276112989665, - -0.6230294638491665, - -0.548854047100455, - 0.0052170269333233765, - 0.08737854097499131, - -0.11398454467930819, - -0.2877610794041485, - -0.03044649744760597, - -0.5622495151055371, - -0.13047107606655495, - -0.07745806242377318, - -0.4200040147479942, - -0.3513464294669507, - -0.48671803179504125, - -0.1375983291639924, - -0.09393807599271586, - -0.45950080862427045, - -0.003456102053839283, - 0.036130708089688546, - -0.08248411084968088, - -0.5412144344279602, - -0.5549177950643048, - -0.4503858894575679, - -0.6305711920361324, - -0.2735109387462456, - -0.6325158648345245, - -0.435198641398885, - -0.3919917743173209, - -0.4061721365295673, - -0.6355618919642926, - -0.0919826829917415, - -0.5278118969987778, - 0.01953080691449971, - -0.5838972633298153, - -0.5682998046120153, - -0.25420661959784463, - 0.02869651256265926, - -0.3790921850731956, - -0.25009228797257455, - -0.5855443941834146, - -0.46658460655455425, - -0.4203608711353093, - 0.10992421913473804, - -0.033605635429112324, - -0.6220390017361134, - -0.22748486708092214, - -0.41307540574050927, - -0.11530463109807265, - -0.653417086946047, - -0.5838714971216767, - -0.26493823376526504, - -0.03875828977950824, - -0.19382899250736524, - -0.17219140975753583, - 0.029287380230502924, - -0.6231938555731376, - -0.5141329217853423, - 0.0944324805147223, - 0.002686705644079135, - -0.47712815142336285, - -0.5121857466140318, - -0.019670715449254694, - 0.06780357319090013, - -0.4222665617179844, - 0.09236389486385577, - -0.5175586804038251, - -0.5262652859930887, - -0.32867518215792446, - -0.003989472885745027, - 0.024918991181954175, - -0.5763586539933063, - -0.587381791177418, - -0.3514460101324938, - -0.2122386181222755, - -0.418992646736565, - -0.25932929939825583, - -0.24699223257530112, - -0.06581900719685341, - -0.533833415966115, - 0.04118491083370823, - 0.04302898940360178, - -0.2950028716327236, - -0.2974924073613618, - -0.5217752265774818, - -0.33004973222589185, - -0.13843511318399004, - -0.5351722697940035, - 0.10601961015691697, - -0.3104803422064739, - -0.054790599026402265, - -0.22572951916828027, - -0.5031318157616551, - -0.44591042539944675, - -0.1897806741932947, - -0.4787413945904758, - -0.27674983258149793, - 0.12259273310639662, - 0.12304559238074164, - -0.08962334849215092, - -0.6132947910745737, - -0.4729352276992446, - 0.02845396705327896, - -0.40377751488963076, - -0.5181220231216446, - -0.013388765320207163, - -0.05841283565117272, - -0.1490072319562522, - -0.6494934640192035, - -0.6611778302687067, - -0.3190637012708257, - -0.06345546605694052, - -0.41037810268842917, - -0.301200909576346, - -0.13231942808482755, - -0.25153255438813243, - -0.3717661237451892, - -0.1700610556190872, - 0.0772436701417738, - -0.6200947911801554, - -0.11317718732025728, - -0.19490007353319266, - 0.008849889901141439, - -0.6501990645384728, - -0.12565401647540309, - -0.5692328442805361, - -0.19029658601022154, - -0.6563809242964708, - 0.04964142783258996, - -0.17390745367806348, - -0.49390339927940113, - -0.35150558857838554, - -0.06425087638980875, - -0.3604508457339325, - 0.0345713673127902, - -0.3417688742164273, - -0.32242053609387805, - -0.606778988723203, - 0.07322102527435348, - -0.5653385209121856, - -0.6393375713260508, - -0.5397213519805313, - -0.18153824683813596, - 0.09609083080204806, - -0.5171147709988683, - -0.10798925815517968, - -0.6049801814709558, - -0.12023933533441855, - -0.4115797711919392, - -0.15058446877380371, - -0.4384036753707836, - -0.4111957524322663, - -0.4803009964308441, - 0.05703965395577193, - -0.47837261323007974, - 0.09139774312103488, - -0.49392476059331564, - -0.04814512701994533, - -0.2186582554089791, - -0.08051633833374217, - -0.29260777995376036, - -0.355330309014048, - -0.4073642602278019, - -0.2935319502992784, - -0.5163463282850402, - -6.347684058188863E-4, - -0.4779388335337378, - -0.2937483993755685, - -0.07529613993075257, - -0.008225859038789252, - 0.0851994445127735, - -0.5817592573434441, - -0.3158955150145574, - -0.47573467689769056, - -0.18699042335240823, - -0.027728875527376462, - -0.3277777687607794, - -0.07524461952665995, - -0.4304611032610103, - -0.42752396043962543, - -0.26485639845871567, - 0.0994721536927492, - -0.34015773577335584, - -0.08091388292698964, - -0.28661136313439206, - -0.521557584906658, - -0.11776615577957095, - -0.2668287625755933, - -0.550978208767457, - -0.3444415775533549, - 0.06090092067449793, - -0.4341489680869147, - -0.6399272080752502, - -0.3298607458204584, - -0.4070878552260922, - -0.5120136739820477, - -0.09892351433452629, - -0.13445335667036784, - -0.2984008256730031, - -0.011765429323949972, - 0.11002460483960641, - 0.11715323706485758, - -0.3717526768908503, - -0.39455820256468577, - 0.04847388427222765, - 0.030574774116081116, - -0.011574574035896346, - -0.34849619376152474, - -0.5466430372110778, - 0.015125746806854301, - -0.28038672102558093, - -0.2964512777786784, - -0.6514851525099812, - -0.37493679068175917, - -0.25174702442688873, - -0.045963995760482046, - -0.5811471010970634, - -0.20723000944991937, - -0.23872900683214066, - -0.28438583546893853, - -0.5647071417721508, - -0.21178632208604597, - -0.1649588007065083, - -0.22247331647105062, - 0.05124472054216578, - -0.07512400418049425, - -0.049538720914168555, - -0.03858177640127225, - -0.5090431732773413, - 0.02027072799636065, - -0.2379127318971424, - -0.020339211542424684, - -0.4499742960922577, - -0.59648991414312, - -0.3154195056128612, - -0.09304641736203267, - -0.4992376503583372, - 0.08874206126995432, - -0.34936612258188127, - -0.4295395333812841, - -0.4113831219790521, - -0.2350324497439707, - -0.3214161909276456, - -0.06320130443112004, - -0.172773917650273, - -0.34275168320515603, - -0.49422032105810554, - -0.5722927908084585, - -0.6161592002753478, - -0.6103033866732924, - -0.09868581535223997, - 0.011980501101184204, - -0.17025836420931445, - -0.4398785088443529, - -0.3730017140629263, - -0.5112413195510934, - -0.2948163173049173, - -0.5070189233109058, - -0.47983057823011493, - -0.4330076459172953, - 0.0885535098955097, - -0.07949767397498908, - -0.4185536267177018, - -0.5612178584668377, - 0.016107378395652683, - -0.6606458941171731, - -0.5296895494400857, - -0.419104508182506, - -0.14165101778606037, - -0.21592143314483397, - -0.06288655086610928, - -0.12521368942287303, - -0.49284945383922274, - -0.25092509464050394, - 0.045985218843428766, - 0.06447773054715233, - -0.37946368738547576, - -0.05900154930666379, - -0.5712161147069678, - -0.041265921657906435, - -0.586125839338726, - -0.3562194394854067, - -0.22173240343991735, - -0.22793966971405039, - 0.1039296849540795, - -0.6579452706094513, - -0.3653902160506153, - -0.6040761172519276, - -0.05404383779395616, - -0.21615081295239053, - -0.2668281454838181, - 0.11483590425312673, - -0.17131712595211818, - -0.14832413785633614, - -0.4798490057260549, - -0.6072654333566597, - -0.42922806620970155, - -0.0658440550122461, - -0.5854935244059444, - 0.06801119508326725, - -0.5147393424988125, - -0.4934293476207793, - -0.39840670395135674, - -0.07386681325843458, - -0.26462131908414965, - -0.2804281732692469, - -0.18801164723363678, - -0.6362643427238671, - -0.5003187308924786, - -0.06766063238103381, - -0.12641108988305916, - -0.08850900780886051, - -0.22897949121477468, - -0.5140253360277296, - -0.38379085492906123, - -0.359871813724288, - -0.005932981384510927, - -0.10363789774468635, - -0.29820798266289433, - 0.04096431735140016, - -0.6419323032258567, - -0.3829241540506495, - -0.5444438960423946, - -0.2018211212340344, - -0.1832920369573794, - -0.4461202941795809, - -0.5332953846222412, - -0.1827937439545747, - -0.1632522555850373, - -0.6210887876415142, - -0.0899078669672857, - -0.15834381429085687, - -0.6046966965884112, - 0.0013680688516549688, - 0.00790800729172969, - -0.3924053665572555, - 0.10093500957273771, - -0.6581914734472409, - -0.20149925252422368, - -0.57616814812929, - -0.31755189240377635, - -0.32188609085156034, - 0.058792258182023494, - -0.03413181842012436, - -0.2539017072607666, - -0.5015281203200768, - -0.45802762537717967, - -0.6423632327450515, - -0.42253422012498854, - 0.023239859304730603, - -0.3646905926634347, - -0.055981014228404735, - -0.5203379947081641, - -0.4249570411615905, - -0.5354344006004161, - -0.13211412633844655, - -0.6449135964023847, - -0.15976369665379742, - 0.034245138844137046, - 0.04887723830484236, - -0.32008167713303143, - -0.15498092026893362, - -0.2578189715785877, - -0.5096070700716336, - -0.4014084056622924, - 0.055772246808155734, - -0.1137996265282053, - 0.026499084349639213, - -0.019727763928103048, - -0.5098829282929986, - -0.45777137824662023, - -0.1297724754829529, - -0.37682133701117293, - -0.26650305245567835, - -0.18770145743493782, - -0.2780731300808312, - -0.46546264461456643, - -0.16823369918570136, - -0.542923525995912, - -0.5374295042472396, - -0.24847192562571085, - -0.304023599311949, - -0.08734092578926633, - -0.05785684361512011, - -0.4460193763666154, - -0.4909769507269582, - -0.2444638209109477, - -0.5985335243000066, - -0.18096123889930688, - -0.3998026212421945, - -0.011965910819965342, - 0.01037105105149061, - -0.49030679951907463, - -0.2219052561950675, - -0.5955234046961184, - -0.2814237708251885, - -0.13948023615087757, - -0.5650289838374871, - -0.22957794872233667, - -0.36531314963617767, - -0.3317403826110018, - -0.2106256332317094, - -0.6312697198529951, - 0.006087754752979846, - 0.10762608933170026, - -0.07428344174824109, - -0.5164027520059801, - -0.655627860160379, - -0.3457087858428038, - -0.21030886499190438, - -0.5567264702162619, - -0.2556714518986484, - -0.6572695118165539, - -0.1490067814850209, - -0.1317584952078954, - -0.6552054084844315, - -0.21382213207436201, - -0.0626567936350525, - 0.09795311845232357, - -0.6413166918768083, - 0.01353832146461098, - -0.4730729941694356, - -0.014491009785799425, - -0.10174557017003016, - -0.5977710744236798, - -0.24606992465398642, - -0.4959481433114717, - -0.1617939513216664, - -0.06387194919659855, - 0.05669976094996987, - -0.050569547506729484, - 0.040549538731731616, - -0.6219804434016012, - -0.422349346537021, - -0.018107764704617724, - -0.030500577833464604, - -0.1644901063746667, - 0.016790109719513002, - -0.019366616915446166, - -0.14164691453066913, - -0.5497043082700489, - -0.16177488136050788, - -0.2796584287288173, - -0.3974608856289077, - 0.09186668405664866, - -0.09140646088916804, - -0.5620779085953825, - -0.5621013550200016, - -0.6263589792231218, - -0.45505832433428883, - -0.12229885678282437, - -0.35849009985639096, - -0.6115929969178476, - -0.3926743972225823, - -0.11325773794774874, - -0.6506961929990973, - -0.053587578372211286, - -0.6017127219916331, - -0.4555891420102256, - -0.06966246735550863, - -0.6120985202396859, - -0.17419317661392503, - -0.5646192895569155, - -0.3114235244823394, - -0.6132793214901164, - -0.02071879594962589, - 0.014232684191238243, - -0.3101435502812297, - -0.4662066971499118, - -0.5399621659708281, - -0.10274143862379115, - -0.3779544016671251, - -0.33082644827941576, - -0.18209456886903613, - 0.0663347546942008, - -0.250581035299323, - -0.08285730388539181, - -0.06951805271491296, - -0.06539732223207506, - -0.07450236513356723, - 0.01783456703473818, - 0.014403921098616435, - -0.5103375185406054, - -0.5588746988672425, - -0.42079625732678405, - -0.5948513285666672, - -0.4403837757815643, - -0.5602909412421521, - -0.06173939912360815, - -0.2436730226569997, - -0.6343823915160721, - -0.11128298022688021, - -0.21173509805254687, - -0.3880621294731675, - -0.5309859104389341, - -0.49925298797025575, - 0.016918959393016464, - -0.13353755350622087, - -0.029624905530200696, - -0.06121206126159251, - -0.17304205279078222, - -0.49778184912270285, - -0.37645476172062353, - -0.4229050412508276, - -0.24396957253266355, - -0.5303625395583881, - -0.23699401681169963, - -0.37042491965810737, - -0.4302979528518579, - -0.08066449227819861, - -0.6422413418368339, - -0.49288594767938093, - -0.39659678477561233, - 0.10397574361102213, - -0.01890066092237952, - -0.2736601617509152, - 0.009981163574357743, - -0.006614085013993742, - -0.008333870346970418, - -0.3020551729373681, - -0.6262043128776626, - 5.529068080585287E-4, - -0.26337471542348095, - -0.1922115099982506, - -0.37583810794100125, - -0.39719526443957814, - -0.08485357422713014, - -0.32092664013386724, - 0.027373551059699408, - 0.08054814433179958, - 0.08794694026009242, - -0.503420990794242, - -0.16506396673047524, - -0.2828741332809417, - -0.04368390041399883, - -0.5192830162217834, - 0.051430885262990333, - -0.3316763195744895, - -0.4917725735768884, - -0.08054217172973699, - -0.19625054709272083, - -0.21428371794084627, - -0.26482772767126694, - -0.5121235994538579, - -0.09682097071413953, - 0.05271713469020678, - -0.5553699988143344, - -0.09958957597391427, - -0.662478087061184, - -0.049843655710134604, - -0.6119501570473083, - -0.40916379857648233, - -0.2795490099131226, - 0.022270479742259486, - -0.27290713048554754, - -0.55212186982849, - -0.4121701257033197, - -0.030383529129365483, - 0.06709879024343923, - -0.1796025504153933, - -0.3503505137501676, - -0.3557706347802966, - -0.49023906280753926, - -0.17076151501058534, - -0.08395813874234626, - -0.6070312108903572, - -0.20878857285625113, - -0.3328739676937222, - -0.5049810543442916, - -0.5993945711438959, - 0.02474635253043278, - 0.04182145907221668, - 0.059049969643502065, - -0.45959461844741445, - -0.5807870000678932, - -0.5742757191498007, - -0.6318438436390036, - -0.5279720174229002, - -0.412908843404131, - -0.12550950599222255, - 0.009680503964538234, - -0.6100459464582989, - -0.5462855185640872, - -0.5045146801273843, - -0.5902727796531666, - -0.16761672279564405, - -0.23823776111539818, - -0.6242112601158604, - -0.18161595873502123, - 0.08366672149560084, - 0.07985504742649652, - -0.223965127917227, - -0.5151130289856722, - -0.5389344194557396, - -0.5418937669317027, - -0.36158347020483245, - 0.032916187912065964, - -0.3070450469336947, - -0.6486086816421309, - -0.4429172876854535, - 0.043934441883277886, - -0.3748228046723809, - 0.09633293908963514, - -0.2939831254351411, - -0.26846526144061394, - -0.5720809100774873, - -0.4221353460636512, - -0.5398456210613081, - 0.12188793720557767, - -0.27509170118483556, - -0.047791080939383335, - -0.23426480851715725, - -0.6562564399055177, - -0.5235390685089448, - -0.15649899200978135, - -0.33662448890428676, - -0.38006367753434817, - -0.5475766146245189, - -0.5182797580749596, - -0.5054597592070355, - -0.48049840223223383, - -0.40509714848353945, - -0.4162374038492503, - -0.02391980253571513, - 0.07842314516960969, - -0.443908223114204, - -0.08793391341788404, - 0.023692666526597517, - -0.4532562463741113, - -0.45707818134799344, - -0.6083240874118391, - -0.1158228680514567, - -0.5171425153578442, - -0.5756172368060803, - -0.62184982731546, - -0.1917624534553496, - 0.09394360688625958, - -0.07783028313770857, - -0.6588918215521283, - -0.0920602277070316, - -0.3313642112118209, - -0.14361651974805945, - -0.523787200333174, - -0.22614283476348068, - -0.19527291487636744, - -0.47312567243292636, - 0.04657460074937736, - -0.09518601590221076, - 0.018124735159303462, - -0.08147520025892419, - 0.04398788033773149, - -0.584950021403083, - -0.27150937996371066, - 0.05174968635695498, - -0.3187867122867031, - -0.0785580282911893, - -0.0489625691960599, - -0.09719912594278779, - -0.5155828756480468, - -0.3438405779431836, - -0.5859694697213778, - -0.06733449774121825, - -0.07768181841332822, - -0.18541188151994437, - -0.5180616857637939, - -0.1541990534885933, - -0.051684205226173674, - -0.5326729104330111, - -0.2560209839228974, - 0.025222751210753014, - -0.568277827351196, - 0.05242744983009151, - -0.14133730084115315, - -0.4231244326305314, - 0.08228753675293077, - 0.0846063194827944, - 0.060012550924950614, - 0.04379353542002895, - -0.0937070401529565, - -0.3173470356768724, - -0.2553976474683689, - -0.5692821420563671, - -0.43133865534337623, - 0.04911971638185575, - -0.18325708507110666, - -0.3260031344349327, - -0.6165076348717022, - -0.49031432684763865, - -0.549538502096134, - -0.1658724334398593, - -0.5846236306266338, - -0.35573392115733327, - 0.11516918627897033, - -0.30838629158349723, - 0.0012554170255358876, - -0.07303994316176854, - -0.3856043498912215, - 0.11807510123191123, - -0.5382238125796088, - -0.5325241142838845, - -0.23111326222854622, - -0.1024467700748879, - -0.5202804896854378, - 0.0517342855497438, - -0.542354803984798, - -0.202859591694798, - -0.37709616135343355, - -0.5334502159716791, - -0.08342843272921463, - -0.5369691045244872, - -0.583094504417943, - -0.45809578060022904, - -0.013423543685320838, - 0.08003686418055955, - -0.24671402604054032, - -0.09167587470614147, - -0.054899967202777455, - -0.19864932624248366, - -0.5744192434962017, - -0.4129522900739349, - -0.1636432863750822, - -0.21779449616528657, - -0.015158659508415662, - -0.18136184042036435, - -0.22683408130131327, - 0.09337847207438255, - 0.11612919559247059, - -0.5572562822706498, - -0.5546296199418937, - -0.11074318743942124, - 0.11709846284300385, - -0.16681362867334515, - -0.6562961515758348, - -0.2157708991406106, - -0.34798552512022846, - -0.5397171843562776, - -0.4369073908427054, - -0.4141155378699115, - 0.04812500249507157, - -0.244617303264963, - -0.08714306122428339, - -0.21500775714724502, - -0.36685430343084663, - 0.11381122248703113, - -0.39897803259575215, - -0.09721590124792157, - -0.3582447997635564, - -0.44488077651213764, - -0.5961555922957461, - -0.19635560522722145, - -0.41406512195055445, - -0.06723926306218131, - -0.5137026141220156, - -0.6591902990137452, - -0.06537904820438678, - 0.0563962922843948, - -0.16596169879202544, - 0.045161852546847014, - -0.3534319215688039, - -0.26784653749314624, - -0.17382712750380663, - -0.3949396137851457, - -0.3460597678103207, - -0.2801761961118509, - -0.02358690787197626, - -0.2146064169877791, - -0.41999252017020916, - -0.1715860907361092, - 0.09214801624158897, - -0.09256177138963884, - -0.19765936244474885, - -0.25508797525149574, - -0.42769562627050967, - -0.22118683126965277, - -0.14881738047876403, - -0.2758922828205246, - -0.18401264269562956, - -0.1713596363394545, - -0.553842350054202, - 0.1133045525351627, - -0.6176719170705497, - -0.29840880821558646, - -0.6555839167942203, - -0.6632299349997535, - 0.10572258752233055, - 0.024223791064977407, - -0.23928865632554008, - -0.6201447434940283, - -0.6047480711449512, - -0.5594137552363283, - -0.009172207496212836, - 0.10222526260570508, - -0.21733852676447096, - -0.41339960262600645, - -0.06218116250400385, - -0.5431720997338626, - 0.07398678885228371, - -0.11886119640519732, - -0.5793131762339951, - -0.09359363339739857, - -0.5559779073761963, - -0.3928744289380371, - -0.43368857648582476, - -0.2825955246440472, - 0.0012394109276073761, - -0.051895222396665885, - -0.09374613601305137, - -0.3789589250575414, - -0.5938351696525842, - -0.10234728187102093, - -0.24030729271186652, - -0.39371958203811136, - -0.2596297443472637, - -0.6026032553018241, - -0.34491965543987846, - -0.1750316622541619, - 0.013396168832035649, - -0.6141353974402423, - -0.006442577369114244, - -0.5851001189090259, - -0.2642581453905816, - -0.5238281108570972, - -0.17287416903225455, - -0.5392458998088342, - 0.06096301734654097, - -0.06367287287917434, - -0.017195514575379933, - -0.12406895079415436, - 0.06124805159723412, - -0.3997024172586843, - -0.2137821913391103, - -0.25221212339731836, - -0.36664004155005964, - -0.11597774677384609, - 0.03087026128906234, - -0.5896600194673713, - -0.2975161652007332, - -0.6400980194289727, - -0.08255231209108427, - -0.5183621599395829, - 0.006796386033526836, - -0.6292455012568736, - -0.33071759433451436, - -0.013082337883412176, - -0.6121864826365204, - -0.4048124156156295, - -0.38880836228451165, - 0.047139154240625536, - -0.5856040703651437, - -0.14634560043958522, - -0.0670066916792793, - -0.1536888907974937, - -0.5885432094599437, - 0.03648058640985008, - -0.6248274287156736, - -0.587188316285138, - 0.03346743527972951, - -0.27525339995379505, - -0.030823842788662903, - -0.1356233474084949, - -0.5697774915167662, - 0.08518896068455872, - 0.07292739717148367, - 0.05255430768157909, - -0.22513538956117662, - -0.29186444680821794, - -0.522960131674751, - -0.2744550558070439, - -0.4502434383075854, - -0.03134448214657615, - 0.06499233222215439, - -0.07492817615843728, - -0.3213213095946824, - -0.09838842916554114, - -0.5015185195426304, - -0.6344872465393983, - -0.3026461476419576, - -0.00957164349365669, - -0.3183120607062177, - 0.12093372814576742, - -0.38192120438340715, - -0.3818486041360611, - -0.12380018046884267, - 0.11895875896329344, - -0.3809974530193942, - 0.04353872008109305, - -0.18291462609860826, - -0.18899690464353025, - -0.3066958197296358, - 0.09782208817515281, - 0.08791178023760182, - 0.024310122406844825, - -0.07079747778493539, - 0.01289776925303976, - -0.6501634436133861, - -0.4781128691620101, - -0.052664143646765416, - -0.09683682605290322, - -0.5372040047013915, - -0.29278333370676285, - -0.5916539563163037, - -0.024333605345920217, - -0.4192719405164074, - -0.2745499366717887, - -0.018795337948350643, - -0.24503273905441175, - 0.09273635373038824, - -0.6448863224220476, - -0.10312730021879646, - -0.537997496127006, - -0.019689923256508868, - -0.39264024575484197, - -0.09655723570804875, - -0.4540403340458628, - -0.17817485045017678, - -0.16510013750419034, - -0.6511118979924133, - -0.03283878373734905, - -0.20422490505404534, - 0.1232101268524165, - -0.21284293651921898, - -0.6231559715449029, - -0.28867133306084003, - -0.6027823442961048, - -0.5635912687867909, - -0.27812253063116005, - -0.49367768173258264, - -0.07147016777731952, - -0.6578849495536687, - 0.11523420551357533, - -0.5144015619804357, - -0.3386094865493366, - 0.03235568038227621, - -0.29112727819344003, - -0.23112074307560548, - 0.09303766869360386, - 0.019705093932306128, - -0.49897491235692437, - -0.5612651868355122, - -0.04495593536866904, - -0.143574878326567, - -0.3758874430240887, - -0.11140300944018444, - 0.09153010539232143, - -0.28123286585074464, - -0.04467047010271008, - -0.26571701675099474, - -0.05636309658678529, - 0.11137404833271769, - -0.41626059949184213, - -0.12056244296840846, - -0.5157140420059181, - -0.38025190263352643, - -0.1741872534622319, - -0.30838849695104353, - -0.31896148743635694, - -0.4353340481837553, - -0.3355353609540804, - -0.2761890190017331, - -0.01664798633177489, - -0.16327472024065426, - -0.08838608459288133, - -0.06431536542227012, - -0.44883297101622266, - -0.5862049057944347, - -0.22061355600598215, - -0.30401610632287757, - -0.3210508676464538, - -0.5220182540919434, - 0.0580268346293048, - -0.08549853009099717, - -0.43908825975352606, - -0.09224099898302784, - -0.1779028757415831, - -0.48992158268433195, - -0.10277927938530385, - 0.06668696671176677, - -0.3620900279637737, - 0.11950864018498941, - 0.027768874892183493, - 0.10954001043665929, - -0.37820101894366137, - 0.0876085993580179, - -7.458331863736678E-4, - -0.5925155515691419, - -0.018785351961791097, - -0.6278853335710044, - -0.39753081356312847, - -0.07872739945699703, - -0.06380587459571685, - -0.44537875823656115, - -0.5118732216409877, - -0.14045180441063898, - -0.34947714602786806, - -0.22690014328791847, - -0.5610918030753708, - -0.30779601843540977, - -0.07145234800454581, - -0.43022786716585215, - -0.21629589318364673, - -0.5323666849703846, - -0.607361003829701, - -0.1271612880470241, - -0.2618043938346083, - -0.3668994356932944, - 0.0613912438970079, - -0.3572140595639046, - -0.10740518134408095, - -0.4314841642095753, - -0.16371215082759727, - -0.12776125659410498, - -0.5107008969566385, - -0.4622367272815209, - 0.038646182529229134, - -0.2022264545469638, - 0.062345589507734944, - -0.4261736620111004, - 0.028158901135519998, - 0.01786448241002725, - -0.5634987086779424, - -0.5083901625150262, - -0.45213926966831963, - -0.2746208037255501, - -0.4015330335530501, - -0.5000788841424625, - -0.26205535620306303, - 0.1007956053561494, - -0.2529087448956385, - -0.27929078187469236, - -0.5624755639456632, - -0.030468539556392726, - -0.24339503428990739, - -0.6067405748138299, - -0.03755921408182061, - -0.22516502441934472, - 0.04030282019818632, - -0.06487766028047959, - -0.429846404172212, - -0.5786985160030369, - -0.3457386545691886, - -0.6285049192720523, - -0.20709863129057726, - -0.024426519871644015, - -0.2851171290283011, - -0.45254142539457987, - -0.012530117670200513, - -0.2841367617859053, - -0.4693439905423327, - 0.015305081874493087, - -0.35523296840970453, - -0.5085416789625526, - -0.0064758245011959925, - -0.004349760388276058, - 0.01797285220956535, - -0.2924706885136865, - -0.4847947705764931, - -0.22882436534766154, - -0.24593746378782577, - -0.5229588310490391, - -0.2786761266937521, - 0.11936676771213528, - -0.2089197052298663, - -0.6175056923078791, - -0.28666386071049715, - -0.23766571617240045, - -0.26339779549448583, - -0.2516267568754319, - -0.5027804325714372, - -0.2418230939358113, - -0.006442122221642865, - 0.09186523533341329, - -0.08143660665036234, - -0.3161028309624339, - -0.6194620497504814, - -0.10060028266286647, - 0.01954816046796637, - -0.21144624834324016, - -0.3354933685646855, - -0.334584375965864, - 0.028689927293330753, - -0.192836754181612, - -0.1473820414916326, - -0.043938323587332295, - -0.11779764163214368, - -0.15971238004270272, - -0.47090910351216775, - -0.47139481205773054, - -0.05769463589209389, - -0.5809725004920057, - -0.5800083770270811, - -0.4384080785505737, - 0.10578787249813015, - -0.4249958829032364, - -0.6462024319479812, - -0.29178999063743594, - -0.5221918992426733, - -0.4736361312071549, - 0.11097844596949047, - -0.6198548296108559, - -0.5998847676112332, - -0.41582246457656746, - -0.41162422834670986, - -0.49614423223356185, - -0.4359060313359252, - -0.1314728419085851, - -0.37782771471859683, - -0.18884874135675572, - -0.36704472268352045, - 3.0235109829102047E-4, - -0.32750878539368844, - -0.44668472571337, - -0.15155264647914402, - -0.4471486272220477, - -0.17127283740520993, - -0.4872365313575783, - -0.021938329961947223, - -0.636255599075701, - -0.022894219280747752, - -0.28289229259730825, - -0.5225692847343094, - -0.05535406234792983, - -0.0669291241990736, - -0.2824689205168542, - -0.21982759993094703, - -0.25181788698486673, - -0.26511901521921083, - -0.27074570141417975, - -0.6085975612048535, - 0.07118219538475123, - -0.4559685883274619, - 0.08782994655804388, - -0.5412743511084777, - -0.5748615207349569, - -0.11479467726241233, - -0.2565044749344109, - -0.46538016199367593, - -0.6346634347601607, - -0.6580181074632967, - -0.370816541264146, - -0.27798270289262855, - -0.25350275240604636, - -0.5477234145763783, - -0.5290766340208954, - -0.5740133130087097, - -0.1963874667148397, - -0.09495523625756319, - -0.14751318739286923, - 0.10259983377890436, - -0.2567299388129232, - -0.48061611688024275, - -0.027986190172149983, - -0.5968275289672508, - -0.5982249049944516, - -0.6137900843888887, - -0.1129116342401425, - -0.5928353455853991, - -0.4402113535073221, - -0.2983834151634731, - -0.23467193913500417, - 0.11453606230016955, - -0.06713877255034006, - 0.03731625429807928, - -0.6517717225751103, - 0.03764805046908648, - -0.6321866330009795, - -0.2237943571710761, - -0.06728009906636911, - -0.5711733077516443, - 0.0886888541483748, - -0.27501100885354113, - -0.05009061268696113, - -0.17076210890806248, - 0.09975090722157609, - -0.3424858241365391, - -0.4397021658657938, - -0.465854442000682, - -0.010418038123404139, - -0.31178878782461195, - -0.3900866661341618, - 0.11771074938905857, - -0.551239415431287, - -0.49652174274316696, - -0.4069518647951775, - -0.05326697963218108, - -0.33733340538142165, - -0.09687357311872924, - -0.41930542576874363, - -0.007283678632348911, - -0.5257906984619907, - -0.254106871207474, - -0.6164683559959054, - -0.43121116109658, - -0.14022114553885467, - -0.3322698167843209, - -0.12052368636275546, - -0.6163522104378711, - -0.662259370193255, - -0.42572436768948196, - -0.18310992800775783, - -0.24962998319651636, - -0.4147911300087809, - -0.17454064223001675, - -0.2964083755015769, - -0.3219490455513164, - -0.46455596053830417, - -0.4004329227774915, - -0.5294660845480303, - -0.19801802204168578, - -0.49154913682335466, - -0.23343795270046247, - -0.6186147934019817, - -0.1987593876289077, - 0.058617615092627084, - 0.09212679122075562, - -0.6431880765505441, - -0.271455489200602, - -0.31502660970515006, - -0.3770268502501811, - -0.15059519612381556, - -0.5761698292709392, - -0.17582511337160384, - -0.15154644888773683, - -0.36543571749429066, - -0.5462913933077521, - -0.06039819794440504, - -0.03467223303774536, - -0.1565609065441287, - -0.002491214614607995, - -0.4628840844261768, - -0.5819941649627517, - -0.08689447886002866, - -0.5023971800935499, - 0.03146551396971797, - -0.42845956065721486, - -0.24818130633560354, - -0.2537163216883941, - -0.3228563259459471, - -0.12417264868655908, - -0.5497380712115811, - 0.007691655105973694, - -0.4463116666216302, - -0.004500883219858753, - -0.0643795314017318, - -0.6231128639904202, - -0.12460791199129084, - 0.02165430315793171, - -0.020013753906362175, - -0.2593128936477818, - -0.31504405796618, - -0.21229083906872925, - -0.2860456398835091, - -0.3663432969291664, - -0.5145453005913578, - -0.30476031900933287, - -0.22684289641398558, - -0.6337419721133869, - -0.43117340561378387, - -0.08428261468734854, - -0.6341721191402532, - 0.058795268217632146, - -0.10639858304236438, - -0.06667243967602188, - 0.09188935672413023, - -0.6185760901793517, - -0.5048471872848357, - 0.013558573710715005, - -0.14790798038755992, - -0.21958239095810683, - -0.6462767785126978, - -0.6349534047996558, - -0.34596411380808334, - -0.198172619310229, - -0.18172757374084803, - -0.021632308337575457, - -0.5849497291818845, - -0.3105942053633193, - -0.2830225527676646, - 0.02695763602386203, - -0.10034478656295909, - -0.5343934620888696, - -0.11388938238172863, - -0.03143721032989644, - 0.08999445806108008, - -0.008474769527996528, - -0.4844470819051664, - -0.4133496580682603, - -0.17056941917252705, - 0.10281470204070475, - -0.5031112706282501, - -0.015587070324590502, - -0.615016526982309, - -0.4996234513534382, - -0.4461984208437293, - -0.1066650785605241, - -0.2387112234228731, - -0.2954804014299495, - -0.3432685583232783, - -0.34227374412579437, - -0.39756233868787205, - -0.6490230916165001, - 0.104215404445824, - -0.5194473682342925, - -0.4442332853849323, - -0.44934710555762725, - -0.22011996642029563, - -0.09488266375737175, - -0.5581567519817332, - -0.15872687029396526, - -0.3063153931660701, - 0.01829032555530663, - -0.6563146198630527, - -0.03521951286913649, - -0.4350412141448641, - -0.21563134385485894, - -0.5749731084023814, - -0.3397623922696005, - -0.10997892870349668, - 0.06694909850904773, - 0.12158917635786848, - -0.3731602482341501, - -0.19503460036239428, - -0.2613690106396068, - -0.3270765437132397, - -0.5618960021678603, - 0.0460266797441925, - 0.04495815899246691, - -0.6462611601084568, - -0.6148114407810965, - -0.05511767135774126, - 0.046336272427827674, - -0.1959495174913855, - 0.10779539310391928, - -0.37752650523123016, - -0.46151971510114875, - 0.10740673333397699, - -0.599965090161083, - -0.601874754863776, - 0.029507451317301037, - -0.1945314175259169, - -0.5380010874520791, - -0.49950409731915724, - -0.0026155353168186846, - -0.07988821949887037, - -0.02027967321015578, - 0.07896058994232569, - -0.37925152013239727, - -0.178588387518742, - -0.13403256252665674, - -0.041258711836585804, - -0.34346063020445516, - -0.3789745942473397, - -6.888600569053827E-4, - 0.029986058359810608, - 0.024595406528878927, - -0.2641508830557723, - -0.3886754648341483, - -0.3790337687029644, - -0.44456554983452634, - -0.5209584959026475, - 0.03161597887293621, - -0.17122175792926425, - -0.6362655633638808, - -0.19630006399106648, - -0.29127705451640534, - -0.21330412853750846, - 0.11741072842295741, - -0.580501784062994, - 0.09164738922227122, - 0.046161551249742305, - 0.07223673976748657, - -0.4624322109156769, - -0.5719888079286112, - -0.16784609590480165, - -0.32364248000022033, - -0.06933650830255567, - -0.27447712542357977, - -0.4039020869638734, - -0.3756217400946692, - -0.24132635930145352, - 0.028299088013270635, - 0.004500570008229343, - -0.06892334555056201, - -0.4807399413742192, - 0.060919246634603574, - -0.6619774013245708, - 0.06569608426290585, - -0.21156565962985857, - -0.40688326343409875, - -0.40607555471456636, - -0.4065760920998656, - -0.1346322820988367, - -0.1092007596655391, - -0.5522548888954668, - 0.04337681484071876, - 0.0140501287280822, - -0.38001533112718555, - -0.5622909171922638, - 0.03324993695745493, - -0.3862006305570465, - -0.21732042034971621, - -0.11116709513737943, - 0.12200379952884433, - -0.3671444950990447, - -0.4310593481614429, - -0.0938793559537805, - -0.545121824251775, - -0.6380914770055068, - 0.04112536231448638, - -0.4376143660216644, - -0.3713825281840973, - -0.6207041869338135, - -0.47909384276891237, - -0.639517423181518, - -0.5424597178255947, - 0.11211936275521539, - -0.364971046250355, - -0.24082909112228246, - 0.11176795147523932, - -0.5244350287855417, - 0.04581199029802585, - -0.3458012030337137, - 0.03465052283832504, - -0.41322688273769903, - -0.46991839712611483, - -0.394641365772213, - -0.5354712202510138, - 0.027547687159113154, - -0.13748714794282757, - -0.15581983516755105, - -0.5161903793381838, - 0.002115494445974253, - 0.020437471415968633, - -0.612386789620686, - -0.5541852041851024, - -0.3090779585527016, - 9.492300362017314E-4, - -0.6388538926837849, - -0.6349374062913299, - -0.13367790286513603, - -0.16793262643655305, - -0.2521830084664088, - -0.6469747766983551, - 0.09855914082402084, - -0.2508988150180683, - -0.23616947391465254, - -0.5001814774990637, - -0.44958060432464325, - -0.25965055259455494, - -0.4005290517717102, - 0.056917035815984396, - -0.02345712505252795, - -0.011742279315313353, - -0.038164814296972605, - -0.6153833169013415, - -0.42577027284698393, - -0.527382860767112, - -0.1461367616557655, - -0.19624186879417177, - -0.17401885362721287, - 0.006152202983281452, - -0.351841104469754, - -0.6606654861061064, - -0.19223669088203987, - 0.10567642381004105, - -0.5636581049635263, - -0.33872427445048525, - -0.020608040468789945, - 0.014176889212460075, - -0.5684945867206573, - -0.42814660485040457, - -0.07766505382963074, - -0.6082409495100694, - -0.3412235932958068, - -0.2005885694068188, - -0.6394300364413814, - -0.23799920010747566, - -0.03634948757800882, - -0.608994203162142, - -0.5820870869012144, - -0.21776796661853898, - -0.467007310060391, - -0.10592233444138388, - -0.11536302142155885, - -0.3689108498190854, - -0.11614364787635578, - -0.26334860329993576, - -0.30092138118837775, - -0.2793920654935309, - -0.028661357805577548, - -0.38498628007820235, - 0.11975170195528184, - -0.37430992834441035, - -0.11488684810197591, - -0.21723227537502432, - -0.3919447110592767, - -0.15216821127997837, - 0.011320223214482672, - -0.601333623932484, - -0.3394484281233205, - -0.4145084211999318, - -0.2865810014822423, - -0.2715312088665171, - 0.0114711275033762, - -0.22312319483986537, - 0.07436298754185044, - 0.07400369677071095, - -0.5524971592773422, - -0.3539942840507853, - -0.5577867056624599, - 0.09051369492293371, - -0.6413961974657268, - -0.03165887868524431, - -0.008097870879171909, - -0.5766748796749827, - -0.12626227982901217, - -0.5865712242787091, - -0.09733553933048045, - -0.33378709767660836, - -0.5799344412348315, - -0.14914711020880067, - -0.03639322472485129, - 0.03834182463417335, - 0.07252394970155951, - -0.6148562281089835, - -0.3410895475451359, - -0.5338734427794856, - 0.04590191146238931, - -0.28807480736237373, - -0.3765501099702159, - -0.23053751608611533, - -0.5546070444257925, - -0.3605439938061713, - 0.025562646791980725, - -0.6325541490290886, - -0.4635070082461099, - -0.5598043295484585, - -0.3518052051823184, - 0.05729932716959585, - 0.0891894225683677, - -0.24922905237912402, - -0.6385535038995371, - -0.35489399915660164, - -0.48177983658877827, - 0.08176667256553893, - -0.4515979604878557, - -0.48730857912328596, - -0.11136588527256852, - -0.5048033221611847, - 0.037083055627707195, - -0.5702189392379439, - -0.6025386505287853, - -0.41194549112796724, - -0.14974733719202005, - 0.022819763813334615, - -0.21419224655261465, - -0.05860069017491765, - -0.3957092148260762, - -0.553502013183348, - -0.01566275476867396, - -0.4418472531838091, - -0.41264163204142634, - -0.6461620575851804, - -0.5607076060355387, - 0.11674449857507607, - -0.6323848198816009, - -0.5990714716777139, - -0.07974402869758779, - -0.5178139013796892, - -0.537192629268611, - 0.022054121287609973, - -0.35687245766259895, - -0.47451483592446625, - -0.20925752989814145, - -0.2964817702267198, - 0.025863310161788444, - -0.28987129125594197, - -0.09088191487333941, - -0.6395602849389854, - -0.22810258191097554, - -0.12515718802502585, - 0.06854178991344018, - -0.12963165327275872, - -0.5247048677203482, - -0.6209019888408362, - -0.3276629051703454, - -0.0630519278126862, - -0.06717840179289358, - -0.5608658997090481, - -0.6247459303873204, - 0.11783981870586502, - -0.5181984200028398, - 0.075041843258287, - -0.37517207466951535, - -0.4061192642306237, - -0.45630037560299597, - -0.029876150748952224, - -0.5616966579468801, - -0.34919912650218626, - -0.17117998870539153, - -0.02303761991221409, - -0.4268124873274204, - -0.08104303745116004, - -0.030998503795020005, - -0.21434912520998062, - -0.3055866413316932, - -0.17541386880526677, - -0.5611556094800558, - -0.5198937522826326, - -0.1979053573568706, - -0.3874479319915266, - -0.24013917045383498, - -0.37344897484688033, - -0.42162269268213903, - -0.060538814182852896, - -0.46874387697759506, - -0.5491022449766956, - -0.6481655689407051, - -0.30696055857120796, - -0.13540984467293404, - -0.5573770680396211, - -0.5819852136484545, - -0.03662691122307138, - -0.4461487345188624, - 0.030845809210627628, - -0.23988077238350541, - -0.563495648052324, - -0.39091336284023626, - -0.4103578792636485, - -0.4254752948245242, - -0.34593649005977795, - -0.6244696534989882, - -0.27488739827709097, - -0.21599530331440575, - 0.07918987583394366, - -0.06181279680637031, - -0.17737007730916, - 0.0358573743423638, - -0.09310336895492732, - -0.5939045231584211, - -0.08128918544549768, - -0.18401960801926637, - -0.28474653939589506, - -0.14429599548195515, - 0.04894708426569616, - -0.1941762808557112, - 0.4412557934211129, - 0.6076791724376981, - 0.3196325437917351, - 0.3848542671821632, - 0.686803606866169, - 0.26268859605568506, - 0.5620526202028758, - 0.6228391974966495, - 0.543158941175012, - 0.4711371535582488, - 0.6155290233932542, - 0.2631141609708186, - 0.3145422680611038, - 0.33209427182850815, - 0.5779906212279058, - 0.6149978779285521, - 0.5903906451467167, - 0.4426823580683257, - 0.4443267189851793, - 0.5954260527292152, - 0.6174476128053246, - 0.5576856572097837, - 0.37685220645710854, - 0.4275802753187365, - 0.5714619293221119, - 0.522203688662542, - 0.4178734493710443, - 0.5499394559945827, - 0.4158848257673885, - 0.3919516584865136, - 0.3917465916004387, - 0.36959567321198794, - 0.593112818394279, - 0.6038498308800824, - 0.46232555076092885, - 0.29323369688238676, - 0.6106143818768024, - 0.30818192498975205, - 0.30226842635702544, - 0.633369582181152, - 0.28580001399968874, - 0.46802518323643016, - 0.37449566175030913, - 0.6280247224852956, - 0.4171417036139696, - 0.4658496050738725, - 0.279931226670965, - 0.3855753131145133, - 0.2900863184806591, - 0.6749116776115691, - 0.44941282977514146, - 0.5721232218351788, - 0.6560162376448397, - 0.39231255573810353, - 0.4312604038371106, - 0.6618814539329555, - 0.6241961875740134, - 0.5967947795258683, - 0.43786107063359986, - 0.49175115436911765, - 0.4476193728790612, - 0.42858296967632303, - 0.36218895857993, - 0.6101177724317333, - 0.5287611772431299, - 0.28238844236857863, - 0.5199531889758582, - 0.4310597417535991, - 0.5904717633431771, - 0.3797487570427296, - 0.3880668656007549, - 0.6277657438049067, - 0.32056749211074403, - 0.557220011530204, - 0.5419969098318138, - 0.671787004145632, - 0.37924149217955583, - 0.5612749456102006, - 0.5270021192297201, - 0.618560887932918, - 0.6664637394675312, - 0.35754000549133913, - 0.5006773377825107, - 0.6614152253623478, - 0.5402804066290516, - 0.34942279269217524, - 0.4045631092973148, - 0.6359746952908315, - 0.6375321602814534, - 0.31293531440749917, - 0.6311569186942152, - 0.508064985069143, - 0.570457624188873, - 0.3666608409801894, - 0.275216341828745, - 0.5405683287745572, - 0.46571625817795737, - 0.5787291342530748, - 0.5653621022385666, - 0.27923170687125, - 0.458554751306941, - 0.5398875759694628, - 0.5402459422787207, - 0.26853784096488054, - 0.53831089854944, - 0.5998963618817315, - 0.37167511865400393, - 0.5515060455309763, - 0.4418959971652162, - 0.6813585296613065, - 0.49296472412668185, - 0.28057873665317756, - 0.32826500184570934, - 0.3269272399987023, - 0.34617300831510456, - 0.5739841189869979, - 0.44007068772489255, - 0.5260293989058187, - 0.3760184590732316, - 0.4207923825997507, - 0.4761733609211084, - 0.49385389064191854, - 0.25900190037754334, - 0.37262754973169165, - 0.42832492502950165, - 0.585572844886839, - 0.5007080998700323, - 0.31772589233540227, - 0.32732192435260643, - 0.5040840062550641, - 0.29199813936300617, - 0.6608699131818027, - 0.35938192594860985, - 0.508823116228821, - 0.2620183210743941, - 0.6441512221037332, - 0.53292867014837, - 0.29559460964949347, - 0.4516100587046335, - 0.27167722490346924, - 0.29464117573603205, - 0.5400188589400812, - 0.4020876084072147, - 0.6206877487416201, - 0.42606271670233253, - 0.4278554191317402, - 0.6058070412959387, - 0.5344781401264824, - 0.5091191759846183, - 0.6143370498400365, - 0.6063559228386779, - 0.494067503951485, - 0.49383536442472653, - 0.3669975753835741, - 0.593087466243627, - 0.2610715475407516, - 0.40591849903386945, - 0.6380431974777302, - 0.43856755411972237, - 0.41779821433787534, - 0.5821716702367342, - 0.41111119120984274, - 0.4721866895453408, - 0.42049952246730793, - 0.5382359596333581, - 0.2597514639980245, - 0.4143472098378704, - 0.4612437594039025, - 0.5378740138037388, - 0.46818730485135895, - 0.5501374502329048, - 0.5609286466750836, - 0.3800060048399104, - 0.5127726102513166, - 0.6707255777432606, - 0.6864982271321756, - 0.4693853140024795, - 0.3633467310977988, - 0.6740610922522337, - 0.663213478742939, - 0.3173074692959844, - 0.626158979915989, - 0.5795193522190775, - 0.6829690510939201, - 0.43204268455678874, - 0.44457260396919124, - 0.6246149832557595, - 0.3317429206843514, - 0.2959540367024699, - 0.4667079117138374, - 0.4217303364806784, - 0.34189937215705873, - 0.33342133358772474, - 0.38208256804190416, - 0.2622138342131183, - 0.2794818746148367, - 0.5347928581319898, - 0.473205263217447, - 0.4984645870516333, - 0.47220247655760794, - 0.5439837402611304, - 0.2971689766271177, - 0.4014623642370324, - 0.5247217372862552, - 0.3444672332557865, - 0.5476508046657173, - 0.6444987663901236, - 0.3663186576532055, - 0.3982308605194874, - 0.49649010644640035, - 0.523537692037314, - 0.3393899461287336, - 0.26801751618211206, - 0.575123749097767, - 0.49410544043680293, - 0.6106078326321431, - 0.28255742806596873, - 0.6641913263676609, - 0.5484421243038183, - 0.6858031806869447, - 0.30175088013278206, - 0.5561993819487925, - 0.4509785800384798, - 0.4826000093366867, - 0.616629649308218, - 0.4680136000951961, - 0.45251383806858014, - 0.26306963004762457, - 0.6805064669315666, - 0.28887228047060226, - 0.5912479331989416, - 0.6588807568353134, - 0.5745760596008371, - 0.4957374388586483, - 0.4750196401766801, - 0.646773799162887, - 0.5355152002994514, - 0.5535600926432008, - 0.37367764907299095, - 0.31928690810348764, - 0.6862129255170679, - 0.3335158449431725, - 0.5733007533817067, - 0.6248276758194693, - 0.6882457617800326, - 0.44494348852218824, - 0.440016513694776, - 0.32112782649648364, - 0.4383350581836718, - 0.4137269208426076, - 0.4696431702324213, - 0.3478882450243278, - 0.3065619217956552, - 0.3437453211701062, - 0.5570707893328468, - 0.29830928738762874, - 0.6805363350432214, - 0.42756954735379415, - 0.42796083312179134, - 0.547823007278197, - 0.4278655224685074, - 0.5065193734848119, - 0.5122080282042973, - 0.6247148021808189, - 0.29061314540483413, - 0.31833196954861176, - 0.5962141885759102, - 0.40720364553819927, - 0.6418376497080275, - 0.5817392980945052, - 0.41576456710652726, - 0.5967871475756867, - 0.2812688451018811, - 0.5974469213405178, - 0.5498553360460605, - 0.6154722915453223, - 0.3149914579001188, - 0.4610177550532399, - 0.6562582597382629, - 0.42888255364180405, - 0.505634344864546, - 0.6083616846246186, - 0.28472330174032334, - 0.26875751162511957, - 0.40023489042558935, - 0.644374572247119, - 0.3669875141415676, - 0.4225670590780123, - 0.49641454734408524, - 0.5672732105147476, - 0.5556012790141087, - 0.3762147287099188, - 0.6103566447845112, - 0.30596589217622305, - 0.3303487353521295, - 0.38374580806077047, - 0.39086665153561406, - 0.2607789847776372, - 0.38741406535487977, - 0.49410400985124225, - 0.405657383035217, - 0.5974198881000099, - 0.511754625817281, - 0.5946651211640346, - 0.33960116192513495, - 0.29420469656270987, - 0.5447350090629581, - 0.3156287325547687, - 0.45789839070758975, - 0.3617217480482949, - 0.48930245456317234, - 0.4135799157014506, - 0.284327700523165, - 0.5366473675459736, - 0.5332440046717635, - 0.6642740693525084, - 0.5198320784233595, - 0.681681006355915, - 0.5047599175102203, - 0.3282171741036567, - 0.4738103699784994, - 0.2627771535660702, - 0.6727633561484578, - 0.44279463331344104, - 0.26263022941847713, - 0.6793183462117267, - 0.5166184336859088, - 0.5608241595465306, - 0.5884186354300747, - 0.5044238171585077, - 0.6055128466169977, - 0.3935727254900293, - 0.5334922464442742, - 0.5259187902404642, - 0.3123522461585642, - 0.47503802869067047, - 0.36138650984977627, - 0.37994076275653466, - 0.5209896152887574, - 0.6539917409948376, - 0.43796548175506567, - 0.6026410081668181, - 0.3164879849981402, - 0.2946053621713773, - 0.619627127194602, - 0.4987005382606634, - 0.4901065788954133, - 0.5295802931194737, - 0.3863448939102243, - 0.3596005950912585, - 0.3931733936285132, - 0.4015303338184131, - 0.5091698287644271, - 0.5840538170199707, - 0.6345739776756099, - 0.33851094384010905, - 0.4913352987209578, - 0.3439029317230093, - 0.37749769480810114, - 0.27841009228262936, - 0.4858913539119284, - 0.4927492157486583, - 0.4730919103803145, - 0.6167023615195971, - 0.5685120766687501, - 0.6504420919598591, - 0.3617628643204034, - 0.276077867705118, - 0.6613293078151102, - 0.42820747745601007, - 0.47496561872544224, - 0.305569552347696, - 0.2751983334100789, - 0.4300781137050883, - 0.4788519014917283, - 0.35998710674263545, - 0.37647649212051254, - 0.6327146076165082, - 0.32156820076066045, - 0.6178241634264419, - 0.28693175114963254, - 0.6883944898207606, - 0.5620510108470091, - 0.5382499645502513, - 0.5787503046392068, - 0.4274063369928399, - 0.32069616173086685, - 0.29025747768189136, - 0.420070517995624, - 0.6798826081813502, - 0.33258088751510456, - 0.6722944927059491, - 0.6058227343498315, - 0.41559080245129054, - 0.6822025097074678, - 0.6188446939549721, - 0.3818681302825281, - 0.48871359333848124, - 0.3460147956721147, - 0.46169880752065073, - 0.575288104547756, - 0.35976084182057694, - 0.4591209580673378, - 0.5134112344267849, - 0.5871225278826726, - 0.385851788745901, - 0.6383951642047445, - 0.4827950441159964, - 0.5918198977286357, - 0.6199523514043549, - 0.49500999385727096, - 0.5619014607053312, - 0.6754019108442599, - 0.6228388891788561, - 0.642681011002209, - 0.3291034274424331, - 0.646201965666502, - 0.27294551235692116, - 0.4388884684448804, - 0.6266056511765096, - 0.5357453265196721, - 0.5246791176014765, - 0.453871834627855, - 0.6483641200906931, - 0.42216202708579775, - 0.5527488836179563, - 0.29444600160168455, - 0.4488145379829538, - 0.6788800848086302, - 0.3358266677335331, - 0.3443117513648346, - 0.5677417996913672, - 0.4914287260364618, - 0.4786680292461859, - 0.32612810299017025, - 0.4948946207316568, - 0.583873733481619, - 0.4424921253056038, - 0.3915427662456793, - 0.386916905984501, - 0.6246325657165533, - 0.5196335545805617, - 0.39434874483220445, - 0.5835649270967926, - 0.3097951751992769, - 0.4157929508882802, - 0.5066539015243399, - 0.3791823297459132, - 0.5695741664204765, - 0.5377628262511591, - 0.6530089819722091, - 0.6574670566910521, - 0.35024302871051954, - 0.32802353009751045, - 0.6792257153475166, - 0.6618556019933914, - 0.6300867095451417, - 0.40480469292631993, - 0.5568124054266779, - 0.535972831841771, - 0.43553918321354357, - 0.6528574775158318, - 0.5920831802414896, - 0.6600602375249893, - 0.5614391322543182, - 0.364282770580937, - 0.5602961688228287, - 0.6031222273815506, - 0.5306828317565012, - 0.6152213868787166, - 0.36338057812806224, - 0.5662634251147523, - 0.5146368671570305, - 0.42332066285442155, - 0.48597310237507946, - 0.5895767911569908, - 0.4185868233562259, - 0.4386658678903729, - 0.6284130416794333, - 0.5052778446725235, - 0.45040152540516437, - 0.5353597955193887, - 0.36644788273533874, - 0.28998440082184984, - 0.37512146024948917, - 0.4469782523420971, - 0.39069457432711985, - 0.2709145950131206, - 0.6186182494312352, - 0.5119902193070611, - 0.3398129215663967, - 0.3716608696473306, - 0.3001942897936771, - 0.46070949264085004, - 0.6556107599941249, - 0.6800227527495073, - 0.28876786164405704, - 0.27226913710638584, - 0.3266938148708885, - 0.3128575199117717, - 0.3316801010544702, - 0.6417469118493102, - 0.3722155032082669, - 0.3232674311206458, - 0.5700349707188266, - 0.2877568988359563, - 0.6784076964102574, - 0.47036114041191845, - 0.31878383911918545, - 0.28913854242725817, - 0.41532597175198127, - 0.5519051429322472, - 0.4825207259741713, - 0.5007073681739557, - 0.2716570652125821, - 0.6765885144613226, - 0.6771676976603451, - 0.26262070617704947, - 0.4635166407943678, - 0.5313272744412265, - 0.5065581722220653, - 0.6325348179656692, - 0.5233163356648948, - 0.49460866412706417, - 0.37967729264362404, - 0.3233665807294194, - 0.5696653876249451, - 0.5924590325305001, - 0.450533096918673, - 0.5143428859020488, - 0.3103534543994366, - 0.3000028042022838, - 0.27545989956380723, - 0.5594158976427511, - 0.6041211515347085, - 0.5804162395834115, - 0.6142220657390784, - 0.5534166158926412, - 0.6721692929901131, - 0.6681416717823887, - 0.42795254718843867, - 0.6698717243786281, - 0.45595514718821495, - 0.6041324301441153, - 0.31723531235026287, - 0.6517722277668051, - 0.5273001882485833, - 0.6647744335857897, - 0.6460511784853857, - 0.47123960462172026, - 0.6041102686468701, - 0.621555954429273, - 0.40049719108887016, - 0.403511306488724, - 0.6853309889117792, - 0.36844607344415586, - 0.5705715891175319, - 0.6572182276388121, - 0.4599309200636594, - 0.6056762909872031, - 0.5842124857964125, - 0.3725798262808887, - 0.6699457333192558, - 0.46633903266647814, - 0.3082051744234116, - 0.535668002672415, - 0.3179215057786139, - 0.4388257336048629, - 0.46066295339562857, - 0.37846704318328517, - 0.4895225833554695, - 0.32300177049672274, - 0.31321049687800595, - 0.47729541489165117, - 0.6749203439501912, - 0.5454110435301542, - 0.4201665043292512, - 0.25857284622756543, - 0.4430239155466055, - 0.53955603251604, - 0.3046402631366938, - 0.2822017893880635, - 0.38300953814233163, - 0.5815603809479195, - 0.3388444419971641, - 0.4768385278517363, - 0.3792845221569469, - 0.5283683978554705, - 0.5468697974357335, - 0.49598804464265045, - 0.348170002299228, - 0.3435766776375754, - 0.3167917078921251, - 0.47819602474261313, - 0.2864199088567233, - 0.35353866254382726, - 0.5335954356036212, - 0.31825355691841595, - 0.2784496666686802, - 0.6131263835373457, - 0.43757046602492056, - 0.5778397414857677, - 0.43388875336897464, - 0.5838873211171494, - 0.5048405500535925, - 0.5809572372200491, - 0.4333570760294009, - 0.43245127769147684, - 0.4315146950038773, - 0.6082561021698647, - 0.5010964296536904, - 0.33174808532606437, - 0.2814113989844661, - 0.44469242936406544, - 0.31856057490209366, - 0.4859876037580576, - 0.5984190217116411, - 0.44831369552475453, - 0.34755992320234946, - 0.38870447847117606, - 0.3992223531649903, - 0.5036969069500942, - 0.6027439289489661, - 0.38086834224576355, - 0.43037034930950235, - 0.47264223167434327, - 0.476686935381876, - 0.5316666387656793, - 0.6681920101054319, - 0.5960118526192586, - 0.2737429856132531, - 0.3133981994201455, - 0.6246308619333563, - 0.343558660751669, - 0.44420869830055215, - 0.5409784460271942, - 0.6400373436044895, - 0.34652801756389223, - 0.6130156077123684, - 0.36357104209828806, - 0.3222953312895265, - 0.567609055166441, - 0.25898262249564985, - 0.677669517831349, - 0.4788302568352417, - 0.3398884888043384, - 0.5721804385292891, - 0.3274814881912181, - 0.5686207689218794, - 0.39688336351086445, - 0.4510530379757879, - 0.44699453531274347, - 0.6699958544857187, - 0.48037548640424854, - 0.38667588261389607, - 0.2818140052023526, - 0.3271745567656534, - 0.6710426387373141, - 0.3381494699742953, - 0.6657027383503706, - 0.3280070109334297, - 0.3238976659659, - 0.4605697688417285, - 0.41296827223054666, - 0.5824041319969055, - 0.5545792455005644, - 0.6585911275452261, - 0.5036349357500434, - 0.2952031626121732, - 0.30342899790269146, - 0.4152174509080363, - 0.3727748742486074, - 0.6603051542154482, - 0.3333364290600196, - 0.4161354118210021, - 0.3644250386910771, - 0.44450644706554987, - 0.6442572280872756, - 0.6838341458000768, - 0.38984841201647225, - 0.6648199467665054, - 0.4131182095392879, - 0.5568969968538903, - 0.5166353106018682, - 0.4814484538182708, - 0.25892308835341216, - 0.28910624035201, - 0.31794276470409805, - 0.5504750941863568, - 0.5178858973486883, - 0.6741893700059515, - 0.26452700290041103, - 0.6029866316780178, - 0.2690709462680292, - 0.267936339012365, - 0.49850808288630166, - 0.5558153166668282, - 0.2619608379674846, - 0.4774648144134327, - 0.3984288523587519, - 0.6457375488629415, - 0.3425650234373958, - 0.3316231096440103, - 0.453686841485488, - 0.5017736139691, - 0.488370262494633, - 0.3924130359980466, - 0.4511256415803995, - 0.50861351033161, - 0.37246992106931426, - 0.6249448167228597, - 0.558011857254978, - 0.3963188095243917, - 0.5455183300240025, - 0.5160369868696102, - 0.2743805940850622, - 0.586266574899208, - 0.5770923504810783, - 0.30498317687043264, - 0.6454684559435849, - 0.3124209026123289, - 0.6145282426726963, - 0.30495054010069156, - 0.44062041848423183, - 0.675764386205443, - 0.5067001708098149, - 0.6859099978592823, - 0.6596381762250837, - 0.26460503515387424, - 0.38471719816355243, - 0.3634309344604761, - 0.32131918386539116, - 0.5253663407448417, - 0.598058891061749, - 0.4870449888361872, - 0.49581476917517064, - 0.600570474508879, - 0.5539897354999143, - 0.39646724841889336, - 0.35945911566070193, - 0.6761524200195768, - 0.31552285426519044, - 0.49516565713178795, - 0.2587013984674797, - 0.5940629634953442, - 0.5863180913244999, - 0.5077559657466867, - 0.4471797901528519, - 0.5446183433192192, - 0.5135522615250143, - 0.6774279185005583, - 0.31401828006701094, - 0.45126813445300684, - 0.40176188102331567, - 0.5584951075914185, - 0.27325880439563477, - 0.4229964535763632, - 0.5357305602761295, - 0.3227114741503407, - 0.298667445675278, - 0.5813842436019576, - 0.6051511921665271, - 0.34053213287400486, - 0.5252342393946727, - 0.31758879645377613, - 0.29046942797090514, - 0.4763159548914474, - 0.41555801740389764, - 0.64495116175089, - 0.5215036848578166, - 0.6286687652839231, - 0.5127779993002008, - 0.29435817310717977, - 0.32411729662017436, - 0.5182321650103352, - 0.5873557357657695, - 0.6349812149249975, - 0.2821749055931272, - 0.49236438104383873, - 0.2631342550611555, - 0.3477314768445843, - 0.5120186566829577, - 0.2670475275088453, - 0.2971490104086185, - 0.3918391368950725, - 0.4296344279361314, - 0.45061608543787524, - 0.5331949483040599, - 0.535624047628765, - 0.4378576186154001, - 0.3017409535461379, - 0.26848078829372357, - 0.6741555737234788, - 0.5259170409184155, - 0.4277210558722281, - 0.4290130915644105, - 0.6447831869767533, - 0.28557232302607466, - 0.508331159278361, - 0.2638735026837855, - 0.34242617590715385, - 0.2580138103286811, - 0.4275531805662753, - 0.4649016855611409, - 0.5544992960420605, - 0.6532252003896699, - 0.46665860246823865, - 0.29956692201425356, - 0.4153514670025406, - 0.5971018231076364, - 0.5094974440027646, - 0.3140166073335455, - 0.3761954991022899, - 0.5804937982775338, - 0.6780589752879915, - 0.5563202063894336, - 0.5017521641572636, - 0.3196026618670636, - 0.5748010293196613, - 0.521776111175847, - 0.687052997564888, - 0.6021388669520122, - 0.6302293962016047, - 0.6189045305303582, - 0.4947815612443337, - 0.4421426316589417, - 0.46765366912004014, - 0.5394295501334541, - 0.31415115675349925, - 0.39603499587898705, - 0.2733828058936504, - 0.5681309913608699, - 0.6766396686297502, - 0.5482468486525818, - 0.3844854406504876, - 0.56078403667883, - 0.3830305368138624, - 0.6476650978975559, - 0.515537842966787, - 0.44195315879585373, - 0.3229502156763555, - 0.2927957246497578, - 0.3504290965849224, - 0.5956029674657051, - 0.3222430441646889, - 0.5403291120555179, - 0.6413320356056076, - 0.3762831810377131, - 0.2748792977959603, - 0.43299932900652344, - 0.5334924119560922, - 0.6587499906404973, - 0.5428858776218524, - 0.5213789744812467, - 0.5258481801000177, - 0.5496060994258012, - 0.6553536685114891, - 0.6711830329001371, - 0.2702275858382071, - 0.3297281843583564, - 0.6197858787451009, - 0.5493322491545243, - 0.4081705777191116, - 0.34887203916193094, - 0.4738178553540441, - 0.46385874816454825, - 0.4580664023025629, - 0.6861286351668151, - 0.5268639501226011, - 0.38579480382159764, - 0.5728336485689818, - 0.2779669403884202, - 0.5521881320238176, - 0.3988748278612636, - 0.6331688272199483, - 0.5104224505687516, - 0.45063647771496973, - 0.3657570404830399, - 0.44113228571768437, - 0.26339415717857245, - 0.4582054408332477, - 0.5719000400510951, - 0.4828915145498862, - 0.6134091750566822, - 0.6384501025001439, - 0.6516671044591595, - 0.4125263378041994, - 0.506642839667785, - 0.6755492826171126, - 0.29502069371739736, - 0.40797808631426924, - 0.6843654362234752, - 0.513448787172166, - 0.33280621290027784, - 0.5666992153351557, - 0.3679288821314015, - 0.5757936547676692, - 0.5448029460049215, - 0.44004519582320645, - 0.2590054680538968, - 0.47872976314100446, - 0.5341538634353157, - 0.44321489455180857, - 0.3591266939618958, - 0.5950771560742374, - 0.6703354748780981, - 0.27673234804866287, - 0.44205340699243584, - 0.4989880499284637, - 0.6376658381181466, - 0.6259332246553027, - 0.32546322645673376, - 0.5557642929054101, - 0.47493450762767386, - 0.49722648375388945, - 0.5581065355242258, - 0.590381585429649, - 0.27818728061637443, - 0.40137462023003667, - 0.5990246294978676, - 0.560756481577828, - 0.5532851887138277, - 0.4381457204010708, - 0.3559312263066019, - 0.5738150087974274, - 0.43422266339518084, - 0.6011433835403421, - 0.36176731252585503, - 0.4157979834038017, - 0.28290436376536254, - 0.4179681065670878, - 0.5371365764569532, - 0.4802070287992143, - 0.4549784678743799, - 0.4484461056003459, - 0.5348149677990826, - 0.5646631117196232, - 0.32418400295750077, - 0.6867048902152235, - 0.3315222083314135, - 0.4207386018509919, - 0.5974128870013611, - 0.43953831593779735, - 0.6645296680498609, - 0.4362322755437703, - 0.5595086784169209, - 0.4881948975498111, - 0.5785748155212342, - 0.40040056432667714, - 0.47880920977496905, - 0.4731310006402993, - 0.3561231297570195, - 0.5569646616039297, - 0.33149313464072444, - 0.3042590660332501, - 0.39101658500345493, - 0.269765807707365, - 0.32972694599832403, - 0.4707361949363158, - 0.6437987429726004, - 0.6269178665770581, - 0.31385617521814085, - 0.495281205480843, - 0.6659648671712111, - 0.4862097740043255, - 0.2880176759325232, - 0.44170275206094844, - 0.6396543289597246, - 0.6376862341389435, - 0.29510792762547167, - 0.6632378003539612, - 0.542888039457133, - 0.31383523194305585, - 0.5375551197125954, - 0.6696183028856202, - 0.4379997669092528, - 0.6566307322041796, - 0.4717670082952401, - 0.2891228703217233, - 0.6038243729938252, - 0.6472492714872857, - 0.6610875928323892, - 0.4821677546051608, - 0.5834312881152088, - 0.4653725066702039, - 0.43677586270938695, - 0.5510086428663638, - 0.4726033049876702, - 0.29902849748636334, - 0.475844491959444, - 0.36201205169616796, - 0.47435296793415793, - 0.44722307686754775, - 0.683799530194309, - 0.3220343163568915, - 0.5754901374766402, - 0.6787316122661466, - 0.4464474076131656, - 0.4454617057525052, - 0.3133381981414262, - 0.36172027632785037, - 0.3377375003311525, - 0.2642650097880276, - 0.5083186107233841, - 0.4505874291771056, - 0.43820692531389493, - 0.47816153729315236, - 0.4652175938728206, - 0.41907684095661746, - 0.5592059994410475, - 0.5676345108635188, - 0.3608773723374407, - 0.6754861259861231, - 0.30612341050620506, - 0.28456534112172177, - 0.35551408102688176, - 0.45397667031736283, - 0.4973830877099363, - 0.49910555524203837, - 0.558926848310755, - 0.36014804475058904, - 0.5613887408198093, - 0.3710647737668133, - 0.3002808929842424, - 0.4119762175763676, - 0.4535934365736824, - 0.6593874724993627, - 0.330574506780158, - 0.5156731456550242, - 0.5234747798792999, - 0.6857908894209161, - 0.6127628698424765, - 0.26092067685011144, - 0.6703282148411802, - 0.4904071554717895, - 0.29577383019608433, - 0.6186644833854604, - 0.3639588432205131, - 0.6570588022546622, - 0.2656300269587552, - 0.385958086283343, - 0.5722419833562551, - 0.6517257008417315, - 0.6439784136810771, - 0.4020008313870882, - 0.5783364849837634, - 0.5147576369721312, - 0.4844722466698178, - 0.44096223012799757, - 0.6247751994256765, - 0.5997258911513463, - 0.35968931386323133, - 0.5198690305983465, - 0.49261484653154236, - 0.6525633773542082, - 0.5483509583677426, - 0.4475358832683013, - 0.454580081855012, - 0.5010716790461229, - 0.4385797650402926, - 0.5744119067003126, - 0.39160193435198065, - 0.5570916564459456, - 0.45126540902243883, - 0.40078357495308287, - 0.5610895350521358, - 0.46584574937922996, - 0.365587243379629, - 0.44111661042186023, - 0.531926561042909, - 0.30369579820474246, - 0.6085253853064643, - 0.5551403880064587, - 0.4778438267311629, - 0.58072151375817, - 0.3604379731108611, - 0.3176929394840586, - 0.4604681509889803, - 0.38518635265320833, - 0.5917824513718186, - 0.3788965005198706, - 0.5335752699466927, - 0.527537331999327, - 0.6294075137420846, - 0.31960900801519004, - 0.5729294659747055, - 0.42329944644342077, - 0.5682809599399814, - 0.42989023964719264, - 0.2736553301806667, - 0.3834754511443856, - 0.5739255790565191, - 0.5003314625414197, - 0.5195317286869041, - 0.4239505320681496, - 0.42370196840346064, - 0.4284060446893735, - 0.2669208612644959, - 0.5732773762207333, - 0.3191264863664642, - 0.5813385190464095, - 0.27525692418491504, - 0.39856151318457145, - 0.35994987441537074, - 0.38597936561865775, - 0.6255700191006854, - 0.5016176843837128, - 0.44523282130086317, - 0.5926881249720457, - 0.5859744485129526, - 0.5082951319638351, - 0.6881757056924054, - 0.608502519688203, - 0.46781757384831996, - 0.6156647928653807, - 0.4368842284281099, - 0.6128805458654099, - 0.5958224110967811, - 0.5448637998470857, - 0.32827013498386787, - 0.2883584263754633, - 0.5123356520020195, - 0.46221370028464576, - 0.5268687362987547, - 0.370051763555595, - 0.3484481966107676, - 0.343733005036355, - 0.5958444701300251, - 0.5891738430079865, - 0.3831489893017619, - 0.6305592379520999, - 0.47151509088492677, - 0.4301730602901068, - 0.29278332890834935, - 0.6146754450482494, - 0.48566021044918145, - 0.4617489650756078, - 0.620345381461479, - 0.6286236338680766, - 0.5989407570878755, - 0.6262827289900761, - 0.6544708602553655, - 0.5594403990163976, - 0.6502143382508964, - 0.4175808197045212, - 0.2581576277932008, - 0.5182254102589375, - 0.45643349252907145, - 0.6138478151841604, - 0.3801748359081182, - 0.3561334448072149, - 0.3619039426392992, - 0.6619265979839035, - 0.3855003485143629, - 0.5151187778666022, - 0.5268419628012062, - 0.5677752076954691, - 0.48046312075459685, - 0.38787831327402766, - 0.35348776245635594, - 0.36131233128353174, - 0.276382116086622, - 0.3482201985206621, - 0.5416426576917779, - 0.261928255497856, - 0.4439123474757566, - 0.47779883014153146, - 0.5698673702765022, - 0.5830990289563185, - 0.4093717031606803, - 0.6537738565810853, - 0.3357940219628789, - 0.6076140298977959, - 0.5115875851875286, - 0.6276582521910818, - 0.29539403738576736, - 0.2947977275516671, - 0.3375559348177604, - 0.3631967478091847, - 0.5437146492302023, - 0.44951397260641335, - 0.34668592719092584, - 0.37238432777283925, - 0.27451201791689395, - 0.37955123940957447, - 0.5308475826732588, - 0.28825284504726717, - 0.6618698925164043, - 0.44608122747534706, - 0.4814771993511112, - 0.48866051397488586, - 0.5259493894428549, - 0.6614281632224221, - 0.6814871189876128, - 0.36288627084524694, - 0.3045871771472343, - 0.25953299063212787, - 0.6802470388707997, - 0.5707429025579815, - 0.38888579140370366, - 0.31510533678979863, - 0.5213519892233192, - 0.40054879609967836, - 0.33845555823403284, - 0.2797070680723771, - 0.5242916082995774, - 0.6600391322275022, - 0.29550132920131317, - 0.5984225307705432, - 0.5166077938594169, - 0.3085696072628129, - 0.6006702541274862, - 0.5454611786675467, - 0.6139738694848983, - 0.4232003126159694, - 0.5794651651787586, - 0.2585700983683443, - 0.3836607633323727, - 0.33831707146877826, - 0.3224964950008745, - 0.4023575185124983, - 0.4002393909574408, - 0.4701364813002831, - 0.5337939200559432, - 0.3107618703614187, - 0.3360487307747292, - 0.4480581214201504, - 0.3449452576853525, - 0.5485446728338002, - 0.3078475168207656, - 0.621899511700619, - 0.6216213874485618, - 0.4921025126747549, - 0.6513368119934437, - 0.2802287986098698, - 0.2877876433889881, - 0.3204808459955374, - 0.27968845822229965, - 0.5662013981353253, - 0.5855216239064027, - 0.624630632028627, - 0.45477365367342554, - 0.5135077178918617, - 0.2881035390025014, - 0.5658737651643947, - 0.5014997332547804, - 0.42579642069038426, - 0.31186200471529535, - 0.6883851493079062, - 0.392368738453189, - 0.6326742384250439, - 0.6727310124705161, - 0.4588794973076643, - 0.42623643957259627, - 0.277460196265971, - 0.6759778590380803, - 0.4645376931977081, - 0.5385889540194366, - 0.5802250791033892, - 0.5550729140646316, - 0.5559982429758179, - 0.429034981588131, - 0.3711792732167427, - 0.27373199538143794, - 0.6803864745278876, - 0.47836004777579433, - 0.3022288432457384, - 0.47004992161974135, - 0.29600607345815405, - 0.35530219711302735, - 0.6043068016008537, - 0.33181247773666833, - 0.6482554426958659, - 0.4995463387771272, - 0.27046284994811715, - 0.6795070291087177, - 0.47571372859928496, - 0.4233790661156298, - 0.3295551695933479, - 0.5271231953052419, - 0.5396833140557201, - 0.29460973048861083, - 0.6420718076898387, - 0.26223836141297363, - 0.6704585727669732, - 0.639393145676793, - 0.3857607531626185, - 0.41974091225674326, - 0.33498693917684763, - 0.6281833072591254, - 0.5889821848914597, - 0.6458408428445995, - 0.5648309761350553, - 0.3671366111328529, - 0.61424787192832, - 0.46589237105728587, - 0.6461728921841342, - 0.6563931560220047, - 0.521975772186903, - 0.39688885150628894, - 0.3135177439811329, - 0.6118605734678069, - 0.46321669479401384, - 0.28728310134813073, - 0.4757540235329034, - 0.37321498103644835, - 0.595198746836877, - 0.6087936766100606, - 0.5168692634663021, - 0.5499074031546239, - 0.3376233736929713, - 0.6578356323564164, - 0.6262978028621077, - 0.6668897639968219, - 0.47822080152251023, - 0.4373919347784486, - 0.47394810649030533, - 0.3863776048459557, - 0.4514833388462082, - 0.609828159742134, - 0.34087034967594676, - 0.5523372306371404, - 0.40766895728345176, - 0.6793639271807532, - 0.44249330297028927, - 0.33868201780561624, - 0.6835844278947094, - 0.518602932601607, - 0.390260262084753, - 0.4613964179385368, - 0.4029305719692376, - 0.3615602305594142, - 0.5559392999066728, - 0.4925088210354912, - 0.6314709342043274, - 0.4595196541780016, - 0.28557286533532633, - 0.6097943482347998, - 0.34819745408953684, - 0.35426811274951264, - 0.35662197923001615, - 0.4168059884046505, - 0.33942964364702216, - 0.5966493400682762, - 0.5014912253687083, - 0.38017745230971955, - 0.5512159010520157, - 0.6378217139223303, - 0.523567448787666, - 0.6079328969637623, - 0.6295521364881762, - 0.5163974720269553, - 0.3055881014665295, - 0.6340933362135412, - 0.42294116968629675, - 0.6591255939583553, - 0.4019620756553858, - 0.6121988688356186, - 0.3047646875648005, - 0.46791249148797154, - 0.4463400418029184, - 0.3815645967924712, - 0.2712597809822125, - 0.2935530328738317, - 0.35791568489922204, - 0.458033369843709, - 0.5319644020270562, - 0.267576109553462, - 0.34053669254712093, - 0.521043919235417, - 0.6486268175255514, - 0.3170645577141654, - 0.509322524905395, - 0.41091405407712434, - 0.5216242551119729, - 0.4568000433839086, - 0.49966708413568117, - 0.5231468349065632, - 0.5120946979100099, - 0.6484174335332975, - 0.4421668412329299, - 0.5436207630811818, - 0.4667059974466009, - 0.3241459029619823, - 0.4389784126705142, - 0.6300293471610461, - 0.5913878949624306, - 0.33119766441187715, - 0.5700127852268063, - 0.5273760555001501, - 0.5346403816945903, - 0.5101379224873777, - 0.37142831159700546, - 0.28790125307417336, - 0.6346927891517933, - 0.3738284666543952, - 0.6142699124806856, - 0.5550136786499895, - 0.662524395526429, - 0.34414212441886116, - 0.30246626272335914, - 0.3337546382714726, - 0.6025758833868569, - 0.5280817194657493, - 0.6485887545148139, - 0.6375905463835195, - 0.4650735134283992, - 0.43098672136228744, - 0.36525698563116393, - 0.6544405529765371, - 0.493990896706368, - 0.4478457119299778, - 0.4417189226776948, - 0.5491564191385496, - 0.686547686829613, - 0.44035081743672944, - 0.5240469557696863, - 0.5238929519828255, - 0.46589227854254434, - 0.44264823051989566, - 0.2807635061138326, - 0.4737114519927067, - 0.4883622326114825, - 0.366972082757374, - 0.2711273001644959, - 0.38866685788838506, - 0.5116966654627066, - 0.6789057597418828, - 0.2697095250822023, - 0.2974307494657082, - 0.5724848676570342, - 0.4170741122406463, - 0.29870490118209203, - 0.6178592679191954, - 0.5805140876603485, - 0.5109393959843263, - 0.5384081623961177, - 0.4945712339444112, - 0.6197754178377588, - 0.5914830868314249, - 0.28098233827577196, - 0.36235442202579693, - 0.39347178788634285, - 0.41425081370159045, - 0.25942565529230144, - 0.27985080609353685, - 0.5722010216127551, - 0.48419916683593356, - 0.36731004885792, - 0.4144283491141647, - 0.26282644761469187, - 0.4466789972809822, - 0.3286939609975305, - 0.5770847807623417, - 0.6079286489122975, - 0.5984339588956105, - 0.3321146957416688, - 0.411019084917425, - 0.2609753814256973, - 0.48478388477670253, - 0.5250468472402965, - 0.4720893465791175, - 0.5362611095027515, - 0.3610662751310053, - 0.28135660351378844, - 0.4622785341320055, - 0.6510300840488461, - 0.5282965206468891, - 0.6460485703924763, - 0.5590103840593009, - 0.6691840512411031, - 0.640311625925339, - 0.3528474730922876, - 0.5329505809334174, - 0.6175482092506228, - 0.5646799122746446, - 0.4223058888574203, - 0.5364526631886358, - 0.5791072685625218, - 0.6241260603587961, - 0.2993799908825392, - 0.29185363829696265, - 0.6247414867127703, - 0.6810840239353912, - 0.29296411500761244, - 0.4866557040801222, - 0.35460418091412155, - 0.3499078284466723, - 0.5616845876356948, - 0.662282571253316, - 0.43192361014333813, - 0.5128386189028203, - 0.5769419648278917, - 0.5745462607940514, - 0.4783891157658402, - 0.4924886486208975, - 0.4682024160452488, - 0.687346166740074, - 0.3209755858506522, - 0.3122924392018366, - 0.4631850383750512, - 0.6221005924518832, - 0.6497270967619146, - 0.6780921580360617, - 0.38810413768788743, - 0.4103419575571295, - 0.6884354521557886, - 0.4733603961723658, - 0.6694269060585327, - 0.6575585479489978, - 0.6737496033227487, - 0.5197355992677284, - 0.3883296451059304, - 0.46967793406778713, - 0.5776617502041199, - 0.3503838909618889, - 0.32406599350758064, - 0.3732906072763198, - 0.3273299449693953, - 0.41721882287743095, - 0.587599157272616, - 0.5997058242049161, - 0.6225644322510124, - 0.6244002495531477, - 0.28306434657330365, - 0.3546303217242826, - 0.5080376491722345, - 0.6230080105581726, - 0.6443686020163225, - 0.601197487333781, - 0.661717301312138, - 0.4125258803160047, - 0.3357678482431624, - 0.2957950164996377, - 0.33178636065326106, - 0.36857129446472126, - 0.30276903787585735, - 0.5975177440438915, - 0.6642650124041718, - 0.297353391916138, - 0.29321150536836876, - 0.5466452866755925, - 0.5344489548978931, - 0.57496099826086, - 0.4828688209893075, - 0.5980327826874761, - 0.4651100546852648, - 0.6633115605311777, - 0.6122216299011807, - 0.6132501923469659, - 0.40322281356132117 + -0.21526389852559014, + -0.5668076639655169, + -0.5634771243075074, + -0.48026675530570584, + -0.6105894952396467, + -0.528834561488468, + -0.20427884154503073, + -0.5816803609518845, + -0.38153783025719773, + -0.26948606942401004, + -0.3688975289296914, + -0.6359853003634688, + -0.4273868730430644, + -0.5410618594727711, + -0.4822991775856031, + -0.6000760136419334, + -0.6770172204223297, + -0.5926089720797051, + -0.28325039167604055, + -0.683727001977012, + -0.6944325720112785, + -0.6365672449941226, + -0.43759186533026323, + -0.6873404885026364, + -0.352291894934858, + -0.6763138774698857, + -0.5344870490104631, + -0.4933794028262368, + -0.40168449364987546, + -0.4767620474605535, + -0.5820975451679147, + -0.3719557442925087, + -0.1920500774993632, + -0.48413852968543436, + -0.23319737468354235, + -0.4183797692069673, + -0.24198083019339367, + -0.5927015932220178, + -0.207306658457523, + -0.687267235706826, + -0.3615524586386805, + -0.47580236234233897, + -0.6482327195215988, + -0.452071335970582, + -0.6794329073406332, + -0.4821681731735029, + -0.3847862455731721, + -0.4585895152390683, + -0.45076666032736185, + -0.1991435229227715, + -0.48437694622178884, + -0.33567761675735586, + -0.16806080974870896, + -0.5854997920723012, + -0.2634266711000602, + -0.6938328365839215, + -0.22022443093669347, + -0.30228225474968207, + -0.473697779730351, + -0.58787501791053, + -0.5747254730815081, + -0.38661090618840144, + -0.4525455738154044, + -0.4852154042526807, + -0.23677108072346942, + -0.5797875050219646, + -0.18960332581143713, + -0.31879215386083337, + -0.2985985193227354, + -0.2479027929285229, + -0.5827320173700912, + -0.3999983089263434, + -0.4384505056865782, + -0.5340810194978354, + -0.14889848273296136, + -0.20716787374985596, + -0.2787442085683768, + -0.1563407697324456, + -0.49365811430562745, + -0.32840489438635656, + -0.4019233308894716, + -0.5800464504993721, + -0.5899015543940788, + -0.6767687635138475, + -0.631705445060666, + -0.3639690707391558, + -0.6283145227777176, + -0.6926201922318653, + -0.4047761496992247, + -0.29614722338752864, + -0.36597979137400555, + -0.6143579857897379, + -0.3592793920823914, + -0.32491271118632864, + -0.6196178613765617, + -0.4905221061569761, + -0.33380004107977485, + -0.34315763094612356, + -0.5730476283140317, + -0.6643791833063918, + -0.4264024723664032, + -0.33960041049174966, + -0.492063563260129, + -0.4518432963066661, + -0.2675590447170642, + -0.47652769182442584, + -0.404460528825577, + -0.40694422283870973, + -0.41866840777093767, + -0.25018158548965436, + -0.3357983193142373, + -0.5119608139525116, + -0.6681389534446313, + -0.4408080929682888, + -0.4296174160693305, + -0.2938403216717465, + -0.298562915938461, + -0.6317950609868391, + -0.4750925677047576, + -0.27754328064793027, + -0.586251582786329, + -0.4034006634826291, + -0.2085841995495269, + -0.2528736251079428, + -0.5484941371120031, + -0.30737080385583193, + -0.3636011409672178, + -0.2374230498058933, + -0.19262544839201212, + -0.2834610648409034, + -0.44176606352562237, + -0.1918394285970243, + -0.43286957130061177, + -0.4705464574790802, + -0.34202151998338487, + -0.2526122317428531, + -0.5101631075415498, + -0.35427361262068663, + -0.1967571490215113, + -0.3692962823049929, + -0.5881504015653899, + -0.3375595528846289, + -0.6708378352307791, + -0.401557770711446, + -0.41743562643710497, + -0.46038129349197976, + -0.5349823492938082, + -0.6874945543016642, + -0.6563036244778957, + -0.4758892941872483, + -0.526602158506708, + -0.4483941038098501, + -0.22575063111469196, + -0.6548952649401933, + -0.6819474994469957, + -0.6206292031472959, + -0.5278033730711778, + -0.3009303163088597, + -0.3912521604400618, + -0.35925670973255514, + -0.28785858027739386, + -0.24724224644536702, + -0.2865296059429153, + -0.196947494232949, + -0.589686853160144, + -0.4610229225374262, + -0.1736911509707474, + -0.27532794151000023, + -0.41935496010648254, + -0.40572664365236993, + -0.5692365980756601, + -0.33879866076302506, + -0.26272847800110677, + -0.5338147495225387, + -0.6803796477431132, + -0.47537211473008084, + -0.2620982128161942, + -0.22017891924789823, + -0.20771787547936782, + -0.43420924228466545, + -0.16498457157702218, + -0.2581621050228022, + -0.1454445829635055, + -0.40493163856591646, + -0.3497626222582684, + -0.6669387057337621, + -0.15332366397516117, + -0.20220118991697822, + -0.17140112395010654, + -0.5531206214097724, + -0.4643250645739929, + -0.6914924877765393, + -0.2666324881832466, + -0.5959941759254339, + -0.5723506226473106, + -0.4624695345383819, + -0.46968615143340775, + -0.6841776754148233, + -0.2929798291387249, + -0.45360084646137266, + -0.482107802843161, + -0.42115711210480716, + -0.523466443078983, + -0.16261207265513766, + -0.43269337370900274, + -0.44559732225615695, + -0.6422268164721529, + -0.4118222177369574, + -0.36665277110116895, + -0.39444379843191585, + -0.6897154325228744, + -0.34720576594930497, + -0.31688817089183186, + -0.5974254940932917, + -0.2597430646311647, + -0.6832730519739092, + -0.49558725060429604, + -0.2949628534445622, + -0.6383697934051112, + -0.35082587597742826, + -0.37721775122359696, + -0.32429790138762615, + -0.6628125503876823, + -0.6400778198389123, + -0.5022114859398216, + -0.44303844712049234, + -0.6576644623407387, + -0.14643411893318437, + -0.5831059084612487, + -0.4962425709841234, + -0.550623437500016, + -0.5682074709905698, + -0.16399640304854746, + -0.47648103205835934, + -0.2564289749333582, + -0.1528424140155097, + -0.19632199326509925, + -0.3976044499503634, + -0.3000757872859389, + -0.4107578923456179, + -0.572738964594816, + -0.4137846489198366, + -0.49387164585427157, + -0.25431908461016905, + -0.37945759300107357, + -0.693098142425255, + -0.6802386498566139, + -0.4185696274767257, + -0.6151313078157574, + -0.3442992009357707, + -0.4030051152553079, + -0.6901212175319289, + -0.1432716503561745, + -0.4023586104529854, + -0.5073081512616008, + -0.35117845702744693, + -0.5317604096148164, + -0.21362812206555531, + -0.16106013241149564, + -0.3916748011481499, + -0.3900175220355754, + -0.2523033776073218, + -0.2700412497278186, + -0.5719202029435765, + -0.4083922406429072, + -0.39934528507908995, + -0.6564849371063238, + -0.5244731471824519, + -0.6865079030405267, + -0.6114530030712465, + -0.25984795905333063, + -0.3625635055872547, + -0.31102676273905766, + -0.378114672750309, + -0.5980100394047524, + -0.5781949044547483, + -0.23618236160344075, + -0.3097239051191674, + -0.541084740831006, + -0.2413716542441447, + -0.5897441132680863, + -0.3799479184436683, + -0.216198339124007, + -0.15108867157946704, + -0.30216525116452847, + -0.5296672053871968, + -0.20349831867406676, + -0.37936016840960635, + -0.32665207102851174, + -0.44969887389629115, + -0.2986271739828252, + -0.5381940276659318, + -0.26557750923869133, + -0.27628547754246796, + -0.6014320866232739, + -0.6431930955560783, + -0.6853213826411336, + -0.46303948132452366, + -0.5236232061363543, + -0.2977564361734746, + -0.2740990260203191, + -0.6490405780222896, + -0.14547515666218225, + -0.6565079025063754, + -0.14247642138476835, + -0.4820530838780044, + -0.6079928653208734, + -0.24367860757577908, + -0.19663664761583544, + -0.2587054844934042, + -0.18568213399400135, + -0.5407509619013914, + -0.19673958479260067, + -0.6845981032143993, + -0.535469369259308, + -0.308640245974398, + -0.6308214673251213, + -0.15075025473135373, + -0.6629058962552222, + -0.2525126583250521, + -0.6255636274305838, + -0.602940233259621, + -0.3418837154564412, + -0.3599463767937384, + -0.2410442171870018, + -0.5071444799436968, + -0.42695210225660823, + -0.46128592074875596, + -0.5271420319114182, + -0.25846378480455856, + -0.338942269624897, + -0.3410116652248729, + -0.3553896458484627, + -0.2905759460828277, + -0.2926982777546428, + -0.19887449151002784, + -0.6320599378707857, + -0.5280739919311576, + -0.29214462801341473, + -0.2780356973323652, + -0.4275590819297849, + -0.6383307253418019, + -0.6466171747590481, + -0.3340031366504746, + -0.5702213103495449, + -0.22505303767576734, + -0.3671116484287669, + -0.6054207810510405, + -0.420031359589941, + -0.379499748649322, + -0.3081047412189693, + -0.5367505933316209, + -0.6971347623405126, + -0.5931303716057673, + -0.5494212591825566, + -0.589403643143711, + -0.22474388174047644, + -0.4191637979037389, + -0.21597748027543934, + -0.4750092056413736, + -0.41955106140438175, + -0.28732072278240217, + -0.5578950366143984, + -0.36594348195377946, + -0.4131531695321406, + -0.5811303548892564, + -0.49217742205479614, + -0.3165246826326464, + -0.6717172886595825, + -0.2611963199866791, + -0.6926435457508168, + -0.4051750988732216, + -0.5926098417255232, + -0.4426878066118041, + -0.3334004634194424, + -0.42771737580572067, + -0.3053665745407606, + -0.36657545409079845, + -0.6448359294437067, + -0.6048529242382151, + -0.628107984162322, + -0.6750159797002793, + -0.3465327301974543, + -0.25998653918392, + -0.44068846209810414, + -0.31195135490012665, + -0.5020058399583776, + -0.6916932996558096, + -0.26801417982607595, + -0.6183877741494541, + -0.24050080972555438, + -0.47586362833497076, + -0.31891178653915686, + -0.37898477353438, + -0.3032546180342803, + -0.27653832305023296, + -0.19026067562873505, + -0.26374549012894544, + -0.6709847769421702, + -0.411481688211929, + -0.15188551584887333, + -0.41950245942357034, + -0.5019243673085719, + -0.5383071043729578, + -0.278176251237267, + -0.2569335776212289, + -0.23012739525959736, + -0.5399787461366308, + -0.4954275622120159, + -0.3924111088882546, + -0.5951346892481899, + -0.15488924095825074, + -0.19894128785068793, + -0.14210967616625803, + -0.6634260585760954, + -0.1557644811268185, + -0.151780585935401, + -0.5715693788390369, + -0.6668129805632896, + -0.4927382836273416, + -0.5331560896806996, + -0.6207281938645495, + -0.40998616806129257, + -0.17575056963284885, + -0.29204455698832815, + -0.6801102390920798, + -0.2737623077672693, + -0.3829516130918535, + -0.5066789535277716, + -0.6284986498822265, + -0.613332798463113, + -0.3727848619225612, + -0.5360828788602103, + -0.4490936462622829, + -0.15821449622659067, + -0.24919460858885628, + -0.2569732847429945, + -0.3739783187753656, + -0.19274127292350862, + -0.29896275981677606, + -0.5505679134937247, + -0.318422153150009, + -0.524366108518497, + -0.2230685936911586, + -0.3516054129096772, + -0.34831479887740413, + -0.3931438743717756, + -0.4113838389039835, + -0.348481892020182, + -0.33116247273639243, + -0.27381404807534315, + -0.5231041249280255, + -0.5564338163207172, + -0.6299229800416154, + -0.2922572879880402, + -0.17951107736091687, + -0.6817545607759401, + -0.45363046831042203, + -0.34078262402305515, + -0.14018493367950546, + -0.4165475408770349, + -0.18873748677678193, + -0.26783974569270674, + -0.49420726147940586, + -0.312212040789134, + -0.3749342414123156, + -0.6680995949541044, + -0.5571183834801717, + -0.5638040325165967, + -0.36391604952451, + -0.37113579085632836, + -0.4739371783977352, + -0.4238631070281471, + -0.6298405328983244, + -0.1580918643272733, + -0.5753149932180412, + -0.3490117719432422, + -0.3354510961509358, + -0.41836152855434783, + -0.6114392830450794, + -0.5249928169409083, + -0.33359454931440413, + -0.14752755064153733, + -0.5801328064105491, + -0.389248755068303, + -0.1689831288211543, + -0.29095640960435865, + -0.3195706283820997, + -0.431114520827856, + -0.5342721929452461, + -0.212032651559186, + -0.15415603315203164, + -0.4898222892229926, + -0.6929628487747368, + -0.3275227033999748, + -0.5518848588283765, + -0.4754478579992858, + -0.5020859362097194, + -0.24970925422517426, + -0.5048822864759303, + -0.5997158603045283, + -0.6305810898323154, + -0.4710465525642499, + -0.3780801672457604, + -0.5642305935303451, + -0.6448248328873669, + -0.6509345385694514, + -0.5055738228527857, + -0.6759089308247426, + -0.4341376317972618, + -0.4979962938144452, + -0.5534335936913292, + -0.1695733300971587, + -0.20093503708074772, + -0.34973724354073754, + -0.6201102597774513, + -0.524894814213295, + -0.5142690771066138, + -0.1976347607106237, + -0.3436386377606183, + -0.3866708034375136, + -0.5917315449239026, + -0.3828862383122404, + -0.324807375216214, + -0.4481373261158089, + -0.5104181225913832, + -0.19612045861830396, + -0.6302298270444524, + -0.2851023471325862, + -0.42585487874073336, + -0.13903618515835525, + -0.28204117658772154, + -0.3232620217995583, + -0.4254402957536574, + -0.3574483949969366, + -0.5147631788946414, + -0.3671369834156951, + -0.6179457967823929, + -0.6820634912356419, + -0.25103464743381904, + -0.19429802640801896, + -0.2421148271217281, + -0.3074977294767069, + -0.14629914981937242, + -0.6461038231434193, + -0.5392657261795686, + -0.6856062608603823, + -0.248821232560411, + -0.6295447746878674, + -0.35855468871349994, + -0.32595118284877644, + -0.6916699430775799, + -0.31843118428171424, + -0.5644172444210394, + -0.5224745560563797, + -0.2551302854369139, + -0.20366263744983742, + -0.2082549425044497, + -0.6055900822903126, + -0.38543355085502956, + -0.39121457488468175, + -0.6030594430125832, + -0.409117903323125, + -0.5444583898331984, + -0.6426906800337345, + -0.2729108758988388, + -0.3287708441741195, + -0.32268395319595705, + -0.24712079063986447, + -0.3319436822747706, + -0.28352778180933413, + -0.3752771401361604, + -0.6640189769906387, + -0.6554988828800513, + -0.41924848059225134, + -0.3689669503124891, + -0.684838599502534, + -0.18266170276580773, + -0.3532130609014225, + -0.6281099366846545, + -0.58586419311318, + -0.3463672386541155, + -0.6414604528214005, + -0.39700693589001823, + -0.6543091181565703, + -0.3676360593828759, + -0.2477704579369866, + -0.6464569756610634, + -0.20587532476586778, + -0.30200044151963434, + -0.44537971266126536, + -0.3698468235780297, + -0.6882188724555194, + -0.31356744361539973, + -0.6081118682218483, + -0.6582168832181572, + -0.17262397240079597, + -0.1750482521519694, + -0.673946497685395, + -0.18589488472975912, + -0.6189946761778354, + -0.3024088544350932, + -0.1821447568945752, + -0.31657674430420524, + -0.42197323163587297, + -0.3284406211197238, + -0.16759427563415463, + -0.27623083502459955, + -0.16868971941792643, + -0.16111398401434684, + -0.27286211932555604, + -0.6496231085951973, + -0.23639958094232083, + -0.5750648539804049, + -0.6532529026682433, + -0.36443315213387634, + -0.6317755106686144, + -0.19334902506191098, + -0.43234580707985015, + -0.33384611403388126, + -0.6590782843644487, + -0.4051135429593617, + -0.3993802361211106, + -0.20934639120672438, + -0.26036343626390257, + -0.4076810880921705, + -0.5640494691387595, + -0.15824715281175705, + -0.19309555180754623, + -0.496603453608641, + -0.2923507989025627, + -0.4077229723263429, + -0.2493675651583599, + -0.5219057715068856, + -0.3984074696982834, + -0.6380185678661527, + -0.6786718833505176, + -0.5422095737954773, + -0.49649805976072786, + -0.6863874299624693, + -0.15312843660300157, + -0.637425883555342, + -0.4646234246420048, + -0.36026506850437656, + -0.46943738393646794, + -0.43378376990406453, + -0.20259938533527183, + -0.4167326708937919, + -0.31765362466908925, + -0.6036113094828982, + -0.6212501267960631, + -0.23795504276512536, + -0.48468728297261976, + -0.427154398538899, + -0.4909307055213845, + -0.5366833759211845, + -0.2058673896910716, + -0.23083859492270864, + -0.5099728089446275, + -0.4301558344491626, + -0.4146446251518383, + -0.1925017743841252, + -0.24201710340933313, + -0.3574754138529278, + -0.1474919127293639, + -0.15498479924438313, + -0.4970964139123859, + -0.26159445162449746, + -0.5533337425859597, + -0.39367904145520727, + -0.3081020121407764, + -0.22989463890251166, + -0.29228789418034157, + -0.5741926606813325, + -0.23848503902486212, + -0.4212099552155242, + -0.48175897074175833, + -0.2603089259201685, + -0.6385885971099798, + -0.6167554980087308, + -0.4011681840005041, + -0.3776057864487809, + -0.19203432692152755, + -0.1611579471981487, + -0.5211993539249601, + -0.5703327222715054, + -0.41056885119204856, + -0.6379065009877873, + -0.4802789227250636, + -0.45362926785667257, + -0.20872328966312526, + -0.15234613770825933, + -0.3525975187184175, + -0.5405421331967066, + -0.2562911294408811, + -0.19903650822664726, + -0.6186608074966065, + -0.1787547020944268, + -0.23999653023017808, + -0.6607564471790724, + -0.6493217435833661, + -0.4148776422042736, + -0.36511243265594706, + -0.5318361811539778, + -0.30556364302553884, + -0.40346773825976523, + -0.49206555682146147, + -0.43056469437672035, + -0.42969308595376426, + -0.1687413298608209, + -0.5814275438027134, + -0.2817088681167917, + -0.3185795449213315, + -0.41030893124033296, + -0.4737656195460803, + -0.3634732939773591, + -0.14066154524726016, + -0.4247196984871438, + -0.6395794009272529, + -0.3193985000343985, + -0.39707617881551643, + -0.605997808538345, + -0.24528775988578672, + -0.3727088453191906, + -0.32422722892552086, + -0.6645838817776732, + -0.33161077759657975, + -0.6943719086347901, + -0.42981396248402126, + -0.407833582234277, + -0.4394836641311708, + -0.5425111707727563, + -0.14313297257858215, + -0.25524889556378483, + -0.3274263901361544, + -0.5943483338024255, + -0.18698872997545357, + -0.45637114953864333, + -0.5472940817143578, + -0.6004294398598552, + -0.6877489319621786, + -0.16149455748478714, + -0.5689182207153135, + -0.31276026047126176, + -0.6215294534594782, + -0.39306245407709844, + -0.38186275225540034, + -0.1651611109583303, + -0.1886630404089047, + -0.21742310544091997, + -0.5072004869150573, + -0.5550007647882751, + -0.3437308618101009, + -0.4938856435608914, + -0.547192252153401, + -0.35913905497508064, + -0.46102959264702015, + -0.40400689920897387, + -0.6620770786357651, + -0.3779663918555969, + -0.3418658168616246, + -0.5643773419256306, + -0.15976561493144426, + -0.6600120640419861, + -0.22721365797485488, + -0.2919887261296891, + -0.45674696880441124, + -0.4527505821808961, + -0.5509143897075601, + -0.33021304364910364, + -0.5038678565118776, + -0.26138011655526394, + -0.3758899645519693, + -0.5969630015851606, + -0.5990197183395755, + -0.37393423495960654, + -0.16030890169055134, + -0.5224869663086269, + -0.17481967232448647, + -0.3288132768025028, + -0.5800334295985337, + -0.636423907226603, + -0.603776975348596, + -0.24451667937931937, + -0.21660673619134702, + -0.44738234802994187, + -0.43023322979045825, + -0.6565112758369289, + -0.218700527106941, + -0.5877579146051259, + -0.42942422395522306, + -0.4776278052460776, + -0.4303073132324879, + -0.6665369885419569, + -0.1998827934250999, + -0.5323620121184691, + -0.16483334326821109, + -0.5331134171275932, + -0.3478633663983045, + -0.5915921264450007, + -0.3918446006761166, + -0.5070608827373838, + -0.38176391402943194, + -0.34978649117433785, + -0.15048750074661676, + -0.1670575693618317, + -0.42297967118637864, + -0.448773692741142, + -0.24474150774745235, + -0.5662797342358559, + -0.3057846651107648, + -0.46442069644261363, + -0.34058230388727384, + -0.17722098994241198, + -0.21565914783149875, + -0.39449398725191087, + -0.5766924963679653, + -0.6072703165380339, + -0.6616638030800411, + -0.45405897265235085, + -0.6345923885971902, + -0.6454373514706581, + -0.4332339371350891, + -0.33785076059054625, + -0.23889285934169113, + -0.16603758340584973, + -0.22238761776917892, + -0.20931878921354335, + -0.6435112376811334, + -0.1601294235136086, + -0.38678975608968647, + -0.29930195314968827, + -0.4855172285717533, + -0.5062201318247195, + -0.19049300245542167, + -0.4122131612936806, + -0.6855047087147019, + -0.5897204765002811, + -0.4670440201143835, + -0.6501345746217382, + -0.145172362008674, + -0.5883179592781471, + -0.3315005839347792, + -0.5879832020318205, + -0.2516000901068127, + -0.5710036716898828, + -0.6610168977831631, + -0.6068987190955123, + -0.22794337001791992, + -0.6162085654799259, + -0.5199903702331581, + -0.309270015069063, + -0.45363458035925075, + -0.6378965880371203, + -0.619870201189144, + -0.3392629033452842, + -0.3843370697781562, + -0.20788753968801932, + -0.3393715073123067, + -0.6813537603604553, + -0.21611453966099303, + -0.23135490170645978, + -0.521883579525706, + -0.6109362101084262, + -0.6317542995329662, + -0.2988094044643175, + -0.5838307818787476, + -0.46646516450737907, + -0.18215708536891762, + -0.4091177984629728, + -0.5942358762847508, + -0.4695296825453138, + -0.5088503152812356, + -0.4846824291133835, + -0.35606078863593554, + -0.49034880492235733, + -0.24216789113609472, + -0.5267940047363043, + -0.5720268824888434, + -0.5629727731824936, + -0.2307347191073003, + -0.3247640788310153, + -0.24207537918923083, + -0.6344044166346695, + -0.4260055472641212, + -0.1672173884143625, + -0.32763137666812253, + -0.52847780619767, + -0.3285216761493629, + -0.47100443470121056, + -0.23171542269570367, + -0.4916085816865508, + -0.18012260758818754, + -0.2547668971935106, + -0.5256522130516823, + -0.21658955543872344, + -0.15515148509221133, + -0.673008132960371, + -0.4290525800299913, + -0.21815705523804108, + -0.3183595521862611, + -0.22857698243135538, + -0.5361420062067028, + -0.5795469660869162, + -0.6781155920441404, + -0.431298939601575, + -0.15846271715932614, + -0.5579777487733196, + -0.49373882704018235, + -0.5185901908881287, + -0.6744431400581559, + -0.26337336224887714, + -0.1389166059153163, + -0.4775685127431716, + -0.6197849510465211, + -0.2806412211320192, + -0.35513511482405435, + -0.6409971206782088, + -0.17411489888441123, + -0.5958233274455992, + -0.17820364085727114, + -0.15103183515091145, + -0.20352832806369958, + -0.21906159287509103, + -0.3110101540479724, + -0.3462623434848626, + -0.5249836086049872, + -0.3163999928725693, + -0.49887966605973344, + -0.33913302730982836, + -0.5433797598895835, + -0.32079382166807957, + -0.5631416946646925, + -0.5076312188601435, + -0.5436281677758499, + -0.2370448810778819, + -0.5531849494411669, + -0.605824058762398, + -0.690148528745593, + -0.6854564524032043, + -0.5911349566536584, + -0.2694367154385903, + -0.2128279556311598, + -0.33784712980067294, + -0.3794364513506489, + -0.36826837975864674, + -0.309057612940049, + -0.577147348817632, + -0.24712293721905215, + -0.6870360245398733, + -0.5177834975540944, + -0.6365032470447659, + -0.6207156967953997, + -0.2882512040062272, + -0.6614409938642822, + -0.2197885450891618, + -0.6632585816358073, + -0.3174426411758643, + -0.5764161736459391, + -0.6489475811320378, + -0.6155977068334704, + -0.5890434487251097, + -0.6376820791042556, + -0.6650287757058662, + -0.5086606388633312, + -0.27363491381257926, + -0.4868465555041333, + -0.2706026202835932, + -0.5416852608322711, + -0.22955220268697274, + -0.6709079826686762, + -0.19189817448769098, + -0.4964472761646024, + -0.2630524725797876, + -0.40394475492848253, + -0.6312625647311609, + -0.13920188867864758, + -0.6366884222800726, + -0.6010561776334165, + -0.6922465072496143, + -0.3389303873277529, + -0.6319337155677307, + -0.5301881410478368, + -0.3500876770072152, + -0.5259530608106358, + -0.301018944166795, + -0.21251279566437226, + -0.43877952874404574, + -0.6799608232001628, + -0.4037323181358194, + -0.41296411079854806, + -0.2674147176848378, + -0.6372020796732246, + -0.34667758467821297, + -0.27510527229675463, + -0.5018056193958246, + -0.24216433519213998, + -0.23306163008528769, + -0.2661498755326439, + -0.5465195840088859, + -0.4627437682169755, + -0.41251198727640437, + -0.546531631719278, + -0.5491969920320365, + -0.6848954930566342, + -0.20791801671965338, + -0.26864996171789796, + -0.20731892136724123, + -0.5216067517234599, + -0.5656367939081292, + -0.5228573837877217, + -0.6289808578824323, + -0.659457452128484, + -0.2567756428499711, + -0.37918273534034913, + -0.5201883080249954, + -0.4528968879286486, + -0.6201536875850585, + -0.14073364884846606, + -0.5200131104245055, + -0.19999043197316224, + -0.6792241878549735, + -0.4484015421953172, + -0.21290263324948455, + -0.18889147731470124, + -0.4029663466828609, + -0.35213351777867397, + -0.5848490127355591, + -0.6953667588773778, + -0.5094809697794198, + -0.5057564308673874, + -0.5448535620621764, + -0.32027178060208666, + -0.5871364908039626, + -0.3749714356257476, + -0.24763907707718752, + -0.3812648746068766, + -0.17696596245552065, + -0.5390103583067747, + -0.4365752500094183, + -0.6750962816467131, + -0.4236486584396144, + -0.6476461519011214, + -0.5691540641061743, + -0.17115979006176296, + -0.20704740305278624, + -0.3716207101215393, + -0.30434797948247805, + -0.6728443650712422, + -0.5282378022573591, + -0.576142207127544, + -0.4855475611428407, + -0.16577110933143846, + -0.6646284688062738, + -0.4664483483608729, + -0.6957869110310251, + -0.27072036079632117, + -0.61194679351218, + -0.6243008423659855, + -0.6445157870129281, + -0.6355208428482841, + -0.46824444204373217, + -0.4916250575439225, + -0.42685603243282255, + -0.6095681499856349, + -0.3618835279900705, + -0.20858534318720817, + -0.38684135815874654, + -0.1779221790580744, + -0.32641273194090364, + -0.6798636341977077, + -0.5722762325627617, + -0.1473040105296105, + -0.5106720895196006, + -0.2628762700365074, + -0.35583479013315034, + -0.2856696223305327, + -0.2206000135477279, + -0.47025443825181057, + -0.1425244770004851, + -0.23959637797649308, + -0.1579292150917998, + -0.6798600097409987, + -0.25144310636463535, + -0.5642693453922502, + -0.5770961175835305, + -0.488809657032539, + -0.4708841607187445, + -0.4950554824402147, + -0.543416829834997, + -0.600173603250946, + -0.2694676014170257, + -0.2851816847057024, + -0.18583543316704487, + -0.5596451938351696, + -0.559566621398417, + -0.5529141097938461, + -0.1400264953252427, + -0.6597776973915432, + -0.19586638678812673, + -0.3485328527034192, + -0.19206219757720377, + -0.41713726145124425, + -0.33010965981983925, + -0.5491230037779766, + -0.5457928707815324, + -0.4988555048263006, + -0.2051174412843369, + -0.6420185703413783, + -0.5366182788803779, + -0.4712681714310408, + -0.34606319274895825, + -0.665125733512121, + -0.17706210325360883, + -0.5432289571298126, + -0.6366102945345036, + -0.2761285145461653, + -0.23927415399451246, + -0.4425735558192965, + -0.3376030641195697, + -0.4522175090859325, + -0.5230036356346226, + -0.3514754785038397, + -0.19747360746088782, + -0.6359034942430931, + -0.17192703618849248, + -0.4032988692005489, + -0.5846927926531933, + -0.5636323470451706, + -0.26534582175869587, + -0.45496353074489504, + -0.22402521692910182, + -0.1421033310591726, + -0.4463748500386117, + -0.42000590269799887, + -0.3948021046023091, + -0.3542710509043312, + -0.6334048855418036, + -0.2435708108300148, + -0.5230203351656006, + -0.4877389439839657, + -0.4837905198393099, + -0.6601693604522773, + -0.2709178836827827, + -0.15092977821672926, + -0.2763166336255261, + -0.540311106690656, + -0.3360134546181453, + -0.6765426423030775, + -0.5329027200283063, + -0.3081169296503153, + -0.4708466772466252, + -0.5761958904876303, + -0.3003684717952377, + -0.3290518108082551, + -0.39158824041534723, + -0.23643601013373777, + -0.17488423592267033, + -0.5082464495135727, + -0.5789348758658969, + -0.1515407070692264, + -0.43891211865309976, + -0.28252264040724967, + -0.32457706731345864, + -0.6413121553527622, + -0.4325933667275931, + -0.480394826151045, + -0.5737925960675307, + -0.3662454962893023, + -0.4581270116110699, + -0.2615000680883083, + -0.25041087947807844, + -0.49672499714693436, + -0.3516271496493728, + -0.299256058000547, + -0.5728918345954431, + -0.5780084293196716, + -0.22507838732020136, + -0.41330645340893596, + -0.378819673922772, + -0.20829334626466567, + -0.6441883187190192, + -0.4015977184413567, + -0.5124560807944388, + -0.2650646525949979, + -0.25426799833062746, + -0.5136440755536551, + -0.3711219199025993, + -0.4777377981176927, + -0.5671923173094908, + -0.4956315920016685, + -0.5869394872673607, + -0.5681490475184714, + -0.5820773829974478, + -0.3345183618393055, + -0.5512252163292427, + -0.6173174520973145, + -0.1630119854748232, + -0.22346422116911668, + -0.5071871347101519, + -0.6214588277996623, + -0.2664257354379401, + -0.23132882815881362, + -0.16162449877498897, + -0.5516521940613478, + -0.6466023715653999, + -0.28820169042378263, + -0.5080915376939064, + -0.30901315735227297, + -0.4302926955699395, + -0.26115449052829764, + -0.35790200088519547, + -0.5751019066236143, + -0.6810664411407488, + -0.43185226844431995, + -0.5715769319741816, + -0.6726875937725952, + -0.31100796217137566, + -0.6374821992354888, + -0.2521575263218877, + -0.445865601966126, + -0.32052716370908346, + -0.5453898608402129, + -0.5860536133454833, + -0.6542712700210718, + -0.4092777500628785, + -0.3758062393550047, + -0.36049888615427833, + -0.46745441924850356, + -0.3095154399801217, + -0.5226727052134166, + -0.5834869680088853, + -0.5628853807204413, + -0.6858416280281106, + -0.6083143615948693, + -0.34890802058959025, + -0.5747751843791069, + -0.6654190811708101, + -0.36930078792627646, + -0.39984649815021656, + -0.14278671829731315, + -0.14602864936102566, + -0.64246655539994, + -0.3532441963707372, + -0.5086223182686922, + -0.563793912548815, + -0.6486358204343223, + -0.4598340302442543, + -0.40964959472987794, + -0.3028903079515562, + -0.2896887582218571, + -0.5493409309008694, + -0.27065715572547905, + -0.49685853677776737, + -0.3255020437444604, + -0.5683862244543183, + -0.38030867641270283, + -0.26448349821420036, + -0.39792724651422146, + -0.6362590153616359, + -0.20677768320293338, + -0.6803170499344696, + -0.32721742475720395, + -0.5952485212709959, + -0.49051856240672265, + -0.47461575861026223, + -0.3075101301860683, + -0.1974810238358603, + -0.5973307193546995, + -0.6537635577324735, + -0.38876849024912236, + -0.6427401485509792, + -0.3219492193016839, + -0.5741173215031125, + -0.39829370025825156, + -0.6798384440173624, + -0.42311314212646506, + -0.3227112648724906, + -0.5452902394889935, + -0.4239345237388259, + -0.4371726618455074, + -0.3732854107511463, + -0.6246631154841643, + -0.5567183721504283, + -0.3859132345916668, + -0.18591022880924757, + -0.3461091701772223, + -0.6933193804241445, + -0.3585930560193854, + -0.1973710567717999, + -0.5451247811360121, + -0.42347470670928755, + -0.6208232956077193, + -0.2221447541795043, + -0.31407318055465683, + -0.3248324760841366, + -0.6542444516751447, + -0.40063424901395867, + -0.4091456248920296, + -0.43455316604012134, + -0.3192151213329015, + -0.20797882929167877, + -0.5977039318794102, + -0.5014431507348712, + -0.3105281477461295, + -0.18218471146070525, + -0.48013162960773714, + -0.2134328196005455, + -0.2042352254180793, + -0.2681635361050539, + -0.6913882918386877, + -0.33634466251132084, + -0.4327837711850377, + -0.46548693334259983, + -0.2149800049214754, + -0.5010580218635079, + -0.5951448259262342, + -0.26188447558482264, + -0.6793165124754584, + -0.6007892516907923, + -0.46620693674063635, + -0.6544342536418858, + -0.4024932312046266, + -0.46306140763121284, + -0.5425001763952984, + -0.39334639247796266, + -0.15984056293009585, + -0.3651123761009211, + -0.4347204844213041, + -0.5091335395997476, + -0.5203937149025698, + -0.6524453674905765, + -0.36494057437793676, + -0.5895833815776289, + -0.185505372788216, + -0.43652074926379547, + -0.6112078378137746, + -0.645479820895079, + -0.6605150207998587, + -0.14537303541520585, + -0.3479154310526881, + -0.2040977807984684, + -0.338866230196779, + -0.5932890032720595, + -0.6170861656540959, + -0.47307497675208365, + -0.44085691346669875, + -0.5852757091698442, + -0.6531845028561505, + -0.6257025838539781, + -0.6089035800358523, + -0.6888475982684314, + -0.20667408939924165, + -0.5199177790162743, + -0.1757443536167892, + -0.5540501130860035, + -0.6269310194028649, + -0.2554042150477362, + -0.5646704607546071, + -0.5707390223721852, + -0.20795064738027347, + -0.6178246812286269, + -0.32752314215172007, + -0.20244711789193992, + -0.5441848912909222, + -0.4839432943254509, + -0.6767054806919113, + -0.575335865712735, + -0.6112461300658194, + -0.480959458297723, + -0.5147976300746403, + -0.5724528786415712, + -0.6835883935954271, + -0.5948093995897389, + -0.6775144420334458, + -0.15637811340671226, + -0.206640184960815, + -0.4704432132860136, + -0.3279448339948115, + -0.4700561815381603, + -0.25543287913628326, + -0.4701512304254388, + -0.48005518721602547, + -0.37355420358435654, + -0.37030763461352706, + -0.5563379029249987, + -0.2796732486113857, + -0.6729736693682975, + -0.28175686450548626, + -0.5875665779949952, + -0.16709121770777313, + -0.6958370311440657, + -0.5042417910738668, + -0.46499559783661876, + -0.35744647512221717, + -0.4366997047223364, + -0.32730583154086157, + -0.2304831285041405, + -0.5969643710554366, + -0.5447979253911532, + -0.4690673443202007, + -0.5315041152743916, + -0.2768372365373985, + -0.2923866785771651, + -0.62611633476065, + -0.24024782823618923, + -0.6885114259693106, + -0.25692902473325446, + -0.30399913673956896, + -0.676692518551268, + -0.24625875713293782, + -0.6828848323375688, + -0.2038487535641929, + -0.35237391058286194, + -0.6712010283061537, + -0.3396109178272301, + -0.3504086486105214, + -0.2784274309417097, + -0.4377148760469887, + -0.17499560339938225, + -0.2489502568749763, + -0.20036112753631424, + -0.3690316859672872, + -0.5326199373418314, + -0.4459464032133973, + -0.6404364498190347, + -0.4427769245192088, + -0.5528483509876833, + -0.6337724781137672, + -0.22851263803991873, + -0.6083504841100206, + -0.18005412577340585, + -0.6642543902232526, + -0.5301104895352735, + -0.6132650894860749, + -0.34569223153609857, + -0.2692534102178566, + -0.5226887011782291, + -0.29050023987049933, + -0.4432878550558108, + -0.6954039945388211, + -0.3266839099539974, + -0.6172510313683279, + -0.28990928645333275, + -0.6128994142374098, + -0.4030669145127096, + -0.4847555208128077, + -0.49397019489313176, + -0.6876424384957432, + -0.2176149720205699, + -0.457711232686981, + -0.6829276398447659, + -0.18445092614427705, + -0.36566650516933347, + -0.23661531076753284, + -0.45358124248036635, + -0.5499294271804935, + -0.27369745645782034, + -0.2525946622806068, + -0.24472032307609126, + -0.2871026731409007, + -0.4452070618499339, + -0.5092935257546303, + -0.2793745061535638, + -0.34712097020685906, + -0.6331284890402562, + -0.25185697588116085, + -0.4414550023002522, + -0.3685027242747063, + -0.1925372982149527, + -0.49166406270657337, + -0.38083782112590336, + -0.15819562426943712, + -0.26159033732166087, + -0.3599157149430414, + -0.35211484451006825, + -0.5038417426698936, + -0.46673328906528594, + -0.5771099118968721, + -0.6499791386421792, + -0.504898654436543, + -0.20132390957024032, + -0.5205220256812462, + -0.44442259494483877, + -0.6457979270567963, + -0.4068771463769635, + -0.5990812066230154, + -0.1939386401864165, + -0.24785826292081642, + -0.659688053274931, + -0.3503029412467906, + -0.6103911814398588, + -0.6615368824306248, + -0.29916414599043684, + -0.5546026170507871, + -0.49063264901166126, + -0.1613701431265233, + -0.318393487281109, + -0.3702135160898773, + -0.6652913363954305, + -0.17599507838769013, + -0.2062058867058879, + -0.19098120502527816, + -0.14986981266320565, + -0.24451365242666656, + -0.4464990791037207, + -0.5589274876127035, + -0.473819870411187, + -0.20309060748424124, + -0.17854883824119894, + -0.33072767427783106, + -0.5702785773367993, + -0.2764642907556683, + -0.1913801906967456, + -0.606695522713022, + -0.16460365948093703, + -0.29920110633427494, + -0.335882258457198, + -0.2971807567366492, + -0.3464239264324735, + -0.6634602762063748, + -0.37166436151446686, + -0.2195118973244451, + -0.35701591706475067, + -0.2510968401235121, + -0.31301291516190294, + -0.39374805970018417, + -0.4927253248211211, + -0.28912361137683273, + -0.28480058855268864, + -0.256665872714921, + -0.37053521844241144, + -0.45891856890758886, + -0.4721875597602352, + -0.6131197960338974, + -0.5497723693271369, + -0.6193277685493983, + -0.5582907149347597, + -0.26336931579672584, + -0.4649351955775263, + -0.2382910311153405, + -0.6659055901618779, + -0.6016683783767849, + -0.2976449070445156, + -0.43110591085128924, + -0.5493943738233544, + -0.6104319849814906, + -0.23044567801555188, + -0.47906953089167237, + -0.5665360334166081, + -0.5143951246322324, + -0.19861769281692265, + -0.281491549439199, + -0.6427418381066213, + -0.24258782843318755, + -0.5674999965749665, + -0.26380149025138716, + -0.30425513166090284, + -0.4449856022834919, + -0.47252615804592135, + -0.5863281015586471, + -0.2637140874955335, + -0.5524944347156457, + -0.5614879067817715, + -0.37723762478405015, + -0.4123526834109719, + -0.5236920184134457, + -0.2106899970383742, + -0.6232835904176042, + -0.6071085355492997, + -0.5618604279280952, + -0.5383710591759534, + -0.2183382695492676, + -0.4391878114625851, + -0.19968271354072092, + -0.15143518883488083, + -0.6809576867295536, + -0.4538879806515417, + -0.661627658926051, + -0.40002226600215535, + -0.14137634905154361, + -0.6280772609260765, + -0.3519468924826479, + -0.6602829514281162, + -0.5242972309816744, + -0.17715203745727237, + -0.16482449522280207, + -0.47496824179462827, + -0.48886942459939026, + -0.6048701701069119, + -0.26215189493399527, + -0.46468103113969284, + -0.39694731534934347, + -0.23932647045613759, + -0.5824552487326311, + -0.24789316210574158, + -0.35571966275125794, + -0.3322086596003916, + -0.1667768493955082, + -0.36962001758323765, + -0.6398363850628803, + -0.6851781210512011, + -0.24101967311878242, + -0.547021674085395, + -0.15999667386322225, + -0.3584946869471607, + -0.5060924989758122, + -0.5078183226137214, + -0.6010371309238934, + -0.14237428118492734, + -0.4072061932265358, + -0.4483457925159152, + -0.31829989356706595, + -0.35335181752461103, + -0.38788246107390434, + -0.5140740416187094, + -0.21674514408886186, + -0.5150597557635429, + -0.3120930176253676, + -0.14831541327081943, + -0.4924750089772758, + -0.6409640361972363, + -0.4181090797658274, + -0.42704024159519816, + -0.2230220998688185, + -0.26284211470215574, + -0.15007246621671955, + -0.48336557846715056, + -0.30606782232296786, + -0.26262293661324604, + -0.4741019922201169, + -0.17305723240536386, + -0.49560375563932935, + -0.22500873743061972, + -0.2206583117198877, + -0.23132542867023426, + -0.2429837279940481, + -0.47290508182070223, + -0.42099107532476976, + -0.20391843269768256, + -0.23360583888988523, + -0.5008686870489761, + -0.33538996161588547, + -0.45169842531099824, + -0.46433324461154557, + -0.5202076296697377, + -0.3516063909375081, + -0.4952383399722584, + -0.5970411981989927, + -0.6058215820753883, + -0.6440434843266442, + -0.6549804843132141, + -0.5185652733559724, + -0.493125789365923, + -0.6245716863224056, + -0.20276216074162184, + -0.6716708016430682, + -0.4084254389881276, + -0.1484007520995556, + -0.2562610513524352, + -0.5118967959460913, + -0.512617386744373, + -0.6281198390835462, + -0.4686224088848978, + -0.5976610709457401, + -0.4465639349911592, + -0.6623084473240427, + -0.3819473084220606, + -0.19011409712229344, + -0.6700085530962366, + -0.1982361719379751, + -0.16291335719890532, + -0.6826241351020838, + -0.5905108583722953, + -0.4132517198820203, + -0.3468577473324062, + -0.6334715045530952, + -0.18061702291267867, + -0.6586417977139849, + -0.1611346703077826, + -0.6231794722000895, + -0.37978208049100165, + -0.30277878866665353, + -0.40425394447493096, + -0.18406924968686567, + -0.5596571007612955, + -0.6911426860359801, + -0.5554219653515412, + -0.28372801501263983, + -0.5550046290705444, + -0.15438361144734436, + -0.640601816767616, + -0.28726929810155416, + -0.2975066849968765, + -0.23120880851170228, + -0.4966658649853423, + -0.23920910830948833, + -0.48331286218301944, + -0.27855690726679094, + -0.6836886169200802, + -0.23652791340621337, + -0.4490985172954747, + -0.3002182153434357, + -0.6859517635987836, + -0.4559358679802987, + -0.6077336359088016, + -0.6237451633032918, + -0.3539234758849741, + -0.40047181842537277, + -0.6255253501587413, + -0.5153133024569541, + -0.6907479372899143, + -0.23248087600153272, + -0.3255161582405629, + -0.3759957933968195, + -0.45643703835163885, + -0.40570481968773575, + -0.2709154972077781, + -0.23053714995392643, + -0.5257692644378991, + -0.5113271970192942, + -0.21083053377038896, + -0.48348825071571533, + -0.5147793004514327, + -0.26518597593565774, + -0.5768937474209381, + -0.4560982071279885, + -0.6066079687956367, + -0.3050598229948321, + -0.6789487928005676, + -0.22044695144029458, + -0.6710674958689865, + -0.2477641726760927, + -0.24181817642614944, + -0.2926499661472735, + -0.5257791365314693, + -0.27876751074066214, + -0.38901736014229554, + -0.21608254298448704, + -0.4196812595457911, + -0.6652178908814388, + -0.36073865289591506, + -0.5000365012092429, + -0.5134555896992783, + -0.3878854857062946, + -0.48633851641207115, + -0.33854706809039525, + -0.49154267042299127, + -0.29217181511676094, + -0.24336091850755237, + -0.2972162637998068, + -0.36850526642536463, + -0.5070725086498591, + -0.3353157855757429, + -0.6057830394746879, + -0.37364605314534044, + -0.46701476349258414, + -0.5495645209025496, + -0.6968961067002706, + -0.5770204828454361, + -0.3447090632770464, + -0.2705725872911198, + -0.49373653394554917, + -0.37896069791118075, + -0.35348152334457295, + -0.3330044587394067, + -0.16348983989369892, + -0.1584136542547715, + -0.3383040097161813, + -0.5288369970901275, + -0.40143651474418623, + -0.439738541338844, + -0.21492902338300135, + -0.39551960105401107, + -0.3646009450570318, + -0.6454181378306835, + -0.6039025361001463, + -0.5531924473557872, + -0.32311959905069204, + -0.33358077650093876, + -0.18089879019184318, + -0.6667170209554392, + -0.4420008472848867, + -0.36259773725537225, + -0.5087441036761549, + -0.6869465490860167, + -0.47356421441533736, + -0.22671349032692784, + -0.295393695447094, + -0.4820591672933282, + -0.21892520912088764, + -0.663814313184951, + -0.5589280392766172, + -0.6377644904114556, + -0.4870631751102631, + -0.3645917703544555, + -0.17287098515103605, + -0.33755682912397844, + -0.29797680690644873, + -0.1634963895678263, + -0.46523109624308934, + -0.6430579832217895, + -0.3227719497396982, + -0.5435070482870433, + -0.5107332211754593, + -0.1702861423744092, + -0.20588296697792308, + -0.34843028310762303, + -0.16837675379293704, + -0.6390948723254801, + -0.4885766907848265, + -0.5751234827483215, + -0.24443073785119074, + -0.4236102636871647, + -0.4680391505543416, + -0.15893373057325, + -0.5819706499584286, + -0.20630801291940543, + -0.47954342419684237, + -0.25473276315901544, + -0.2733954113923092, + -0.16597234714666576, + -0.2873949101757904, + -0.26680785302798715, + -0.6016678343454654, + -0.5970580213161133, + -0.5378796720817348, + -0.6969762402895971, + -0.4263373740161499, + -0.1749930845831713, + -0.38760108310601227, + -0.40711598125417087, + -0.49785582153023306, + -0.5295030416014236, + -0.314170864931736, + -0.1536359706918493, + -0.23941049248721624, + -0.5665972749899315, + -0.6287367478371023, + -0.5844480020038801, + -0.625665882799165, + -0.33054376336696445, + -0.1576644709302777, + -0.624931455520598, + -0.5679218416889156, + -0.539873268103978, + -0.356495704103858, + -0.5409555394599159, + -0.2570190927490823, + -0.3304027956602548, + -0.3796657857624455, + -0.34343034134164474, + -0.6172467547181834, + -0.4660251034674804, + -0.21242197404921315, + -0.4903082265417735, + -0.19577386172997102, + -0.5828917353042345, + -0.3159382804008806, + -0.4031858131525055, + -0.2058827472068317, + -0.5689717050627853, + -0.3052542005603106, + -0.2750625185905648, + -0.48386364073180294, + -0.6580328455229698, + -0.22661000003808995, + -0.4627455950072892, + -0.42593529404832026, + -0.5688876407458247, + -0.15264885835703546, + -0.6825128612606827, + -0.17288830242293107, + -0.6415254806024369, + -0.30213428792756003, + -0.6209053684552044, + -0.6462200335825122, + -0.4663645387545592, + -0.2792126843322692, + -0.4543222227911812, + -0.5374522383498594, + -0.6808516018006979, + -0.4849320096845968, + -0.5721804914149684, + -0.18921114235416592, + -0.5424581156370087, + -0.35228040536358435, + -0.2107779679164722, + -0.35979618134084757, + -0.19023244092054237, + -0.34748649223632977, + -0.6407199774224873, + -0.3156857068713596, + -0.1411971567691488, + -0.47835257939553655, + -0.2061742221020922, + -0.21164678765954364, + -0.6737565883388463, + -0.26193665893493917, + -0.3102018465203943, + -0.34979936850149324, + -0.46608487401677223, + -0.2238550615369425, + -0.1783494665331552, + -0.5675649615906753, + -0.47009720364373575, + -0.20830983706662942, + -0.2046091921343302, + -0.3736574686056042, + -0.5675117554943652, + -0.6349303576241387, + -0.43883508251214565, + -0.6183632085204468, + -0.25143629771329423, + -0.4634378445002818, + -0.5014394721426256, + -0.22132587056099184, + -0.24256004497791056, + -0.2402424921413565, + -0.21584044855674295, + -0.48096611496833436, + -0.30762686442623777, + -0.31536023387846956, + -0.2080533190044177, + -0.25872852673856883, + -0.4850024175607818, + -0.22741753613656007, + -0.4418320783760565, + -0.47222426557807357, + -0.44146684363647776, + -0.42663416714770486, + -0.454374796472328, + -0.14227207536891773, + -0.4849061891136409, + -0.2275518599374569, + -0.5552932507697677, + -0.26139184908798585, + -0.6621206641905439, + -0.5359387566283387, + -0.3508471719127619, + -0.5380902654853653, + -0.25437675899498596, + -0.4046309216730565, + -0.5344643292175854, + -0.1712799585067345, + -0.5228525676085944, + -0.2992373052559397, + -0.6563053053810255, + -0.6520132315686499, + -0.6778010160190175, + -0.4471075555283985, + -0.2993859232233131, + -0.34381946348075987, + -0.5140914882428028, + -0.4288799481350359, + -0.430462997219822, + -0.3938189938432971, + -0.6868159464421992, + -0.21357915320182141, + -0.5501292801677248, + -0.46660630035728534, + -0.47858992928958977, + -0.47447319068640537, + -0.4436006647060263, + -0.5257241176353348, + -0.6469687070277422, + -0.6012894529671902, + -0.4010163168843008, + -0.6815530862089391, + -0.43969028203696525, + -0.2396778261314213, + -0.14962928015967036, + -0.21970528525103844, + -0.2636349806489746, + -0.28082182514959947, + -0.1579144662321028, + -0.5187255126715082, + -0.14766464774019028, + -0.20587352264808872, + -0.6637387949975775, + -0.41805221184711977, + -0.42192282763998096, + -0.43649966250463984, + -0.3053917108693551, + -0.14680189865457727, + -0.6720380491430138, + -0.32703654455336245, + -0.3151345284333896, + -0.6172957662605544, + -0.32677928155855074, + -0.30265924355803336, + -0.6910019202910792, + -0.2753246971038279, + -0.17359221848477246, + -0.6907027336082538, + -0.436556294011129, + -0.2367730171557753, + -0.514197263033976, + -0.6150501714099212, + -0.41803437780142516, + -0.6691290274037455, + -0.5210547595576934, + -0.46814446893917894, + -0.4396458283630313, + -0.4680235294869731, + -0.6827883302742399, + -0.5961812977843441, + -0.5268569950795859, + -0.30884385315897417, + -0.14426642924393573, + -0.2773077136510659, + -0.28961328980490525, + -0.28736931875437516, + -0.3499713571614286, + -0.22460898716811456, + -0.1986450801388775, + -0.5926547427926874, + -0.4523493421278899, + -0.5714748701861464, + -0.1887325029972936, + -0.5235360805120632, + -0.5805108957333345, + -0.2272566012337286, + -0.345696995478531, + -0.6182554225080709, + -0.4315560754133858, + -0.2590769421585908, + -0.37811037815872733, + -0.538190798983518, + -0.6459663006940373, + -0.17232994615385455, + -0.6855592572286049, + -0.27816399220775173, + -0.3498403374555076, + -0.5390408300952667, + -0.5579530435051643, + -0.32271014076766313, + -0.3765465695809104, + -0.41094663585130725, + -0.5607487070835331, + -0.6938395983947996, + -0.3988519274003659, + -0.5059251247105391, + -0.477496397474565, + -0.2703425472634014, + -0.4547910015375742, + -0.6131800256743482, + -0.40891029232427384, + -0.4462490063391778, + -0.1445463831214162, + -0.23572270931534295, + -0.4487036117852111, + -0.4871801347788639, + -0.601640182367128, + -0.3581504176288492, + -0.535544043367207, + -0.16745624118802627, + -0.2869966573648924, + -0.418571992721151, + -0.49316308123261726, + -0.2944953678501513, + -0.6222259268918033, + -0.2227808235586754, + -0.6087423228533239, + -0.3447455236770971, + -0.23760640228738494, + -0.4007508026125178, + -0.3502579897699632, + -0.2559877681561005, + -0.6932243247924073, + -0.45977186322213354, + -0.16502638350649323, + -0.30258472503407746, + -0.31459633597824876, + -0.47220592930142147, + -0.1650825558567014, + -0.49417784807214427, + -0.6831555309241946, + -0.2746696652588833, + -0.3355454869853901, + -0.46825831862327494, + -0.684135417152865, + -0.29166947938128795, + -0.33498473881460294, + -0.39559500778244977, + -0.3100734126374124, + -0.5819837157810551, + -0.5481803968758564, + -0.6962514515224557, + -0.5546999644965561, + -0.6358206804822168, + -0.3812398986814836, + -0.218044084312417, + -0.5428667281197248, + -0.3324329630998251, + -0.22783673838619217, + -0.4908827710827772, + -0.34515426063892846, + -0.6786375478439451, + -0.3635267386012745, + -0.3510287441799869, + -0.62759940029181, + -0.4708490667524717, + -0.29835428857473123, + -0.5765331967885178, + -0.616441578767649, + -0.596055055363337, + -0.38976251464724126, + -0.5462362866650496, + -0.2400959602905548, + -0.6123111975171991, + -0.5885346045659614, + -0.4915929392645513, + -0.30593862937079824, + -0.3313299923953876, + -0.6228794083100686, + -0.2889610808604691, + -0.43589988681658604, + -0.360679598691643, + -0.5973637515046298, + -0.4096218023684683, + -0.28191319108233304, + -0.4550228489020458, + -0.6713245520089431, + -0.3939153930246734, + -0.6157680531728147, + -0.14263703062953703, + -0.1903586693300392, + -0.5633330081394394, + -0.20714168371016783, + -0.4997792995221596, + -0.5237620153921917, + -0.5368472796148128, + -0.554966157529462, + -0.5307015524388787, + -0.22501472012557194, + -0.5963171915332275, + -0.22334960965379713, + -0.15480337568362967, + -0.5906181417710783, + -0.3156912092494582, + -0.6098489156276501, + -0.3601333477173675, + -0.5933066332798518, + -0.6947293340417288, + -0.2938641697715465, + -0.52498887766831, + -0.364741340727469, + -0.6034593668108267, + -0.16238972466524348, + -0.29223602062326554, + -0.5144274683484572, + -0.46241653139985395, + -0.4023137867341873, + -0.24874471582922786, + -0.36191444178766125, + -0.4348725922514744, + -0.5700293119808684, + -0.6884830075525666, + -0.5081887473466097, + -0.2509760684770025, + -0.24273938494774328, + -0.21666707468260538, + -0.45693707552087615, + -0.537743859610006, + -0.4458554402136453, + -0.3000547546152809, + -0.6127834084129812, + -0.1793891396715238, + -0.29608092489374366, + -0.17432287022307846, + -0.6447987899349, + -0.4167561348254531, + -0.19728520540474082, + -0.6457533655792365, + -0.32049320486254856, + -0.6208328576568976, + -0.21462942871342205, + -0.6625240006764958, + -0.44995707255919765, + -0.21658819080693814, + -0.3355883334642532, + -0.28967871700013276, + -0.21685189246423814, + -0.34877277377160726, + -0.552126770353246, + -0.4850236435838392, + -0.37720096073449827, + -0.4447218926706864, + -0.5695504131527556, + -0.4056823082551809, + -0.5254630076284528, + -0.1566972161020539, + -0.29937498238515226, + -0.6210529584425715, + -0.1501565376063675, + -0.1561775921511297, + -0.5043793050598048, + -0.6144088872729624, + -0.4436516182607864, + -0.5760466537661907, + -0.2952919510195779, + -0.47024854484405265, + -0.302466804789149, + -0.17159407917750735, + -0.285323176343367, + -0.6897461221621296, + -0.19729015174800335, + -0.5669856482832573, + -0.481674165665547, + -0.6447013377400417, + -0.37478193005412014, + -0.6732370392629002, + -0.25846595021474067, + -0.3107713284794074, + -0.34363472003769685, + -0.45050018714693474, + -0.1430540160539967, + -0.5002052213981034, + -0.28112786527663114, + -0.3886606189039532, + -0.5971780549304747, + -0.29788778341486244, + -0.5811294065693272, + -0.22788573740732504, + -0.5909582552758298, + -0.22783980194109704, + -0.20808002624990363, + -0.6298174694581868, + -0.6227029662175054, + -0.6142914618814894, + -0.508501654346083, + -0.19308891007954143, + -0.4765832727416601, + -0.4426230929633969, + -0.533462228085103, + -0.4649664013468523, + -0.5130592991990818, + -0.3705385174670819, + -0.19691867105555438, + -0.31355681045985484, + -0.3097415339422854, + -0.528488159414436, + -0.3688295420640026, + -0.40514962342543, + -0.27891410758602875, + -0.34958305179830235, + -0.6718744172931909, + -0.5695277069674688, + -0.262282007213443, + -0.6249991488809882, + -0.38389777911688633, + -0.3418002196794364, + -0.44675314265867105, + -0.45255963671145966, + -0.5982609304706917, + -0.63114180136123, + -0.40320699070631916, + -0.4399360645451375, + -0.6197406821776819, + -0.14954472497695004, + -0.38503055945224846, + -0.15837459044369073, + -0.20696053322800173, + -0.6730501269800848, + -0.6794889527301838, + -0.5682696634217249, + -0.557545115184297, + -0.3610322217762479, + -0.32812959927363444, + -0.1802040638051805, + -0.2584221288356995, + -0.27113855695860356, + -0.5860399906501059, + -0.30843146787177705, + -0.48333457180246997, + -0.3330262684062325, + -0.6972582993358418, + -0.408166773623477, + -0.5233911682545934, + -0.34039989230505735, + -0.30543316742770793, + -0.5878038900861462, + -0.46485172644415695, + -0.25858831977165625, + -0.27130987310027904, + -0.3692267222254641, + -0.3095023212342885, + -0.627032340080248, + -0.4111711088877481, + -0.6327731897848936, + -0.48573360180759717, + -0.14800872756079586, + -0.3778424763903071, + -0.608385871859984, + -0.5367918823342233, + -0.3600133749117479, + -0.1907469846521488, + -0.5380380293115128, + -0.5771215964799928, + -0.6270619360627895, + -0.4622388884588364, + -0.22787883194419462, + -0.4208915990709243, + -0.18636016334170613, + -0.4816936431767215, + -0.4056989278599296, + -0.4647801603204605, + -0.2999643535032726, + -0.6382598285606598, + -0.375441323746701, + -0.24864158754283627, + -0.6808982900636589, + -0.23309872254778713, + -0.515444773700059, + -0.4523857533843107, + -0.6335894950175873, + -0.5389206588936817, + -0.5461704759547342, + -0.2898404689950254, + -0.19645039751936055, + -0.5689155952842265, + -0.5662635637017702, + -0.5607823219209065, + -0.5419926855129759, + -0.41662010119445114, + -0.152326464827635, + -0.558866885986063, + -0.22123750849959306, + -0.5524933279365088, + -0.5670266426000203, + -0.2899255895624541, + -0.2798812217905355, + -0.515212252632532, + -0.6315017619078307, + -0.2251696867520085, + -0.29996013648254516, + -0.29559999242975266, + -0.5071087744530316, + -0.5429861180395336, + -0.6726097084583905, + -0.21849201579947802, + -0.49642499873584733, + -0.29728910916715556, + -0.35195139169612805, + -0.640029063783447, + -0.6703597638831219, + -0.26743355832033877, + -0.32444889781763664, + -0.30486405201036687, + -0.43360902047320865, + -0.4176329750824126, + -0.5799104193021158, + -0.21603383363973117, + -0.6860993500204704, + -0.2741936915476106, + -0.16385126835271813, + -0.20976522122343078, + -0.41149452129775277, + -0.31172142225997523, + -0.38645131996270243, + -0.5450371398183422, + -0.15733037567426045, + -0.43763536640748174, + -0.48821064249474144, + -0.24037098645442462, + -0.22957979031675796, + -0.5962377540980696, + -0.2655193728045078, + -0.30369129329149946, + -0.46146560125937675, + -0.43334133033815697, + -0.5017270681823127, + -0.39987551335387406, + -0.2897757309759858, + -0.19530864766531608, + -0.5957758486459863, + -0.38005628072741754, + -0.3950606000334997, + -0.6192055558887066, + -0.6138524522635403, + -0.3189143891316185, + -0.49436555509468977, + -0.6625574525508934, + -0.5510327649303648, + -0.4320790022857521, + -0.6359934992434723, + -0.14531953383205032, + -0.3130652300186997, + -0.15156119907569088, + -0.34979566049430394, + -0.5923391655016566, + -0.5918889092833239, + -0.4766432329469643, + -0.4706861247619064, + -0.6226062355924186, + -0.2724317373576457, + -0.44682397628943366, + -0.18898173866808143, + -0.6758046700168059, + -0.5455004404481654, + -0.5798809967756733, + -0.16350757404560767, + -0.1477215425752415, + -0.6869161421873478, + -0.2124797024076242, + -0.5231152858327419, + -0.5607658840834397, + -0.5132075324655035, + -0.5547323133238043, + -0.3685122127282173, + -0.21059627525888486, + -0.3102250677005998, + -0.2836862111587277, + -0.4388347008787322, + -0.5384089784051138, + -0.1885911316630846, + -0.4743032028260534, + -0.25430306631768695, + -0.6654170232670378, + -0.37820581901869815, + -0.6652434474724773, + -0.6038102382993106, + -0.33139031452884066, + -0.6681317462813369, + -0.4810600150989025, + -0.46972954087340213, + -0.5542215083569058, + -0.3205187263835013, + -0.1986742215818213, + -0.5135756700575111, + -0.15353258851615248, + -0.6736755696731032, + -0.646144797243887, + -0.19524629462212406, + -0.5126058825969538, + -0.409761801117589, + -0.5219042216269343, + -0.1432720822504282, + -0.5450245893644031, + -0.18628407374534228, + -0.6217474373758298, + -0.5001197240403761, + -0.175527172343673, + -0.30275802853411016, + -0.6521096989687373, + -0.1955810236065918, + -0.6582459501782433, + -0.6052019933916629, + -0.2673259871346996, + -0.6161417473163971, + -0.6037639038844814, + -0.6068682275850261, + -0.672976079322892, + -0.33992381970200963, + -0.5681006977067995, + -0.6722048712609971, + -0.4265590758057028, + -0.24818199362946747, + -0.16528279266541712, + -0.635114576161567, + -0.26247913201668593, + -0.3966114944855676, + -0.15880042072555067, + -0.6782131998621612, + -0.5813557751804872, + -0.404220011707522, + -0.2383045088096425, + -0.6000914260519458, + -0.4611235620297337, + -0.582074085388447, + -0.4171272630219391, + -0.22152735751549762, + -0.38485474344075765, + -0.27407817409922863, + -0.6186271667191646, + -0.2142922488436783, + -0.5662329791179925, + -0.5114883613846072, + -0.197882566759298, + -0.5977616653217308, + -0.1663884862738796, + -0.6364944087654472, + -0.27894915163766787, + -0.5325941003420076, + -0.6147452765069357, + -0.5865692697023576, + -0.5835057373528144, + -0.35272134449788795, + -0.599707598199983, + -0.3160377876365414, + -0.32738270617949605, + -0.2029367934803636, + -0.30267431052784133, + -0.16132883109056362, + -0.615307804478529, + -0.3661240839611725, + -0.6767427648374674, + -0.2715231387304312, + -0.5231715381228065, + -0.49720376109213515, + -0.5419399056494152, + -0.5454260230712198, + -0.30730872899529044, + -0.5431090873485983, + -0.5155273239393956, + -0.1851462145148891, + -0.4201032100954105, + -0.2713041114493992, + -0.20382997768490696, + -0.4092080374489499, + -0.656900975804509, + -0.5560218266828364, + -0.20883408353796568, + -0.32389230508173666, + -0.394592704826462, + -0.5351280619099864, + -0.32832757320523265, + -0.400301676892984, + -0.21732845052429206, + 0.2849156155200059, + 0.2745484650647288, + 0.18842729251404416, + 0.23389898101046774, + 0.059139629753226564, + 0.26103734021579394, + 0.146934144224512, + -0.1260038068545996, + 0.4132671089891746, + 0.3391310751474464, + 0.36087941597401935, + 0.4555777025304648, + 0.048453676661123185, + -0.08877484319903489, + 0.3139161788202603, + 0.26790861039514524, + -0.04355959511900656, + 0.3725056062161528, + 0.3383930801268272, + 0.3890281087659214, + 0.40745050318833453, + 0.22508456792779574, + -0.0994489110978676, + 0.3853588872258765, + 0.09355870996673918, + 0.35196702019950277, + 0.48378215530981916, + 0.43224902339090976, + 0.31017413910325536, + 0.008104690472674064, + 0.1746171975277494, + 0.18052195799806087, + 0.3565566966740598, + 0.1392248949883167, + 0.35187599366947653, + -0.1170602598782324, + 0.35252121297272904, + 0.29442647253686105, + 0.42582563152543174, + 0.45677927625933945, + 0.469005682374955, + -0.08095924651895098, + 0.23927981098972206, + 0.030659917784301965, + -0.06338198280744164, + 0.40882701421620105, + -0.08581974002080342, + 0.2643507897623555, + 0.4340229232330608, + 0.49777037573893856, + 0.016360188754554916, + 0.4203369505865856, + 0.06405118853807432, + -0.055440033939089695, + 0.2832881023847097, + 0.6099410560782216, + 0.4982552400575312, + 0.22992439496911032, + 0.3636039745282408, + 0.24695969961328096, + 0.21429253219573774, + 0.14613519399147795, + 0.02319215482061604, + 0.5740889376304266, + 0.13433288728003195, + 0.25718951516310934, + 0.33604309181217995, + 0.4307777827340561, + 0.15856900336617202, + 0.36231524394994935, + -0.08668395608816676, + 0.349974789292997, + 0.5159841675245991, + 0.21795826175783578, + 0.4817684692857238, + 0.5859596764669456, + 0.07217332079940306, + 0.13837034195867576, + 0.528655321023558, + 0.519482988857115, + 0.0255512083584567, + 0.09703380665506744, + 0.5306634270979409, + 0.03367991747574875, + 0.2921579588362706, + 0.34647624355466533, + 0.3691400574119712, + 0.34777020483736204, + 0.006501834754100766, + -0.0583574175524955, + 0.5825475491738455, + 0.2955951885897046, + 0.5868730714609514, + 0.3359590258487897, + 0.057398774141872, + 0.42548897934538776, + 0.5986419984555654, + 0.564105573139245, + 0.3842903806577904, + -0.08025111749719982, + 0.4076846818582329, + 0.43583657757854344, + 0.40121157698965126, + 0.4947852632587768, + 0.5590059568130376, + -0.08398981265032726, + 0.1495313536143597, + -0.07293827869646001, + 0.308796058538076, + 0.5662297480124795, + 0.5448738296420313, + -0.10364925273152148, + 0.2783962518726758, + 0.39354590804525547, + -0.022911898602104894, + 0.5134707444702444, + 0.3210517662632041, + -0.07702668031958343, + -0.056888905637410614, + 0.30330312680732074, + 0.17525993631708475, + 0.054202396078386256, + -0.03818945062933869, + -0.10527095356430338, + 0.042004348314507806, + -0.06186345863608793, + 0.15207407142774226, + 0.34291521487159876, + -0.07606178134957764, + 0.09128352788318508, + 0.2987907039723255, + 0.006287263328451448, + 0.38008135284509614, + -0.01623126360169712, + 0.26924064724022273, + 0.4413481936490401, + -0.10781177137153707, + 0.2969527591467414, + 0.05157339004519515, + -0.0013160525572026294, + 0.4469860083577696, + 0.33637333179152407, + 0.5559838821906932, + 0.3985949468766449, + 0.4765479713052805, + 0.5943895032260813, + 0.38734121131778243, + -0.00736238486615981, + 0.4680038330716887, + 0.5213517544628326, + 0.1885362065411692, + -0.11873581913103744, + 0.107124434134072, + -0.08601410080587202, + 0.13440372129767192, + 0.007228152745858252, + 0.3776668793857759, + -0.0010321947016824762, + 0.3308649666569675, + 0.39215261042289107, + 7.435875510353185E-4, + -0.06738970288181614, + 0.09043864142653527, + 0.2416154677099337, + 0.4468666209917054, + 0.1929156955409459, + -0.005773418149675441, + 0.22850131533591872, + 0.01011857346556172, + -0.008990567701987029, + -0.05986996973191806, + 0.3228567534666069, + 0.07893559823933102, + 0.3483962298816882, + -0.045034909005189694, + -0.05073215040508748, + 0.547716636200296, + 0.32448369770609337, + 0.30427808141385243, + 0.5476479702371895, + 0.16293589370898776, + -0.13021976787425812, + 0.6046958931962637, + 0.2559922824501306, + 0.35552228489039783, + -0.0735575463533325, + 0.5831996083657951, + 0.28747385130496234, + -0.09667094344969843, + 0.24430524560686007, + 0.43866636243849755, + 0.2845969245181767, + -8.082964707982199E-4, + 0.5822683505879419, + 0.06425209119504613, + -0.03482236184495023, + 0.37112999907193633, + 0.32638640471418345, + -0.04951736855141772, + -0.13578174814346367, + -0.027988248692111126, + 0.603050371562814, + 0.06363560630601267, + 0.09320584307659788, + 0.33856936352632583, + 0.3335755156056493, + 0.4389803158016695, + 0.5637082854749179, + -0.05034278636454184, + 0.03086035455137895, + 0.1546570757010468, + 0.15380947716917176, + 0.5771292693155335, + 0.3765334567299139, + 0.5798487943636943, + -0.05457877676264848, + -0.13211946656365878, + 0.47019711713888757, + -0.09484160013148701, + 0.1079080351994055, + 0.32138854076950474, + 0.5921135156180827, + 0.5477827561593789, + 0.029707757564824716, + 0.4454188063112997, + -0.009523445163245436, + -0.09723318215284055, + 0.2600319900094897, + -0.10158568032256088, + 0.27383911198987004, + 0.08900461862357023, + 0.04322094544159988, + 0.39635930702050315, + 0.5374097779145798, + 0.009251684229416801, + 0.3209273676586467, + 0.4191917358169943, + -0.027472638678185585, + 0.1873594160341155, + -0.09791546557571117, + 0.002410326032637994, + -0.020041713139368852, + 0.2579226049355678, + 0.5995270883901519, + 0.32511236236201174, + 0.5445950363854037, + 0.1565003976486249, + 0.3226219610482225, + 0.5966789174563414, + 0.4495939054770407, + 0.5805846280543914, + 0.35530343638670703, + 0.0037348685295767736, + 0.6077219619060661, + 0.32876133853525563, + 0.16785518683443051, + 0.3581733289991417, + 0.4763860390980921, + -0.12182572483055172, + 0.20776832232868708, + 0.4384585688345457, + 0.388424473380408, + -0.04729931830595385, + -0.008498582186939246, + 0.29826748039313167, + 0.4291028797240304, + 0.4786441562989161, + 0.06240184824385295, + 0.09401821905757105, + 0.23600084613549738, + -0.10584459442424154, + 0.02173622138447362, + 0.08034970822215545, + 0.04879743786655236, + 0.5057877215453551, + 0.00748715268138056, + 0.1960149263440124, + -0.09893217537691103, + -0.06333345827301802, + 0.4372434930538278, + 0.030375644503818522, + 0.4902541343889415, + 0.5374757079384904, + 0.4595059285227332, + 0.432218048349412, + 0.3385712600895077, + 0.533224685105739, + 0.5990079886437947, + -0.09666992439780277, + 0.49152899802980876, + 0.5592128793963373, + 0.5458450929453263, + 0.43159783272460783, + 0.41583498420906995, + 0.20794219184741863, + 0.17092157104573014, + 0.4427223251825948, + 0.04263007609492711, + 0.3821184081601182, + 0.3089916842129298, + 0.03570790882893937, + 0.007875192834767897, + 0.37278767135935365, + 0.5221175583371449, + 0.11529087796565374, + 0.08566461469880027, + 0.2434917379464901, + 0.023830934553561445, + 0.36461270690468295, + 0.12645757480537917, + 0.37621600751945317, + 0.03850538523281233, + 0.043639097169954705, + -0.05726686658387292, + 0.07096334678718705, + 0.24241212566352643, + 0.2045064311446126, + -9.564384180251462E-4, + -0.10097227530639255, + 0.3311049762589248, + 0.25531514949895784, + 0.384171490857913, + 0.4336737785795167, + 0.3109549905836186, + 0.17136103200326724, + -0.052252399149696274, + 0.573414239869844, + -0.1084832286244233, + 0.4373380089303436, + -0.07589692393417992, + -0.0055077103292068, + -0.02433058598772199, + 0.3491373880399051, + 0.3614724360204149, + 0.0010033048765082375, + 0.567011489943491, + 0.07752422432465539, + 0.002445637079249885, + 0.04655312399072159, + 0.34461500544150137, + 0.4851597897874129, + -0.11252636485589695, + 0.47864497837566167, + 0.45625008497916153, + 0.2622235953019627, + 0.13020126598435944, + -0.10393629680536193, + 0.22567972563293054, + 0.43444407958586084, + 0.38594301224863503, + 0.10621864625295954, + 0.4699808436726788, + 0.300275835961705, + 0.4489681496001352, + -0.019310474104897737, + 0.09399141713898149, + 0.3005932393053402, + 0.601984559208396, + 0.06117822774386725, + 0.1420733257531815, + 0.3478296998824416, + 0.08322994707692277, + 0.4787760490547994, + 0.5572993233967954, + 0.30367097310383123, + 0.39819286838468393, + 0.18280157899733723, + 0.05713349134721621, + 0.12007793507130321, + 6.482444022171685E-4, + -0.01613258613486497, + 0.46139231217828214, + 0.16677951889806014, + 0.2955650524467677, + 0.15972307192237095, + -0.029363345573152094, + 0.48715474044548723, + 0.40791807868645735, + 0.24620534350662177, + 0.16231001525198951, + 0.36602662132037556, + 0.4057668122351713, + 0.22904244366120707, + 0.4787500905956793, + 0.21482052366251242, + 0.08694575227771864, + 0.1718321571444545, + 0.4404816010442266, + 0.3005939172512869, + 0.5510095809557758, + 0.24551977160965183, + 0.5349778216270228, + 0.5379542772465458, + 0.40436953930088537, + -0.09876695188973426, + 0.36762038257401575, + 0.33974073376286285, + 0.38619048208639595, + -0.03207607971655742, + 0.5495225470343728, + -0.0032159554484535724, + 0.024075852791693386, + 0.4692727671496034, + 0.5564200649795921, + 0.32621985549990784, + 0.3266215992770526, + -0.018751864651470385, + 0.30645265551268236, + -0.056557886055166096, + 0.30883440209283247, + 0.44877184122210234, + 0.1834582575742429, + 0.02032141667967194, + 0.5527366852334301, + -0.12352836009533809, + 0.47889889568140376, + 0.287023289435428, + 0.1281730860847704, + 0.3614698299064607, + 0.43559336648660085, + 0.07131979052167389, + 0.5803517131852739, + 0.2991595627241803, + -0.008567794509189597, + 0.01443390158656016, + 0.5108308253192952, + 0.26243102272490043, + 0.09437395659294595, + 0.5679619243511373, + 0.2800040253292118, + 0.09752919069782359, + -0.059744185417086676, + -0.04546748836567614, + 0.272158957788079, + 0.03941460496267807, + -0.03591992197988071, + 0.04005333653979659, + -0.12586176993870962, + 0.30955093940289186, + 0.5864172211934798, + 0.5082862919371623, + 0.19788089234919048, + 0.6072538378083695, + 0.10139006116294155, + -0.051171294823884966, + 0.4489848638732571, + -0.06793493300700244, + 0.15876822814474945, + 0.4004941944590009, + -0.06019455728127765, + 0.20689082787026425, + 0.3720877557909652, + 0.37550893636718063, + 0.50965695474686, + 0.19589250124760565, + 0.21748766896647953, + 0.5975163026536937, + 0.33799764158447704, + -0.1032435414525366, + 0.03042716274800697, + 0.3962761791614303, + 0.3777262940151799, + -0.030801011685378257, + 0.4028267150213406, + 0.5168463175162874, + 0.33021938087785574, + 0.3912936484280226, + 0.07340219628482716, + 0.09839482115990891, + 0.45878358216215653, + 0.400680720977754, + 0.5798503259469574, + 0.2141611276241106, + 0.5817563415022372, + 0.22041679893963106, + 0.252485744104776, + 0.5647344909530482, + 0.34305175969815604, + 0.5011531398683854, + 0.47868211489261536, + 0.46692682474334357, + 0.4425623824615956, + 0.17529275502689134, + -0.05530060199054264, + -0.11725931790594721, + 0.5159246496850274, + 0.10268931915053567, + 0.06299899057478991, + 0.02509051792637379, + 0.35754150688943165, + 0.12047833175106376, + -0.13182090648415926, + 0.011155852851660625, + 0.1191322420006447, + 0.5643649236223088, + 0.035938803183220513, + 0.4425431184001982, + 0.40983832259562536, + 0.4904822673717578, + 0.010720853132296093, + 0.16334348345643557, + 0.5306581142936577, + 0.3360615938281325, + 0.5756307930431407, + 0.0018393728421626787, + 0.5887891968746345, + 0.12315923341737939, + 0.2732496442318268, + -0.08223719685505851, + 0.08713838253666681, + 0.18008036742151767, + 0.08870257100786844, + 8.80279335122025E-5, + 0.027661432212370357, + 0.5741038249207425, + 0.031825345942632255, + 0.22537199633629107, + -0.12007592133427843, + -0.030082421642590562, + 0.32669334923457943, + -0.08769261061074583, + 0.2013038375246768, + 0.1060045587427039, + 0.5136705354167161, + 0.287464781166839, + 0.2399664979585162, + 0.3555681432055978, + 0.04809984873308293, + 0.3861708508833208, + 0.026363567618576556, + 0.369122272264651, + 0.0010025855526971938, + 0.2669987755890048, + 0.07416291825242785, + 0.28455458668317807, + 0.32909563220155513, + 0.12252236655861981, + 0.12589238107112538, + 0.041552139748876754, + -0.05199055394421587, + 0.4892717491763283, + 0.3768143398020084, + -0.03392221168805487, + -0.006604096075923299, + 0.07573098226432012, + 0.24616891804435903, + 0.20233067941156424, + 0.09670635480630771, + 0.4356471021205556, + -0.10281386565292819, + 0.3879595670413799, + 0.11003436403599096, + 0.44436651758018864, + 0.564669514394151, + 0.5081173072283133, + 0.5669398642844283, + 0.20697853407006067, + 0.4102650390107724, + -0.03781914423965685, + 0.45963138121509295, + -0.006027739328479997, + 0.17360194072713364, + 0.13500995381185527, + 0.3509728435983288, + 0.34718853600686167, + 0.2231880046194326, + 0.09459867220967647, + 0.4599779710442504, + 0.23322403286215482, + -0.008666914890640143, + 0.09590782116752877, + 0.5359198773427284, + 0.2898357166286284, + 0.28039903967943147, + 0.20868175916060444, + -0.07527825210500781, + -0.07317078673227656, + 0.35902864546025315, + 0.21772988927858838, + 0.1892383013856943, + 0.48499906467063914, + 0.5735298640788726, + 0.541980077828332, + 0.5239687851873776, + 0.4202511868498465, + 0.23870376874251792, + 0.180398046415071, + 0.4132727160659496, + 0.4247904476714134, + 0.27407216140244917, + 0.49971484675299105, + 0.444074433667315, + 0.1161637076702281, + 0.1850302507246394, + 0.47605673687453764, + 0.38773966623538814, + 0.24821301603163431, + 0.04789548283331385, + 0.3775268333902636, + 0.12300333952202519, + 0.2632117919293015, + 0.3861414737519073, + 0.4245470336837698, + -0.07097765227118442, + -0.10067099556761834, + -0.04016582270249154, + 0.38054918996224407, + 0.4884757271663962, + 0.5970834004167795, + 0.2576092636586318, + -0.04789136234701323, + -0.04721595258927366, + 0.5123104844916347, + 0.5349530654057932, + 0.2955335202273747, + 0.07599695123606603, + 0.0636406902362209, + -0.098260805497389, + -0.1324816558033198, + -0.034680761475278654, + 0.21412315102777513, + 0.4663976234476336, + 0.004796612610709128, + 0.5663587072371962, + 0.2400753084815907, + 0.5525293016552281, + 0.09729776480882268, + 0.326291868525764, + 0.06059839176393039, + 0.45083488069343514, + 0.07293278399610131, + -0.011780271540754061, + 0.4918189776483055, + 0.46194123295529144, + -0.11884134397834804, + 0.22820385384687447, + 0.5209360589427369, + 0.12456593889924406, + 0.4542349605466416, + 0.07279273950265602, + 0.03319350899654405, + 0.33162580153837645, + 0.4742929352241789, + 0.3931127225955695, + 0.431017625272883, + 0.2717479111107357, + 0.19974970056081404, + -0.10241360989441053, + 0.26399916087288683, + 0.48315849896810725, + 0.11773927146210184, + 0.28589542768483583, + 0.2419313214120783, + 0.2842187843228923, + 0.5301321995136463, + 0.18769082156871902, + -0.06788011508795169, + -0.0844958843252415, + 0.3253282138948535, + -0.02011798913437357, + 0.30839264553362605, + 0.1986860509997153, + 0.542621094690184, + 0.1486777268336481, + -0.03965456470511593, + 0.4037829791000591, + 0.5219895076630919, + 0.5597647554583675, + 0.030937229326242238, + 0.17281917082875514, + 0.4864731270770538, + -0.03199373999110189, + 0.3834202924560811, + 0.1680075360528286, + 0.2400776412688973, + 0.2502413708212283, + 0.31866255777901425, + 0.27497660908691907, + 0.2585381041688748, + 0.3007697216220945, + -0.08983547585762416, + 0.1453030016971137, + 0.44909993127216796, + 0.5436836442228341, + 0.41150526197146564, + 0.24943236255540485, + 0.07311363994287282, + 0.03100654523350524, + 0.2024725754290273, + 0.11874367544225684, + 0.30792778071781124, + 0.34466876196222673, + -0.09860785015495933, + 0.37326974900471677, + -0.1013827008169667, + 0.2697930844592585, + 0.43313365306607277, + 0.10260441274289306, + 0.3912259906457657, + -0.08449486599516033, + 0.5457426654613766, + -0.03250692873361155, + 0.32548877279899374, + -0.03357926450475829, + 0.3097346144278502, + 0.09999877340024654, + 0.19356111304481344, + 0.31177419781371346, + 0.21169827197048963, + 0.21442467933253134, + 0.029970815834074904, + -0.04153608328948431, + -0.1011831000709752, + 0.35999343172606757, + 0.16806845522415792, + 0.05846905707417188, + 0.2537798144399031, + 0.48786813730182477, + -0.0557719174951397, + 0.20543862098706328, + 0.5104559682361097, + -0.056804481009986765, + 0.45804725737051455, + 0.35779827880881865, + 0.31189222825439666, + 0.2389449888417412, + -0.05762893173051174, + 0.036501117606941885, + 0.5480746264598942, + -0.040466170129530216, + 0.23915110608728718, + 0.0707390968951471, + 0.5381163926298617, + 0.30066744785009636, + 0.11963787183448482, + 0.13028611979956406, + 0.25814025783388506, + 0.5335248019926252, + 0.5939957579788535, + 0.037381834554104265, + 0.2883195591607639, + 0.10267376501972789, + 0.17207867842765567, + 0.0013501392755145836, + 0.15360377016010124, + 0.08862787865144034, + 0.4781254669103847, + -0.033811203842210175, + -0.08117526801776592, + 0.44457557899552247, + 0.17854921153157066, + 0.06196061680265508, + 0.5969712439776793, + 0.3712179022782157, + -0.04819571669316862, + 0.5089497092294548, + 0.3156680890886033, + -0.051088823627788674, + 0.24695560375857128, + 0.014353703144775298, + 0.5430547412676965, + 0.3809020495842206, + 0.4853388492578474, + 0.2469571550904769, + 0.4294335422362361, + 0.31798601604322096, + 0.11015260924858578, + 0.33976055433198205, + -0.10515888805532468, + 0.12067510836789552, + -0.10423806497551438, + 0.4780207572656081, + 0.11040345030352755, + 0.36366376298921765, + 0.10133762400526461, + 0.34666800988318314, + -0.032843766756216544, + 0.3655154532330258, + 0.40198563448216784, + -0.006898334535042738, + 0.05000796154347073, + 0.07850957844974507, + 0.3420471420039598, + -0.07630381952972336, + 0.2368411856009615, + -0.019311710079764927, + 0.3730430982377876, + -0.04721521166376638, + 0.01103458781158434, + 0.5865647226336216, + -0.11655331250382871, + -0.09907169643712593, + 0.5968079385420917, + 0.3595905369343171, + 0.08772053986883527, + 0.30406375145494835, + 0.1648234384131746, + -0.04687290523203094, + 0.05829436379707628, + 0.13529769000273228, + 0.019065329237039602, + 0.5106067998588489, + 0.3278448016501918, + 0.3829501596413648, + 0.02638707157125139, + -0.008173612459713125, + 0.5770464200926431, + 0.5631989494208489, + 0.5733941406502303, + 0.2744992263628912, + 0.14867909553260922, + 0.03690369078407571, + 0.0467727974021927, + 0.507685874213534, + 0.17830592988291488, + 0.5081492018309156, + 0.11697287661450162, + 0.5076185376161517, + 0.5420481363496006, + 0.06894001374446568, + -0.04095636962371926, + -0.11271991788377315, + 0.3928567443223464, + 0.16687417354245088, + 0.47359376436914213, + 0.12372391734222049, + 0.46576471291313826, + -0.011693116128684039, + 0.2185122205022763, + 0.00872040082792458, + 0.43958815123779504, + 0.4896364828284675, + 0.1625193979519316, + 0.07832695760449668, + 0.19681155992718674, + 0.2621430210945579, + 0.41289336371984997, + 0.1685660059895151, + 0.2116192014235061, + 0.10723318743943577, + 0.5279831932756827, + 0.012438937830508645, + 0.5275276661792178, + 0.00763170680283759, + 0.04106771043963872, + 0.6038669702377336, + 0.31350438793989427, + 0.48982050154951906, + 0.5314542921441644, + 0.4259771063808113, + 0.4229598703337428, + 0.04224114988976527, + 0.5908789445887701, + 0.14011424543050638, + 0.3578417650182568, + -0.0168103542753128, + 0.2071802422627705, + 0.4370806286125598, + -0.10753844839169883, + 0.28587986080502575, + 0.07396891933070149, + 0.5407377783355061, + -0.11793617976449762, + 0.4079618814509085, + -0.06719868115503459, + 0.5616253566321366, + 0.38131796668228757, + 0.5325614157948347, + -0.11114710083946588, + 0.4139624949224374, + 0.5040868554128566, + 0.5754020159833199, + -0.05816948545794025, + 0.20867339913109378, + -0.03713535547967463, + 0.18607962881042722, + -0.008941936386503924, + 0.23937101189263155, + 0.509619958126795, + 0.40559888217933704, + 0.2632968648236435, + 0.00877722657893834, + 0.1801134827224023, + 0.08501564566680347, + 0.5892092485594413, + 0.19035121118315873, + 0.5218499664746921, + 0.18891410170799727, + 0.4890585667494789, + 0.308751013136418, + 0.08565977117453985, + 0.08336751527005479, + 0.27817622458308616, + 0.48936772307488174, + 0.5032406388186458, + 0.38116911665060627, + 0.1955527477166069, + 0.03506816913844246, + 0.15961516937896458, + 0.2133245204304689, + 0.605837730765285, + 0.13494923219160998, + 0.3673791296661141, + 0.08853980421618246, + 0.4263715206375662, + -0.03507503124196251, + 0.2785314534182315, + 0.08564051491861469, + 0.2804194050646434, + 0.048008420850683964, + 0.41306273081983325, + 0.5622688117935581, + 0.6014934989929339, + -0.004378375501769116, + -0.06382099616252393, + 0.0077471590559417824, + 0.15446070458097083, + 0.5031750680955398, + 0.15464789414582458, + -0.031191399527904687, + -0.08523688325623449, + 0.11136342135421434, + 0.08349020508852456, + 0.34813907873644934, + 0.20664614045433227, + 0.05446025824880238, + 0.213987650984028, + 0.474658487115899, + 0.4391099346332985, + 0.37759910282882725, + 0.5720689156722212, + 0.02932089011483488, + 0.04503641499198366, + -0.08621969108947343, + 0.4305168839983913, + 0.003286588556969866, + 0.33089945767470413, + 0.17727458524929102, + 0.042357486300031666, + -0.12378211021733347, + -0.04906034431238861, + 0.5697449970331907, + 0.2243723515872626, + 0.24790878129755728, + 0.03647356946870964, + 0.5428334712461519, + 0.4301178126496903, + 0.23360319848606176, + 0.06906100138961865, + 0.07604566731263016, + 7.451225592357003E-4, + 0.601307177436081, + 0.33505650254620734, + 0.2953308477020174, + -0.11471397679690545, + 0.0799366175924828, + -0.06737550558101442, + 0.45541215749730846, + -0.009696861887847935, + -0.01562937055299174, + 0.16955819462167365, + 0.11115364156500962, + 0.37756328347679946, + -0.06509707820486078, + 0.03596393631182196, + 0.5401312965314807, + 0.3879060730755777, + 0.47831146137164005, + 0.4155631183361911, + 0.4113730740688335, + 0.4669705413307166, + 0.2642771952705223, + 0.3106367179372098, + 0.06521929697264708, + 0.13527971445469417, + 0.5953182475742416, + 0.3853032193131899, + 0.2182273364738896, + 0.2092063745731873, + -0.1059386641604404, + 0.3430252156732625, + 0.2987990301327319, + 0.4219863873691446, + 0.3774736696925979, + 0.2620688274858473, + -0.06559857549619662, + 0.18743960476879534, + -0.11491218181086396, + 0.4362971479217944, + 0.5639241061407931, + 0.12483993149918049, + 0.41762057998714996, + 0.20795972955392783, + 0.16855763023314885, + 0.045097021893975964, + 0.3594226700342587, + 0.38450300751985733, + 0.5078299629272672, + 0.0849717009044931, + 0.28906829728871086, + 0.13301955784607722, + 0.00493329157088232, + 0.5431776239152531, + 0.12784529562440872, + -0.051921542985894215, + 0.23302915715216138, + 0.2910256312403452, + 0.1647145037352606, + 0.30346599283637193, + 0.36545959157453867, + 0.1078340678443104, + 0.5288699111819102, + -0.063297685359017, + 0.5324803039673852, + 0.1587340733615824, + 0.5539342983971275, + -0.04652024132819313, + -0.13617398532318686, + 0.3978278378092549, + 0.5616288433342479, + 0.21901535386529813, + 0.5154066292619706, + 0.021037130428710776, + 0.2596468187669036, + 0.015553081197571678, + -0.04601791178463539, + 0.17450858261383467, + 0.47683218877354705, + 0.0748264221302461, + 0.13393885016564372, + 0.1756678419763819, + 0.46018315403095866, + 0.06865735949761509, + 0.21107796852887667, + -0.13642316227771042, + 0.46781195284350885, + 0.07011932850820313, + 0.0618374179630464, + 0.49874130306973674, + 0.43937483159068524, + 0.08051294037982687, + 0.14827878384302046, + 0.007984243101085364, + 0.16787968425168304, + 0.19416600386247884, + 0.4068082635482605, + 0.009219998571200372, + 0.25772726230216986, + 0.2076038749778853, + 0.1321003812720234, + 0.3155160697830066, + 0.1771561235702539, + -0.09181583848505716, + 0.5932464275169883, + 0.5458550295051966, + 0.15876601672302537, + 0.1439015099931275, + 0.4342467468360526, + 0.5119856024076237, + 0.28199486044522437, + 0.4805746639655737, + 0.08849426411957367, + 0.37754475380860597, + 0.34186681686016834, + -0.03333215120836833, + -0.0521418273625265, + 0.39299681306974066, + -0.10605900059008931, + 0.5939697724977784, + 0.24174662003622088, + 0.425171386912401, + -0.06239814157019029, + 0.4606177127380148, + 0.36336208393375535, + 0.052561414412505975, + -0.12376685992029929, + 0.47170084560849146, + 0.5571261626809199, + 0.3794311203633952, + 0.5284050858320153, + 0.47147182505381247, + 0.4724737090514879, + 0.5271988319046087, + 0.2652711482267518, + 0.41294053303765343, + 0.06632643893586002, + -0.09519152661893673, + -0.12962521988272663, + -0.11879480980850382, + 0.4702298573041346, + 0.26723283921506713, + 0.3426962422667663, + 0.10389379690926565, + 0.3769588244372314, + 0.2826515204298474, + 0.33591842123093196, + 0.4742371593152288, + 0.5020246999641065, + 0.27501891201348766, + 0.42689779126276695, + 0.5470543603608736, + 0.017664166590103614, + 0.01965425616784877, + 0.07324358077413981, + 0.09380163101548539, + 0.40958513207539604, + 0.590880754339729, + 0.5475613082258823, + 0.46341605057754776, + 0.3669013701013115, + 0.6081499794365001, + 0.10832009972682316, + 0.23317363443799177, + 0.32980334484739726, + 0.24861153055409824, + 0.29893017507113423, + 0.3320144058769098, + 0.40450441792362646, + 0.24633985489379717, + -0.0582084042761684, + -0.09324640198161233, + 0.4624132419106527, + 0.558317876912098, + 0.07923284312284237, + 0.09727230669404074, + 0.5568741997865939, + 0.4186857452227717, + 0.06026670975883869, + 0.28733535776446945, + 0.16262176877261875, + -0.11127341175764274, + 0.5218377016596556, + 0.34087723938196657, + 0.5056989684454853, + -0.10250416264485297, + -0.12069771485833863, + 0.22907585814261056, + 0.17106966680507651, + 0.4503590264867898, + 0.35156712094617204, + 0.48722653109197056, + 0.0777945269061236, + 0.19480296121119123, + 0.4255350992136133, + 0.42604293695515394, + 0.5603512098674337, + 0.5712542208586365, + 0.49903925306021346, + -0.11635536063511696, + 0.36092555502797324, + 0.3049035942585415, + 0.17669523507276014, + 0.24432536641548375, + 0.34110901807824856, + 0.6058504793215178, + -0.047985320358963066, + 0.09574049284834887, + 0.03371250246469354, + 0.31051392462150673, + 0.28705434676207614, + 0.06218191308787244, + 0.5296753915076353, + 0.2135574273641373, + 0.11339105710246233, + -0.13109467777291928, + 0.14583574831165574, + 0.4947532784643136, + 0.39937463393812256, + -0.10808462910602794, + 0.49323694441849586, + 0.2903047520632139, + 0.018088333774633036, + 0.33538177888905646, + 0.5558103701638045, + -0.07715456270121145, + 0.35791299134494925, + 0.24551446199479066, + 0.03438608638856597, + 0.35027727513944984, + 0.170670666261866, + 0.07711312176863391, + 0.4502099140433855, + 0.16152289620312327, + 0.04031825924265128, + 0.06271048538012533, + 0.4657145880653778, + 0.21340754916859994, + 0.13385462300911982, + 0.35843183125363404, + 0.13741137895609062, + 0.2181810104903959, + 0.26160359459951327, + 0.2907104270380823, + 0.5302994647950594, + 0.35242063264073603, + 0.3818836301133287, + -0.10449330211947595, + 0.521350625092338, + -0.01818252181807893, + 0.32659080622728304, + -0.09231960816089692, + 0.014929712709634335, + 0.4247624445029342, + 0.13520834536174864, + 0.02909039561061308, + 0.24376019195789794, + 0.20615376695788679, + 0.3907196796934338, + 0.509666199358883, + 0.21863223734330822, + 0.5422824832501394, + 0.36358566355731714, + -0.11130792714886703, + 0.515855959510218, + 0.03501132952172528, + 0.6063961987523858, + 0.3730755462515284, + 0.3663545725446862, + 0.23178227885847286, + 0.4974255571444166, + 0.5121920790082954, + -0.01964598317397534, + 0.21396448917117727, + -0.1299057415053938, + 0.31220276699989497, + -0.034700520064310916, + 0.5600261687482246, + 0.08553333109906397, + 0.1935914963790199, + 0.4564535476370074, + 0.2832194184954982, + 0.3693083690741459, + 0.5876733588791899, + 0.49759301733030603, + -0.005375647962556518, + 0.5387994069659269, + -0.03037587742209584, + 0.08863029539898101, + -0.03993550927598433, + 0.24144444797098674, + -0.07726371119515768, + 0.3798710033545446, + 0.5323014966613353, + 0.09782600353320794, + 0.18475370773874156, + -0.1132759855117247, + 0.22243336519851137, + 0.1734187860079059, + 0.31754277966223404, + 0.37313411761950876, + 0.13782329004531985, + -0.08199512191393035, + 0.5873103663235255, + -0.11685024545025001, + 0.3116383981906192, + 0.29444109523567547, + 0.018690661006848602, + 0.2949217938144738, + 0.044320146601283306, + -0.06918086155081093, + 0.350986307522645, + 0.28208413407462235, + 0.1907961676391905, + 0.5605777133757651, + -0.012798176653691234, + 0.6101751811031405, + 0.1733448565331861, + 0.5044556397276262, + -0.06904722948503196, + 0.5125659035458706, + 0.3978792554740732, + 0.529708153791676, + -0.11828833055651958, + 0.030961488235874163, + 0.5982171403154051, + 0.4989471148475666, + 0.5302668584585334, + 0.10353947506888028, + 0.077021620745989, + 0.5427016807307125, + 0.19916895449803462, + 0.04094695316158578, + 0.5666798492975195, + -0.05781288630597964, + 0.509163939274034, + -0.07005905564928616, + 0.017299001107875633, + -0.12656975827973888, + 0.28692545248725754, + -0.05198500055662979, + 0.17594708428262912, + 0.060637000530194135, + 0.40168779898683715, + 0.45628798952812266, + 0.1301494213040627, + 0.4560468735165978, + 0.3895083632639115, + 0.1563032917050844, + 0.14247851468490458, + 0.5181438265020908, + 0.0389832672957201, + 0.5077563424545192, + 0.29158418880408066, + 0.14904165774548445, + -0.03216289784637959, + 0.2600400888781981, + -0.04107352827662698, + -0.0998654042691377, + 0.44354721235346783, + 0.29131528574911636, + 0.1447290893532887, + 0.10931795763769925, + 0.5901489338435535, + 0.5099286156088593, + 0.11926850233328168, + -0.11978510926391527, + 0.5891416567396948, + 0.5737096722852831, + 0.20871233120867738, + 0.3378393950169729, + 0.29040354740050855, + 0.20636455839475, + 0.5175577727365355, + 0.5019683714295622, + 0.16684762155165195, + 0.5165470209576121, + 0.26587903062026086, + 0.0913754807626137, + -0.13638496175350634, + 0.10485944057755514, + 0.20504718063301242, + 0.3867839352937483, + 0.17813953558703383, + 0.4286087109520117, + -0.015325407358874762, + 0.274167609699956, + 0.1814557811838437, + -0.030440695017037167, + 0.1863928330414869, + 0.37269990919119966, + 0.01829809477152916, + -0.01647178448843467, + 0.5615110524123887, + -0.07580563290719808, + 0.13403539208273957, + -0.06977479894311228, + 0.10728693971956679, + 0.3346722727334178, + 0.1436244162491429, + 0.20622636920356885, + 0.1991128657138896, + 0.4913420113935215, + 0.0584333540962618, + 0.3338445742668825, + -0.09739185832876976, + 0.04559042464415192, + 0.044381816980617994, + 0.23218322508945083, + 0.5830765344428624, + 0.44926591390237813, + 0.1897806022479931, + 0.183507362207469, + -0.10359501028777501, + 0.14213924493845564, + 0.2350094349504004, + 0.14316848330535398, + -0.09608320700650735, + 0.5864233691253916, + 0.5455014940299413, + 0.5131851277478383, + -0.11790900045903212, + 0.17340146422774827, + 0.28147944181549756, + 0.0016754225702281245, + 0.12469199016603949, + 0.4372836507272324, + 0.0885888718772459, + -0.12363922527420093, + -0.09546674359291321, + 0.45855883374247064, + 0.41026976315075325, + 0.40713320660926133, + 0.4213361199168507, + 0.2986203137106599, + 0.5857262942091473, + 0.21599477404994977, + 0.06701230856349419, + 0.15634355110443915, + 0.4030989667243613, + 0.19702538593917662, + 0.17882777856540055, + -0.08768613857202469, + -0.03754185883248726, + 0.09424374854812942, + 0.136788506294229, + 0.5311104234652526, + 0.5267365899357813, + 0.5955459719970032, + 0.4953345608793839, + 0.5366580465025078, + -0.07523651006545697, + 0.1692293562533611, + -0.13168243320808135, + 0.4082775917771908, + 0.5241210980831327, + 0.1951867008121907, + 0.357733417978717, + 0.33653439333552043, + 0.49680478811550255, + 0.23997711402055827, + 0.44499475461289106, + 0.4790156711911491, + 0.3135174473020175, + 0.23482633852398316, + 0.17371621043199703, + 0.2499326442309377, + 0.43076965294135716, + -0.07060108172859778, + 0.3933761297101219, + 0.13463607704537056, + 0.04164067381008599, + 0.06488841766572317, + 0.4582967357752873, + 0.2783127991402629, + 0.5269536849367987, + 0.420246163662399, + 0.47911144382044213, + 0.44265314067049, + 0.20256019062964176, + 0.2195041952454561, + 0.381179481335314, + -0.02103383615560382, + 0.46136407896742493, + 0.2571481441072441, + -0.01814865855819807, + 0.2878753438717705, + 0.4429251609784035, + 0.47002098910284096, + 0.019194983059636156, + -0.07883486880719617, + -0.05328587784285334, + 0.37964741394476387, + 0.14836907812025446, + 0.35418802494376, + 0.2763978830014891, + -0.034050921535329584, + 0.08560518417859903, + 0.184527123155992, + 0.5731721503083054, + 0.5610157643319746, + 0.3324774228728021, + 0.513403612150063, + 0.07150127645884394, + 0.07589944939590207, + -0.0657407858406643, + 0.17386273618665932, + 0.01411242572589158, + -0.13361282740730507, + 0.582833983533426, + -0.10703231148268286, + -0.08621175979722495, + 0.04550781452263225, + 0.4022125483045982, + 0.46223595652706884, + 0.440792148956781, + -0.1341541051287397, + 0.12241833940631652, + 0.22206873046189646, + -0.12569550773459562, + -0.017410001681002665, + 0.4353518663632291, + 0.18158620727929242, + 0.20121799044338595, + -0.12625153996230193, + 0.11422396194223039, + 0.4859556702252862, + 0.4920702581071148, + 0.22056078626666464, + 0.12890806784809244, + 0.570004159009124, + 0.056566470860971746, + 0.02219159595384096, + -0.08625091411140307, + 0.35867814874279513, + 0.366527212510404, + 0.6079621510523775, + -0.0318293782026734, + 0.28919395086548305, + 0.13353098084755888, + 0.12418357791232892, + 0.053816857545839036, + 0.5083193699920053, + -0.12903558258043307, + 0.225704884569082, + -0.06436910151485649, + 0.5884326284517606, + 0.3837292050783979, + -0.00795902708002355, + -0.016155000923047044, + 0.4563057296898787, + 0.10265505927327634, + 0.5680747146422992, + 0.2674643599255288, + 0.5620601763388975, + 0.304422599979637, + 0.13877665306442288, + 0.0017357308191860987, + -0.06504037668764703, + 0.2811514651838732, + 0.33406554812894296, + 0.1565025242300615, + 0.5246935162784946, + 0.006269742271678508, + 0.08397410507669917, + 0.10368600054879054, + -0.016903394490193818, + 0.0642756152983458, + 0.6053014581645829, + 0.17547024552839036, + 0.16281867969041958, + 0.49331902947411066, + 0.39603849627963317, + 0.1364542144387057, + 0.0498840520560454, + 0.3094972108439458, + 0.1839670572516548, + 0.47135518729239445, + 0.5599950131202732, + 0.1717805846596483, + -0.03142197785521013, + 0.27898761813557293, + 0.3729658132451563, + 0.5711069527754332, + 0.09271847283530865, + 0.4644109824000494, + 0.15978771336393394, + 0.44829270072179117, + 0.46065398238562727, + 0.05972347444545062, + -0.12156810039600807, + 0.44353001857455177, + 0.5417460719856291, + 0.25272067780585933, + 0.02935049240098192, + 0.47497626521087233, + -0.06790172323928578, + 0.4208379875739999, + 0.3941029866222727, + 0.10474737233029546, + 0.26142216528040496, + -0.001498820857415234, + 0.45433940656938687, + 0.45054769897275193, + 0.5749740855846787, + 0.001270267111346951, + 0.4678597371372888, + 0.350364004737489, + 0.2985078129188371, + 0.3928362533162062, + 0.46290378419487666, + 0.09395946240663774, + 0.19652035519081335, + 0.06510735633815729, + 0.3329491948839812, + -0.1162348574849493, + 0.21150056711207038, + 0.5013044010402365, + 0.47516787779925995, + 0.17600170727646236, + -0.055131853807697195, + 0.46126777025266685, + 0.19671045336072196, + 0.18148998449626408, + 0.24886635591340617, + 0.5358104908695159, + 0.5053400723663876, + 0.012278923555058163, + 0.21268809897590257, + 0.5445057534172204, + -0.02630704157874554, + 0.5090475085267308, + 0.05310853559128226, + -0.11886108879688342, + 0.31974103009962823, + 0.16005414013088726, + -0.10200221948840638, + 0.11731269119232296, + 0.007561389733247381, + -0.13658096180572457, + 0.20743321323019398, + 0.33780127858890496, + 0.20431613792322428, + 0.4646259645495585, + 0.543315386109017, + 0.41202833666737515, + 0.10251401872135704, + 0.23002237384450508, + 0.4318895285807387, + 0.1389224130779108, + 0.3012859297404203, + 0.6108857078123269, + -0.08079429551978991, + 0.5356322754110534, + 0.10981506303591826, + 0.5401525006638617, + -0.13722581929412075, + 0.5080022607043287, + 0.2854943201675218, + 0.15435403641751488, + 0.5371491474018089, + 0.5280289772743961, + 0.3848405215558731, + 0.1511960231053387, + 0.043473063101350184, + 0.4927858476553836, + -0.09255840140924018, + 0.09130904113612603, + 0.5042219459889767, + 0.4807026822627354, + 0.3351965421728467, + 0.013341110638871445, + 0.3543019442789457, + -0.11602760893111702, + 0.15993081451049085, + -0.08540640072258043, + -0.11994470378508972, + -0.0841415224661956, + 0.46424457288549537, + 0.09803032308140222, + 0.415771671065578, + 0.16768683030455622, + -0.07862579333400874, + 0.4007683576726574, + 0.10146794592407254, + 0.45604273200927625, + 0.04692927525939569, + -0.03650007595186314, + 0.14567524239498897, + 0.1065795479895941, + 0.5245771057178611, + 0.02722056945226156, + -0.008352907645996582, + 0.33703188771904774, + 0.23311014409865688, + 0.002648215816281191, + -0.054977842675595384, + 0.16682026992677124, + 0.11002226412540045, + 0.5368448888191316, + 0.17351048830174598, + 0.5464428911862212, + 0.3214064829516144, + 0.16575959194834416, + 0.15584801091072814, + 0.026728554897296447, + 0.12465932681477199, + 0.43142449730457144, + 0.2539708185260728, + 0.24104734229275582, + 0.23443011819095594, + 0.16530582213763922, + 0.49776977865430383, + 0.5192380916440791, + -0.012588664123298884, + 0.5889960087027716, + 0.5779535392896441, + 0.5886367906935551, + 0.33216839487439376, + 0.3128242014284931, + 0.1964585082741665, + -0.11843368093370428, + 0.590765299329787, + 0.4715455835211658, + 0.17800012172141966, + 0.18767392280508383, + 0.34408122794854346, + 0.16095095143888455, + 0.43425572238246424, + -0.05496938372464663, + 0.03536400839651169, + 0.3983444123366797, + 0.3716562543359919, + 0.45635937874765076, + 0.2394812245387274, + 0.20681591436872943, + 0.5027457237984714, + 0.47602084803415057, + 0.42886701190939114, + 0.22823018917308735, + 0.3750086193409138, + 0.33964228900732313, + 0.2617822226934168, + 0.34861236357592224, + 0.13374179820793586, + -0.0945151785416155, + 0.18475330797415213, + 0.5553497339861103, + 0.4947218050121034, + -0.10674027652778292, + 0.547701230480717, + 0.04697214497665195, + 0.11035980338397133, + 0.07596977737775132, + 0.460765717131577, + 0.08754331262051723, + 0.214530034911323, + -0.09625218249786924, + 0.5553058236002155, + 0.22755979956784123, + 0.5081080882681417, + 0.3789056923506824, + 0.5886800017970186, + 0.03138095605243199, + 0.10083512843761502, + 0.4697269856028534, + 0.06505447201935469, + 0.48998785956081214, + 0.40468617903763715, + 0.3706836684471285, + -0.05089087097422074, + -0.04340136793189686, + 0.6028692717322057, + -0.08261955931202575, + 0.3322831215749198, + 0.098378127707859, + 0.14495062666407293, + 0.34837682379399976, + 0.3195843661047258, + 0.3347449226156885, + 0.5449880664826039, + 0.2596177207533336, + 0.04907629591552268, + 0.020903616416014487, + 0.28408059317069145, + 0.1661295020046628, + 0.027016453421143144, + 0.08543667642517586, + 0.33093401880765333, + 0.11191698280563556, + 0.36790528479485973, + -0.09252248032185577, + 0.16641056352259775, + 0.2989340897391913, + 0.48965486041702566, + 0.08319398427965696, + 0.1559707046521575, + 0.47875412328499567, + 0.42419617516295216, + 0.044654824555711486, + 0.1286761741259706, + 0.46185564854594574, + 0.23639702299870213, + -0.016722419334566876, + -0.055342059986317485, + 0.3734777488925518, + 0.5475532417503912, + -0.05863942102367539, + 0.5258050995644387, + 0.13275088453695072, + 0.3415347591427909, + 0.39048521461312247, + 0.5723609954486547, + 0.008833317900245607, + 0.29578504938897293, + 0.08721284871952753, + 0.39394811335260516, + 0.3271483842036204, + 0.05994814004447288, + 0.15291136186202436, + 0.0982290411162127, + 0.24149958388606624, + 0.5649688238809005, + 0.4445538226832815, + 0.14838077067402816, + -0.018070966033271033, + -0.011221420748540545, + -0.019053931504857943, + -0.1330476997023332, + 0.027661285190812845, + 0.5959834433264459, + 0.04335637775533155, + -0.05309907034788386, + 0.26438689367806306, + 0.43440270358122146, + 0.2695897446785602, + 0.2903908837570677, + 0.49804376621844193, + 0.38353725902602676, + 0.5068305960618386, + 0.3557937396557838, + 0.4930835521461938, + 0.2688293211039796, + 0.4535645082435287, + 0.40784743164406667, + -0.0433685383362345, + 0.564985579887999, + 0.06835730827358025, + 0.08818663462474471, + 0.25657718998758167, + 0.31962222074350816, + 0.10176780924448428, + 0.5639197035263348, + 0.22453704930433493, + 0.4360169591489049, + -0.13041963619879457, + 0.46387851488612775, + 0.2825357407625872, + 0.3053764353589386, + 0.3930501296625045, + 0.5427892295855158, + 0.03001427074914792, + 0.20408131032457688, + -0.04424764436747583, + 0.4712056952439774, + 0.11829359721950233, + 0.26438450278286924, + 0.0070376926607536305, + -0.05066775512331165, + 0.5234557897712531, + 0.3514471260497967, + 0.5264718743796712, + 0.06636589091256095, + 0.405536405277686, + 0.24487003456779632, + 0.5230540890276063, + 0.3447715893751539, + 0.6017269148948841, + 0.07011191504558617, + 0.439993753746599, + -0.017063735852688208, + 0.49666804475079607, + 0.05862739986720519, + -0.01619362804507765, + 0.039849319136113226, + 0.30716196757578124, + 0.0011772310715257306, + -0.13368034541730608, + 0.03913628846768308, + 0.03357464222548315, + -0.07946864236367886, + 0.21395029960229706, + 0.22163478636218636, + 0.2057246703696481, + 0.33091791771546847, + 0.48306157184709, + 0.24778707853943188, + 0.2748453731522442, + 0.3470205190093743, + 0.2701015813100718, + 0.5176887929112499, + -0.05987149896920292, + 0.5738470427357055, + 0.3498467568550912, + 0.6105345700100769, + 0.17438303729127413, + 0.15582112200349008, + -0.08383462506608992, + 0.342435957809375, + 0.48601669332898845, + 0.12229770522282846, + -0.009782252983123046, + 0.6077375014246559, + 0.06646143285350772, + 0.6097079820568975, + -0.013714053953991334, + 0.5666544748265586, + 0.4129012916384299, + 0.27840291554499863, + 0.28403485052388744, + 0.39171715531172, + 0.33511456082930074, + -0.12735251440837153, + 0.5090145077177612, + 0.36639825202292375, + 0.0918527382344145, + 0.012099169017364741, + 0.34184826854528677, + 0.14908694900736047, + 0.33977717779363314, + 0.18937923178873212, + 0.384637998054858, + 0.29058071199110425, + 0.15947556286005654, + 0.38834458664401184, + 0.5043560049327878, + 0.2803905411365618, + 0.3824253204879484, + 0.14046907907612827, + 0.5013317915679459, + -0.05039278415510014, + 0.1325093581761091, + 0.5270738649053709, + 0.23863435964109242, + 0.05189177397858796, + -0.0978902986922896, + 0.5575904264901255, + 0.30818164840101564, + -0.010115472561209787, + 0.1638552829586838, + 0.21429630965907948, + 0.4635953442920926, + 0.0219473624159581, + -0.06303289997283744, + 0.5243390679649493, + 0.47421514836978484, + 0.2479561838763959, + 0.25579376800309916, + 0.4506449696716974, + 0.006326852486399165, + 0.22998320117531224, + 0.16731154932341225, + 0.45510211156537217, + -0.09457211170450916, + 0.3193812968583997, + 0.32626513738267815, + 0.0412327923082004, + 0.25610477453653885, + 0.5299042885569305, + 0.3496589434401481, + 0.13675782467064562, + -0.002027768533363866, + 0.2860730255563419, + 0.4287001884799374, + 0.5412602578604806, + 0.24391202924927263, + 0.5019766825070419, + 0.3188042241716155, + -0.07465408744345883, + 0.2940728176041355, + 0.580906388402356, + 0.2898957349081792, + 0.20498891294859883, + 0.1344584037438568, + -0.02499442508294633, + -0.11968778787113794, + 0.357092305454376, + 0.42926679170663173, + 0.37469365574572366, + -0.11365971458714319, + 0.055632238096841286, + 0.10832153340351042, + -0.031188978893107816, + 0.5726690106657937, + 0.15975992009313272, + -0.024323506217155594, + 0.5676252856758184, + 0.3612059551026381, + 0.07598093871258502, + 0.44804603943587973, + 0.2959658829219815, + 0.17219153945639426, + 0.08565310505929036, + 0.4655100641526698, + 0.38228249566759687, + 0.07144969711311233, + 0.23990192977507713, + 0.5412829616555621, + -0.1366702671936378, + 0.36149303384040216, + 0.07113534247241268, + 0.5120537904358765, + 0.31616362852288954, + 0.08760843550249772, + 0.5134660526546866, + 0.5953594039140859, + 0.4636361608331526, + 0.1220910115969775, + 0.06864272765916585, + 0.5123315282013203, + 0.47535683809039786, + 0.1772412156277705, + 0.46872550921826184, + 0.15833600243258766, + 0.5817708247877559, + 0.4149348983141157, + 0.2652589503453975, + 0.2789544197896485, + 0.556758108953402, + -0.09658920425854041, + 0.300705234736655, + 0.5340476492461189, + 0.46453726909215176, + 0.12367695884544838, + 0.11120415899972041, + 0.4180808886968237, + 0.0739617579031133, + -0.012035275933706818, + 0.35154848187032145, + 0.14176607282065157, + 0.289095192977237, + -0.061862578976675756, + 0.17100242134595994, + 0.401426353373427, + 0.07801785490443253, + 0.2885244981608636, + -0.08889615901403727, + 0.23669476300017006, + -0.011784281939218127, + 0.10307366985782493, + 0.11309728597965996, + 0.43667105817058527, + 0.4174682693303158, + 0.4559319508057894, + 0.3228691751958065, + 0.056021138674065746, + 0.41979381662949655, + 0.0376393704964442, + 0.42948402246352424, + 0.4321638197017563, + 0.5160654825982508, + 0.022552584009734422, + 0.5722339247786029, + 0.380302006971336, + 0.25732159525621334, + 0.45862838871212197, + 0.15828953442360483, + 0.5427784564279414, + 0.5984595581181332, + 0.420564934340507, + 0.21098860640150047, + -0.027688480418103636, + 0.5817474668448536, + -0.12157667570440414, + 0.3192621276504468, + 0.3276831384405841, + 0.4314510842279419, + -0.06893547203978874, + -0.04125429272051297, + 0.3992362534381022, + 0.0421260075481672, + 0.2904313002747567, + 0.1781869888467557, + 0.5004020186930568, + 0.4687704781563473, + 0.3128322180605871, + 0.02101083058875497, + 0.5513014492629587, + 0.08388354520908983, + 0.4684215863073101, + 0.019922856903197117, + -0.07183564521506192, + 0.027191298797716007, + 0.1748595977743982, + 0.11313359301653092, + 0.10820260398781523, + -0.11528209556588238, + 0.33318121327589084, + 0.2841498064641219, + 0.4005532137254745, + -0.09089473571129283, + 0.1748062172415541, + 0.0375278464600024, + 0.11802506739267676, + 0.273812367743249, + 0.3292816654917191, + -0.13045978022221516, + 0.5082286386010959, + 0.3326447547215549, + 0.4422874829996629, + 0.3571137844254819, + 0.35359095464355766, + 0.4037018936842366, + -0.10522217762475083, + 0.2154292693097944, + 0.5696393173020513, + -0.04625597716886151, + 0.212287150671228, + 0.4326580399294315, + 0.5292053415103407, + 0.14197994443419926, + 0.2085593607879186, + -0.003926657952371598, + 0.42475977158169154, + 0.4657071459381641, + 0.24173615699284356, + 0.40192097987804665, + 0.45866441383791823, + -0.10560249065022348, + 0.5692105174335332, + 0.06907665319393022, + 0.35058299227477413, + 0.5816519091445227, + -0.08812857923064357, + 0.38829483817737, + 0.2939650794983963, + 0.5379716163410015, + -0.07049989735964841, + 0.49871031229516405, + 0.2133527913290918, + 0.5483341334541701, + 0.1366120840368385, + 0.5084426369937696, + 0.11745514076662689, + 0.08117714667206602, + 0.27345194623813696, + -0.045820174551937265, + 0.6106956342979503, + -0.1293993873613253, + 0.11465386255791504, + 0.1713150903206152, + 0.06774589460443503, + 0.2804546876279884, + 0.566975721333123, + 0.5996773535118601, + 0.08726149544635195, + -0.11264701063509472, + 0.2029050660304097, + 0.12995431225754017, + 0.5314328270460583, + 0.27795804495366516, + 0.43477053874550453, + 0.14571563838052004, + -0.1289779248346495, + 0.009431741511017305, + 0.1604200894375412, + -0.055099496603256484, + 0.26106049479269317, + 0.609637358732483, + 0.07801410501102768, + 0.4803005449936134, + 0.0685859694468487, + 0.5346075542649379, + 0.09988546456547248, + 0.027673644061704444, + 0.606357655606873, + 0.015248878158076795, + 0.27032439228189775, + 0.2620379235474418, + 0.5921419607391434, + 0.17327955894184766, + 0.1292104236729908, + 0.22887175499617785, + 0.2111852627365095, + -0.06878456291299821, + 0.22874245725736625, + 0.47165729088449004, + 0.38555395789661584, + 0.19353410666257248, + 0.0807245893926945, + -0.06803229149715546, + -0.03249647418034536, + 0.16833412193451602, + 0.4855235442075285, + -0.11644786655877945, + 0.4612883840822457, + 0.5273133821956026, + 0.3292301720955355, + 0.06984780732731966, + 0.46323224730059287, + 0.25017639015742604, + 0.49504997684504437, + -0.051333356679210684, + 0.0522683950101791, + 0.38996408780070146, + 0.39394638913412305, + 0.24901368387863143, + 0.4031886914465266, + -0.009430245560946765, + -0.04975743466242938, + 0.30952980331673835, + 0.412441383411027, + 0.35132447568334857, + 0.29930988777500417, + 0.20272126429401577, + 0.24617760672823025, + -0.06688514755411883, + -0.06347183701424323, + -0.05652335890316039, + -0.011954423303128792, + 0.5743695980025744, + 0.37596961298952736, + 0.12015436722903067, + 0.2792031365138131, + 0.6090496335776785, + 0.34734317652437185, + -0.053002764010896194, + -0.13497531553030223, + 0.5599421832607909, + 0.39899997559046174, + 0.5438829136506539, + 0.06769260652620124, + 0.3578628040657533, + 0.6014654074338454, + 0.4791098308505851, + 0.439668085651142, + 0.4928180627944123, + -0.13697130824027512, + -0.007027462752235841, + 0.536571765012766, + 0.31841428670134475, + -0.09223147565190931, + 0.1314896237222018, + 0.49086789703009537, + -0.06768011598058715, + 0.12138438615729719, + -0.033234668974533976, + 0.3427091007030372, + 0.43299250886999907, + 0.34142052240691617, + 0.1876426799408395, + 0.058302610432529156, + -0.03810817569184789, + 0.13204798118401773, + -0.0857517064659218, + 0.4983642459418629, + 0.5943099630800691, + 0.4134309477867322, + 0.13402101772071529, + 0.49713305726315604, + 0.22229032315080544, + 0.5283168758009137, + 0.21883448442543396, + 0.5734200521907824, + 0.325336832146613, + 0.41073489686319986, + 0.06743034529622746, + -0.03526567964632697, + 0.5620438481876545, + 0.24353548224043142, + 0.561179365687331, + 0.4982295942294799, + -0.04253958542651988, + 0.5488405138187095, + 0.23082404732400325, + 0.31254503650997606, + 0.17861518879439875, + 0.46619571060126996, + -0.059493860447461355, + 0.22595736312244502, + 0.11641647157869095, + 0.15427726540345627, + 0.20983320170638203, + 0.402782877124659, + 0.14231962982336682, + -0.03767029963085697, + -0.0672142973658382, + -0.11108756834258565, + 0.23063996005874843, + 0.49217730078679134, + 0.5799476123394505, + 0.23215272078489302, + 0.5977832178446759, + 0.48915170404012875, + 0.09566590682051893, + 0.456541345693971, + -0.040302505128512786, + -0.06969034009609738, + 0.4050539849434295, + 0.21645669756165564, + 0.22008263372981257, + 0.028982631347593074, + 0.10256650104993989, + 0.5141861008931137, + 0.06179669378564409, + 0.42465335361674406, + -0.12056007783777771, + 0.1289518710745169, + -0.12707214179591417, + 0.4557072695620039, + 0.4084485583342917, + 0.214315040534737, + 0.2619856435364618, + 0.2246197102669072, + 0.5512721970726222, + -0.006915741433568684, + -0.0020713598982188275, + 0.007676449338899716, + 0.31105072623999946, + 0.44025473820886574, + 0.4019055624520166, + -0.10456356175710856, + 0.08120765028836066, + 0.5306265981100581, + 0.5687504841831893, + 0.4466064606546978, + 0.43324216578419317, + 0.25646594485764346, + 0.33776666324603116, + 0.2952367483123858, + 0.21230500437750865, + 0.5747246795795716, + -0.022499834367122384, + 0.4582153647837274, + 0.46341152054949786, + 0.1842354774533917, + 0.5953283576245592, + -0.1226127546827244, + -0.07053368541491231, + -0.029986092019773702, + -0.07716063723949343, + 0.34221893066992026, + 0.41957018298204496, + -0.023087222248670186, + -0.033618402715360304, + 0.3544651828434022, + -0.10513516466916387, + 0.47063017371853877, + 0.2962116323233484, + 0.19292620299287394, + 0.05489669696638061, + 0.31670148513769175, + 0.23909649375974756, + 0.09909804832990946, + 0.24250600837119712, + -0.03972621619554746, + 0.5559503153322273, + 0.09416139561675854, + 0.4568725934615411, + 0.59206877379263, + 0.20996925663688398, + 0.52784379013855, + 0.3380533930140957, + 0.23853645505485815, + 0.48978499794809194, + 0.036500719182886054, + 0.5361302384377497, + 0.2761340269468837, + 0.5669834633070224, + 0.3295616870891309, + -0.04689108991587135, + 0.04019649567557412, + 0.08825054289387294, + -0.061401144294815246, + -0.028596853748023274, + -0.09992412776344498, + 0.04634787500442494, + 0.2976043619106587, + 0.15255232174396804, + -0.00626475449741376, + -0.04105263459797817, + 0.22754519799762252, + -0.0506288533916604, + 0.0676344157977962, + 0.09681074844699966, + 0.05060987566448455, + -0.005302963106987357, + -0.07559726896520359, + 0.2245271650096281, + 0.41960763670575096, + 0.56972791385477, + 0.36623690160820777, + 0.42378863252971766, + 0.186698168612572, + 0.3433792554751624, + 0.2434544972968778, + 0.0629546207157001, + -0.039789261165297074, + 0.44641469148720747, + 0.3842661974735788, + -0.05418096888010085, + 0.08355968529995678, + 0.6013609700080208, + 0.2078367889766516, + 0.4600449952694903, + 0.020806325153794075, + 0.439818842681455, + 0.5568413413909061, + 0.512654980047776, + 0.2802821007562825, + 0.17008083203313323, + -0.03397225281088122, + -0.04223650170185503, + 0.5633404439640026, + 0.28686181311577724, + 0.029717167507109926, + 0.37447832139413695, + 0.19862432298661892, + 0.5552751161352054, + -0.09652442004072939, + -0.03616493518984773, + 0.1303298390841578, + 0.5893146935471523, + 0.2705448764444133, + 0.1985143303196814, + 0.22115654547649433, + 0.3541765968620121, + 0.22760105084197257, + 0.007719840924440391, + 0.312491318074978, + 0.3765214220301687, + 0.27556837065419904, + 0.5040312534605088, + -0.0027710430834536615, + 0.04826362779674237, + 0.06366647708920287, + -0.011411632728584337, + -0.06915004354045885, + 0.3642924183350651, + 0.1191344285972874, + 0.02827178468180025, + 0.35571247651025467, + 0.4181615994303476, + -0.0739022283546181, + 0.3274287239641861, + 0.3575597290916101, + -0.0674751772491435, + 0.4223608124974567, + 0.29274274203896894, + -0.10068689594402859, + 0.21196290895759118, + 0.26677886307412174, + 0.5750909844488384, + 0.05002283345082778, + -0.10753858934774543, + 0.23550925201706702, + 0.23904483612620597, + 0.5258639994579777, + 0.2934839155012105, + -0.03684751401478893, + 0.1319006246450305, + 0.2809803337865945, + 0.16052983123502607, + 0.37704077898886423, + 0.24891344487352884, + 0.47507661962861825, + 0.48901686063001437, + 0.5843777443389644, + 0.435772179524616, + -0.030217939178573586, + 0.4988073522451071, + 0.3413984030306078, + 0.28132261503859085, + -0.07861796838094673, + 0.15304216813178112, + -0.06458921250951682, + 0.35038141013635843, + 0.1248162989614151, + 0.2352644875516261, + 0.38064548934811404, + 0.043762068600872644, + -0.014067866030171669, + 0.31178601388138816, + 0.07389909392900973, + 0.5458806054334431, + 0.25816114854381556, + 0.032640709727340095, + 0.33543559985680976, + 0.13982637457883973, + 0.5987904142344431, + 0.5832102329337365, + -0.08831888260570372, + 0.13172216844195395, + -0.012211969409191281, + 0.020929225655425515, + 0.4150107002952005, + -0.12713916376959, + -0.011579969784716149, + 0.03176524578790879, + 0.16945372566595374, + 0.5452841012070294, + -0.09851715571128893, + 0.17738854226902329, + -0.04693921595273655, + 0.32406729635670817, + 0.532486533300872, + 0.5281732101058886, + 0.022961095183551217, + 0.49754366660665605, + -0.11139885651130502, + 0.2748759368657001, + 0.2592721503664618, + 0.5462167699752926, + 0.04439726113188022, + 0.25649498800802784, + -0.021497528670672353, + -0.05360925615769917, + -0.055939153687247486, + 0.1796410517048524, + 0.2320002793134991, + 0.6043340381556147, + 0.44208895184520447, + 0.5842468816446799, + 0.5439441756279866, + 0.6007951315006198, + 0.585154483544518, + 0.029569868235943764, + -0.03931176887805356, + 0.36358854786208616, + -0.0694208301952309, + 0.506496751201539 ], "type": "scatter" }, @@ -41187,10 +41338,10 @@ "mode": "markers", "name": "Expectation", "x": [ - -0.20638117589512645 + -0.10024653371663643 ], "y": [ - 0.003724452792381816 + -0.08188011319811177 ], "type": "scatter" }, @@ -41199,31 +41350,31 @@ "mode": "lines+markers", "name": "Mode", "x": [ - 0.09867441654205322, - 0.4300057888031006, - 0.4300057888031006, - 0.09867441654205322, - 0.09867441654205322, + -0.7666139110834805, + 0.6633025782322575, + 0.6633025782322575, + -0.7666139110834805, + -0.7666139110834805, null, - 0.09867441654205322, - 0.4300057888031006, - 0.4300057888031006, - 0.09867441654205322, - 0.09867441654205322, + -0.7666139110834805, + 0.6633025782322575, + 0.6633025782322575, + -0.7666139110834805, + -0.7666139110834805, null ], "y": [ - -0.558321088552475, - -0.558321088552475, - 0.3203643560409546, - 0.3203643560409546, - -0.558321088552475, + -0.697788532493164, + -0.697788532493164, + -0.1388998086540928, + -0.1388998086540928, + -0.697788532493164, null, - -0.558321088552475, - -0.558321088552475, - 0.3203643560409546, - 0.3203643560409546, - -0.558321088552475, + -0.697788532493164, + -0.697788532493164, + -0.1388998086540928, + -0.1388998086540928, + -0.697788532493164, null ], "type": "scatter" @@ -42073,13 +42224,15 @@ "plotlyServerURL": "https://plot.ly" } }, - "text/html": "
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" } ], "source": [ + "event = Event({arm:\"left\", grasp:\"front\"})\n", + "conditional_model, conditional_probability = model.conditional(event)\n", "p_xy = conditional_model.marginal([relative_x, relative_y])\n", "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", "fig.show()" @@ -42087,31 +42240,108 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:15:43.321629Z", - "start_time": "2024-03-12T16:15:42.344156Z" + "end_time": "2024-03-13T13:17:08.248386Z", + "start_time": "2024-03-13T13:17:07.484957Z" } }, - "id": "1811b5e17a88ebdd", - "execution_count": 6 + "id": "825dceb35326faf7", + "execution_count": 22 + }, + { + "cell_type": "markdown", + "source": [ + "Let's make a monte carlo estimate on the success probability of the new model." + ], + "metadata": { + "collapsed": false + }, + "id": "f6e58eaa8d627dcc" }, { "cell_type": "code", - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "100%|██████████| 100/100 [00:15<00:00, 6.66it/s, Success Probability=0.53]\n" + ] + } + ], "source": [ - "# fpa.policy = model\n", - "# fpa.sample_amount = 500\n", - "# with simulated_robot:\n", - "# fpa.try_out_policy()" + "fpa.policy = model\n", + "fpa.sample_amount = 100\n", + "with simulated_robot:\n", + " fpa.batch_rollout()" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:15:43.323571Z", - "start_time": "2024-03-12T16:15:43.322300Z" + "end_time": "2024-03-13T13:17:25.859550Z", + "start_time": "2024-03-13T13:17:10.842375Z" } }, "id": "6bfc00e5d93a19af", - "execution_count": 7 + "execution_count": 23 + }, + { + "cell_type": "markdown", + "source": [ + "We can see, that our new and improved model has a success probability of 60% as opposed to the 30% from the standard policy." + ], + "metadata": { + "collapsed": false + }, + "id": "c270cd173a43b342" + }, + { + "cell_type": "markdown", + "source": [ + "Next, we put the learned model to the test in a complex environment, where the milk is placed in a difficult to access area." + ], + "metadata": { + "collapsed": false + }, + "id": "98bfa937581a9c47" + }, + { + "cell_type": "code", + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n", + "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n" + ] + } + ], + "source": [ + "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"apartment.urdf\")\n", + "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", + "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", + "fpa = MoveAndPickUp(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value], policy=model)\n", + "fpa.sample_amount = 200" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-13T13:17:30.641037Z", + "start_time": "2024-03-13T13:17:28.025570Z" + } + }, + "id": "90d7cb5e1e1cc7fd", + "execution_count": 24 + }, + { + "cell_type": "markdown", + "source": [ + "Let's look at the density of the relative x and y position of the robot with respect to the milk. We can see that he would like to access the object from the right front area." + ], + "metadata": { + "collapsed": false + }, + "id": "eaaf99db302255e0" }, { "cell_type": "code", @@ -42122,20016 +42352,20016 @@ "data": [ { "hovertext": [ - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457", - "Likelihood: 25.972408031624457" + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 30.091528326798986", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 48.02373812816365", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 44.64846346790239", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566", + "Likelihood: 22.828118667793277", + "Likelihood: 67.47658213569566" ], "marker": { "color": [ - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457, - 25.972408031624457 + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 30.091528326798986, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 48.02373812816365, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 44.64846346790239, + 67.47658213569566, + 44.64846346790239, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566, + 67.47658213569566, + 22.828118667793277, + 22.828118667793277, + 22.828118667793277, + 67.47658213569566, + 22.828118667793277, + 67.47658213569566 ] }, "mode": "markers", "name": "Samples", "x": [ - 0.3418050044209915, - 0.42046289382091045, - 0.48810300202734136, - 0.4187827740915557, - 0.4705772942227926, - 0.4781452289763214, - 0.48309168342402675, - 0.5442943845121979, - 0.5315863645867595, - 0.3435085802309865, - 0.603781343783121, - 0.5504520379475959, - 0.37158248149876005, - 0.39456619996327447, - 0.5703835615125314, - 0.3671055066828624, - 0.5618150201032995, - 0.42832116488254884, - 0.3794676095448985, - 0.42995694698024683, - 0.5992332680182701, - 0.538438320162445, - 0.5075291077971777, - 0.3757486538815614, - 0.38094265823621554, - 0.5575078503610276, - 0.5659602164563106, - 0.4323932672621166, - 0.5936343869124514, - 0.49536724032059054, - 0.4469609865678917, - 0.6066118256417401, - 0.5138906602935309, - 0.4345392092766999, - 0.37401643042715393, - 0.5195647442239216, - 0.5493208962851699, - 0.5207675187022458, - 0.5262119471285246, - 0.5579526886429735, - 0.36070389114107854, - 0.3459472051400382, - 0.4337613620258962, - 0.5919431586772768, - 0.5273699503304089, - 0.42043620622279815, - 0.5446058973748606, - 0.5270447090663273, - 0.39840371170449096, - 0.4460208729991434, - 0.34669152072630643, - 0.42104060702535784, - 0.5522872550567137, - 0.3837377161213302, - 0.5780286914010967, - 0.5575899916239728, - 0.553296258476877, - 0.5477753187960491, - 0.3820731081849196, - 0.5452762441745149, - 0.4105534416608081, - 0.5681290010949585, - 0.5467012231047081, - 0.35428445939475456, - 0.5857895383189562, - 0.5626551258797161, - 0.47551643619236594, - 0.5862828572736039, - 0.50483555862688, - 0.42422059932831807, - 0.6057381220491029, - 0.4233448892949359, - 0.5486517705273007, - 0.4521250090813296, - 0.47686613797257527, - 0.4027652004853193, - 0.5353004553063754, - 0.5961425881536002, - 0.35898628456861864, - 0.45961054950877933, - 0.5829007560360822, - 0.37491379018207294, - 0.5190360861308956, - 0.43190498111437503, - 0.4165759516165968, - 0.4344813534692188, - 0.4735758359947455, - 0.546745518943785, - 0.45122964304486995, - 0.445119677506937, - 0.397395847187173, - 0.4134347480886363, - 0.5593323564705878, - 0.49055725824742424, - 0.4811105641877005, - 0.5211846126435176, - 0.4855909942145834, - 0.48363320141500826, - 0.45957552755767606, - 0.37838391780639846, - 0.5311797269372021, - 0.4268431058955042, - 0.5853497029631878, - 0.5211101644967847, - 0.37880642954208865, - 0.3607564188282458, - 0.4796413392359218, - 0.4247603008690887, - 0.4220248713078427, - 0.3594771701746183, - 0.58796828134802, - 0.5240799509003502, - 0.5512682330300651, - 0.4523673283844806, - 0.4255733109218371, - 0.38441205766836173, - 0.44217577081246684, - 0.4599894811627133, - 0.4109615190357875, - 0.5937880529884361, - 0.4944378751031075, - 0.3520844122797129, - 0.5190914496368122, - 0.4374819681643781, - 0.5591500621116273, - 0.5412963139073228, - 0.37603819641104536, - 0.38847396349388397, - 0.4032250024516821, - 0.4924560426283685, - 0.42086937066789404, - 0.4377345821230907, - 0.5122981954640152, - 0.4615735595265509, - 0.5541615701910219, - 0.5910663794297686, - 0.3837607812198708, - 0.4130275081138012, - 0.4165348041313972, - 0.35894869511526184, - 0.5145242367943522, - 0.5361395729533764, - 0.5039829582625056, - 0.47443433435163485, - 0.4831235378191445, - 0.549973061612568, - 0.4080920528076598, - 0.5100989489052936, - 0.3699179851507403, - 0.4155715476537355, - 0.5693689999424961, - 0.4705469761038527, - 0.4801240143554987, - 0.38748116623545326, - 0.48562037498672805, - 0.4722297271679715, - 0.557274899602064, - 0.38828791391059786, - 0.34724720685448135, - 0.5294519261029174, - 0.5536338065513148, - 0.4524898698433684, - 0.37063524426673955, - 0.4776500695926752, - 0.37196290028519025, - 0.5888293502998804, - 0.598369123636812, - 0.4946860527859774, - 0.451312616919999, - 0.5386536815414474, - 0.42137599250273033, - 0.4047268712312119, - 0.4363656762114295, - 0.3708796072993625, - 0.5637979612148067, - 0.3753290421171312, - 0.5357246981946138, - 0.49227880803839263, - 0.5483333215307123, - 0.5786464200447774, - 0.38977478581252745, - 0.4803259289169385, - 0.5391310372584164, - 0.4721955210526435, - 0.5575439611242762, - 0.42765923669174366, - 0.4873031733600067, - 0.3947155080501368, - 0.5373224198890412, - 0.47958640195826285, - 0.4148924713202303, - 0.6048835649587367, - 0.4118773291379324, - 0.5692551639564323, - 0.38084193240986425, - 0.5458891345421714, - 0.39726126307120335, - 0.43628092811580865, - 0.42182168439114637, - 0.4079438937048501, - 0.5990363636897748, - 0.4283853209746475, - 0.455401028400296, - 0.5090943311669857, - 0.45828691822825723, - 0.3870017874529029, - 0.4825897183751542, - 0.5740055369285366, - 0.3491943689753291, - 0.5727940002645229, - 0.527382677048351, - 0.45288711124681785, - 0.35090038529314405, - 0.5979905376584136, - 0.4369820154882582, - 0.347301844360368, - 0.39823102448812764, - 0.5343952740480163, - 0.42462646033846, - 0.42806138988553294, - 0.3548538692940955, - 0.34434641491759554, - 0.3742213383693845, - 0.4259450562242172, - 0.4714730095132724, - 0.44131543821839003, - 0.4273601630333004, - 0.5150302704931038, - 0.47039763891435604, - 0.4262175908469459, - 0.4843730426565765, - 0.4953798061486048, - 0.47349958800865344, - 0.606016705445918, - 0.5703363407871588, - 0.5253468259409346, - 0.4593281894255417, - 0.5731230280609131, - 0.3550769748293646, - 0.3448133977639368, - 0.39928619819974126, - 0.3602313712495848, - 0.509923338306495, - 0.4381816896798335, - 0.6048458046435725, - 0.35380625483404027, - 0.4976721565519823, - 0.4394503088497847, - 0.4564761397354343, - 0.5481786455718839, - 0.35136243638525727, - 0.4668248774194044, - 0.48101827984721834, - 0.5203163771652594, - 0.5353866093241932, - 0.5304272763249565, - 0.5575014598338159, - 0.4180265012754054, - 0.41635215748632515, - 0.572786289297615, - 0.4138492779168663, - 0.4912302783001208, - 0.37300226755993215, - 0.5532154068039915, - 0.345469132188884, - 0.4563700531850752, - 0.555105555836032, - 0.4724852623703465, - 0.5547359292054037, - 0.4691213566209098, - 0.430646120311847, - 0.5321907977577964, - 0.4051326028575885, - 0.37922302373874617, - 0.5642873332242331, - 0.39522261868056924, - 0.4199920828604664, - 0.4546367566417414, - 0.3664239825399167, - 0.5070956223113164, - 0.5907621012909742, - 0.38380415132416223, - 0.45700890039294384, - 0.5672300657643817, - 0.49952544574048674, - 0.502742834785098, - 0.37542615459366224, - 0.5610482393554925, - 0.35324051900281495, - 0.38683591055208866, - 0.5187059517016726, - 0.6069826431766234, - 0.4746358790858021, - 0.37947460855274545, - 0.5950988773371437, - 0.43394270441128424, - 0.42470052888732357, - 0.601506290589547, - 0.4836574368265671, - 0.5357119285119457, - 0.40105364976484953, - 0.3933365642506542, - 0.5065042908275231, - 0.4630004708632466, - 0.5384975641466532, - 0.42614875438690925, - 0.47793499970453157, - 0.500047440585773, - 0.5230421788531616, - 0.34591109922841434, - 0.4702380726339741, - 0.511851950832901, - 0.3453731029303581, - 0.500344915606301, - 0.48643341147651475, - 0.5825380574841507, - 0.39346628195932926, - 0.4551245741849041, - 0.45506291357056117, - 0.5458306785287304, - 0.5649031547786072, - 0.44385068633177677, - 0.357375583121979, - 0.5931094326752944, - 0.5912218357537184, - 0.4366874156434475, - 0.5028370875301964, - 0.5183589245573642, - 0.5204314796589822, - 0.555717165484436, - 0.542489579485379, - 0.4004308658690381, - 0.4468073136283036, - 0.5472724683772513, - 0.5515889572914914, - 0.4903176414681521, - 0.4950075288891008, - 0.3676160759447097, - 0.559582433055563, - 0.4742595980219382, - 0.34311552895437103, - 0.5672136922943017, - 0.48968039947007164, - 0.5877250901375654, - 0.35683204505023985, - 0.470464260723502, - 0.49932212721642977, - 0.34606829265864353, - 0.5741082630683694, - 0.45996334786767373, - 0.37706058127455805, - 0.42048596370067204, - 0.36433469493265047, - 0.4870593427974892, - 0.41509557110579565, - 0.5616749958263956, - 0.4183791363442587, - 0.44115838504540894, - 0.4305499673133141, - 0.45064179870048787, - 0.4824053436375251, - 0.49047880565681656, - 0.40680569938488687, - 0.43027096382095253, - 0.5445271830946932, - 0.48352870458515307, - 0.3562593519870652, - 0.4340151394465868, - 0.4220339644208058, - 0.5576622854086145, - 0.42849349641651435, - 0.35514014616730527, - 0.46453057978869167, - 0.4556737999473217, - 0.5145912265164778, - 0.4232598937763039, - 0.5827168642500915, - 0.6042270539665575, - 0.4196009148311382, - 0.4162381950889067, - 0.5522686887519869, - 0.47098512361658473, - 0.4497211300770748, - 0.571291844662733, - 0.5220114509744439, - 0.34198721369407653, - 0.5492845731107243, - 0.47310042557922294, - 0.3697430501474994, - 0.5831464575810755, - 0.4991417275437521, - 0.3879106589555589, - 0.39290901491987085, - 0.4070194843148901, - 0.567360447699915, - 0.5853373224690831, - 0.39130022549666976, - 0.6073516939931729, - 0.3515124474407596, - 0.46397531869876296, - 0.5331086738808357, - 0.5605502885656051, - 0.4232159949419967, - 0.5881475923021946, - 0.38244472114858563, - 0.3895715158309093, - 0.5541518802765582, - 0.5540350252719712, - 0.386325232345691, - 0.37702272918079827, - 0.5666105689396475, - 0.41962014725654556, - 0.4883526168229082, - 0.5017176425169911, - 0.4184204438049325, - 0.5684073485670914, - 0.5668555891446393, - 0.44979722461756494, - 0.500787484165339, - 0.47495501152657393, - 0.5255501977942031, - 0.5055073985545164, - 0.46816320894378816, - 0.3548002033278716, - 0.4554460962858839, - 0.49970934277717305, - 0.5056835799878427, - 0.5538339093188502, - 0.5406653280088244, - 0.5776933652323823, - 0.3944791130182638, - 0.4536000151426348, - 0.38892969661281074, - 0.3994798483797707, - 0.3909518671782786, - 0.4046262202245543, - 0.5693420798827523, - 0.4085714184385464, - 0.5559829586390747, - 0.5693660243753869, - 0.5112609472276227, - 0.49414100978993714, - 0.4158907804423544, - 0.48946438517834845, - 0.5609260730068716, - 0.41908655049793975, - 0.36263897925145283, - 0.49136555980786434, - 0.43135030741708724, - 0.37130440365499867, - 0.578345047796383, - 0.3654310628809949, - 0.5278785708494265, - 0.36935206409020915, - 0.49376595070440066, - 0.3661952703176776, - 0.46188924766777734, - 0.3971579032590189, - 0.5323992785517696, - 0.3600624234057818, - 0.5873045518940048, - 0.5326456121932067, - 0.44446782071962593, - 0.4047184789231033, - 0.37097260388287184, - 0.47184085655186686, - 0.5122539587661926, - 0.3653866138452558, - 0.5332906210426898, - 0.5923468052544637, - 0.6032595107955263, - 0.41427218240248836, - 0.48496742055429287, - 0.5655480870300347, - 0.5182318258182519, - 0.4210299596914131, - 0.37448626452496103, - 0.4713133374240237, - 0.45515307143982964, - 0.36629048281125864, - 0.3535669945896626, - 0.4786371418070452, - 0.4231123330379258, - 0.5835767798472082, - 0.5288241485351058, - 0.40745991473549986, - 0.5736699955266886, - 0.4120339301429695, - 0.46020292469017826, - 0.5819833899575882, - 0.39274248337114387, - 0.6053181748211147, - 0.6034615450010086, - 0.5027138442610434, - 0.5645048929873853, - 0.6009975955220158, - 0.3464112411657779, - 0.42583700911134437, - 0.3969341878594123, - 0.5865688262254342, - 0.5939059784094451, - 0.46450094965295496, - 0.43543591169009005, - 0.42703208431351314, - 0.3927218843706935, - 0.47282248410249783, - 0.3962767871486313, - 0.3719207829212973, - 0.48578754331603013, - 0.4110370346123026, - 0.526008565051441, - 0.5507179506021536, - 0.4713630217185355, - 0.5468796831448549, - 0.3902831947579364, - 0.49036271369844986, - 0.5591194914825147, - 0.3932708382209499, - 0.5053775259235191, - 0.5159363025463032, - 0.5159875843333668, - 0.3920553750603311, - 0.35388573532117334, - 0.6073671470752882, - 0.4681643922234685, - 0.5696438707300826, - 0.5030281072046372, - 0.5400524491621141, - 0.5505805988083616, - 0.5637201046160271, - 0.4494011986326907, - 0.34312189733108256, - 0.5873153594611857, - 0.511911159930812, - 0.5207533655709462, - 0.38925849424828723, - 0.5535177512537484, - 0.3691933930650747, - 0.599940326861013, - 0.5970922797916359, - 0.5919562426489086, - 0.4670148345538072, - 0.5771390253783447, - 0.4351681235647079, - 0.5710250868233444, - 0.3737855709496639, - 0.6063094677954497, - 0.36895582480369266, - 0.38138896603828126, - 0.4794679932365303, - 0.4427800685100388, - 0.4450047476015143, - 0.3546693878039054, - 0.4544569841168816, - 0.4104276562579435, - 0.39132258827374466, - 0.5265312098601524, - 0.4516579553962491, - 0.45009214973859885, - 0.353082941705289, - 0.40472712087553686, - 0.47632093155821287, - 0.4491809011576849, - 0.5037554821831255, - 0.48453605716532083, - 0.4448319333697399, - 0.41012964213380443, - 0.41158228744711034, - 0.5900780604899777, - 0.5319852807846981, - 0.42352140874872235, - 0.5965660560048065, - 0.5757669622895147, - 0.4945030394866377, - 0.5520046815720451, - 0.5725019362210265, - 0.5601029804593164, - 0.3757874035008278, - 0.47655280365422514, - 0.4193357071425664, - 0.5153804327906357, - 0.35035514047775507, - 0.5820094230420183, - 0.4434608142308336, - 0.4653979904342358, - 0.342434415673505, - 0.4690135169177803, - 0.5341312652383704, - 0.42195983235722956, - 0.3982024160275346, - 0.5969828927969294, - 0.5591079725721156, - 0.4484826058028812, - 0.3623391518905481, - 0.34367175981323766, - 0.4706192289986152, - 0.45085538412410775, - 0.4752468067674138, - 0.589494358107242, - 0.3850828094194676, - 0.5551175353082214, - 0.5128646363014648, - 0.37965180440672075, - 0.3590572551444592, - 0.38747536239478736, - 0.5340772553702514, - 0.3549693338727901, - 0.5639140336289648, - 0.3551788907962904, - 0.5159173083109188, - 0.5788219684475677, - 0.39845053923211426, - 0.5665400239854612, - 0.504045450980162, - 0.40121600461562795, - 0.5563984134110226, - 0.5507541158608086, - 0.5010631455482744, - 0.4742473686132547, - 0.5960954687771511, - 0.44598803369623924, - 0.5102804234128492, - 0.3518714890462425, - 0.4762818839156858, - 0.4775758296779308, - 0.5454199279067482, - 0.4629751687190453, - 0.5242696648974423, - 0.5437565282143462, - 0.5086850346491032, - 0.49863518502355547, - 0.3813376788322677, - 0.5476877445150633, - 0.5031559684268758, - 0.4072566101567615, - 0.5063796367720175, - 0.3537351061928446, - 0.4116514033756369, - 0.5334929473637947, - 0.35857401950170525, - 0.5739937704326459, - 0.5449637557473108, - 0.36724268390950804, - 0.41309275125647577, - 0.36128042193358084, - 0.5304325096229855, - 0.5629321531326743, - 0.46777188864137836, - 0.5906491304581328, - 0.3632956698619843, - 0.5928748927326136, - 0.4455638048902415, - 0.4843314914298229, - 0.5195833052312449, - 0.38869536848953895, - 0.5169128147980115, - 0.5606579840396742, - 0.5606872788825054, - 0.3852819916055446, - 0.42137722573907754, - 0.47668852031141185, - 0.4649500455121294, - 0.5707089649462989, - 0.5902086168034774, - 0.5007230954938793, - 0.4902206502954126, - 0.46574224275793435, - 0.5979178718054408, - 0.42321927621987554, - 0.37998064753963545, - 0.3522797306230855, - 0.5977124642955361, - 0.5220948489466776, - 0.4609279012289877, - 0.3786426774361397, - 0.43121920495978916, - 0.5289272725729629, - 0.46964224170069246, - 0.5159758986949573, - 0.38373138475105656, - 0.5937522616557724, - 0.4329531861823541, - 0.48325978960862703, - 0.3848690323735415, - 0.48031671160734934, - 0.5972293505723218, - 0.3456306546768843, - 0.46818900821656506, - 0.5630358354110924, - 0.36678641861952715, - 0.3875294442248968, - 0.40024465315002433, - 0.5897001775534649, - 0.5940801121013141, - 0.5892354875948655, - 0.3477475591544767, - 0.5836560777460615, - 0.3994047024058845, - 0.4947635393534486, - 0.4407473774753668, - 0.43021965578967075, - 0.4727862918979651, - 0.40823214497503413, - 0.4323653275463216, - 0.5328707000800581, - 0.4186444341389905, - 0.3674355384436607, - 0.4560689360281785, - 0.5014736053867173, - 0.544413041226391, - 0.36799876845183643, - 0.3554170565475439, - 0.5467570826523778, - 0.44842925793121297, - 0.49551718914524556, - 0.5051619034229737, - 0.5295046804560828, - 0.5167885878367219, - 0.5893443546291093, - 0.43290995123445536, - 0.5064648317976532, - 0.4476360324752185, - 0.5241053432280334, - 0.3971216966470027, - 0.4609846382458378, - 0.35192229391114666, - 0.4326082956274897, - 0.3733907671070571, - 0.462965494143488, - 0.4372046596977981, - 0.5894289379142832, - 0.3831392915296863, - 0.393640556560316, - 0.49113923906297385, - 0.375085773312048, - 0.49918853089601745, - 0.49049442686396766, - 0.558470366620296, - 0.3735446928366424, - 0.4384849816973547, - 0.482510389974109, - 0.46726557888811915, - 0.39879614805306984, - 0.4540794470335071, - 0.3615471549788125, - 0.5498705000979084, - 0.5591087896516915, - 0.5076995853616341, - 0.4140633448885778, - 0.6058704953701393, - 0.48858740637947673, - 0.4680799659814403, - 0.3790819517633766, - 0.3452060115089, - 0.5597743236075825, - 0.4161178995374226, - 0.47745495553068507, - 0.42216656824107746, - 0.4683760597292973, - 0.4851843288862344, - 0.4814246482178729, - 0.537943992438922, - 0.4664276136421387, - 0.34751961450677993, - 0.40458598304356896, - 0.41086318350288786, - 0.45333571718614396, - 0.5688438247331922, - 0.5710919225013837, - 0.44935871653999876, - 0.520234266803157, - 0.4773498877855949, - 0.479657920017467, - 0.49425894591864794, - 0.40195869060845946, - 0.5211366198368661, - 0.34612194950464575, - 0.3685194451441486, - 0.38099707493856155, - 0.5755613601109767, - 0.4267467073262868, - 0.4934533475353434, - 0.34209164401081243, - 0.540695411135333, - 0.5571691834808344, - 0.3814166237877245, - 0.5233641140068109, - 0.3681660045353565, - 0.566768506188571, - 0.4560396107959273, - 0.43267814331803406, - 0.566925802477404, - 0.44358095264039366, - 0.4149614237351253, - 0.5832913910880755, - 0.37290581229974096, - 0.3759174244220248, - 0.5146667765882483, - 0.44787174995184037, - 0.4338513719440353, - 0.3693395018368529, - 0.4653276128837221, - 0.5628953802660652, - 0.45773076606647944, - 0.4762781061903889, - 0.4502459764823845, - 0.3558523170454293, - 0.408528408199931, - 0.44403350259185204, - 0.5692069650609863, - 0.5598268936202506, - 0.430977686011557, - 0.5219150791309493, - 0.5969408278978459, - 0.42397770995408307, - 0.5778444778315747, - 0.5333912877553382, - 0.4618029853398552, - 0.5497536324500718, - 0.5022381853290987, - 0.5597920466234443, - 0.3413211166304529, - 0.39285722438042225, - 0.4457643467460786, - 0.38310894695805336, - 0.3480125421885832, - 0.5952086679792236, - 0.432343210813199, - 0.422360079373964, - 0.40531298508617625, - 0.4321160679577169, - 0.41900427628870185, - 0.5009038443394201, - 0.4538630406645209, - 0.5553022310986414, - 0.5715160880044118, - 0.5290995955449675, - 0.6037303639998648, - 0.3610488951537596, - 0.477067582855881, - 0.5912330290777326, - 0.5724350033757576, - 0.588703580944484, - 0.35167382665782015, - 0.45406475706780186, - 0.45750251078897297, - 0.5461754369850642, - 0.5430806331230144, - 0.4753058758596046, - 0.5647063927824121, - 0.4993185739791919, - 0.5790976317157648, - 0.38832487367103324, - 0.36454661788011755, - 0.47700852696980034, - 0.4882683618568661, - 0.41153800703049376, - 0.600879915001096, - 0.3501774832247708, - 0.518304479505953, - 0.561922484708129, - 0.5812714582973075, - 0.4729152000738767, - 0.48855397806849304, - 0.39469568297150903, - 0.363247819524434, - 0.42512051887844937, - 0.47030567163502046, - 0.46017949358134574, - 0.4980376977288078, - 0.5103147362751859, - 0.37696089437818797, - 0.601600742922141, - 0.39603504048794813, - 0.39604902130991465, - 0.3902842588142154, - 0.5944569241886681, - 0.42230313910991124, - 0.5971612223348683, - 0.5505069059361313, - 0.5276941769208399, - 0.5841868204127173, - 0.38450140084918183, - 0.36857784948114575, - 0.46649179627252735, - 0.3811651262988, - 0.38089413387726534, - 0.5127142949690029, - 0.47763586579957906, - 0.5085876667582309, - 0.5508238215692671, - 0.42617152900249505, - 0.4762923131576057, - 0.4512576762969043, - 0.3488693950335889, - 0.48333976945188306, - 0.34776322982406255, - 0.49839377716243344, - 0.5175239481662307, - 0.5661281048651898, - 0.5085188888400605, - 0.4569557703776227, - 0.5400339212272878, - 0.4657553139450715, - 0.3430054963135999, - 0.40030879874997743, - 0.5461444328153299, - 0.4964816225736033, - 0.39175239181123417, - 0.4994808663191305, - 0.5554144503690076, - 0.5336284094662216, - 0.5507766668300478, - 0.4341518882866944, - 0.408857608762657, - 0.5361948636672714, - 0.5946391822356529, - 0.3565568594010011, - 0.34924007471018687, - 0.5675554582834661, - 0.35919749993473526, - 0.5124724563606644, - 0.48692452233994865, - 0.6064765710501503, - 0.36062096968556034, - 0.38675478362991444, - 0.42536214975996456, - 0.41514468269768723, - 0.4542930657418876, - 0.5130408334421371, - 0.511104718154213, - 0.5545527730518054, - 0.5195340897665097, - 0.4820076288849965, - 0.47843227646982917, - 0.4494341418377483, - 0.460997892727249, - 0.5878754204485115, - 0.5188707133686966, - 0.39141637034879284, - 0.3900819612045877, - 0.5525439287676416, - 0.3772965574566514, - 0.5605430778671425, - 0.5488067119787274, - 0.3472505778110037, - 0.48300163535721763, - 0.5435862071905465, - 0.4500575464999361, - 0.601444870945393, - 0.3795018398077262, - 0.45188404214486244, - 0.3827733807902073, - 0.5565507670026301, - 0.5493387971532355, - 0.5075475394375325, - 0.4617855080453377, - 0.5834482739572837, - 0.3958186492976678, - 0.3585776820688415, - 0.5596010188906496, - 0.5487266329353938, - 0.5419630476274999, - 0.5341062204172816, - 0.4360177576039962, - 0.4150147194164592, - 0.4173071722496712, - 0.4531013642950532, - 0.3713644083885882, - 0.46973108966098753, - 0.38218255884171454, - 0.4681956244454821, - 0.519040650959924, - 0.5371869519812372, - 0.5609755059373175, - 0.3493912698697034, - 0.3546371561265873, - 0.5173657676620915, - 0.5991255033422764, - 0.3475695106983017, - 0.3596917043353417, - 0.4791165413357966, - 0.5860832180480118, - 0.494794721452843, - 0.494285312412303, - 0.5105520810366437, - 0.4084825550856339, - 0.49616493686480445, - 0.5106647062688094, - 0.42116090096085046, - 0.5767676340975374, - 0.5288022184997668, - 0.42405534108263016, - 0.3675406494678646, - 0.4121943653793813, - 0.40641199994799976, - 0.4795675279071252, - 0.4217346589919411, - 0.5485296742062635, - 0.5529474340161399, - 0.4802389408906298, - 0.5501090166600342, - 0.4373055571544473, - 0.5159137021014512, - 0.5433131737694117, - 0.46900399409539173, - 0.47664578289523696, - 0.524598931222689, - 0.39858549011306765, - 0.4005741961953101, - 0.5204368279325485, - 0.4102762871777138, - 0.36593026203504786, - 0.5997429520850301, - 0.37752042937663444, - 0.409228979139513, - 0.5317902459865063, - 0.4452558606895077, - 0.5841478320394538, - 0.5976979318940462, - 0.49850232571895275, - 0.3806390546667547, - 0.49789181015025924, - 0.3921425655336298, - 0.5204784539833935, - 0.4158971063370702, - 0.5390035176921297, - 0.3717686243329384, - 0.4513218000482286, - 0.5145778934985099, - 0.3599685549105291, - 0.37977414698556966, - 0.5755118353842792, - 0.34567092400399957, - 0.43207441168593125, - 0.5379236798948418, - 0.5497947549097533, - 0.5861495988526599, - 0.4870248892642786, - 0.46608196173995226, - 0.35267816246117323, - 0.36177201992153785, - 0.4401486734633157, - 0.4876304816012202, - 0.4207044421692101, - 0.5549279150443177, - 0.4212713664130435, - 0.5011931191855039, - 0.5499644397152684, - 0.3494226740657319, - 0.4040587294105462, - 0.44494596480131027, - 0.3985971736300473, - 0.3923178663674774, - 0.5984118300255239, - 0.43289408651228506, - 0.36157076283281786, - 0.44763881155715035, - 0.40671220557116883, - 0.42687196432000524, - 0.38729463914446133, - 0.37620747639506, - 0.5117155765752572, - 0.3893791779154112, - 0.4262078610041713, - 0.5453043407243159, - 0.5181580784422574, - 0.3494224323542498, - 0.5821328974676583, - 0.5760442603398617, - 0.5749077736789385, - 0.3509548907424325, - 0.36806066371790136, - 0.47932854805590264, - 0.5635375648551246, - 0.5012271699073241, - 0.37775590665989756, - 0.404688831056476, - 0.4692621879829995, - 0.42081861067281806, - 0.3985597516564739, - 0.3652351077009996, - 0.5685994451794981, - 0.5917394607970419, - 0.44363037585051107, - 0.48437179907875005, - 0.5938076894361478, - 0.5245994141066175, - 0.3551634877493606, - 0.4447755926451189, - 0.524791112897769, - 0.5390764048854781, - 0.5848022697394551, - 0.5377318199547328, - 0.5280184417838356, - 0.5562396140574288, - 0.5822791074201548, - 0.4139022346476278, - 0.4440258673687219, - 0.41780729816955664, - 0.5096313360146618, - 0.43914686489989024, - 0.4169913831977342, - 0.38395539747936686, - 0.34673936655866966, - 0.6032165091988764, - 0.5569336958503369, - 0.5347727068885018, - 0.40004200842992904, - 0.5538516672488639, - 0.4638023065487117, - 0.5924296471839444, - 0.5708624696982371, - 0.5566577012389169, - 0.46975087232348534, - 0.5278700291165634, - 0.35426532349050016, - 0.4426965839164455, - 0.5392766191140718, - 0.5822796645862357, - 0.5135094965303912, - 0.40908851207997754, - 0.49040256612337696, - 0.5099730330773409, - 0.3984912268318044, - 0.4779933861330685, - 0.4151416237449075, - 0.38574086932520346, - 0.4329378683081606, - 0.4903466763727349, - 0.5043349054907943, - 0.42376427936074085, - 0.42913929512246324, - 0.5545876739355654, - 0.4873924644880851, - 0.4102639477412568, - 0.4705378735419574, - 0.4602598546369153, - 0.4722992627977438, - 0.4602289180684951, - 0.5542645659297213, - 0.4277181994850236, - 0.5131392772238891, - 0.5258411627079675, - 0.48256855981863533, - 0.551679788292831, - 0.40449635219275804, - 0.4093439869156161, - 0.5791091649804749, - 0.4867964070761205, - 0.5741482080300446, - 0.49612168732630907, - 0.5001771923231492, - 0.4989848182571631, - 0.46529754890204017, - 0.4639342636323957, - 0.6043388655620308, - 0.3452031223821156, - 0.4377079598971051, - 0.4264831637235553, - 0.47773630315051163, - 0.5683746406343471, - 0.4095659154778148, - 0.43700489345671684, - 0.4808462831827053, - 0.48084349469725846, - 0.3727546599432704, - 0.5141152315456583, - 0.44580589273511656, - 0.5229878666211187, - 0.42166254414194865, - 0.46359478618961314, - 0.5448697829129506, - 0.3807814022803044, - 0.4710590894760348, - 0.4906746172597636, - 0.34383596274425354, - 0.35142325144067976, - 0.485649891906331, - 0.5919593366279876, - 0.4330496118976616, - 0.3551411942564184, - 0.5578136789726261, - 0.5488170525455053, - 0.4432562010958158, - 0.5108785495466552, - 0.3443965511710134, - 0.6054912384857585, - 0.5512042519658078, - 0.387627570340434, - 0.5890032302168721, - 0.40206621711334395, - 0.4752476439113572, - 0.5779191430636944, - 0.47246865854179865, - 0.450733380650573, - 0.49065455520353735, - 0.47141975312452983, - 0.5457300046736495, - 0.5945213751828275, - 0.4025227542053948, - 0.46293163955958433, - 0.5439932435601947, - 0.3531446136862463, - 0.406174907097594, - 0.6035329279755755, - 0.35820464800526164, - 0.41592354858649805, - 0.5067401222862093, - 0.46007431270828497, - 0.5166541796672329, - 0.606660543372301, - 0.5270967616313977, - 0.5384087476115993, - 0.34370147443890486, - 0.5661129158806429, - 0.42931277059027706, - 0.4979980047977233, - 0.4650722969488757, - 0.5758942106560527, - 0.5734857874929075, - 0.5509739658362858, - 0.35776981328632246, - 0.5586920655674166, - 0.40120937937731016, - 0.3417393295567787, - 0.42069209310361083, - 0.36841641300892974, - 0.5112848638920253, - 0.4695631923835515, - 0.3944100363641463, - 0.4976200953268122, - 0.5694108509855249, - 0.5853371494159534, - 0.5344733144475069, - 0.36301907461119565, - 0.6053925053987789, - 0.578097126094147, - 0.5578179474403271, - 0.5717838467049554, - 0.5847874916852009, - 0.397871624190293, - 0.4912126658170014, - 0.4019151982292043, - 0.6052452159370221, - 0.5828515197753213, - 0.5378979810222226, - 0.44747484208303767, - 0.49429297369969705, - 0.4884186995970845, - 0.4787866955057921, - 0.3427118594444619, - 0.5411194997107612, - 0.4061653882778526, - 0.42140110903370115, - 0.3652821251927276, - 0.39892571035596625, - 0.36443776468180744, - 0.5021766232479261, - 0.5493581366831808, - 0.47936849348665056, - 0.48313144968849187, - 0.5089359691340426, - 0.47827345596436155, - 0.45809709834995693, - 0.406961680691158, - 0.5401388859888177, - 0.5405289049609743, - 0.45421706303546977, - 0.43884938922451705, - 0.3866559499030143, - 0.5598501072917277, - 0.5965474235682422, - 0.3677329250794242, - 0.47962325799555355, - 0.5651506605940745, - 0.5470317233006022, - 0.5540817346064688, - 0.5941257357992997, - 0.5675150513676889, - 0.5618269025213701, - 0.5528250352793151, - 0.5285035563524196, - 0.4057948136778905, - 0.35825667469766365, - 0.43706226936383824, - 0.5376444498369544, - 0.3967112037900809, - 0.4251881580540937, - 0.35352090657965846, - 0.49075486444327476, - 0.5277915797382433, - 0.5494753310446482, - 0.3656473775965038, - 0.48169864003889, - 0.3747822603789379, - 0.42092838173496583, - 0.5865037581904856, - 0.5092179317145871, - 0.4532303905983471, - 0.36804419646419473, - 0.5907101230843081, - 0.41599566493357515, - 0.5661356005784269, - 0.5346400172610124, - 0.4605869890643859, - 0.46120459171452055, - 0.4924294044571569, - 0.49668740039052056, - 0.49590707540851064, - 0.6054443314637221, - 0.44057492673362086, - 0.3927729595262504, - 0.5704993400711761, - 0.3520725272808028, - 0.539198466905225, - 0.39487362249921965, - 0.5413949331225973, - 0.3670117601856999, - 0.501958985728708, - 0.5273175289118641, - 0.5484868371903794, - 0.5062465486149542, - 0.4665669844792709, - 0.5671535351853063, - 0.45855821464053004, - 0.36058412411277124, - 0.43062928321663013, - 0.405001632753064, - 0.5337485494264602, - 0.5133967472084515, - 0.44310639444811134, - 0.48334612100127855, - 0.4552567648260003, - 0.5427375663754783, - 0.3418045649162545, - 0.3551398296115273, - 0.48326114042567936, - 0.4932084584290826, - 0.3642590181935925, - 0.44396201617357184, - 0.597358418218051, - 0.5536693614389065, - 0.4020207489260304, - 0.5952207556998241, - 0.3660961407027712, - 0.3785491622581903, - 0.4242627679404203, - 0.606695763753605, - 0.392461173710016, - 0.41885786885559406, - 0.539784309246004, - 0.4090084569644603, - 0.44042604795964874, - 0.5730081789344831, - 0.46577256518341387, - 0.3675912931302057, - 0.42619890681929967, - 0.5708482929502462, - 0.511296106097015, - 0.5133682067666803, - 0.3536055064486195, - 0.45197936225170265, - 0.35349651026365303, - 0.34641495784255383, - 0.5467879379178933, - 0.4575673907874381, - 0.40037120080808997, - 0.5403972273840868, - 0.34283755809663113, - 0.3652610449498642, - 0.37305869542444264, - 0.5955174873404755, - 0.3516078721277744, - 0.4831651576349084, - 0.3783084665323867, - 0.42259266751213687, - 0.48324112363286786, - 0.577526186389424, - 0.5923123775795511, - 0.538016400979911, - 0.4671252251498206, - 0.3610849201295662, - 0.40176300707374646, - 0.525447858158189, - 0.3578576990299993, - 0.4687082973515295, - 0.5238135873319546, - 0.4065742911278351, - 0.4977709253748299, - 0.5207403029582378, - 0.5771624131905057, - 0.43342985790604144, - 0.5969294889070169, - 0.5793050669716379, - 0.4787464520812086, - 0.47258453523838606, - 0.5197913899908064, - 0.44232320739945036, - 0.44216555232432736, - 0.4080231217559076, - 0.5003194464656302, - 0.5762335339481615, - 0.44226009187476456, - 0.4212149417877318, - 0.3443636552215967, - 0.4062108402268042, - 0.606326787007728, - 0.5056925322121428, - 0.37109575729067146, - 0.46800129726912076, - 0.45104349414376793, - 0.4292873547941039, - 0.5627432140844206, - 0.5451734099122009, - 0.5373691614494499, - 0.3887973006643662, - 0.4510710050706381, - 0.4004052483347408, - 0.43515287027600696, - 0.4976603863827777, - 0.4314414681730773, - 0.5070565444570232, - 0.3616193100519047, - 0.5006617045828884, - 0.3449995705840502, - 0.4818353381291514, - 0.4556686405562417, - 0.5978572542279198, - 0.34897114025882314, - 0.3409822274894937, - 0.5415914668947654, - 0.5176308694711975, - 0.3763088829380787, - 0.473755923337486, - 0.4526280059247925, - 0.36012705079526675, - 0.4260984998972496, - 0.5226166210850928, - 0.5891235604473557, - 0.3479133059552282, - 0.5016689510466745, - 0.3447043183950339, - 0.4700949197329335, - 0.43623223697363783, - 0.3505050161618999, - 0.5861478628999355, - 0.3780899107226463, - 0.5965781823060655, - 0.5959367427314861, - 0.3779940956576678, - 0.46340736138897937, - 0.5818669526198004, - 0.5613940052643753, - 0.3696078423562674, - 0.34970690793943515, - 0.4456167247707, - 0.47026306459450046, - 0.5489119139892007, - 0.4587471176687994, - 0.39781795925203706, - 0.4199147676768043, - 0.3415684181387399, - 0.5631757333036549, - 0.5210242341668159, - 0.589444974119202, - 0.39202685482927535, - 0.5786953745437059, - 0.4424620343925433, - 0.5857535998972173, - 0.3831702528856662, - 0.603404614094308, - 0.4864843822226469, - 0.5098100668593947, - 0.5484185599539609, - 0.3609724246593813, - 0.4302904772798027, - 0.41831359967031806, - 0.44241129785445177, - 0.5296957392290019, - 0.4493594120407865, - 0.5758531447548155, - 0.49371803702158823, - 0.49883740141594846, - 0.5179544163701408, - 0.399097146895844, - 0.3790416591666389, - 0.468161040731337, - 0.3593834988126361, - 0.4696885172783928, - 0.4903528002807924, - 0.47888945584544146, - 0.3941243172410985, - 0.5949751532910679, - 0.5792030585272847, - 0.516260113265514, - 0.592639896417546, - 0.5108246650003956, - 0.4621711375940228, - 0.3549921782881267, - 0.34419042844772707, - 0.35592151329234717, - 0.5366962390025276, - 0.380996249350582, - 0.5390645749831615, - 0.4815888441435784, - 0.4137922919188369, - 0.5642540067912105, - 0.4472557744419753, - 0.4816715402349563, - 0.5584985960992093, - 0.5123938021877864, - 0.3614155234170871, - 0.4092593716631853, - 0.4003015821420569, - 0.4561079914526023, - 0.5532737605549063, - 0.5507594548125366, - 0.4601950285571985, - 0.56423751736139, - 0.4830252538623965, - 0.4979114833595524, - 0.42958506741739944, - 0.565437858396905, - 0.4180710650143092, - 0.5117342457791612, - 0.45922459560038653, - 0.37567715383453715, - 0.593049920500933, - 0.49651641403614377, - 0.5475541550580917, - 0.4374183549772779, - 0.5688798097644869, - 0.39737852423029557, - 0.42805323896908526, - 0.42935982631376324, - 0.35729542253336816, - 0.5915915867502046, - 0.49974439159439143, - 0.5364984904350721, - 0.3763109213030394, - 0.543790487333214, - 0.5472909749440531, - 0.4017165218891652, - 0.46836141303809786, - 0.4296626770451416, - 0.4552329385539034, - 0.431504662907053, - 0.4357318458951015, - 0.4906276997106476, - 0.5739848189584823, - 0.47643815249411137, - 0.35943210068620807, - 0.49908593227073306, - 0.582510008898103, - 0.4785465768901364, - 0.5525311387060066, - 0.47364719908757924, - 0.5900961364769591, - 0.4989347455329335, - 0.5374627152765787, - 0.4388284469175143, - 0.49656496078448287, - 0.5722171120099486, - 0.5344004097437738, - 0.44761203782931736, - 0.4959797440940694, - 0.5928494439529697, - 0.6018383463952373, - 0.37047954886205947, - 0.5241524042501857, - 0.46999761043232113, - 0.5688667714533728, - 0.4808262896437844, - 0.5218902150646384, - 0.4268504771707149, - 0.5637630311820285, - 0.36255079749969393, - 0.38434342162691504, - 0.47754310889422075, - 0.35221939416819675, - 0.590774303162905, - 0.39710962499107594, - 0.5208095864858034, - 0.38488131014046695, - 0.36657874081817193, - 0.5797554715469266, - 0.35202209156267744, - 0.42862559663343186, - 0.5436237138225644, - 0.361694919099174, - 0.37123440841445204, - 0.5989587145286132, - 0.48347856687466284, - 0.3622709707812483, - 0.4184696753687244, - 0.40918016041480854, - 0.5135210549708782, - 0.43104402053884705, - 0.35134999803656375, - 0.5100477942387148, - 0.39859536921978916, - 0.5299805251002494, - 0.546190026818351, - 0.4956723017107683, - 0.38141256458959044, - 0.4199818201363078, - 0.5984475814408099, - 0.5487399277534105, - 0.4842771226870802, - 0.38586242710097507, - 0.5424567071799237, - 0.4474693419998597, - 0.5435982195838254, - 0.40355403389597616, - 0.46091025074890035, - 0.513291270281824, - 0.5828382207881566, - 0.4629646286829769, - 0.4458819293065666, - 0.43630804022546626, - 0.4853797245015391, - 0.44722416173211904, - 0.5246940485467683, - 0.5645903050587975, - 0.5966971746473727, - 0.46294552666447697, - 0.5132953656220485, - 0.5095213715006454, - 0.4765886280760146, - 0.40409511496883754, - 0.47670217013125155, - 0.36498720848992344, - 0.5845940374728326, - 0.4130792660627183, - 0.37356265169504843, - 0.4399114197402956, - 0.5036059197835155, - 0.500082142453562, - 0.36311832006305156, - 0.3890316668314808, - 0.4488864946009695, - 0.4243462499807549, - 0.44665308394986575, - 0.3793758396033923, - 0.5958784453708247, - 0.5559226637617731, - 0.540310350736598, - 0.3849038340289976, - 0.43371715544760514, - 0.48780177165088, - 0.536637871763491, - 0.5447438693536855, - 0.39475437510706285, - 0.37820052524232817, - 0.3972292567458137, - 0.5878197672505225, - 0.3738287382375631, - 0.45831577060727, - 0.5447679302022996, - 0.37047096601347257, - 0.6034015704511099, - 0.4414872774322497, - 0.3581792790311684, - 0.48268683757612635, - 0.4351224851182274, - 0.5126286197532355, - 0.5660686655002676, - 0.4522209186469125, - 0.4297563423378059, - 0.48176575710218456, - 0.5568075552939239, - 0.5122737192992761, - 0.3897719561528098, - 0.5303139603526139, - 0.3890735944662835, - 0.5156910254651415, - 0.492265389645744, - 0.4543400116809689, - 0.4315192204057235, - 0.3517682755416012, - 0.4458799725307709, - 0.48348261260610204, - 0.5361232202682916, - 0.41741332709021106, - 0.3598244905762465, - 0.42308651755084087, - 0.5443162756989902, - 0.4692497890006355, - 0.5493292845388383, - 0.4823487616656143, - 0.5927394826218776, - 0.45291898008964787, - 0.5647822221789737, - 0.4222863973893678, - 0.572437485070457, - 0.6072671509795817, - 0.378493550054688, - 0.3618665149594862, - 0.4982309972816673, - 0.5356049797282111, - 0.39092952343652043, - 0.4751317058727445, - 0.5447436272406033, - 0.481135246889857, - 0.4790468770082716, - 0.5738145645332279, - 0.40514715854339295, - 0.5730767010911577, - 0.5637371839504364, - 0.5779303967577918, - 0.5803651489945478, - 0.5251813936646836, - 0.39157773178963695, - 0.5147832589206653, - 0.587081956536606, - 0.5925045850481256, - 0.4708974309105739, - 0.47743333070548905, - 0.3494952619487619, - 0.5406174012589257, - 0.47208730160054113, - 0.5325605722115214, - 0.5856971282646489, - 0.4287317918905761, - 0.4594243619267505, - 0.491826809873512, - 0.47226564135738924, - 0.5382753559203767, - 0.4585170894853853, - 0.39175127980288205, - 0.39084045304016474, - 0.5724782917701027, - 0.412821166133059, - 0.5250816769630482, - 0.46378122513385617, - 0.4642306132137287, - 0.39635907376612906, - 0.5710115086071117, - 0.362069688157322, - 0.5511502987910317, - 0.52858616508491, - 0.5561599961867905, - 0.5383692844219772, - 0.45599045085718215, - 0.4348805315801754, - 0.4580328383220731, - 0.5490123780806453, - 0.579378881507812, - 0.4624101759760124, - 0.5656358083069314, - 0.4482145729272018, - 0.3984893041671749, - 0.38808574339373403, - 0.5859427078396667, - 0.5021175538645386, - 0.5937790372235039, - 0.6000843283112475, - 0.3727275144592678, - 0.4893443149651098, - 0.477915779298977, - 0.48047670229103845, - 0.5591144327995468, - 0.4642371933965854, - 0.5224901144551484, - 0.38096228461726084, - 0.4134934889234984, - 0.5458326470269318, - 0.5470773190847519, - 0.5262718169740518, - 0.5977991604872139, - 0.5881744882881204, - 0.3858866199562464, - 0.43871752564816385, - 0.5307343881858637, - 0.4639455868091231, - 0.3759985005301699, - 0.504282550038908, - 0.5688263543348893, - 0.536388011552948, - 0.5559997467100166, - 0.3441022128290943, - 0.49006327399236077, - 0.35005151870369816, - 0.5005544166318121, - 0.48153638929069026, - 0.42914614834059217, - 0.4913255829409019, - 0.3756202993726586, - 0.3704749206471512, - 0.40107975828391446, - 0.46514651338668256, - 0.4835215323344906, - 0.46349410842704597, - 0.4363624629148393, - 0.604617583193086, - 0.4940654660671455, - 0.41023122516756366, - 0.3946376612725568, - 0.43209728328794733, - 0.5049950297279239, - 0.6054037498711096, - 0.5074431682817182, - 0.538832603853358, - 0.44695991137230606, - 0.45154354365483795, - 0.46070498600617615, - 0.5429191875456703, - 0.5334693264539616, - 0.3681650929949051, - 0.38087821821721624, - 0.41887579338151437, - 0.41348527097894294, - 0.5424270563759517, - 0.5897118559496941, - 0.48818471035237576, - 0.39784320707796833, - 0.3475927922349093, - 0.4010968842099402, - 0.4164637025131879, - 0.5813192315501314, - 0.5565592378430699, - 0.5732294958091141, - 0.38470904275546264, - 0.35666385731839556, - 0.49835103127225533, - 0.39764500224053884, - 0.35832996477324186, - 0.5041522249823469, - 0.4540196224982539, - 0.49542443367269284, - 0.41172333353430157, - 0.5655527717624992, - 0.35091940962711166, - 0.41040375770404025, - 0.36996424612362355, - 0.5620274690102021, - 0.46381486597565447, - 0.4246272592011066, - 0.4526916826329957, - 0.34439248096933495, - 0.43750099781222834, - 0.36758406126375104, - 0.45176748547064927, - 0.4822453973812701, - 0.36704579921416397, - 0.3465623331408789, - 0.4020401306508859, - 0.5209421000833968, - 0.4988270327275549, - 0.43810339174486645, - 0.5292477574055329, - 0.34381783039692204, - 0.4180089464233579, - 0.43543082629526, - 0.5840615198611738, - 0.4143304315487832, - 0.48707260870602465, - 0.5224169061061676, - 0.4914426770721485, - 0.47443819130651455, - 0.5059929060336875, - 0.41848194299583463, - 0.5416917751709962, - 0.6052600806803394, - 0.47397518543088857, - 0.4550221214810435, - 0.6007174144976646, - 0.45567305098776084, - 0.41543441629082006, - 0.5238956991835527, - 0.4579849326936323, - 0.557291601566468, - 0.5157644580697222, - 0.574486685995402, - 0.5235643984204038, - 0.5784757518325264, - 0.3771143180121184, - 0.5002793155811469, - 0.34371736722743523, - 0.5789218736715671, - 0.6031944717190088, - 0.4363314010678456, - 0.5400483259258544, - 0.546546034568991, - 0.36361558996215515, - 0.6047473676331951, - 0.4980419147893706, - 0.5686990224778705, - 0.5111650295491694, - 0.5677807439290499, - 0.5626251826156322, - 0.3692570359810935, - 0.4996160457293035, - 0.5993861226588986, - 0.3781336397090818, - 0.4796287500021098, - 0.41764636730704024, - 0.558457873530459, - 0.4336952337979916, - 0.36354081139064137, - 0.49577635830334876, - 0.5997234436182977, - 0.3833419758697108, - 0.35561128677037196, - 0.4595680432230874, - 0.46720292006924424, - 0.3608082940693741, - 0.48487006160398416, - 0.42110333203818895, - 0.5998259165935435, - 0.5770972028447763, - 0.37494788261952544, - 0.5660755327808039, - 0.45072271186855345, - 0.5569975939959351, - 0.5041257351341618, - 0.5402113941375282, - 0.4727194533216551, - 0.46117540710941907, - 0.49827888954305893, - 0.42684577829670395, - 0.5333083765592986, - 0.450629158285831, - 0.5385174774911126, - 0.5172283499706463, - 0.35829604400709725, - 0.4313168986634953, - 0.3647069651057848, - 0.41872348517273295, - 0.5541903570512077, - 0.4287421566382332, - 0.6066725398616125, - 0.48535929324288285, - 0.5044759227653379, - 0.5055803226242288, - 0.5940182450467646, - 0.5670321958466793, - 0.5843877152250271, - 0.5737302316867929, - 0.359460088370601, - 0.5750074927545036, - 0.5229223728348661, - 0.525623867329186, - 0.6040554795602362, - 0.3680555433511406, - 0.44309251089218693, - 0.49747153399776733, - 0.45223254007034897, - 0.4813330286071019, - 0.34769222207182743, - 0.43858346589417385, - 0.5462125600304433, - 0.3921608872345419, - 0.4252736727044042, - 0.48735035843839725, - 0.3919319875073238, - 0.4229385013730056, - 0.48923468898649775, - 0.5402259272232729, - 0.5880193197805855, - 0.3600559089058265, - 0.48415914104379704, - 0.34390882754128327, - 0.6020519347530171, - 0.4285075639376177, - 0.3733675752221049, - 0.40806757100349667, - 0.5600835276416463, - 0.4270187187628765, - 0.5561200081008018, - 0.49142282125712977, - 0.5205932278849679, - 0.5650620368971974, - 0.383138710273459, - 0.4008507333781728, - 0.6028197490899224, - 0.42895530474869714, - 0.3455640269514752, - 0.4624088890599434, - 0.5290348755870589, - 0.45173578784678936, - 0.5588767124120043, - 0.3700130358864547, - 0.4782073667698169, - 0.4200445703396176, - 0.4581896604709206, - 0.4427967544265796, - 0.5639366895262188, - 0.4928958248049241, - 0.4329847610061154, - 0.5367941504284734, - 0.40228817729076105, - 0.5369659580439285, - 0.5655691832654881, - 0.4881916405947886, - 0.5806028833843923, - 0.5239377008660213, - 0.40116096688369923, - 0.47020322822442695, - 0.5596187213443222, - 0.4858937015844428, - 0.365019502906801, - 0.39594394669596816, - 0.4629861989697638, - 0.4958554263705953, - 0.3648921494875471, - 0.48876063160793304, - 0.34960799191057845, - 0.566552390695838, - 0.4393016987762499, - 0.49784216718705, - 0.4724076711140998, - 0.5175845031088082, - 0.5673779869307186, - 0.34806867423039684, - 0.43664750887595183, - 0.5106061876771942, - 0.44758317148271987, - 0.5406325306481734, - 0.3458526180567025, - 0.52558942848519, - 0.3674678114050265, - 0.5895592042634485, - 0.5343730556540154, - 0.34241522376939365, - 0.6031524836911649, - 0.539488326702104, - 0.5976321727786149, - 0.43764683588953746, - 0.4457562392906118, - 0.3762688888752953, - 0.48433791270700943, - 0.37472883085236997, - 0.5127848846512508, - 0.36570113422386424, - 0.5435933980770954, - 0.4656150582366835, - 0.5533021824679818, - 0.5075451259884742, - 0.5382769478523386, - 0.4520249020213211, - 0.372360401958235, - 0.5718517062205781, - 0.56212588297668, - 0.524101147742825, - 0.36565966488040685, - 0.39790661343766043, - 0.45238730300529595, - 0.4215557840958121, - 0.4325427708147481, - 0.49989503391839735, - 0.5461496456582927, - 0.3513849223987647, - 0.5920244137098933, - 0.4491056571111683, - 0.5694116345689199, - 0.562649323268183, - 0.5577054727513088, - 0.5172941976937043, - 0.4095836564399813, - 0.47175239211708675, - 0.5520720570796005, - 0.5637401473073307, - 0.5704998554569636, - 0.5463175841589537, - 0.553410900995879, - 0.342826102887559, - 0.4255966133698375, - 0.5195661229166846, - 0.6041520709927526, - 0.5334347758900477, - 0.3982809324813973, - 0.45656108486365854, - 0.5048319172463278, - 0.3471281060371162, - 0.5573155572364891, - 0.5878211371113131, - 0.5632622163543164, - 0.47102101058494644, - 0.5304900710721557, - 0.3943490983760981, - 0.6026584540976604, - 0.5027188209571614, - 0.38669932777478516, - 0.5098948370341785, - 0.5955773368924072, - 0.47366901174210485, - 0.4984146443474535, - 0.43388579675386507, - 0.5725548574964232, - 0.4814306491024427, - 0.38088407951730496, - 0.5284153682387986, - 0.4868438330754675, - 0.5159301975718916, - 0.3409034339487584, - 0.4560692175084253, - 0.5378727680804956, - 0.4616437563550293, - 0.41880877994646243, - 0.4712516632079647, - 0.5551301940454775, - 0.40558349684862394, - 0.43451035483935835, - 0.43677970771060837, - 0.39848359912597353, - 0.3655010333607104, - 0.5211479780547938, - 0.36593816784253397, - 0.4200227996482171, - 0.5586375421430192, - 0.3811451623076212, - 0.455671873836934, - 0.5379643385873132, - 0.3851014377092196, - 0.4513906341588465, - 0.4947886416224355, - 0.4099451136431704, - 0.5717642037331849, - 0.5446692987385748, - 0.5147355806201437, - 0.52461770171248, - 0.5038610426983585, - 0.42499711174396415, - 0.5835852220380184, - 0.37138976612348956, - 0.49971169729386716, - 0.536588472706207, - 0.5967979804195329, - 0.35863147573086396, - 0.36565371490260484, - 0.5873672243629264, - 0.3690016482192036, - 0.38082632780464437, - 0.45740005881091916, - 0.3755906879636911, - 0.47992634818451474, - 0.36344064319502944, - 0.4154486612861844, - 0.4612961295521035, - 0.4303868674515872, - 0.4356531256192087, - 0.6023095930929667, - 0.4941947501228827, - 0.4852175293499573, - 0.48939974004316644, - 0.4683801830556315, - 0.6017693888901976, - 0.42471361561447835, - 0.4389681923840648, - 0.5840023348865531, - 0.5984206236845462, - 0.4262435913996844, - 0.4297562809081923, - 0.38392223550469956, - 0.3477721778336985, - 0.5361326773915226, - 0.5022498445678856, - 0.4362531519411411, - 0.3999986129061441, - 0.5429349159337243, - 0.3458400573355226, - 0.585710067345121, - 0.42136472398450303, - 0.39554260702791433, - 0.5906177326724089, - 0.43455383343691933, - 0.42001725653099703, - 0.5860014725854814, - 0.3455577414795612, - 0.38717372224781776, - 0.5924424788660981, - 0.4993672504784784, - 0.5050506992888779, - 0.6031179940300071, - 0.570140133446224, - 0.4572558286251834, - 0.5318683005310849, - 0.4109621658358643, - 0.5905781262479999, - 0.58077252668856, - 0.5767278372824144, - 0.3842403746807115, - 0.601242812755018, - 0.40055683907139944, - 0.36021311711170195, - 0.34350822439067447, - 0.40426421415919567, - 0.51466232179607, - 0.39250581060215567, - 0.38187348620284683, - 0.5174849658788863, - 0.5180765129420417, - 0.5853854364410551, - 0.527402031111851, - 0.5877559275113711, - 0.5767727872850834, - 0.5818896816600602, - 0.5969519658012206, - 0.4803385161120309, - 0.584207945429351, - 0.5937387338960768, - 0.43114666240668237, - 0.4173854441837846, - 0.43525139667319046, - 0.4026618567735406, - 0.482243217207434, - 0.5150571057136888, - 0.5636333381914264, - 0.47181902556097377, - 0.5266145015840384, - 0.3656633235432021, - 0.3816279303351911, - 0.5924915637636213, - 0.5077142557855513, - 0.5242538692837724, - 0.5582099140189751, - 0.5390990145427298, - 0.5699443460401585, - 0.43545541795029663, - 0.517886888070764, - 0.5103985672893961, - 0.4553408916462779, - 0.36674023513969195, - 0.5542372958090295, - 0.38694112095324995, - 0.4394978465896851, - 0.5141891988411978, - 0.49689943849386853, - 0.4804903388262922, - 0.5551343230424937, - 0.35192853779223837, - 0.4001626720759709, - 0.37069077739587314, - 0.5867694482361421, - 0.49765564858833566, - 0.5700707484206068, - 0.39664341074338394, - 0.45242336978221964, - 0.41143949808597274, - 0.548210563084936, - 0.531583712603067, - 0.4957087669462903, - 0.5444753544340261, - 0.4407876884547026, - 0.5362198582711942, - 0.3995295587248442, - 0.34854244840153303, - 0.3714284828416545, - 0.37128704193864936, - 0.5150938887977593, - 0.3679680799645099, - 0.4727455710272873, - 0.440895853136057, - 0.43573937907781796, - 0.5690186593413963, - 0.5683022081837414, - 0.5711851431735742, - 0.561889379993446, - 0.4382381353641992, - 0.357175846820834, - 0.48184732007769177, - 0.48959741823454006, - 0.3976964143536792, - 0.5413700775630486, - 0.44603669298668147, - 0.5575093466539597, - 0.5759501843300838, - 0.47089703885608536, - 0.4576481516225741, - 0.44649076996060016, - 0.5880840745162972, - 0.5762730322910441, - 0.5065214547646866, - 0.43339409755090114, - 0.5975890437096028, - 0.37129697382075844, - 0.43055161821694843, - 0.5905503858744674, - 0.388854593693407, - 0.5668736610733817, - 0.5515749981388804, - 0.40706471995567556, - 0.3502994417283673, - 0.4508369655300074, - 0.4506269194521547, - 0.5194815464266922, - 0.5695055032868659, - 0.3930679862345533, - 0.40052819933087125, - 0.6047863916946136, - 0.35569004672340504, - 0.4433654625988125, - 0.5181739757852903, - 0.35694959152255323, - 0.4142641867597158, - 0.45083266277075773, - 0.34620199442476235, - 0.43499649585099437, - 0.5480474644732848, - 0.35269147557840363, - 0.5481515657522653, - 0.5389910370012247, - 0.4822044154136622, - 0.468151991414449, - 0.35933451853204235, - 0.5293301321840558, - 0.4918205273176812, - 0.5525423992205885, - 0.3445728307874536, - 0.4600437703664185, - 0.4531674009316183, - 0.5244210942776948, - 0.4429456859254012, - 0.47494113906087865, - 0.43614472578259905, - 0.47497018069638786, - 0.3815841010711111, - 0.3836194076478524, - 0.36513381839740205, - 0.47095072903990665, - 0.4406932220600682, - 0.44705133732263597, - 0.434485134308049, - 0.3905251669072398, - 0.5963936231540962, - 0.5774346604026814, - 0.3697529337010669, - 0.3979327316297813, - 0.5836098009393933, - 0.4329320991345441, - 0.36959571961303234, - 0.3675015679422302, - 0.3938217962774474, - 0.5300071892116893, - 0.5138783614097975, - 0.47154607780997126, - 0.4463348542341557, - 0.4965455177958962, - 0.5772358861063113, - 0.4432138698142227, - 0.35227460650078624, - 0.3533142638430749, - 0.5464167343709512, - 0.44928888430556263, - 0.5126934806894776, - 0.589993442505031, - 0.5081571705809269, - 0.5433456316360263, - 0.49043538133217407, - 0.38017202006235884, - 0.43654149911389006, - 0.3793651681897868, - 0.38151228093507655, - 0.5332002179974936, - 0.5089177654644226, - 0.5700581381281749, - 0.46703956947001485, - 0.5214227017731614, - 0.3472858082360989, - 0.40117351082777963, - 0.3630934365929554, - 0.5645231798164867, - 0.5744940120643287, - 0.6066662376181085, - 0.4127692014038956, - 0.4785979860638449, - 0.5871894278605647, - 0.4029527364817791, - 0.3780905004869681, - 0.44219801807717, - 0.5974364773569296, - 0.469457899358338, - 0.5955015639393018, - 0.5901560842834087, - 0.5642393447272207, - 0.3499933857863502, - 0.6030229136683062, - 0.34185699589264434, - 0.389499708592053, - 0.42704361003387065, - 0.5381973769710526, - 0.563367342750058, - 0.4475014364143385, - 0.4690846572296624, - 0.3568869397905371, - 0.5075145053452167, - 0.3728177124197881, - 0.4113246222168306, - 0.5085539903464926, - 0.3525915309708196, - 0.5380302498920292, - 0.41291089844232204, - 0.3577458690828222, - 0.4377909249580116, - 0.34955937432682305, - 0.5166671524056243, - 0.5883804906409171, - 0.5027459519767858, - 0.4457200531120105, - 0.44549725746013347, - 0.34979952807115056, - 0.46863153085403575, - 0.49903095618170845, - 0.36606014990888647, - 0.5903941265627326, - 0.548117931968185, - 0.43396967142961324, - 0.3641551166131207, - 0.5688856782718663, - 0.38910355504639277, - 0.45998889965437734, - 0.34139331944112483, - 0.5683517703892648, - 0.5874492933185416, - 0.5470498563043013, - 0.35986508461983047, - 0.5137192607248188, - 0.3901621191655087, - 0.3692500726123208, - 0.4036059557279845, - 0.47162556139481027, - 0.5982376791508018, - 0.4716336119866198, - 0.574337095809456, - 0.40207124670766786, - 0.4601119308621689, - 0.381015174876138, - 0.4574311717413131, - 0.4188863710707065, - 0.4521973692795802, - 0.44508251075240113, - 0.5983626761901739, - 0.398624392527328, - 0.3957109344590092, - 0.3821304914705967, - 0.5476669365147218, - 0.4121818398587784, - 0.5881618525073584, - 0.4194602619024192, - 0.5374228876403213, - 0.5677951681126381, - 0.5277292794422975, - 0.5145737830205208, - 0.42800106522486525, - 0.5255608407999002, - 0.4273271994528143, - 0.40749624570427445, - 0.3998876750953001, - 0.4714843689694087, - 0.354121638891267, - 0.42384069316731704, - 0.5714953026658576, - 0.5575541456172901, - 0.37145020552999664, - 0.43504187662142874, - 0.4407236929707368, - 0.45842328772325397, - 0.5211857192663406, - 0.5324902035307142, - 0.5414192247121028, - 0.5774103195542553, - 0.5733414024202672, - 0.4038472743174902, - 0.3812371511033552, - 0.4425202940384548, - 0.5964265254590978, - 0.5840680838022165, - 0.5991792019266406, - 0.5156430406820665, - 0.47939831958903206, - 0.3887283628090319, - 0.5790277110575255, - 0.57801725751734, - 0.4433228199419039, - 0.4713900596088169, - 0.6043557031977409, - 0.3502814209274927, - 0.5566321855954661, - 0.3835650242384078, - 0.36566350196533576, - 0.474989559921265, - 0.4529110958193883, - 0.6062372260507487, - 0.46083736495472816, - 0.6062127015813248, - 0.4377688898584898, - 0.5551403250673934, - 0.3995512312300459, - 0.4604005180761992, - 0.4273295328599033, - 0.3631495960769759, - 0.5162970209701361, - 0.521325568162219, - 0.411529185936083, - 0.5330699093913727, - 0.42676211702059164, - 0.4619149753539925, - 0.5784511330591268, - 0.5407101080507138, - 0.5253272989604495, - 0.5369198054541772, - 0.4013412648674857, - 0.39107887671715724, - 0.4054912895521653, - 0.42703288498803416, - 0.4958308912252307, - 0.5965458080578074, - 0.4839946699986284, - 0.5364755138070304, - 0.5560537224176804, - 0.4210829548956295, - 0.38944307840944725, - 0.4748973088116586, - 0.5180758435461542, - 0.4723194295437103, - 0.42414170256388384, - 0.40082337890387676, - 0.466430972604146, - 0.5211067513464067, - 0.571760619451934, - 0.5868770845276051, - 0.5976977604869778, - 0.41870515793495444, - 0.47157242479704864, - 0.42048573119433685, - 0.47129767082589125, - 0.45050175174797935, - 0.4578374490780328, - 0.5704646368619033, - 0.43397166522973546, - 0.5668399175770066, - 0.36563803737028966, - 0.5624490378382778, - 0.3831607600926631, - 0.38377805820981387, - 0.6069129661939516, - 0.4204855186366302, - 0.4725872560948969, - 0.5942599101750501, - 0.5964913571391558, - 0.552153607447438, - 0.5345768710123384, - 0.5509380132145133, - 0.4478094125742072, - 0.47992685502273236, - 0.4918387520564884, - 0.40655296574534344, - 0.6032892859373337, - 0.40170494552588026, - 0.35393576320652564, - 0.5941840476244853, - 0.4668984292308642, - 0.4359776468353096, - 0.5697811618600199, - 0.3432293215950925, - 0.4206352370467111, - 0.355214362164549, - 0.3872671515077638, - 0.48439397922880795, - 0.42229664518451493, - 0.34291235768405176, - 0.6000929221858134, - 0.5396789270573518, - 0.3779068474109781, - 0.38587871048232236, - 0.4279876678646749, - 0.5416679695366442, - 0.3601083011053589, - 0.44005386599393204, - 0.4910213271885211, - 0.4636678724614484, - 0.5845740483743382, - 0.474230263010182, - 0.47364289338845733, - 0.4002599702424151, - 0.3982839851334967, - 0.4407340638654539, - 0.40415959225706616, - 0.5952155668475108, - 0.5096063098008807, - 0.3836381108006843, - 0.4370080011538227, - 0.4046069136065773, - 0.3810701509709522, - 0.41709308939612677, - 0.582652272165155, - 0.35597351162161806, - 0.5103572653387155, - 0.4686358136251968, - 0.37573524634998307, - 0.41173245824528387, - 0.47535681365027516, - 0.4467799291116489, - 0.543105421599735, - 0.5031893369128076, - 0.5015801193796757, - 0.4413124840412973, - 0.5404332219747517, - 0.49843528559711636, - 0.35853161455181504, - 0.4286966138533015, - 0.5109215734884437, - 0.3755380029169503, - 0.48768232797104694, - 0.36729109943254645, - 0.3858414582431581, - 0.605841659887945, - 0.40128511846321163, - 0.5461065028361636, - 0.5401197283074233, - 0.5002079725243912, - 0.5681896095256078, - 0.5896894395784137, - 0.5455403900758713, - 0.5224744447392173, - 0.5003262418875674, - 0.4639850764903982, - 0.47538704022230105, - 0.4204326527833532, - 0.4359724784297591, - 0.5690844163317792, - 0.3877210718302619, - 0.3886932072336763, - 0.5669233017571499, - 0.581882439836231, - 0.37306801926872946, - 0.5213067842721167, - 0.3788056534354651, - 0.5258205088957082, - 0.5887920388062594, - 0.4287802738985794, - 0.5207521292111031, - 0.40002288801776437, - 0.36445535376609345, - 0.5487790624052529, - 0.47840887659460946, - 0.5779748039330346, - 0.4181900668535201, - 0.5897117342421704, - 0.5947784789180255, - 0.4111880888177135, - 0.533290204713131, - 0.5243048954583456, - 0.41758470452940655, - 0.49729672695167937, - 0.3794110405103833, - 0.6026404460188377, - 0.4646859782490979, - 0.47850143895117325, - 0.4346691909622664, - 0.5160374010799846, - 0.4160922425802653, - 0.37629639770629547, - 0.5210144246771757, - 0.5805594963423566, - 0.3465032819848858, - 0.3467111778626129, - 0.5606132528715901, - 0.5898612182041103, - 0.48954384482125723, - 0.5498191779346736, - 0.4602197980647327, - 0.4495642330630609, - 0.3678680716556008, - 0.36622785828181653, - 0.45803917338777284, - 0.5691407748152236, - 0.5663513036573249, - 0.5175707224199956, - 0.573143108941977, - 0.5360058469741674, - 0.4143760581596253, - 0.5083069936631057, - 0.5208780699994776, - 0.585888960739959, - 0.48230585601314396, - 0.476327830239332, - 0.34602968501691844, - 0.3693312791539548, - 0.5114317826309651, - 0.5284399369064399, - 0.6073883480412614, - 0.5424380511999232, - 0.4773155449660213, - 0.5647220260128138, - 0.44810391701323254, - 0.4125477552730398, - 0.5693496340278668, - 0.49217467854028374, - 0.6009529922026036, - 0.5245060854009949, - 0.43217751465723486, - 0.40117173395518047, - 0.46817516801214143, - 0.40843432404281094, - 0.49576950164331934, - 0.5232494570070706, - 0.48640912038487427, - 0.4407309712084316, - 0.5935512375286917, - 0.6024286205839332, - 0.4383746007715627, - 0.35377591492877997, - 0.5429421601181543, - 0.5545601379995072, - 0.41355463277432275, - 0.3427438928789937, - 0.5529839083804439, - 0.47753975660995635, - 0.5182356401373046, - 0.44984379736644137, - 0.38158050444554753, - 0.35089126511001734, - 0.43670773737018415, - 0.5144892868730309, - 0.4796643107759119, - 0.37675697483409093, - 0.5185126930837999, - 0.4404928288973715, - 0.5543321331263863, - 0.549049524633487, - 0.39917770001123576, - 0.4191751935004053, - 0.36505527260429954, - 0.5118052433877915, - 0.39183837394041177, - 0.5062444317542475, - 0.587701452812981, - 0.6030429503483237, - 0.46263875389781445, - 0.37672882232936167, - 0.503650953953524, - 0.3425711395249922, - 0.5081825000715521, - 0.4175024580726619, - 0.584463329400742, - 0.43038328103323825, - 0.46016524881188287, - 0.38158492466439614, - 0.371849368096073, - 0.5356287973253003, - 0.37841142063715727, - 0.3907784183564876, - 0.42841232785362554, - 0.41630902215859805, - 0.3606987524405799, - 0.45378203671036704, - 0.407117955734074, - 0.5706907618669468, - 0.48333574165558085, - 0.40059323878244524, - 0.4404208948834411, - 0.5751270515308207, - 0.5891131236689426, - 0.4218469856569072, - 0.41527848115622407, - 0.5585607772341628, - 0.4910677643379465, - 0.4606655373564502, - 0.3874241649166903, - 0.5361418979673104, - 0.5541114987178543, - 0.5519753767815289, - 0.4960662563391007, - 0.5994383995595594, - 0.5748209067914986, - 0.47345266621037, - 0.4666972181531208, - 0.4204484336728031, - 0.5997394004434058, - 0.4305944683983949, - 0.5273135288434979, - 0.5620858740896157, - 0.5257199490998822, - 0.3776345073250535, - 0.558225235787473, - 0.46723283550841876, - 0.4325607363784433, - 0.3723276709066616, - 0.404605294649374, - 0.5834366988449935, - 0.42457033178019615, - 0.553031869162783, - 0.5729033552503078, - 0.49167368691694624, - 0.4511260148124397, - 0.3532290512025263, - 0.558711293281765, - 0.5785771941912105, - 0.45893701272541837, - 0.44580654079920917, - 0.3941468529623248, - 0.4174119400836544, - 0.5227834167372666, - 0.5467960885767733, - 0.5612900524320981, - 0.5612399453320689, - 0.5532867850256648, - 0.3862881564007677, - 0.5362950077233517, - 0.5844258607490441, - 0.3885821758413086, - 0.5484825671317772, - 0.3866782070720891, - 0.3893912560503786, - 0.4419469979178036, - 0.5264998938548889, - 0.5662070165423535, - 0.42473948006847995, - 0.5688812791317233, - 0.40200618805945393, - 0.3836022866938881, - 0.39741425139103265, - 0.5671975871222379, - 0.5454008794503439, - 0.35408775083511607, - 0.3593925268086878, - 0.6071152824147541, - 0.3494843397801426, - 0.5083096297156754, - 0.3650195868390244, - 0.36715665889095506, - 0.3590501595051067, - 0.5590917342228394, - 0.5224384488456307, - 0.450734119810024, - 0.5571365391002817, - 0.5331296102050722, - 0.43599747274555334, - 0.45620696584466, - 0.4038502434300028, - 0.4540866261299499, - 0.3514656632103268, - 0.35676845245647526, - 0.459989935978494, - 0.488829062886094, - 0.4342691962254997, - 0.588240456663972, - 0.5481865817103585, - 0.5186891097129764, - 0.34090810719554143, - 0.4023528455617401, - 0.44847995895697784, - 0.37073725211438474, - 0.5132161897157604, - 0.5220094455007769, - 0.5131175489600297, - 0.44907216136827854, - 0.4714329237465483, - 0.5177235019346635, - 0.5939385759077853, - 0.5534036659446222, - 0.5383987708601117, - 0.49627327311124614, - 0.40363457611947545, - 0.4524393673914104, - 0.3754049436495784, - 0.5632522491275106, - 0.3525310608627026, - 0.3636537531160835, - 0.4339491433989592, - 0.46380312294220405, - 0.5233192313668771, - 0.41557374369200023, - 0.6017510639672878, - 0.5624086592935513, - 0.5486718541717376, - 0.554384807000126, - 0.34530876575406794, - 0.5566658218906735, - 0.40992440521803086, - 0.3420295095936165, - 0.4272591072683827, - 0.4379236152997013, - 0.5735181466728441, - 0.5540274383455197, - 0.5950063944469508, - 0.5508139750390755, - 0.5571909264198418, - 0.5103801232568488, - 0.43199907652290054, - 0.6064174194892114, - 0.39983366988841457, - 0.42740671801269225, - 0.5603295064586449, - 0.45116374041482643, - 0.4220991580032228, - 0.5815112310261376, - 0.3935500583393764, - 0.3637450042715051, - 0.4004253109645629, - 0.5488808288569419, - 0.5069151822931237, - 0.46405300047841747, - 0.5988968297932331, - 0.5780611781059347, - 0.4689664033663137, - 0.5304900448113623, - 0.39655055999039873, - 0.5101546834723075, - 0.3736721700132078, - 0.448941712498251, - 0.4621207803887918, - 0.5830368264032357, - 0.5492617445654724, - 0.3898079794098416, - 0.5936588664409554, - 0.4712876686345207, - 0.5792779087788412, - 0.4433789946388818, - 0.47726034496035996, - 0.5598440957405566, - 0.5741240350225446, - 0.49432427309369287, - 0.5354588792698488, - 0.37781732732953244, - 0.4069340987756215, - 0.5108348365105546, - 0.5290715875982267, - 0.49430291009409544, - 0.5446506948650276, - 0.576644721594663, - 0.4135877867232166, - 0.39712622137208925, - 0.5027435052680292, - 0.43143970092347034, - 0.4052982561729646, - 0.4352938128921654, - 0.5521213674947341, - 0.5497034279113481, - 0.503552169437041, - 0.44221681964933446, - 0.5806079041716172, - 0.4932912573115048, - 0.4179250226693302, - 0.6074712677406384, - 0.3713451266081315, - 0.5420948958744889, - 0.5343785186325769, - 0.5605371042843921, - 0.5326010017155108, - 0.5504934960158249, - 0.5595582339089981, - 0.5814011323600579, - 0.5087620016345406, - 0.5586422012570111, - 0.4138948188581598, - 0.43814987254907656, - 0.5830826043736005, - 0.4547230010899324, - 0.5833631491219198, - 0.39275540949721094, - 0.3773016582023501, - 0.37266213310624685, - 0.430808403358036, - 0.42381145482254495, - 0.4580162963035302, - 0.4547745716303093, - 0.34534295103486934, - 0.37860558139247596, - 0.4692119219935719, - 0.5125162922241411, - 0.522342334213131, - 0.4987162252533879, - 0.5766515985328261, - 0.46164843214726525, - 0.4684073312065953, - 0.4556593378075725, - 0.543024696363872, - 0.39801617597583117, - 0.5763189837823455, - 0.4298212958312958, - 0.40327787932447795, - 0.5370990791196664, - 0.585534910093353, - 0.5185304328086593, - 0.45593923429914124, - 0.3806944350646748, - 0.3685764421023524, - 0.3772735377180935, - 0.42593836600757934, - 0.47135220517077314, - 0.37325369365516947, - 0.37436717587975493, - 0.5863053316417584, - 0.35661734801324113, - 0.5089293274789144, - 0.5829615809622218, - 0.38106238748627863, - 0.5857853506667445, - 0.5401125291007263, - 0.5136479941510288, - 0.5529609228766391, - 0.5430907058200701, - 0.6060734135981808, - 0.5723121154362468, - 0.35359871084715994, - 0.4334117558922804, - 0.38428711336038895, - 0.3717780339154314, - 0.49471636205615077, - 0.4024902047380177, - 0.5811671013327211, - 0.3797670452441879, - 0.47109852489709547, - 0.3461616202579337, - 0.5350342011138994, - 0.43791075754662856, - 0.5460511369323462, - 0.565216562209372, - 0.5094399963926688, - 0.48578590233197616, - 0.5872539139141981, - 0.4008270023886836, - 0.47117734922044624, - 0.4191038584462795, - 0.6056977200396751, - 0.45184791262116636, - 0.3590284770162765, - 0.5977352616069678, - 0.48525292206730575, - 0.6074516453584541, - 0.46554436039050795, - 0.42369881497364087, - 0.47067559085924426, - 0.45267008942262676, - 0.3919739301044632, - 0.4871073723684186, - 0.5384676120684293, - 0.5590342551189883, - 0.5686301309942984, - 0.52629685784497, - 0.5658232903990247, - 0.3778350610321216, - 0.5520011665434325, - 0.386404602767803, - 0.4234732241639996, - 0.4778664520850671, - 0.4544024307184627, - 0.3818238910374095, - 0.39730468286160614, - 0.5668049535935197, - 0.5226206358163625, - 0.45572419171845385, - 0.4813346071728015, - 0.469579768355647, - 0.41993797391417165, - 0.5783733047584265, - 0.5668971346845088, - 0.43070561150833053, - 0.36450953585223383, - 0.43443043658134256, - 0.4712016693200071, - 0.4840456501348993, - 0.5248998190113422, - 0.44949494709967536, - 0.3956778449278586, - 0.5121829942018588, - 0.4618384048227203, - 0.5267347925107942, - 0.44462289243993464, - 0.4526550525279818, - 0.49890116975383214, - 0.5107045371927033, - 0.5253897366076823, - 0.5620774551655525, - 0.4883129203781044, - 0.38709467686968724, - 0.6005200160970801, - 0.3542266094508042, - 0.5751492107194056, - 0.48441701434601725, - 0.43265617648849264, - 0.3544674523618376, - 0.5943533675804176, - 0.5267761342415445, - 0.5763894858341427, - 0.5271241213380121, - 0.3592191830760683, - 0.4178738302486784, - 0.40709670748947496, - 0.35125863735653623, - 0.3788183429582538, - 0.4898196525053947, - 0.3555337909207506, - 0.44470936859570864, - 0.5432514537749391, - 0.3741496066243864, - 0.45725800067355526, - 0.34547925435923665, - 0.487788376849713, - 0.4613572977521411, - 0.4826442900497505, - 0.5628003781792423, - 0.35619022713522575, - 0.3812124910163937, - 0.38505352256221265, - 0.605790217577272, - 0.349416815866856, - 0.5187615460499315, - 0.46146866555680205, - 0.40135402735078757, - 0.460207478636744, - 0.34261312354624274, - 0.3799903297236374, - 0.47726941625831876, - 0.5913398998146797, - 0.4045854185359133, - 0.5891278346959188, - 0.4374151514890701, - 0.35738763295966813, - 0.3525248351055207, - 0.5533867500116006, - 0.49969417896642854, - 0.4643648810054173, - 0.36174877833335933, - 0.5019653880239938, - 0.4339811812168522, - 0.37480910014627, - 0.44597264843567563, - 0.48693957904059054, - 0.5306593140284617, - 0.4380831865954437, - 0.39336447645837225, - 0.6015675148200721, - 0.3468939079020783, - 0.5369352234992394, - 0.39331857395573333, - 0.49856014567735996, - 0.44201321908269364, - 0.36424416828636896, - 0.37125342597053046, - 0.5119284690721071, - 0.3623307521667819, - 0.5417042633164135, - 0.3475571179231943, - 0.47455316314966767, - 0.3711803989478287, - 0.42144550198528236, - 0.3756043102315688, - 0.4702163707253253, - 0.5642207492291764, - 0.5564988198473257, - 0.5260612615880274, - 0.3880994434140918, - 0.535422547236674, - 0.37233737245658316, - 0.4373204698554875, - 0.6054412931823943, - 0.3987251168783118, - 0.5432847947572155, - 0.3731927250900135, - 0.36603854193552193, - 0.5370123072651758, - 0.3856768385267346, - 0.5495487397370384, - 0.5043403628210006, - 0.4581377671788185, - 0.5413836213428785, - 0.602963603814641, - 0.5309843474396683, - 0.5658246692115715, - 0.48736395427555856, - 0.42581962364287657, - 0.487307793214388, - 0.564999668877728, - 0.4586417566840275, - 0.4094908126341903, - 0.3615113589044683, - 0.3635721585045815, - 0.6038223124850606, - 0.39906667677603597, - 0.4868372785937547, - 0.5123389097053194, - 0.45724730132817104, - 0.4955397216362575, - 0.5186824150125873, - 0.4845731459853546, - 0.34536041129603506, - 0.3823797116496993, - 0.44284952862601934, - 0.36979732736235105, - 0.5633155759258658, - 0.4174525925399927, - 0.5860325774541582, - 0.48252953419758404, - 0.4340454697873471, - 0.5664889913720148, - 0.47043422500997956, - 0.5720377897081493, - 0.5575912027978682, - 0.4041122207792169, - 0.5480704318276348, - 0.5993143392110265, - 0.5140063492175228, - 0.3440658798309921, - 0.3766118331037919, - 0.5420509234717317, - 0.3965165047105589, - 0.3749204164081752, - 0.3767200061304764, - 0.42861525502901593, - 0.568995282406549, - 0.4220049137054084, - 0.37252167363623795, - 0.49156356885332636, - 0.47256357663975285, - 0.46439726772536516, - 0.4569302661208675, - 0.477315497920905, - 0.6011464110433786, - 0.4744513124074101, - 0.36697619133648485, - 0.5243914562739552, - 0.4587408969051862, - 0.4152054181292112, - 0.5688709169958153, - 0.5100609250880032, - 0.5423260458282435, - 0.34870370541565143, - 0.49521777455155036, - 0.5192797796028793, - 0.345825474050742, - 0.4845598745831817, - 0.6056972958128469, - 0.38222051289887793, - 0.45850212267175217, - 0.5728764779368047, - 0.3432042206460658, - 0.3946362717965675, - 0.5964822397974529, - 0.5205247012053839, - 0.5222913233314215, - 0.4858988814106598, - 0.41293500764055424, - 0.5597007901531723, - 0.42387325384242514, - 0.5707503916172328, - 0.34774035829739136, - 0.4961642287657727, - 0.4523986539056766, - 0.37848478059649704, - 0.5914172433078867, - 0.5185779384656706, - 0.3417239523881096, - 0.45933736525567714, - 0.598044549514267, - 0.5492443365516928, - 0.49950748379851073, - 0.44052048749180595, - 0.42578074689108575, - 0.5950107951993762, - 0.46565915059333834, - 0.38461608738700637, - 0.4742198602502873, - 0.5643380004927909, - 0.562810286934021, - 0.5871233662879286, - 0.4260410132317157, - 0.5622333803404066, - 0.43805177066293227, - 0.44733077860638537, - 0.3553112781436645, - 0.4629947471165362, - 0.3952475805898368, - 0.4490863361349348, - 0.5023014456892471, - 0.46096292477794654, - 0.37366891254694107, - 0.5354559005676247, - 0.4160530304845248, - 0.5402906947487107, - 0.5862305176955951, - 0.3438938743729029, - 0.5633559367745218, - 0.40594160444474786, - 0.463197916087352, - 0.373099243965012, - 0.5833678416147268, - 0.48940699474056604, - 0.48545005838357946, - 0.4700870141287482, - 0.4010501391416275, - 0.41597629367627376, - 0.490828661028552, - 0.3910772634614243, - 0.54473099713442, - 0.4410369789821863, - 0.411621192453115, - 0.4624060786925399, - 0.4458801651470508, - 0.5118697435249231, - 0.5673378636377864, - 0.4203150015749538, - 0.48537321685543144, - 0.4801750821476951, - 0.38080442938105796, - 0.3588777772135786, - 0.36841217785384917, - 0.5591745186287411, - 0.3472744728242063, - 0.36143774429260433, - 0.5259306376906994, - 0.39945433141380504, - 0.4387440245318839, - 0.5321107941197453, - 0.41972986722602307, - 0.43624407088624795, - 0.5685755134068498, - 0.46780538233041075, - 0.5465036246783694, - 0.5630948922159955, - 0.5624489779020856, - 0.5836333159500753, - 0.4895182263306348, - 0.5004190392670085, - 0.5645945443282065, - 0.4397684504985465, - 0.4327061591036255, - 0.35526256602173817, - 0.3567453289330194, - 0.3870239327049966, - 0.4714327190300249, - 0.40793212599875783, - 0.4994242961596933, - 0.41721716827917155, - 0.5304972725934265, - 0.36611298709491263, - 0.3900569408204053, - 0.5779215888303988, - 0.3631598540778635, - 0.5858011115453455, - 0.4156309626226138, - 0.4421940303825647, - 0.5902637115669084, - 0.4581720060192019, - 0.48960709204416875, - 0.49380047965089235, - 0.47349646675537005, - 0.4156223997113885, - 0.5512015787134226, - 0.46345612526310626, - 0.45420131688038157, - 0.38141296035800953, - 0.3453387383049242, - 0.5502050387866538, - 0.4168427098575536, - 0.5114204717791284, - 0.4216996498857426, - 0.37618708303066256, - 0.39587223349160444, - 0.605178727200705, - 0.5103136253606742, - 0.47853255003690853, - 0.393270189752326, - 0.4495474067028054, - 0.41455517453612883, - 0.5076256399232619, - 0.5826167187109501, - 0.45808567946618556, - 0.47295216542000545, - 0.4358469669028647, - 0.3437843154743614, - 0.595704334358534, - 0.5266303594222764, - 0.4276912208830249, - 0.35376671968723306, - 0.3554343983578698, - 0.5090485371041243, - 0.4507220779131251, - 0.4582943396209131, - 0.5727921932241615, - 0.4184557386960739, - 0.38038264027941904, - 0.5581536417772492, - 0.5736292603198803, - 0.40764186869040614, - 0.4795777600197143, - 0.46057219979427866, - 0.45980780651274744, - 0.34125017957687426, - 0.5557572441087544, - 0.3863343629226124, - 0.5822267562765219, - 0.45036503862155597, - 0.3572207792805657, - 0.4207195745812701, - 0.5311566928713617, - 0.5771569069121293, - 0.5766503165681591, - 0.5937105908978431, - 0.6062578265968763, - 0.4300495119556589, - 0.5718327131212645, - 0.49797809825207573, - 0.5931617335206425, - 0.4824855506923792, - 0.38905472348848547, - 0.39779810457366466, - 0.4118616379657478, - 0.40282731184572607, - 0.3690801718713093, - 0.3645229178623783, - 0.5943183582779802, - 0.5601506661992932, - 0.3576523297314117, - 0.39339095793506484, - 0.52361379843068, - 0.4809908615442905, - 0.430380422271326, - 0.38750512193317715, - 0.4513720856185813, - 0.3891027141387473, - 0.48051386032249543, - 0.4328898885406558, - 0.6073883956200621, - 0.4911960243160319, - 0.4182481668815258, - 0.3996570381056072, - 0.3629742392178112, - 0.35407228699226706, - 0.526257153123645, - 0.49727549839638163, - 0.3505884404194626, - 0.5464131423059072, - 0.401578968126833, - 0.4460925795234328, - 0.5430197564409367, - 0.5868127631694509, - 0.5467089222005685, - 0.4695355884362545, - 0.5778747580844565, - 0.47755739665333274, - 0.5091305484255901, - 0.48178006378560767, - 0.5037550360444328, - 0.5325835217792009, - 0.36865123226193114, - 0.5987902895503201, - 0.5363448868577034, - 0.5841345722697826, - 0.38927862631418986, - 0.50638699124064, - 0.4092866617748159, - 0.4149012017203894, - 0.42436868008612333, - 0.42850269749068204, - 0.602894826576039, - 0.44385424335993046, - 0.5087026894452966, - 0.4638233875796688, - 0.5520345715239271, - 0.4840530702083258, - 0.5201212543308893, - 0.460932243243816, - 0.5396020502973393, - 0.6014794494157422, - 0.5651745250152241, - 0.5226558398972037, - 0.5084704805565091, - 0.5833440726604656, - 0.34527702259951165, - 0.5075207810611682, - 0.3716485419846491, - 0.41360092780997165, - 0.5861284742657106, - 0.4824402906830467, - 0.46176870178965923, - 0.39301447225806735, - 0.5976338737534614, - 0.4608178651477017, - 0.49779619214539705, - 0.48410869872485257, - 0.4670482180379872, - 0.39104057548519827, - 0.5979735803433226, - 0.5854476759211044, - 0.5995866442152274, - 0.46991352159076116, - 0.5788644426285883, - 0.3793654251586627, - 0.584690037396948, - 0.39188825254003357, - 0.3815436693719645, - 0.5651610131753612, - 0.3640011107124968, - 0.43962302814442733, - 0.4548295958177012, - 0.5743829115783157, - 0.5528261771213715, - 0.3680644427274761, - 0.4949813650808912, - 0.3820539433693031, - 0.4979357139668468, - 0.5301466948678694, - 0.4826985315880906, - 0.5509636012481239, - 0.37412627669716964, - 0.3950661656212815, - 0.3487811024652465, - 0.5654534607901051, - 0.5542352428636733, - 0.38344560480173295, - 0.37845944475808024, - 0.40994787070756056, - 0.4098042600279297, - 0.5824528062740094, - 0.3677819042513511, - 0.5667421903982117, - 0.5823098350362161, - 0.4997354606595198, - 0.5577228717543639, - 0.37599816309134687, - 0.36460166186300336, - 0.39776649894842664, - 0.5029836657076963, - 0.5446670584974052, - 0.41635432137191997, - 0.3747724066364892, - 0.5648710418041084, - 0.5229557425354546, - 0.43470589357894773, - 0.5096539890440522, - 0.5493011015673386, - 0.364659006530313, - 0.40595928088074873, - 0.5635193226305706, - 0.48844950906225715, - 0.35559809356832767, - 0.600011817130077, - 0.37656692691979204, - 0.4688931014175079, - 0.4191055274303525, - 0.5917983156040607, - 0.5629791462873793, - 0.4765892715933069, - 0.3489056856214575, - 0.42298416013668316, - 0.4134646286376371, - 0.49036157657622015, - 0.4369761052483312, - 0.5000002109697097, - 0.5311212855627583, - 0.4889066007161451, - 0.38370646646169804, - 0.496763177838493, - 0.34223873459542287, - 0.5633076355260674, - 0.5057857517364384, - 0.3695563858708719, - 0.3468905455666179, - 0.4695972605854418, - 0.4141619667332289, - 0.6012511424376816, - 0.41861742848578715, - 0.40219784676180925, - 0.3508856963239504, - 0.6009730955018464, - 0.5303029268710294, - 0.552270055309989, - 0.3870509336687766, - 0.5084792862736575, - 0.40008537260432153, - 0.48246843532826944, - 0.5121266519517882, - 0.5219039388856647, - 0.5306620891326109, - 0.3679562141849163, - 0.4061084800135673, - 0.3939881887592522, - 0.5464277673350729, - 0.5515407851580473, - 0.5737073040556503, - 0.5319421741875525, - 0.5610022481238619, - 0.4444769927395537, - 0.5468531780208243, - 0.5413089145754962, - 0.4490399287067752, - 0.5310804860651113, - 0.43132031736826215, - 0.425031809249402, - 0.35627977700852836, - 0.391828662156411, - 0.5585938822476366, - 0.5751730360215569, - 0.5460971387714127, - 0.3505415328756662, - 0.35610536257132896, - 0.44287292011606155, - 0.43866971803312277, - 0.6002496439391074, - 0.5173499312431159, - 0.5433434657710117, - 0.4858784378616148, - 0.4186920525554594, - 0.4703120902841126, - 0.42505275108860374, - 0.6024320863957435, - 0.524019716493683, - 0.5518777838819348, - 0.45529456413244535, - 0.5334458534487957, - 0.425198712729584, - 0.441115805578113, - 0.4793604623757344, - 0.5972366894718695, - 0.6062324108620794, - 0.5078091049400574, - 0.45421249985553264, - 0.5766961113418808, - 0.39894580986409156, - 0.39050101407425203, - 0.6013233462563512, - 0.48161778465440014, - 0.44154388594326244, - 0.3464969345224911, - 0.41141568887747293, - 0.6030161355558906, - 0.4371641000633485, - 0.5113923612089871, - 0.5328532752398514, - 0.4170688111212659, - 0.47593253962851867, - 0.603681414298519, - 0.4732769529455384, - 0.49340642519296174, - 0.3554451847761289, - 0.5291490255275522, - 0.4207853285950746, - 0.5011501624702486, - 0.4624766412862178, - 0.5885238569599306, - 0.3724478127845692, - 0.44306831446701844, - 0.37856609230532184, - 0.44057869815649786, - 0.4224483171886429, - 0.3652100480270075, - 0.44210861170660554, - 0.3844104595299572, - 0.39152426694676035, - 0.47587595917086367, - 0.570914664812442, - 0.570242137245777, - 0.5157957516372845, - 0.37464287404659474, - 0.5860840211028387, - 0.38421703526859385, - 0.5002348004547492, - 0.5109270577674532, - 0.5860969529316052, - 0.42933086298940115, - 0.41486111758568067, - 0.5153304777814366, - 0.4182411393011742, - 0.5018162240633419, - 0.43279307284180857, - 0.44579531203820816, - 0.5322029361603091, - 0.5871961565802967, - 0.5802632709945637, - 0.5655812710769048, - 0.5477996499392461, - 0.44060246166685, - 0.5259692464438083, - 0.46844954816988876, - 0.4699842809428605, - 0.5710934768186695, - 0.4642517574591238, - 0.41356934532671863, - 0.46941610197982, - 0.5841602491824366, - 0.5567929810414571, - 0.3513665173974507, - 0.39613104328474463, - 0.5284655633546714, - 0.509506370648284, - 0.35977187236664676, - 0.3648047519307317, - 0.5020882886217386, - 0.5191022325269707, - 0.39328240442584006, - 0.4820738325056765, - 0.45329101346962647, - 0.4793175452988537, - 0.40762876965469486, - 0.361131070320503, - 0.5287169478541102, - 0.5481594819326585, - 0.36719948540243247, - 0.4358641644472253, - 0.5371549727900025, - 0.49362440912066863, - 0.43269426023543056, - 0.41718744143355874, - 0.3837807765687033, - 0.5991559200467184, - 0.47624389040456394, - 0.3947819531136556, - 0.41235829959266024, - 0.5161763569255718, - 0.4932545633005001, - 0.39522137351942177, - 0.5064785973626273, - 0.5922611265887539, - 0.5459657004133738, - 0.4787210564800114, - 0.5534952313329465, - 0.5753993692109349, - 0.4502262334296868, - 0.39779936409766264, - 0.45598457184313684, - 0.5404345164140907, - 0.5358526207842351, - 0.437509209155544, - 0.6068864176435489, - 0.5473513412968533, - 0.40397623272386546, - 0.35742068705397567, - 0.559318633167904, - 0.34626248127803916, - 0.39085976371184633, - 0.38066367245698735, - 0.37703446583989497, - 0.5922138801754192, - 0.5324428994503232, - 0.564334557452713, - 0.5833797361457658, - 0.3471380050002642, - 0.5257455116357597, - 0.6004202824696133, - 0.5973272470410753, - 0.4281849829419391, - 0.3473922168431479, - 0.5679608007020709, - 0.38581286523108327, - 0.4643001921490008, - 0.567446977130964, - 0.5774026614078034, - 0.4122499401133527, - 0.46859659296365413, - 0.3470092896285691, - 0.5676266603884793, - 0.5072991944314883, - 0.47115530361089136, - 0.4699731878548561, - 0.5171983601413559, - 0.41700090704844595, - 0.474030917644699, - 0.4624737739782429, - 0.34201327187107117, - 0.45019533022510555, - 0.5263796044088731, - 0.38480505286385164, - 0.3434692593986602, - 0.5569124348203793, - 0.3945365683990615, - 0.3638436962932965, - 0.44145831408401454, - 0.43482092070023004, - 0.5859426769984667, - 0.5903842742844772, - 0.4302163962513328, - 0.5675014898466846, - 0.46783722320299015, - 0.5405388483068034, - 0.451772431140587, - 0.4900106800891879, - 0.4198275748512944, - 0.5008977080159845, - 0.372062843714078, - 0.5825601485729913, - 0.5624136641957483, - 0.5662513751375922, - 0.43640768356295917, - 0.417360119968949, - 0.37159748499135004, - 0.3663368459618999, - 0.4848374015024614, - 0.5405118482746795, - 0.6061034238201766, - 0.6032756774681289, - 0.5379328704964061, - 0.3439958456498413, - 0.5641359573270452, - 0.3948906107922503, - 0.46494403243446686, - 0.5328090962883387, - 0.5078623834831664, - 0.5701814163583913, - 0.34749601917302886, - 0.5901485441221049, - 0.5092394551857343, - 0.3959609331107027, - 0.5437687545546162, - 0.3790994159399483, - 0.5274211266541007, - 0.46941104913848763, - 0.493645564224092, - 0.5140882173719808, - 0.3607377608420632, - 0.5307025734064756, - 0.5865318472958503, - 0.578674015374796, - 0.3840989082506972, - 0.3572174197084665, - 0.5345465646148913, - 0.5573905285180834, - 0.3997596835393332, - 0.3934350497539687, - 0.3608918460695084, - 0.4432696215756754, - 0.5872731913329365, - 0.49111586604328694, - 0.373667943710018, - 0.45668820840474433, - 0.5247495297137788, - 0.37304070535325323, - 0.5655014458510781, - 0.4880975354956855, - 0.4728743440775973, - 0.4852589543887331, - 0.5211382244829801, - 0.3681153028192835, - 0.5883853568846613, - 0.4849228161139142, - 0.41468918686369954, - 0.40965754059041254, - 0.343393320193682, - 0.6066472892570084, - 0.4465169537818027, - 0.559836873395669, - 0.4511430045355601, - 0.5222701301094441, - 0.3495216635636515, - 0.41940700601411646, - 0.4088154557328828, - 0.39478295348538983, - 0.5282867810843822, - 0.3743979046656387, - 0.5535542252153165, - 0.5135138535629309, - 0.3442700601487605, - 0.4214374290607636, - 0.5149767872479609, - 0.5478982956722004, - 0.40369816650991264, - 0.3959137294123751, - 0.582295441642607, - 0.3703035596211211, - 0.3639299244363224, - 0.43949922529567576, - 0.5967422058144787, - 0.42761486243568747, - 0.5835623043890609, - 0.3765502698104801, - 0.5710841111232354, - 0.35004748583744133, - 0.3648000797120282, - 0.3976322036051092, - 0.4744623389810701, - 0.4322185745604355, - 0.4611441895398234, - 0.4470469417982491, - 0.5113507043137422, - 0.5733724104323815, - 0.4472487185854437, - 0.6048111615737413, - 0.3460304535630738, - 0.48105121477850843, - 0.5313306397034293, - 0.3645444342090415, - 0.598852993644403, - 0.5550215926381291, - 0.39585895754998174, - 0.5820101336331552, - 0.39530797658424105, - 0.4757668916140924, - 0.5804823315308345, - 0.5137485457996178, - 0.5884756911588035, - 0.4754113752325224, - 0.49076370478525766, - 0.4693439056690016, - 0.5139036073899077, - 0.4842753744263778, - 0.559074695576061, - 0.5308432188371117, - 0.5191753153261178, - 0.5960788200220881, - 0.3522458282581329, - 0.4539574221008101, - 0.5482479854062349, - 0.3558507313454642, - 0.5305720207051022, - 0.5935521937922867, - 0.6019875834898445, - 0.3677686410280343, - 0.4561128845309906, - 0.5677233641940589, - 0.6008488177326224, - 0.5709346760542268, - 0.6065195805492309, - 0.42921489183596206, - 0.3907517048959432, - 0.5202765116302817, - 0.4869480928569118, - 0.5804592674687689, - 0.3555954457207898, - 0.3737826263572326, - 0.4918013155645874, - 0.4789075261457857, - 0.5569292160026967, - 0.5918986609931349, - 0.4774049416812103, - 0.5251309927171721, - 0.37622893213511743, - 0.5367649149810325, - 0.5200556787822774, - 0.48585684380685745, - 0.36746941118793014, - 0.3504144909631903, - 0.3546429891811521, - 0.5660053152046313, - 0.5721780503065808, - 0.5682009546254901, - 0.4530636507320803, - 0.44429489920583154, - 0.5694766869478887, - 0.43915435347020954, - 0.35465900912768644, - 0.41024635885887756, - 0.40448817757323313, - 0.5261038431042016, - 0.4570117667405817, - 0.46562678417122577, - 0.39971027684784805, - 0.4981824629293409, - 0.5759615515096852, - 0.3724624940372981, - 0.5770631236900441, - 0.36990061544106634, - 0.4341166775822083, - 0.46148252740269097, - 0.4171712689290905, - 0.34602200295925845, - 0.3517899585054631, - 0.5987405697049963, - 0.4713507543161679, - 0.5689535653298192, - 0.6031863668566751, - 0.51088811349767, - 0.47976329772664206, - 0.5946489557784276, - 0.34243786376367924, - 0.47816156323227, - 0.4946104589166014, - 0.5594041130815413, - 0.4143872636016822, - 0.4198877071634649, - 0.3532714534580506, - 0.37651955214480914, - 0.47624143065079516, - 0.5135648746053688, - 0.5404308774183231, - 0.389500512906384, - 0.48675976770616874, - 0.46214400519591947, - 0.34789040966450213, - 0.3544543480584944, - 0.5281427836513264, - 0.4834667608380754, - 0.4664120249091887, - 0.44002047438692576, - 0.5065050997131403, - 0.5179882969949285, - 0.5554751528313422, - 0.356026965533862, - 0.4483228951414117, - 0.5393320055967439, - 0.4329543892111828, - 0.5497121219164326, - 0.5134689540483622, - 0.4884442862457684, - 0.5698882919124081, - 0.5993856859230287, - 0.6058209144144544, - 0.45951765458461713, - 0.5821240414709833, - 0.518957014552565, - 0.34150460952778805, - 0.4858431587887959, - 0.43595318798496363, - 0.4395244862971496, - 0.36574765579195034, - 0.49134564432101024, - 0.4683710634392918, - 0.4219523061092252, - 0.44814764802209517, - 0.34528163299237574, - 0.5823911196981766, - 0.34149086541454515, - 0.48819098983151027, - 0.5701729694009546, - 0.47092364277394183, - 0.4226641997127095, - 0.5837118949782591, - 0.49746863910139494, - 0.4657360309983918, - 0.4905029621970316, - 0.5376121699481634, - 0.47397373353035904, - 0.4830536446076111, - 0.5767464617534703, - 0.470691342717877, - 0.5644633121820126, - 0.5863199526913101, - 0.40420047891907196, - 0.39755345641695994, - 0.5538966815026581, - 0.5008824123424567, - 0.3737221531096048, - 0.5149637772698328, - 0.3834133155008275, - 0.4249427989267169, - 0.47579532239346956, - 0.4660155924053905, - 0.5707858448562337, - 0.5699252726463766, - 0.5532737227095872, - 0.5522154463895019, - 0.47429694164093505, - 0.4544489050031495, - 0.5731731389111667, - 0.5322910605048028, - 0.4839729798732396, - 0.36467990216799184, - 0.38432563967231836, - 0.35957443127297456, - 0.5906800017389878, - 0.34645397245125703, - 0.39091988997719923, - 0.3848332019082021, - 0.4715693855009661, - 0.5266316042716914, - 0.34684054782187773, - 0.34855266133987595, - 0.5994990199566795, - 0.5029368671219209, - 0.5695850316694051, - 0.458076530365192, - 0.4956063557413368, - 0.5067296376475224, - 0.4763475896242703, - 0.5829473364548814, - 0.39075815811805004, - 0.5450002593763409, - 0.38869035499641447, - 0.5743012747548941, - 0.5774946365903953, - 0.5024150771701814, - 0.5495888312897252, - 0.3657862237389591, - 0.4843248281163902, - 0.370096743260127, - 0.5362987040119, - 0.5173002014741588, - 0.4951406353323875, - 0.4237568936837267, - 0.3712469477529068, - 0.549147071062476, - 0.5230235825142091, - 0.5250253074799901, - 0.4920321190784082, - 0.43921442443358794, - 0.47122593403692314, - 0.4583082347517169, - 0.4643907097798591, - 0.3647914109364705, - 0.44375725062944255, - 0.5155370485521075, - 0.5575363822075549, - 0.5984778144125309, - 0.3886879106230864, - 0.5474294528123468, - 0.4743804617805184, - 0.4761327737603044, - 0.565857067100405, - 0.49650733450444096, - 0.4601512993183491, - 0.4917651113935273, - 0.44501725294122174, - 0.43903745481763407, - 0.4016396117973403, - 0.3577730973540187, - 0.505403227571768, - 0.47456627889745784, - 0.547198055179868, - 0.42335695190131184, - 0.503695219392275, - 0.6033187350517535, - 0.4477076329642996, - 0.4842381915613864, - 0.3449953675627985, - 0.471835833748945, - 0.5472353469599572, - 0.4434390663485666, - 0.44753283457625037, - 0.4335882513416939, - 0.5824167239850992, - 0.47894887839193545, - 0.5272095632268465, - 0.5078053706833223, - 0.5726813351055593, - 0.4225344695252811, - 0.38589849452461666, - 0.3750515583215873, - 0.5024321017490514, - 0.5204654123975265, - 0.3702976989869829, - 0.3792972052300271, - 0.5234878758663732, - 0.5588953031988377, - 0.593614094337761, - 0.3586762243593869, - 0.5618298216852471, - 0.41738068203148576, - 0.46036901227969995, - 0.3836721623758067, - 0.45060741290574213, - 0.45761345284610594, - 0.5090778733717967, - 0.5657991318680067, - 0.5071182588143011, - 0.5451202840160405, - 0.47897244912445935, - 0.5958904795183888, - 0.49102470192837355, - 0.6067936320656305, - 0.3780071033093939, - 0.5825276687411751, - 0.45443528755822954, - 0.5209601700631128, - 0.3781906112578498, - 0.4532466846082218, - 0.5280294548249118, - 0.5935696816911536, - 0.5323728617608161, - 0.5904641290861875, - 0.44906107451856697, - 0.3905929174669371, - 0.5086470163509907, - 0.36238713750838814, - 0.3961575664876973, - 0.5057007807764886, - 0.4813679743078634, - 0.604412417286877, - 0.5522107377789962, - 0.40106349952596987, - 0.5562927740636022, - 0.5647262485652431, - 0.3895753588271701, - 0.5046162266358994, - 0.4087592949589765, - 0.5536254368227302, - 0.5926355257940781, - 0.5920934788219747, - 0.5261319483250526, - 0.4957319166232663, - 0.5190132187478506, - 0.43734455915692727, - 0.35812077730890635, - 0.5623079492988083, - 0.4878677424349044, - 0.5098346902573396, - 0.494664482895344, - 0.5672837590807926, - 0.3607635929182386, - 0.45795487808838886, - 0.5675155129864495, - 0.40339477951946356, - 0.5983797114417004, - 0.597385668970684, - 0.5227130284111274, - 0.5165561759316293, - 0.4799873403317158, - 0.3976284942638267, - 0.5031673120388171, - 0.3978030174459169, - 0.522106706914395, - 0.590653206035138, - 0.44278948245742744, - 0.4386303672880802, - 0.5604897241496405, - 0.34653638322198016, - 0.504261242629784, - 0.5797301098940912, - 0.41134131873804936, - 0.5046560135571326, - 0.4833439805419989, - 0.3758263664536135, - 0.44978199927716733, - 0.5001788430756449, - 0.5907321051800793, - 0.4222995914660374, - 0.5590305923250589, - 0.6029767852600068, - 0.5340033965423121, - 0.5034935183670421, - 0.5131650410007257, - 0.581755355364706, - 0.46011556639662876, - 0.5385781047238366, - 0.5663183705722679, - 0.5576963075635891, - 0.46960242184052425, - 0.400478776041546, - 0.39921052395909346, - 0.6035974104398611, - 0.43077981315705627, - 0.5395370643138631, - 0.46291669080702663, - 0.3516941552442199, - 0.5822351994694762, - 0.3735975791899136, - 0.5716624663590919, - 0.46879475462080955, - 0.48816922856378875, - 0.4348107883843224, - 0.5527210158686148, - 0.3462129475783856, - 0.437668813225119, - 0.45398361266931764, - 0.45252915779414904, - 0.44082766067008256, - 0.571693984421884, - 0.3974536784799768, - 0.4203774209064467, - 0.37004100725958616, - 0.6023415544134177, - 0.5607789947674344, - 0.34214072491560066, - 0.40474447338640385, - 0.42091444359644614, - 0.4735040418746259, - 0.4370139922059038, - 0.42710397829133867, - 0.4813719951863104, - 0.4129671175881058, - 0.5044804374508585, - 0.5016479619431254, - 0.5941994195498617, - 0.5823968323521261, - 0.4701113363802019, - 0.4802095254835834, - 0.5012998232480464, - 0.541992343498247, - 0.5121212012819445, - 0.5591365320624495, - 0.40247189303756353, - 0.5210939488482902, - 0.45101805788071825, - 0.5043138926474448, - 0.5772985986066969, - 0.4716641735381307, - 0.3459072202373014, - 0.5954124019932168, - 0.3873075873960608, - 0.43097655837316384, - 0.4151877122248693, - 0.5713744577807444, - 0.45715808683145037, - 0.38326756628546005, - 0.5319350111535439, - 0.519806867156658, - 0.4008698554323408, - 0.5399730071742894, - 0.34910975232956304, - 0.5343339985736141, - 0.5936681080734139, - 0.5974876287056963, - 0.49703431371897056, - 0.5217598513243877, - 0.43749613139740046, - 0.4991513301229619, - 0.4732297030987782, - 0.5915849840441882, - 0.3934490717325936, - 0.5092012639206055, - 0.37223464733700995, - 0.4035982291530634, - 0.5852440269673262, - 0.6071191407576472, - 0.5997719720131358, - 0.3521013171715909, - 0.601724913434594, - 0.3733029341598839, - 0.4449180553499292, - 0.44670758269238975, - 0.5485365387393195, - 0.40615791871476625, - 0.5108702656952671, - 0.44589286973325926, - 0.4884132849545837, - 0.5992836344578305, - 0.48205373502240867, - 0.34564099166510776, - 0.4328075589338448, - 0.47892340830025504, - 0.37481696642389223, - 0.5212899919293463, - 0.37842480328219474, - 0.4923977338141691, - 0.4364907593165683, - 0.47587484554020604, - 0.42019841736010893, - 0.3698744302763331, - 0.5880647889451256, - 0.4040544699014921, - 0.595027371365836, - 0.46459440123666046, - 0.42602632911939115, - 0.3475582972398608, - 0.5764929316615062, - 0.5424990140841538, - 0.5311635603461717, - 0.3722118726551341, - 0.5242338250695099, - 0.4335675949280007, - 0.39250497045910215, - 0.512532929952984, - 0.5145646433344467, - 0.5529553000787272, - 0.49387560451724755, - 0.346536989651044, - 0.417907951271126, - 0.44731248683336067, - 0.5271414419244951, - 0.39912782531530133, - 0.5400391209910202, - 0.5596542436906078, - 0.4125788900763856, - 0.4206073351908389, - 0.3788635873731357, - 0.5596414977137669, - 0.3522436544324449, - 0.5677690983420309, - 0.540354132488851, - 0.5488643714710834, - 0.5810043073480815, - 0.4279494245954359, - 0.45571630372698, - 0.37506181156147456, - 0.5894363670106264, - 0.4930742807416797, - 0.5841310497886043, - 0.5998932493776483, - 0.5947239190736979, - 0.36679464481645147, - 0.5982747587160111, - 0.45992683438857496, - 0.38537851659094635, - 0.4615025463949791, - 0.5971143173467043, - 0.5277364344547224, - 0.39114049240478144, - 0.6008324982668809, - 0.3961105902281261, - 0.5915360171793451, - 0.5831168646409269, - 0.36098739147600867, - 0.3419362570292779, - 0.5572174527453038, - 0.457923771629149, - 0.43129614950135714, - 0.5178825180505575, - 0.46466835838982495, - 0.36544629716169635, - 0.43266785961139265, - 0.4021908479370423, - 0.5744105715621559, - 0.5686870973596833, - 0.3680529416898909, - 0.4903914992933715, - 0.5453064846945199, - 0.47442137559913256, - 0.591503958423782, - 0.380728466654642, - 0.5689459633978493, - 0.5508907698930872, - 0.4224918561359484, - 0.5936325579714719, - 0.39215183895125205, - 0.4529734171729353, - 0.3469129238902181, - 0.4314419249816683, - 0.38334697433608056, - 0.5436899263148411, - 0.3641271171845005, - 0.4241119213507395, - 0.48155639713355364, - 0.449139046774904, - 0.3706756462326638, - 0.4798353566427822, - 0.3700891914970429, - 0.34235714436599224, - 0.5500710890729612, - 0.44821888404261917, - 0.3903444878597054, - 0.43709871365488234, - 0.4510532979454064, - 0.4594557014881545, - 0.5135886634695406, - 0.5633922471625707, - 0.4383884087025855, - 0.3552130183224168, - 0.5184019191747087, - 0.4276127961477535, - 0.5162974805899209, - 0.34332630362375666, - 0.35676309319277555, - 0.5913361742253135, - 0.44610818852244316, - 0.3935449140459696, - 0.4920029864995243, - 0.3882269998825654, - 0.36649023767574124, - 0.4890105870390613, - 0.39335827469356055, - 0.4688768887978604, - 0.4997540310859362, - 0.3418400476985648, - 0.43626926262450183, - 0.41267208098648683, - 0.36629738712429255, - 0.6074664344180866, - 0.48929641232407667, - 0.46391553464193536, - 0.3740877047011589, - 0.48115527067829134, - 0.37966477514112545, - 0.34250105807292286, - 0.4912859977711309, - 0.34379043780102886, - 0.5838124794649393, - 0.35360041567600875, - 0.37429217713928914, - 0.3724630215753679, - 0.40326531763365586, - 0.41629852309486703, - 0.6016944351680409, - 0.39913490000006124, - 0.4278913101230549, - 0.40272050258015907, - 0.3903072384416554, - 0.559903397118928, - 0.49727754120318046, - 0.5187675969852753, - 0.4975295957161495, - 0.585554168684486, - 0.5084001990955314, - 0.391701969234127, - 0.39944264994412926, - 0.6051774718704273, - 0.34511613268827973, - 0.35078965367531956, - 0.5057073935346219, - 0.5923236640836789, - 0.5453576095783862, - 0.36085344941020625, - 0.4133714887847928, - 0.40854910753881635, - 0.4347092379364686, - 0.4126268611580694, - 0.3997037220203131, - 0.4913830597225295, - 0.4582023432222499, - 0.5072154780633854, - 0.3572205104303414, - 0.5136833559838432, - 0.4295656537352782, - 0.5476209704089816, - 0.3552848552124917, - 0.46746622705855534, - 0.3647275912385317, - 0.4874197562913253, - 0.5000377438703938, - 0.45975051326899746, - 0.38580663499312023, - 0.3918695994902058, - 0.5608777722515441, - 0.5400018136188159, - 0.5533310770302281, - 0.4772632785498062, - 0.5332677345736225, - 0.5204048138390205, - 0.5520297504253833, - 0.3679866466694846, - 0.5884779855904613, - 0.42769001087389047, - 0.46401649102419307, - 0.34918739263106574, - 0.5187020689567168, - 0.5425677072157232, - 0.5681116622271386, - 0.5443208331118151, - 0.4160927999884095, - 0.5268745081254159, - 0.5398006250847165, - 0.3849742095053288, - 0.3727442846320017, - 0.47337020760573184, - 0.48347322942303367, - 0.3907315482748321, - 0.4244851048370886, - 0.44001619412291937, - 0.5893045045324475, - 0.46465444543165013, - 0.3634207626365035, - 0.3950765065986035, - 0.6047077876204787, - 0.4098654225965914, - 0.551204142417468, - 0.49688938937664606, - 0.47076213599869465, - 0.5068539131646489, - 0.3807246829262258, - 0.38067800940673213, - 0.4538419103453752, - 0.4600826430033671, - 0.5340216522864689, - 0.36509890927320576, - 0.4214738916362818, - 0.569871284589341, - 0.5543740013382217, - 0.5167120262927474, - 0.3968792955996972, - 0.3778601032327837, - 0.37153465769039196, - 0.5745846720245934, - 0.38865087211598337, - 0.4895991416081877, - 0.383197498629208, - 0.5255986057282869, - 0.34790345654789684, - 0.5099653918602463, - 0.5095168839500009, - 0.4207702693166155, - 0.42954089120450073, - 0.39254026609205944, - 0.4007114321392893, - 0.45529865357396176, - 0.5240445669041448, - 0.5771929969808298, - 0.4204596203180939, - 0.3500870949167038, - 0.381135899139763, - 0.5818442691918664, - 0.38945379988614404, - 0.3423098804219534, - 0.47717959776044494, - 0.36457841980673766, - 0.393385446899411, - 0.3984245585464987, - 0.5883908423063522, - 0.4041872077675681, - 0.36939965405345315, - 0.5615059873314738, - 0.40992605078222777, - 0.4918106335476047, - 0.3928376603825265, - 0.5267379926754716, - 0.4614809616411724, - 0.38827682411310493, - 0.40594598536619564, - 0.4002433077273559, - 0.3497913830687303, - 0.4781696104635077, - 0.3414788999182605, - 0.5703053390935924, - 0.5097854729057353, - 0.4529116283362318, - 0.5083335464525203, - 0.5987837162464902, - 0.3884784154060667, - 0.5385308401025692, - 0.39708311571965665, - 0.5167347867414727, - 0.4242661530047943, - 0.3411885852533423, - 0.5445958413574707, - 0.5663409284192276, - 0.48480820343110353, - 0.3713793218614828, - 0.38020699303039407, - 0.5294822870589435, - 0.5750736137767595, - 0.3642299163669337, - 0.41270311844065366, - 0.5833371957133184, - 0.4813444427566243, - 0.3627744644587118, - 0.47251915975372194, - 0.34137481158666644, - 0.39343826698311946, - 0.5114240009276504, - 0.43709432697066214, - 0.41667524496223945, - 0.3758381450641613, - 0.42752412715835414, - 0.4573916287015163, - 0.48645247842772754, - 0.4272193254903053, - 0.5400170416382577, - 0.4956599616460471, - 0.544271497624742, - 0.4970515047509537, - 0.6058227734098991, - 0.4305034321937202, - 0.4309935507290957, - 0.46205229967209344, - 0.34970632651195793, - 0.5737867371802711, - 0.5009394699197431, - 0.4826382759841752, - 0.4787146566527033, - 0.4597996058691921, - 0.5230942687437785, - 0.48475854808454544, - 0.3966273427427452, - 0.586364655625246, - 0.5923224685951092, - 0.34892795120330283, - 0.5887917830686717, - 0.351521254036404, - 0.597290809048604, - 0.5174872642400983, - 0.4137998031215848, - 0.372240027544362, - 0.5237118369485276, - 0.5338577886242866, - 0.5492853051651385, - 0.3825044442963137, - 0.383285002551392, - 0.43417547326286515, - 0.4062538574734079, - 0.3935902412161791, - 0.5213598441781024, - 0.47367235895290616, - 0.5248862593214834, - 0.46743733895717426, - 0.4830331352031305, - 0.5371735997507262, - 0.5043286114024138, - 0.5831024760055453, - 0.5846215387690342, - 0.3626002138831306, - 0.43510405088476717, - 0.3721655667180501, - 0.5552185664992114, - 0.36338583981280154, - 0.38674404341355223, - 0.5055639079402703, - 0.4211923143897498, - 0.48064686668167256, - 0.39710529287933544, - 0.5295440771714732, - 0.4998455389007025, - 0.4156717115150133, - 0.397267273770501, - 0.4996795757797521, - 0.4480929406439922, - 0.4449212211481069, - 0.3578000593232174, - 0.5553667164218544, - 0.4678283872543554, - 0.5183257739474413, - 0.5288359935927611, - 0.5519967648094677, - 0.5517873233699306, - 0.4773242067858652, - 0.39575454402181764, - 0.4799154380164413, - 0.41686156787527845, - 0.5008112254901099, - 0.4058004100692964, - 0.41158155433580484, - 0.34475975583327134, - 0.3442510880504321, - 0.40401566002428135, - 0.5714549301323948, - 0.4402087340725136, - 0.4947345041333346, - 0.5412025500120745, - 0.5241689051654169, - 0.34222214824981273, - 0.3735759715225314, - 0.55826319366802, - 0.5585894044863704, - 0.5302291462403189, - 0.46102173890706677, - 0.5159008295550984, - 0.4370887457483057, - 0.5548028540916912, - 0.5548333118679825, - 0.351406317878043, - 0.4534911415584578, - 0.5841200356782686, - 0.4580904856382134, - 0.5620763661316551, - 0.3557330268074045, - 0.36819051992942353, - 0.5240540220873334, - 0.5315099911858809, - 0.5137267161849198, - 0.430763695374527, - 0.3595220371261201, - 0.4540242895139506, - 0.40333042059344265, - 0.4535363434495942, - 0.4630769882972854, - 0.4853290677213228, - 0.3448909568947941, - 0.40685767032005593, - 0.38337008957040536, - 0.49229940615302953, - 0.5129651360114913, - 0.49141613525500905, - 0.5255727253790384, - 0.38004825128709147, - 0.4329659904115168, - 0.5500235148228885, - 0.5912333105760745, - 0.5746835172603368, - 0.5543641333784942, - 0.5536975944359347, - 0.46468959138921073, - 0.5564452621367266, - 0.5991182494296027, - 0.5721753214470617, - 0.4150348159555953, - 0.36850232592127663, - 0.567241210216017, - 0.44662733448926534, - 0.46301093825639406, - 0.564965508580315, - 0.4160400088918695, - 0.4510916165724716, - 0.389761043203716, - 0.5239818441059906, - 0.4950709141508422, - 0.5768673801820388, - 0.437809405298741, - 0.4948668919813999, - 0.4025063832900456, - 0.5867752147147857, - 0.5874999222180233, - 0.5576597116872626, - 0.5291178095767435, - 0.4580411176820145, - 0.4583705615744973, - 0.554604973292439, - 0.5577044130435422, - 0.5387560254945231, - 0.5613873157057301, - 0.575421484151117, - 0.44261561211221057, - 0.4450586608612164, - 0.3645856135427268, - 0.37695051429643844, - 0.41798698305826754, - 0.4183488578877683, - 0.5480086205513909, - 0.40763245237979095, - 0.4707049135735989, - 0.5079415805523493, - 0.451372851429892, - 0.34927030294909645, - 0.43683363125392527, - 0.37916923742005376, - 0.5289833365825204, - 0.5601416129859287, - 0.4111902095231964, - 0.524589947194502, - 0.40815028486489224, - 0.4283270661428335, - 0.3615722453926818, - 0.6034060126314916, - 0.37859348951440813, - 0.4717420863729158, - 0.4635673595352632, - 0.4985916648114221, - 0.5416300222264527, - 0.54883804682161, - 0.5530708091635006, - 0.44651362468378325, - 0.3672239263068148, - 0.35842150056125766, - 0.41968597491730786, - 0.5014301141346466, - 0.4782744789362869, - 0.4354337968334267, - 0.446263083789423, - 0.4776611200055896, - 0.40707014709005607, - 0.5793909048013394, - 0.5929466064379292, - 0.40823173090963216, - 0.589355957862494, - 0.5223563928941342, - 0.415519337991591, - 0.5680415547422528, - 0.539633688774512, - 0.5319034481124587, - 0.35622423345998483, - 0.4054859181407606, - 0.5091489567860088, - 0.4774141773261595, - 0.41944229735658556, - 0.54092184775684, - 0.44691065903840665, - 0.46920751659240834, - 0.6017623629313197, - 0.4991337311351475, - 0.5977526729559919, - 0.4006779571688617, - 0.48381281841195134, - 0.5119331907423459, - 0.48270256565146175, - 0.4975244408113628, - 0.3675105655794304, - 0.47301817791355805, - 0.4122024433957162, - 0.5241380214222524, - 0.4670801937286404, - 0.4728537784356728, - 0.5590319908074751, - 0.378466258539071, - 0.5747264235501557, - 0.34645381332576297, - 0.42960485017231137, - 0.4881331906380566, - 0.38140210476046527, - 0.39607154710216397, - 0.6053485232672091, - 0.4285824300000046, - 0.4318358220386066, - 0.5285443035198489, - 0.500566148427715, - 0.4480597135722135, - 0.4499564316862005, - 0.5549101769795989, - 0.47620771388879896, - 0.3691688263728796, - 0.5859970470841185, - 0.3676223814695163, - 0.4841121757047685, - 0.3690730973051444, - 0.513196622034859, - 0.36408234604989187, - 0.49096087275831174, - 0.6060400769100164, - 0.539728149909178, - 0.49516462487182245, - 0.592791822527154, - 0.5509611897495419, - 0.39270275378863634, - 0.5474711420761857, - 0.4200106439609876, - 0.44787324661189, - 0.5151962792014102, - 0.45753591889491013, - 0.3464547802296827, - 0.586370419678967, - 0.3998134711705603, - 0.5607621957094835, - 0.47076905764088783, - 0.3601098410939672, - 0.4987166046783881, - 0.4363547217619918, - 0.46782380841604265, - 0.4163549086597488, - 0.48469665591761624, - 0.5824142160115512, - 0.441184814096548, - 0.4578671050919416, - 0.4230268230986026, - 0.5387602042919764, - 0.46501641388326675, - 0.43859268530553713, - 0.4375734246699945, - 0.34253304911026916, - 0.476698314384301, - 0.4296640313408992, - 0.49661564441789074, - 0.5297974539693031, - 0.5762243720327239, - 0.3561106409989898, - 0.4689415981683758, - 0.46361058174055303, - 0.37142021566183414, - 0.4698112299188447, - 0.5615547067809443, - 0.5472472615475871, - 0.5179319666066513, - 0.512822187479498, - 0.4178557637079845, - 0.4740227323028231, - 0.5318912244564038, - 0.542626881127761, - 0.5700183959477447, - 0.5247567401902204, - 0.34573598548861334, - 0.5979566894613755, - 0.49735860610456395, - 0.39801069366411995, - 0.4918062104483265, - 0.5330773555821162, - 0.5382031726994014, - 0.3628490469013822, - 0.5779800650155372, - 0.43646865480474173, - 0.4339106955338005, - 0.348419953680698, - 0.35268365317094275, - 0.5616270400385045, - 0.5512456962144441, - 0.35752837967505097, - 0.4954440322444712, - 0.5023033244843494, - 0.47160346945548415, - 0.40606730537272306, - 0.48374442501841053, - 0.3500597911621852, - 0.49238336525407245, - 0.6055041287717009, - 0.4117080963886307, - 0.3558826281489457, - 0.3543922696932283, - 0.5055606283167466, - 0.39874755174750576, - 0.3408594237640574, - 0.5451509246422763, - 0.5773693402742773, - 0.517014845383349, - 0.47191770841892544, - 0.5578997936308838, - 0.4856564239558189, - 0.5444237501367024, - 0.5255593829621887, - 0.3777746915252527, - 0.36078294797582156, - 0.3902434036499134, - 0.412617181274476, - 0.3644918752091448, - 0.5445875453431477, - 0.5758737525129956, - 0.4629527447239072, - 0.3971536916239647, - 0.5213562308909236, - 0.42857942085452466, - 0.35349703765073914, - 0.4067896653619118, - 0.5559190750562196, - 0.42062792438274543, - 0.5227512322031312, - 0.4491767086096571, - 0.5479535347567401, - 0.3731828850590343, - 0.5955665274196172, - 0.5665146035684071, - 0.5389758329341348, - 0.5602975527741487, - 0.4423687494335502, - 0.46527386293054385, - 0.5338313110560828, - 0.3953867057376289, - 0.5936726984395257, - 0.37484077223969575, - 0.49133352717758544, - 0.5671971118682897, - 0.35186113820271275, - 0.41589487825669835, - 0.3539477546610759, - 0.6051933242646395, - 0.531005373289706, - 0.5953481803061773, - 0.4178666902979937, - 0.5606855343401739, - 0.34940007180050425, - 0.46547736221437563, - 0.601957536955557, - 0.5884186323915922, - 0.5580939776988318, - 0.4465817458393127, - 0.5479061154664016, - 0.3784427375447932 + 0.4905591618699666, + 0.5516717616766008, + 0.4790742675747113, + 0.480645760625706, + 0.5432644053176138, + 0.5312480726488219, + 0.46803891731613156, + 0.43565338893117883, + 0.4215833909281689, + 0.4428606237063729, + 0.4973339306971872, + 0.43501729528375643, + 0.49409614858853107, + 0.43626095058543557, + 0.5570138846496575, + 0.4467076142209238, + 0.43820595942077367, + 0.4818910799475662, + 0.4991522355419699, + 0.5040113775498051, + 0.48394403960496185, + 0.5457881061457825, + 0.4553876727381054, + 0.507106251523887, + 0.43504953951425435, + 0.5087395445647241, + 0.4614453304374614, + 0.4871352467805301, + 0.5034182376027745, + 0.541897302640506, + 0.5166700038252846, + 0.43197292112412905, + 0.5244349057659807, + 0.47229352785711975, + 0.49545451597337736, + 0.4351632305082429, + 0.4204530923461802, + 0.5014815436528849, + 0.5597087754286846, + 0.5153402893418058, + 0.4241838688365221, + 0.4428547420351033, + 0.49512895882765934, + 0.5278258597727286, + 0.5373097550051186, + 0.48716980585872766, + 0.5261363222839406, + 0.5149289450815936, + 0.4601743627885638, + 0.559732644994293, + 0.5494482312676707, + 0.5280078802383266, + 0.5359802363005264, + 0.46321752299367236, + 0.43158147519649553, + 0.5165475001267693, + 0.5383362241681406, + 0.528744468853051, + 0.5419829726846053, + 0.44617142047073677, + 0.4463461226929807, + 0.46106698722152106, + 0.5177982110271153, + 0.535256235606594, + 0.536350688595701, + 0.46809196920991686, + 0.5032043400996469, + 0.4276792740037433, + 0.49920946760897394, + 0.4608768073953631, + 0.44424496442264394, + 0.5504287567482792, + 0.47796942562117833, + 0.5376494011849174, + 0.5019674716996712, + 0.4676118369098697, + 0.4772439858789415, + 0.4333540800606849, + 0.5234071955246892, + 0.4958726850427261, + 0.47189533596378674, + 0.5002299394447363, + 0.4919430565661693, + 0.4830465928482867, + 0.5214003259890607, + 0.4400266957470094, + 0.46177618957706695, + 0.5077149879987751, + 0.5298025837421618, + 0.461494226890884, + 0.5130870748258489, + 0.5588283106487462, + 0.5283703690808557, + 0.4536821945176296, + 0.42315021557559473, + 0.4267041153778884, + 0.42941911676780037, + 0.43753245013600567, + 0.43773575964586076, + 0.4666301357878745, + 0.4238310561875971, + 0.4641099062078938, + 0.4814752431861758, + 0.5319964872988311, + 0.4283931945545535, + 0.5578248335591258, + 0.47736256698968993, + 0.4936416038747841, + 0.4561656524257176, + 0.532321643608201, + 0.5005300885474115, + 0.5259713079942137, + 0.4667581158087286, + 0.5165925344207315, + 0.4540160847040554, + 0.5499753540527009, + 0.5349494623189285, + 0.45502856433569094, + 0.4659050479660257, + 0.48200318718544655, + 0.5079258189016995, + 0.46753606649412, + 0.548372954199307, + 0.45203087562281286, + 0.5143354445396339, + 0.4298780149685375, + 0.4713006871245582, + 0.5326088885048545, + 0.5247896408121969, + 0.4205642786455023, + 0.5063579054588674, + 0.42517766164806614, + 0.4855292919833238, + 0.49658885210186976, + 0.4750542852507247, + 0.533527109736083, + 0.4999205184682987, + 0.42268389142263313, + 0.43000459700346416, + 0.5187921016388372, + 0.5385550138253897, + 0.5303492826446319, + 0.45663395365377674, + 0.4342176250041899, + 0.5448767670585315, + 0.5463985268354181, + 0.5245818880978801, + 0.5354781543853468, + 0.42641874806170116, + 0.5138731068335951, + 0.5216590241318608, + 0.46650498228856446, + 0.5167681532737276, + 0.4247354869990692, + 0.43408386636981666, + 0.5534403228839637, + 0.5083426027795693, + 0.42631163324486016, + 0.42124745648844464, + 0.4646693666881031, + 0.44488758158325614, + 0.5208691178396178, + 0.5480716641464831, + 0.5326835112574649, + 0.5377991744385804, + 0.5043472121732779, + 0.5030154557605829, + 0.514622888436876, + 0.5519884211257884, + 0.4385162410144874, + 0.42364929215172475, + 0.5225390784806002, + 0.5099697918953106, + 0.5296643170562929, + 0.5563638554225862, + 0.515972751015057, + 0.42608335231522837, + 0.5100133476566324, + 0.45059788671186607, + 0.42181470086961687, + 0.4607170126472727, + 0.5485222757550451, + 0.4932081340146549, + 0.48786749584618905, + 0.4741129752939235, + 0.4225929354020509, + 0.4994370306965763, + 0.4694518236303803, + 0.5050790023751958, + 0.5589616015436553, + 0.4279696789897156, + 0.508114958711041, + 0.5210546478397772, + 0.49396244529859223, + 0.4609046768849655, + 0.5493501422533443, + 0.5211654563261653, + 0.4424523749941371, + 0.4656794091589282, + 0.4817301331720862, + 0.523256245828136, + 0.4414037310886546, + 0.48633916940488087, + 0.47409024283489287, + 0.5196524982292928, + 0.5469925778582805, + 0.4550099339997873, + 0.4397899062006768, + 0.49199151678955066, + 0.45859947918934524, + 0.5573601354623221, + 0.4717100403782704, + 0.4445757028090285, + 0.49550533849515127, + 0.5123011833269584, + 0.5442484011870232, + 0.4462173760356874, + 0.44210615588540153, + 0.49530387412995425, + 0.5131811136203477, + 0.4532422632716309, + 0.4986586432895398, + 0.44600394139040694, + 0.45280553746416474, + 0.5370341918604162, + 0.5271598729375023, + 0.45433696442265203, + 0.46103748047793713, + 0.5371677062926871, + 0.5194974852795395, + 0.48967076582059105, + 0.4919546686380737, + 0.558795572005863, + 0.5587677086568894, + 0.44963959431370426, + 0.4368242413876246, + 0.5570665933851285, + 0.5548626069009404, + 0.5589605732942228, + 0.46243640629279753, + 0.47396071019465624, + 0.5157365854010402, + 0.4711379677455171, + 0.46298814615099754, + 0.5085739747782168, + 0.4454033355516573, + 0.5384993905770833, + 0.4665714898958382, + 0.43753266853806133, + 0.455003801393021, + 0.5340876391230893, + 0.5401735126020366, + 0.5406322077441975, + 0.5467840452233218, + 0.42023625672334053, + 0.4303893129935143, + 0.4751588315327141, + 0.5479634989054165, + 0.5436797269541135, + 0.48273853648189385, + 0.4870284789237199, + 0.49210523533468564, + 0.535752957637063, + 0.4639371130174475, + 0.5324041864688108, + 0.43167362586846747, + 0.46397240709054116, + 0.4266729700853558, + 0.5051609815307132, + 0.4962799730079546, + 0.48370266793573446, + 0.5144511335733633, + 0.5005850424776852, + 0.4648988646269511, + 0.5003034673962461, + 0.5034583525126808, + 0.5488388842644799, + 0.5599838456742683, + 0.5437982598571316, + 0.5006722779374964, + 0.5035973345971798, + 0.44046122452770176, + 0.46630304815140816, + 0.43967990589005723, + 0.47978167301206004, + 0.5284842343139424, + 0.4515760362924833, + 0.4449820572425699, + 0.5039140931932946, + 0.5456884678252764, + 0.4471696586818966, + 0.4583486923224653, + 0.45068274993091145, + 0.4396508886240779, + 0.5202526329124679, + 0.4540578638185848, + 0.4284160964651863, + 0.47157031080746237, + 0.5236561924578306, + 0.5023291809672111, + 0.5202463774866419, + 0.5598901778171093, + 0.5540561312541388, + 0.484481546755412, + 0.5418202922574613, + 0.5503211997604112, + 0.5355705559745283, + 0.513696835676123, + 0.5454737115002004, + 0.5122545196429243, + 0.5445814472752626, + 0.4980514473874753, + 0.49896559507715177, + 0.5575815936931424, + 0.42065404451959515, + 0.4528760200382605, + 0.4953092191353945, + 0.5406919536456657, + 0.49399243233450163, + 0.5277279635360734, + 0.49326321874927864, + 0.45571925640297384, + 0.46007494222779693, + 0.44367047759483896, + 0.5136613740341041, + 0.5572472518845537, + 0.48392399694469124, + 0.5067230739654188, + 0.544854728899556, + 0.4332604410856834, + 0.5213696023856746, + 0.5215267291108454, + 0.5077742238272112, + 0.48462374595784696, + 0.42010418984549686, + 0.430982286699331, + 0.4821080153371603, + 0.5054939467426104, + 0.5315594975981851, + 0.42308631040592637, + 0.5305533185144266, + 0.48423357433336617, + 0.4386865758568948, + 0.514809257568055, + 0.5191220021650773, + 0.4284418187855607, + 0.5315529003352681, + 0.5329451451490799, + 0.5130697597095762, + 0.42546749738184886, + 0.49137890220836855, + 0.43760877284433, + 0.5578850799221917, + 0.555981951138588, + 0.5510932095726737, + 0.4266789535699512, + 0.5528997758851775, + 0.4403133414252198, + 0.5067102932542191, + 0.46780143826410103, + 0.4581178091581757, + 0.5396264749367379, + 0.46463583677625914, + 0.4683170163834156, + 0.4821056342419195, + 0.4486438416972412, + 0.5191640840068574, + 0.43806887461039984, + 0.42229604191476183, + 0.5026261802883695, + 0.455674714230107, + 0.5060229397715745, + 0.5223628274825639, + 0.4573771772433342, + 0.5599387620293514, + 0.5571157324567086, + 0.5126761016493635, + 0.5389941336411641, + 0.47512474914666764, + 0.508119154881844, + 0.5316365957375738, + 0.43651174814590393, + 0.49955966432093984, + 0.4637270778863378, + 0.46588407008109534, + 0.4471244963853867, + 0.5596528822906413, + 0.4749617361240286, + 0.43407460110864876, + 0.549512929750555, + 0.531597223322439, + 0.44444542700546597, + 0.4792654556253019, + 0.5468215680083712, + 0.4447787086100258, + 0.45443980106492604, + 0.5561459559530993, + 0.474841896109786, + 0.44867723785574454, + 0.42696958205151186, + 0.42767441817888086, + 0.46331649228880684, + 0.4546343417746808, + 0.44644397985369444, + 0.5311153972281489, + 0.5577816771409948, + 0.48522671623458435, + 0.4830178638446174, + 0.4392443193084068, + 0.5416428208390714, + 0.5505765553962698, + 0.5475349408067338, + 0.4810760368445099, + 0.4756339328353852, + 0.5360739165827098, + 0.47004263356339016, + 0.5209593672169226, + 0.5436790089633725, + 0.5053573421811499, + 0.5477415504535041, + 0.4461057993739469, + 0.44252594044906346, + 0.46629843276675853, + 0.4558846939236738, + 0.422939413990959, + 0.5022697468062881, + 0.44705214695906137, + 0.4810334444340353, + 0.541588322269886, + 0.4736241379459288, + 0.5501967071891746, + 0.5560127779683482, + 0.5378512963731161, + 0.5436476139766966, + 0.553670724611869, + 0.5036113517065816, + 0.5065537558156094, + 0.49000583478269677, + 0.5256169229266838, + 0.5032118211424959, + 0.43224174370703505, + 0.4400152057586105, + 0.4866580281396071, + 0.4704382287903727, + 0.4227393390029014, + 0.4925093894763093, + 0.516548702744744, + 0.4773889941872379, + 0.4958258334449899, + 0.5365153177619078, + 0.47075998684560727, + 0.4443392092330809, + 0.4267203955272717, + 0.44187279608733, + 0.559748454301284, + 0.4970509570064208, + 0.4222480259206397, + 0.5167526302203168, + 0.5151590305907228, + 0.4671066801301891, + 0.5265124516184005, + 0.5120844233944395, + 0.5334814584116291, + 0.5548575565659476, + 0.4536725350275045, + 0.522126433652728, + 0.4360034521044277, + 0.5300640902552406, + 0.45134367566957817, + 0.5553646966220642, + 0.46106363318878374, + 0.5575013917402707, + 0.4240030687157332, + 0.44798928145291106, + 0.44410549263757515, + 0.5391268404450653, + 0.557607065045453, + 0.5455165180517338, + 0.5271806175038709, + 0.5421779480060089, + 0.545942229169182, + 0.5279075822684627, + 0.5171152566632201, + 0.43212815519471165, + 0.46070259990016293, + 0.44542478054889595, + 0.4202987550102304, + 0.5453165318871546, + 0.5091761975381326, + 0.5123260225357882, + 0.43200636252323, + 0.5552257509078923, + 0.4603167786544235, + 0.5260973555867372, + 0.460842250398404, + 0.43363206479666416, + 0.46637940611227957, + 0.4453229878063086, + 0.4485431443039898, + 0.4432746503881077, + 0.44371181775469853, + 0.48910835098728755, + 0.5429733401574245, + 0.48146106596892396, + 0.5312929729437973, + 0.548358130447499, + 0.5306418949549038, + 0.44563056469131773, + 0.5366194353280577, + 0.4705610288514195, + 0.5422017148395508, + 0.4661771387477044, + 0.5193584120028858, + 0.46028744135342364, + 0.5185108707618762, + 0.5262362371993399, + 0.5170837440571036, + 0.46634009487333483, + 0.49407651220731397, + 0.5480669136411975, + 0.4673178035270616, + 0.5205055930220265, + 0.45758494176370623, + 0.5072535544437511, + 0.45879403023596266, + 0.443440956602887, + 0.5129660376622768, + 0.5504991993141645, + 0.5478932413965926, + 0.4916399906817064, + 0.5178570745399825, + 0.5539194660911984, + 0.42252159138936446, + 0.45142129924896984, + 0.5336645025468681, + 0.5268718119280773, + 0.49956908686873436, + 0.514761199707233, + 0.5407376241967714, + 0.4930916404194676, + 0.4541758901811524, + 0.5598810253622983, + 0.45341921208791486, + 0.45605960499941667, + 0.4732173858232187, + 0.45478305444622824, + 0.4359007401092397, + 0.5167122651033879, + 0.46638271106500656, + 0.5597226908272183, + 0.529011136619826, + 0.47095382943117325, + 0.5495045601522025, + 0.4852387152266056, + 0.5413374229734148, + 0.460002510080524, + 0.5406127946238419, + 0.44214367250861847, + 0.4667384924185706, + 0.46953755613700354, + 0.42148646063678047, + 0.4484213933942726, + 0.5450788538910286, + 0.4454784916557663, + 0.5481268773496843, + 0.44029391858135447, + 0.42885071097711946, + 0.44275601887222216, + 0.5296513714331302, + 0.4690502242898728, + 0.503535806924637, + 0.4929247081467515, + 0.44821394601900383, + 0.5054902086149918, + 0.429638755118767, + 0.5235937510413452, + 0.5131161356437438, + 0.4676502724929987, + 0.541932811654141, + 0.5410085591528958, + 0.51049589641832, + 0.5353268954422326, + 0.4670542119260123, + 0.5395135129904413, + 0.4904193059483777, + 0.46689874829950706, + 0.47998250583598984, + 0.4492731514812546, + 0.4247774302807127, + 0.515146547056379, + 0.44483629131483055, + 0.5340173719572691, + 0.5196369028144066, + 0.43576995514690975, + 0.43202674230680904, + 0.4561852949601885, + 0.48023936352426305, + 0.4236346317452358, + 0.5370469049128229, + 0.4758435452948945, + 0.4801242119963212, + 0.4765426579975997, + 0.503286466898945, + 0.49572804550324023, + 0.4666234329517999, + 0.5109834692234847, + 0.47037683697471405, + 0.5025059773458191, + 0.46275824516878256, + 0.5085418068552648, + 0.4744055284286103, + 0.5385023661785685, + 0.5008106478339536, + 0.4259291163404673, + 0.47260083207517584, + 0.5463564089591569, + 0.42755958897827445, + 0.42550162258552704, + 0.5227159934235086, + 0.5096359111786853, + 0.4311444307036384, + 0.4247331027549425, + 0.4305426383680627, + 0.5304648980555866, + 0.4618457674869688, + 0.5161584237880488, + 0.4435216347291532, + 0.4437654420992488, + 0.5520240624259594, + 0.4862934937903507, + 0.4284197626581037, + 0.4469128577295855, + 0.46164132922439166, + 0.4948433636025917, + 0.46571837202046734, + 0.4910204958036243, + 0.5031043250503705, + 0.4949609238376096, + 0.43187111448645843, + 0.49810631952641116, + 0.553129094900231, + 0.48149330419078434, + 0.5313178767781501, + 0.47744091698424374, + 0.45587177148095925, + 0.4683781673965895, + 0.5015823068449886, + 0.5385781492437114, + 0.5558394041422533, + 0.4926902599022547, + 0.43903490513252785, + 0.42067010349148504, + 0.551749051136768, + 0.4265578357231545, + 0.4652098128135455, + 0.4929943057243738, + 0.4420671804902241, + 0.4598984453469901, + 0.45646968913241714, + 0.5096030512768509, + 0.4317320500133343, + 0.42659491784001174, + 0.5371833037820996, + 0.5175269059060921, + 0.4559964750172232, + 0.4228882039592853, + 0.5092528311054653, + 0.5394814693775909, + 0.4856600423518334, + 0.5020083725783258, + 0.5217988598985762, + 0.5555115964078094, + 0.446255715657348, + 0.5488683870958848, + 0.4688684206929537, + 0.47439915718307807, + 0.509849041302761, + 0.4442547182534308, + 0.46801500691886877, + 0.49894051833445097, + 0.5532024277278029, + 0.4621921197290583, + 0.5189382236074832, + 0.46746371681459786, + 0.45156753835494035, + 0.46154567414890646, + 0.55787385302351, + 0.42950342091552074, + 0.4481310980925645, + 0.4666572456880842, + 0.4970736839578902, + 0.5128790014164709, + 0.5122771781665333, + 0.5501505036395749, + 0.46053241934515554, + 0.4387736893022746, + 0.5439413842382868, + 0.5535843896417497, + 0.5594748480875243, + 0.5411007219514778, + 0.49200111818835685, + 0.5579665477573577, + 0.5258212788283906, + 0.48060456017775965, + 0.46706387004636324, + 0.544386588268817, + 0.5139789581560625, + 0.5035473262583539, + 0.4751911164912665, + 0.48631107761552844, + 0.5273821541876441, + 0.4342234326303349, + 0.49660012085955385, + 0.5232486040507252, + 0.4507856592648926, + 0.5215272200048691, + 0.5237059226092268, + 0.4211511874097379, + 0.48910043445676427, + 0.5223002648412697, + 0.4565680504068061, + 0.4886127253402253, + 0.46743675920886807, + 0.4392410515687342, + 0.49549844076499355, + 0.48319805649485914, + 0.4848601475570168, + 0.4352916581804716, + 0.4893275059713252, + 0.5512576337305362, + 0.5510999653556787, + 0.4665960711608636, + 0.5216873809841863, + 0.5038663758765061, + 0.47194660884833806, + 0.539510298673395, + 0.4724482336898549, + 0.43186118547323665, + 0.4974358007396271, + 0.5365544706002775, + 0.4970283376303055, + 0.47284436862858814, + 0.465182210262885, + 0.5347086735086608, + 0.42268476888655204, + 0.4631318253309618, + 0.4363797257677811, + 0.465941447516018, + 0.4367193410173248, + 0.5409360885751008, + 0.5287486644144405, + 0.4406147278465668, + 0.47748716172229866, + 0.42346134001290636, + 0.45969725317746285, + 0.5040428099979503, + 0.5251066343191994, + 0.5462452534368445, + 0.4429499846482246, + 0.4388512356270236, + 0.4647024494845904, + 0.43280145290809885, + 0.4966382999542671, + 0.5332612052864432, + 0.5061735593402289, + 0.47336287040099034, + 0.5544777668625019, + 0.5167294051917959, + 0.5429578441653818, + 0.5315681060024975, + 0.4546536495402296, + 0.4808363569533827, + 0.4200298053765452, + 0.44070061145776995, + 0.46358768863844074, + 0.5107249392660633, + 0.5453735006843935, + 0.4455629994378313, + 0.440104509628542, + 0.537454758721457, + 0.4396182480076277, + 0.4461793222308473, + 0.5474361322687532, + 0.45492498332959724, + 0.466445774375579, + 0.4450424750055613, + 0.49047409636084494, + 0.4815969942806557, + 0.5391009233305671, + 0.435223638898211, + 0.4495197895588027, + 0.46771681310283747, + 0.44346915485197985, + 0.47077253886330706, + 0.4815662589589093, + 0.5378326613964353, + 0.5475009873455128, + 0.45266958444688915, + 0.4993957709441753, + 0.4903964490802334, + 0.4839232823458408, + 0.4431419593102446, + 0.5250211461443633, + 0.5157680542090332, + 0.4501206058394932, + 0.5246811282478441, + 0.4768244848138311, + 0.48803196108877855, + 0.5542612171117799, + 0.5062166101524102, + 0.4939541109585167, + 0.46057842827647477, + 0.4849956533190807, + 0.4468531391652827, + 0.4470992609039954, + 0.4216268785085575, + 0.4565768972889219, + 0.5361858108976397, + 0.4756808129026121, + 0.5519226655086406, + 0.4219515350962207, + 0.47703450685165677, + 0.43294326191408605, + 0.45929740587532736, + 0.48471085779332257, + 0.5250546121609777, + 0.42933308579975, + 0.4533557255243672, + 0.48342657157623004, + 0.5559565031482876, + 0.5571368755242107, + 0.4285852535680217, + 0.5386434775317176, + 0.44153115788680836, + 0.5572533394079908, + 0.43700317890591056, + 0.4491646976448631, + 0.5131101118393775, + 0.5332523255996796, + 0.540102532719686, + 0.4868978656727081, + 0.4621983684012656, + 0.4381792583234371, + 0.4604901533830079, + 0.45389797674847815, + 0.47234343415728236, + 0.5013002238628532, + 0.5332682256172141, + 0.473908070876866, + 0.476397998199507, + 0.4521815388116853, + 0.4486063421306411, + 0.5423849418511396, + 0.43260098009556947, + 0.540130074184728, + 0.48959672883274596, + 0.4595052474928613, + 0.4297557641049296, + 0.4685024899647484, + 0.4234153845012784, + 0.45281065244201796, + 0.4607820332787096, + 0.5310672270222856, + 0.4807851228605046, + 0.49720590641085727, + 0.5473186402115402, + 0.545561937804224, + 0.48005192725391965, + 0.48791424058972316, + 0.5104489049266244, + 0.43355168074251715, + 0.5181442838054167, + 0.48277708244933404, + 0.5012864683176981, + 0.46655454934068313, + 0.497890960594006, + 0.5374716777437918, + 0.5127897201806157, + 0.4329725995665827, + 0.4776486568348324, + 0.44491891795687183, + 0.5538182367361051, + 0.42749725097720054, + 0.4639609784307241, + 0.46244504248713203, + 0.4430766926397516, + 0.4281217883771539, + 0.43615820036550823, + 0.4700836666448264, + 0.5008307337986525, + 0.5413129090670988, + 0.4515458074758248, + 0.542184960518777, + 0.5230642812775991, + 0.48385117647434683, + 0.4692896721499664, + 0.4317484512475401, + 0.49250817979051315, + 0.4580911133173475, + 0.5500388357765424, + 0.4440625878074374, + 0.4226884234110932, + 0.46467210665754866, + 0.44372380314695836, + 0.4412141352114542, + 0.552057878299024, + 0.5084528884104225, + 0.49358268153688284, + 0.4997193220952584, + 0.4905736633721533, + 0.4357512023559013, + 0.4279185767899768, + 0.4887577129226172, + 0.5495280283965389, + 0.46088976157332767, + 0.5480540468123467, + 0.4374839090565673, + 0.5141914790310019, + 0.4828738420725382, + 0.474052936801726, + 0.4665109458643335, + 0.5138229789773113, + 0.47112675870565657, + 0.4609612782752446, + 0.44534021665467055, + 0.5037972078058232, + 0.44606376998589575, + 0.5298275418872324, + 0.49500950818034667, + 0.49264167944952497, + 0.43892915771120117, + 0.5095923978916157, + 0.5086027762475082, + 0.5000024045244518, + 0.4901030650336101, + 0.5446043742453578, + 0.4536612364650127, + 0.517518209318667, + 0.4928306594381166, + 0.4938326631709732, + 0.4950415961516809, + 0.5051530711296066, + 0.5594449988342832, + 0.5429946510973354, + 0.5060744273279368, + 0.5458015457082697, + 0.5256042832450235, + 0.4539152306017574, + 0.42046670104253275, + 0.4869774847718094, + 0.558441471600647, + 0.53293910604304, + 0.4600411550855274, + 0.4796044324290207, + 0.4662156136691472, + 0.46138707984535765, + 0.46938511964190505, + 0.4427871449253075, + 0.5128558125485321, + 0.48896199468662677, + 0.4975550378502418, + 0.5151137641731177, + 0.5562404230935318, + 0.4709877074141944, + 0.5124029836445607, + 0.4608521360655619, + 0.5100375879073864, + 0.5130528742769633, + 0.5310704089279388, + 0.45701675210627013, + 0.5495178827343438, + 0.483967727683085, + 0.5168410669216102, + 0.5337863968158659, + 0.4531800266428175, + 0.5553213953513731, + 0.4810490053493783, + 0.43254058517006067, + 0.53607987377814, + 0.5058836758975652, + 0.42333085002664866, + 0.5177448434630586, + 0.4720652028380054, + 0.5274055945424411, + 0.45093053788473647, + 0.5258468623658983, + 0.4707206239405402, + 0.45904734153963295, + 0.5084958940768048, + 0.5583013381901297, + 0.5212169472828779, + 0.5177617022743579, + 0.5087288466067813, + 0.5549883727980229, + 0.5514581724349337, + 0.5055565618272712, + 0.5181518574189029, + 0.47540534669833356, + 0.42250443064537135, + 0.48466333940659845, + 0.4368292229528091, + 0.48595552504469275, + 0.5160012690559286, + 0.42649298482686526, + 0.46661264547039183, + 0.4665853961968336, + 0.42197185585723807, + 0.5446078667094412, + 0.5216631131083311, + 0.5135700155260168, + 0.4892415758363057, + 0.45029267903024706, + 0.570286988284926, + 0.5794862648671476, + 0.6333682562927927, + 0.6020097152022865, + 0.45123928872241637, + 0.5878462215656923, + 0.6464483672044865, + 0.4461478860047812, + 0.4408865517069536, + 0.5891479147609632, + 0.5314712473313276, + 0.511451061231593, + 0.47013259134173513, + 0.6593148524311402, + 0.46896335969990977, + 0.5025691031853627, + 0.5732254138941845, + 0.4586336021083235, + 0.634267322907903, + 0.4423948480682358, + 0.46979014709772854, + 0.4530433726465093, + 0.6562976535867787, + 0.5069799285304726, + 0.5250477401874099, + 0.633573428592878, + 0.446947110935833, + 0.5688197207153616, + 0.5967414901773355, + 0.529117859372725, + 0.4470146857894404, + 0.4471321067382465, + 0.5843665633692028, + 0.5435936027406657, + 0.580050188075589, + 0.5422990166824461, + 0.6225997437688816, + 0.6477545146394261, + 0.5017556053085894, + 0.5076336029531726, + 0.6313117256035133, + 0.6127122538992517, + 0.6344424344519289, + 0.5420760646397078, + 0.4642370600987805, + 0.6154362145444623, + 0.6529411402659915, + 0.5979684626609523, + 0.4934336997038841, + 0.4932974113762861, + 0.6059073826388699, + 0.6590288618180524, + 0.6400002089011607, + 0.6340737033599894, + 0.554263843245606, + 0.5781846794140888, + 0.5440672050696278, + 0.5365523373318049, + 0.47712720591380814, + 0.45234316746232517, + 0.5093835788556704, + 0.48533586747418156, + 0.5192981989630171, + 0.5201658514194644, + 0.5445330121996443, + 0.5682174013447352, + 0.6579545901309921, + 0.536363877007709, + 0.5085869277515381, + 0.5141503510952671, + 0.5296311451912077, + 0.5391270289231864, + 0.4735080141173954, + 0.5937674120286944, + 0.5169202224549958, + 0.5838564691978522, + 0.47863736602862, + 0.597382843526152, + 0.6557392551543055, + 0.6333299103753988, + 0.6534515302498736, + 0.6239426470118117, + 0.46794875282063886, + 0.544051415155195, + 0.5384169028301887, + 0.5294266805064154, + 0.6252650933193009, + 0.5304582332121351, + 0.6455864477232257, + 0.5519415917361687, + 0.5271847996656108, + 0.5838633610082963, + 0.5905464862774545, + 0.4458874587469817, + 0.623430147894676, + 0.6155092593761924, + 0.4506830662976475, + 0.495709214211565, + 0.563912737730167, + 0.5403556201653604, + 0.48807230006592794, + 0.46346509767176297, + 0.5995541247451346, + 0.5334058998747474, + 0.5945546409583142, + 0.4853572051879187, + 0.44233077315337693, + 0.48703435987310684, + 0.4618201295593254, + 0.44519405405588225, + 0.502159073239301, + 0.5478394252973057, + 0.6174641841424786, + 0.6103519077524294, + 0.45084032886798514, + 0.6518530851537893, + 0.6148754466566302, + 0.6064655979359257, + 0.5399205038112664, + 0.482299028692846, + 0.5094795955796142, + 0.48114760564874554, + 0.6551940899546821, + 0.5144665928737769, + 0.5024216680709631, + 0.5293537685097207, + 0.5336160078088312, + 0.49085641438894195, + 0.6570892910723276, + 0.643423524394263, + 0.5039595669665831, + 0.5724133319733196, + 0.6556097130297784, + 0.45931509683038585, + 0.5536095133732826, + 0.599148524891669, + 0.6392219689322751, + 0.5983884259352062, + 0.6010849479044851, + 0.4568714724201069, + 0.5030192021742828, + 0.5099295057134303, + 0.6322537966306738, + 0.5192696962726273, + 0.4503841311232381, + 0.6504931801713129, + 0.4799934453437237, + 0.6270890980003707, + 0.5032380823874738, + 0.5311550559819217, + 0.5376258955143035, + 0.6531298336108134, + 0.5298964074020034, + 0.5835458465580896, + 0.641419935427289, + 0.578673275400503, + 0.5170946155208408, + 0.5307266777258178, + 0.558296448927336, + 0.5432088467405898, + 0.6142727498035815, + 0.4960643025384184, + 0.4693936601405554, + 0.6101953996751316, + 0.485758005459361, + 0.48170197904264306, + 0.6087752260217804, + 0.5031800662596757, + 0.455446029179229, + 0.5277027654745251, + 0.5847018165995103, + 0.5438390212095581, + 0.47215586051194075, + 0.46711522464012245, + 0.5438093794446065, + 0.537261825381794, + 0.48248395776799835, + 0.6603917479272448, + 0.5270897909262955, + 0.6138009426258654, + 0.5183474500724548, + 0.5261542462836607, + 0.488512179116874, + 0.5037006653809543, + 0.6395214710218263, + 0.58880052421507, + 0.5256368096061783, + 0.6363229500068782, + 0.6149488894864399, + 0.6561882084482501, + 0.6030749109915563, + 0.5561818979630969, + 0.6191514089283676, + 0.638008064532487, + 0.4681260934216831, + 0.5323070383642473, + 0.4461914866822256, + 0.5212453560520244, + 0.6303453688863603, + 0.5300993207454672, + 0.6479940215711066, + 0.443247823611399, + 0.4895215225276733, + 0.5691844705536737, + 0.566309099222034, + 0.44046915910094064, + 0.6002490124015598, + 0.45679388593476977, + 0.6144598992009855, + 0.5727453136294723, + 0.4881909419265302, + 0.6159466787128092, + 0.6461747430316069, + 0.6439697364962624, + 0.5988903961520551, + 0.5703157322539334, + 0.46780215673528275, + 0.5647676682271082, + 0.5243692875762995, + 0.4832819099524418, + 0.6619816540782069, + 0.5955768776123288, + 0.5226444855086176, + 0.5293549948483988, + 0.5207869830342614, + 0.5363290291952582, + 0.5728419623916627, + 0.49443590109961866, + 0.582742610746812, + 0.47655915121741627, + 0.49751016663751246, + 0.5722920235257372, + 0.4443246803158507, + 0.6080610849972928, + 0.5710656069236841, + 0.6254621116024797, + 0.5334513219567788, + 0.60304857455972, + 0.6619867468278937, + 0.4807447237434256, + 0.5123591483603755, + 0.4934993002419229, + 0.5419029547361225, + 0.4775926675983641, + 0.5225094545251464, + 0.4415433451855878, + 0.6386251543097714, + 0.5415663431290286, + 0.4967462420257747, + 0.6031614548597182, + 0.48999760481989363, + 0.5125333579979512, + 0.48196231941227047, + 0.5389640060100112, + 0.45495918050583, + 0.602501093743488, + 0.5789530907660191, + 0.5977318151131172, + 0.526976347697868, + 0.6169928473745914, + 0.5772860107111354, + 0.6326927817443195, + 0.6460693232215375, + 0.5555964788421279, + 0.5108522721423667, + 0.6355244874359489, + 0.6480963790802657, + 0.5039263486408188, + 0.46119464855181524, + 0.6602032112876555, + 0.5308867579260079, + 0.49898960407065335, + 0.5026555547796746, + 0.4959009310662372, + 0.5373292480348895, + 0.48043112869286114, + 0.4980854252978672, + 0.5532572404052807, + 0.5012150426324772, + 0.6452691445518932, + 0.6227298279479876, + 0.6077843843595065, + 0.5485670230435764, + 0.4410711914731909, + 0.5342295545801204, + 0.484620299827096, + 0.6543436253366806, + 0.5488509076090876, + 0.5085221523081681, + 0.5486411960327727, + 0.5658627644705025, + 0.5673406749968384, + 0.5284811846211239, + 0.6108578983939333, + 0.45537991857327836, + 0.6572832816767984, + 0.48602335736810676, + 0.47429824635620776, + 0.5834079501693352, + 0.4403771495741037, + 0.6049008167399924, + 0.5175447574871777, + 0.6127204971958488, + 0.511893166526707, + 0.621115257905003, + 0.590549800013125, + 0.6102070929861345, + 0.45340243541780917, + 0.5579908360441868, + 0.659927258102413, + 0.5458523357197262, + 0.5605571322070984, + 0.6544204353344795, + 0.6561513170902781, + 0.656083213640741, + 0.4547200131710281, + 0.551853591218566, + 0.5824388649962925, + 0.44727842900188025, + 0.6559848713127586, + 0.650030274140297, + 0.5888321803046863, + 0.5038577253086953, + 0.62380682766385, + 0.5548510622198658, + 0.5590972015104739, + 0.604478764108121, + 0.506670332319051, + 0.5163745256386891, + 0.6437683652732163, + 0.5235118081110188, + 0.6232982828330574, + 0.49082918513791146, + 0.6562590461873462, + 0.6204820266098858, + 0.5133585521819839, + 0.45508312534413414, + 0.5108054776166103, + 0.6063103309705359, + 0.4744482674327513, + 0.5987302374801192, + 0.49383671219409625, + 0.5850626627801379, + 0.4549456661306571, + 0.5838334450560456, + 0.4612510005141441, + 0.45347395134252466, + 0.5010793803957101, + 0.48457285088808555, + 0.5449641581629685, + 0.5935705808133128, + 0.5344966005320435, + 0.5609901512010285, + 0.5227506523191925, + 0.5105022419967638, + 0.6156098482788064, + 0.4839943986252904, + 0.48753151365153125, + 0.5043173146061682, + 0.4566234752820283, + 0.6089341133684718, + 0.514302809423054, + 0.45136441879817263, + 0.5426699266944331, + 0.5738377037454088, + 0.4476194257622068, + 0.529013195070678, + 0.4793925483012868, + 0.5794360758486614, + 0.5846664056045607, + 0.630072137159644, + 0.5192003636968925, + 0.6358461027413439, + 0.6357232979836727, + 0.45422548458231987, + 0.5707260562618128, + 0.5651247898011604, + 0.48313448406153636, + 0.46130281727127176, + 0.4663596633214763, + 0.5509657230594117, + 0.6528291773942925, + 0.49806110069060006, + 0.6584401787519607, + 0.4954553780317167, + 0.531266328827407, + 0.6294951640978386, + 0.4701663726484921, + 0.45451278933399103, + 0.4476734792426804, + 0.5132109787743163, + 0.6480354000166207, + 0.5849872968681107, + 0.5906102384840323, + 0.45462822477341697, + 0.5053569164776324, + 0.6163998105514483, + 0.5195149545473976, + 0.559158693208645, + 0.5678521900604183, + 0.6158299860417198, + 0.4824938199269902, + 0.4706135996756476, + 0.5173596128562277, + 0.6554337455631034, + 0.5020056217692329, + 0.6087771566940664, + 0.525624353117038, + 0.6078036904797095, + 0.6403795512763293, + 0.5531204716844453, + 0.4431076031683427, + 0.5184602227937609, + 0.4856964533487342, + 0.5052602774081829, + 0.5539267308422963, + 0.606958928627126, + 0.4502791669043164, + 0.6299329962931199, + 0.6482061512170076, + 0.45765144309139283, + 0.5633895469513795, + 0.4668303071583017, + 0.48943626872461016, + 0.4739591860878424, + 0.620874611162541, + 0.49905317381263736, + 0.5366829570956647, + 0.6259609339085448, + 0.649834962749509, + 0.4409094218264931, + 0.5200054998826095, + 0.657766377805072, + 0.580171153720205, + 0.5216844016560771, + 0.6448770406679027, + 0.6070440351217641, + 0.5992003675826187, + 0.6322198603960993, + 0.6445419654530551, + 0.4825389652430815, + 0.6026666329330553, + 0.5467268489211372, + 0.48145128520196695, + 0.5783606813524147, + 0.45880072314326636, + 0.440849430615728, + 0.6125259152252689, + 0.5506091151035524, + 0.46534672241902847, + 0.44647461241061326, + 0.5610393543964243, + 0.6436283885683345, + 0.653980660995752, + 0.560384647170865, + 0.48519853000109486, + 0.5409734568657686, + 0.6371973975220144, + 0.6420982180205911, + 0.5272275438821117, + 0.5135076230294281, + 0.5412813344076757, + 0.5028646596500485, + 0.6602103627173849, + 0.49408782958363906, + 0.5467901809872764, + 0.44400962264557625, + 0.4642336441342303, + 0.5614469436532149, + 0.6148691608566188, + 0.6178994743970335, + 0.6001701115817168, + 0.6512745977126109, + 0.5565423829114078, + 0.6230244824851101, + 0.4763780981842214, + 0.4547796460509259, + 0.6357456857830494, + 0.6088350590139342, + 0.59384381240401, + 0.5657781702434156, + 0.5666151446905275, + 0.45623316347236026, + 0.4602109809906714, + 0.4793091298647895, + 0.5304410152254307, + 0.48271633301986194, + 0.5670682320922336, + 0.5983470417569804, + 0.455402095210643, + 0.6240667000018583, + 0.6469968694830509, + 0.6407863072919027, + 0.6516112197115117, + 0.6533833535440211, + 0.6319400936367996, + 0.45888916390399437, + 0.5838181611385844, + 0.5139043466691003, + 0.545032991213096, + 0.5930023471378436, + 0.5980716433046545, + 0.5882785967504065, + 0.5246489689896944, + 0.4606762217738319, + 0.538312282174235, + 0.45085298351285086, + 0.5648784563162933, + 0.6288457079983127, + 0.6518874507156335, + 0.6128619314170431, + 0.6386819677933825, + 0.5994544260798289, + 0.4787022993449153, + 0.6510992932940077, + 0.48581210933400715, + 0.5895172818367502, + 0.637127190925552, + 0.6328991145271539, + 0.5670544091733767, + 0.5761096989070076, + 0.4418298286322434, + 0.4786523833689567, + 0.5164519356051187, + 0.4424567280319428, + 0.5427811497521842, + 0.6082616464798525, + 0.6425706080204155, + 0.6015998624109904, + 0.44186466406558533, + 0.46500728443718875, + 0.4787486574246481, + 0.4927193090284299, + 0.5195772129879508, + 0.6624195935970703, + 0.44165450565630576, + 0.5744204265758505, + 0.6375426841359454, + 0.5769650046556105, + 0.5193811330931977, + 0.5214302787653768, + 0.507266811294021, + 0.466630256555366, + 0.5171351526713941, + 0.6215683597528683, + 0.647981708809198, + 0.542923731052805, + 0.6147243031061349, + 0.655509655334112, + 0.6004544709951205, + 0.6096785908000424, + 0.5617082574157262, + 0.6425910523456395, + 0.4682078127349712, + 0.5944975532782257, + 0.641795308482924, + 0.647024454273252, + 0.6570342603267779, + 0.4530689449250315, + 0.5174991350984213, + 0.5619314074134159, + 0.5392377162652808, + 0.5743608343393791, + 0.661899698208048, + 0.6347464478755767, + 0.5403073939728757, + 0.5509039256083538, + 0.4695086462535613, + 0.5928987082068862, + 0.5354405267699661, + 0.5871436958916201, + 0.5638770787729424, + 0.5713430984677835, + 0.48054972851161465, + 0.6290679392682278, + 0.4782478078728675, + 0.5220423684887253, + 0.5660015275327361, + 0.5319148405247384, + 0.5263916314205485, + 0.4554432926656597, + 0.6613984614494952, + 0.5673794863696144, + 0.5177937605056242, + 0.6272222062826138, + 0.48096447981231705, + 0.5967951732351329, + 0.5939026762188784, + 0.5472139416628178, + 0.5851929633165285, + 0.5760341905490214, + 0.5632292195739835, + 0.600269199105226, + 0.5069321898688987, + 0.5147156610519621, + 0.5672403251391909, + 0.48304101366957886, + 0.636680981862075, + 0.6199444835419128, + 0.6325841579098597, + 0.5594094328695006, + 0.6357488613019424, + 0.46658374011037895, + 0.5684395223247247, + 0.5471685108196138, + 0.4620776777977894, + 0.6125653443740956, + 0.6396866173663095, + 0.5176775213750482, + 0.4541069324595469, + 0.4642380630667161, + 0.4756469617054887, + 0.6248992166093998, + 0.6137247875163022, + 0.5160261953842827, + 0.5439524020794332, + 0.5281839392194863, + 0.5181364130318814, + 0.5084679385635187, + 0.5451648752515763, + 0.5739612627255812, + 0.6066460654003762, + 0.5331499598306815, + 0.46319625675324166, + 0.48521740762825916, + 0.5940901536935365, + 0.5400998091488218, + 0.5235808271790197, + 0.654362979375953, + 0.5107073749030717, + 0.5559636742381051, + 0.469060803023433, + 0.5694341189942012, + 0.6155156857959978, + 0.5810929978196426, + 0.45846886329983877, + 0.5229683692961816, + 0.5226789660611564, + 0.5415769695079619, + 0.5510587242604245, + 0.6045159309229557, + 0.5151349852303287, + 0.5967852109237135, + 0.6195629109923751, + 0.49092088331176037, + 0.45354475855584997, + 0.5257117647577074, + 0.6481001800913444, + 0.45629735237430885, + 0.5362993892938946, + 0.5670152984309351, + 0.5643307345784775, + 0.47093879463749466, + 0.5852278446977282, + 0.5476940536202562, + 0.6214209007187346, + 0.6246554324473409, + 0.4799137103200544, + 0.4529935467729769, + 0.6300843466742793, + 0.47823930403981535, + 0.46107500580059585, + 0.6082296385879375, + 0.46217926329112585, + 0.5097421124947384, + 0.5818678006712544, + 0.4845544906294958, + 0.5804718706736385, + 0.6027783546501776, + 0.5651111468906074, + 0.6277844509766798, + 0.5805152439060823, + 0.45102097809751035, + 0.45046306008115194, + 0.5746632777170653, + 0.5770558854857711, + 0.6558845388406107, + 0.5320160238139364, + 0.6133353575352212, + 0.6213276373967607, + 0.6542546532812508, + 0.4845963956484827, + 0.6548860414491646, + 0.538592546856089, + 0.6630693889776484, + 0.6040140635222491, + 0.6135309422214247, + 0.580068225967308, + 0.5845263854244127, + 0.5096052693271259, + 0.6600841546870828, + 0.6211403263297962, + 0.5215810942194128, + 0.5249723359197244, + 0.5557292942821961, + 0.47399850696102475, + 0.6321615413547238, + 0.5156139701838984, + 0.6020853675045754, + 0.5346984440760153, + 0.5960295863147084, + 0.5906564165341648, + 0.45382071319401257, + 0.44902822882220456, + 0.5653637704427499, + 0.4634444141384257, + 0.46913000424699575, + 0.6556062132631639, + 0.4444357253088923, + 0.4878612959769503, + 0.4601326018905063, + 0.5561906665052043, + 0.5023765533219454, + 0.4797918177063639, + 0.6063264538399342, + 0.6048902893437624, + 0.4751881385774848, + 0.6323056407642552, + 0.6288529135845954, + 0.4850855231336758, + 0.6498359002561654, + 0.6330683931157077, + 0.5594676169550676, + 0.6558735422857936, + 0.6250348110244428, + 0.5061421303881768, + 0.48276750856342127, + 0.6394631781652951, + 0.5062610134238463, + 0.6494726125185997, + 0.5007238052431172, + 0.5867046711629913, + 0.6473988832241105, + 0.629062924903846, + 0.4591960900119295, + 0.4887667923335594, + 0.48905632786779907, + 0.46765320922647174, + 0.46129306009968457, + 0.5452077055518313, + 0.5808722150453007, + 0.4481022840906842, + 0.6325661563220918, + 0.5621399001885377, + 0.5833254147991627, + 0.4994475926083504, + 0.4558109440978301, + 0.5310453809177492, + 0.5954140712954206, + 0.5364725949964514, + 0.5252162182641927, + 0.49605174105575184, + 0.48680244128557004, + 0.633858382848257, + 0.5880685756832397, + 0.6325247823627455, + 0.5903552261956084, + 0.4412552971164392, + 0.6377033028076852, + 0.44051100284481404, + 0.5189778771485404, + 0.5830228031514648, + 0.603971703124002, + 0.6520020661775217, + 0.4751615916382285, + 0.5764365374951732, + 0.5070789076649321, + 0.6157187261461375, + 0.562818079217114, + 0.46135122948884477, + 0.6311835615195656, + 0.5202277915724293, + 0.6604148400343296, + 0.598153188991214, + 0.5783621204104556, + 0.5148320054387332, + 0.6400011985682708, + 0.6611248071851619, + 0.5855309152160098, + 0.5784955993471156, + 0.5908801691137882, + 0.5855600786972665, + 0.5804404635342439, + 0.6202308038449794, + 0.6436322831169088, + 0.5677365020133058, + 0.5723952179073282, + 0.6387725135555039, + 0.5688610570616689, + 0.4655269002969925, + 0.47026094952715103, + 0.48793529357721743, + 0.6385631814142494, + 0.6090118062566627, + 0.47672283994564646, + 0.44429654656194145, + 0.5072172987863357, + 0.49830262904004996, + 0.5427558043939685, + 0.5653515341237689, + 0.5317093327754757, + 0.4901318689194839, + 0.5742018871087593, + 0.5043354827196777, + 0.4410198841830598, + 0.48251017642521593, + 0.6561142122909649, + 0.4838551830690673, + 0.5735801119369076, + 0.5414651590493275, + 0.5748682394471226, + 0.4865949981033042, + 0.5070629112595159, + 0.5137002555834275, + 0.5512232675512174, + 0.46400204998721706, + 0.5259518578354021, + 0.6572306606691584, + 0.4633204039641789, + 0.5039061460665446, + 0.6629523749514681, + 0.661315851905704, + 0.49305121476790337, + 0.5738894595364112, + 0.5749050754883673, + 0.499208380006098, + 0.5319164661811308, + 0.44250246849320624, + 0.5684753280016858, + 0.48792689596953465, + 0.6625688814150315, + 0.5114519936542131, + 0.661019556899547, + 0.5107905615336208, + 0.49835833095149806, + 0.6030861439506308, + 0.6374607267537789, + 0.5229416557917741, + 0.6187658125020379, + 0.6430529999712825, + 0.5640367809702789, + 0.5975513439054756, + 0.4627987142309011, + 0.5917351472739534, + 0.6614548297424638, + 0.5922753425734026, + 0.6275049365859854, + 0.5097605699533989, + 0.5459534343431944, + 0.602933634705015, + 0.66125105611303, + 0.6447247783677491, + 0.5691891084843566, + 0.5580210454267189, + 0.5243078335948529, + 0.5030898668135418, + 0.4709038211243367, + 0.5410351652406133, + 0.511941377187228, + 0.6149228793649737, + 0.45422952626328483, + 0.5366425631278653, + 0.5385320625676169, + 0.5363514245667227, + 0.52608028922982, + 0.582312942561269, + 0.622512774960372, + 0.5176087946401635, + 0.647237943015212, + 0.480084343377193, + 0.4793927731126365, + 0.5451333649268473, + 0.5797831663753645, + 0.6434759722591414, + 0.6372486673260018, + 0.6618891907327141, + 0.5267283683328766, + 0.5651128243126554, + 0.5921951775470526, + 0.6153386044694602, + 0.5878278981110814, + 0.47655422917690626, + 0.6342567054422774, + 0.4736468213136832, + 0.54050436675501, + 0.5067152768128856, + 0.47149456690790814, + 0.5778844102487215, + 0.46255517684474856, + 0.6141791334760152, + 0.46389503628950524, + 0.5628800330155299, + 0.44486452604514587, + 0.591515679317123, + 0.5408924414371395, + 0.5443533869744454, + 0.5454609228532747, + 0.6613667261946548, + 0.5963793993754197, + 0.6292091798603765, + 0.656402665503931, + 0.44789122322082153, + 0.5567719031357828, + 0.5697304945076305, + 0.4936408751683292, + 0.6524379281056092, + 0.5276203717595562, + 0.5830102964756902, + 0.48258802910602744, + 0.6049688337954138, + 0.6242148789583893, + 0.5344825306433154, + 0.46147457024776484, + 0.549279861572526, + 0.626115215799149, + 0.5765714396077777, + 0.603775689170384, + 0.5316136366071892, + 0.5744250393837361, + 0.5365978145419047, + 0.5898600641597395, + 0.6537953578535443, + 0.6125737307645818, + 0.606781512343515, + 0.5379481740669403, + 0.5166758910047837, + 0.48724756048469897, + 0.5952878133178541, + 0.5051169105537862, + 0.612286563888966, + 0.5124224661684611, + 0.533874404448397, + 0.4657065872938351, + 0.596519221115591, + 0.516451756415182, + 0.49142548472243897, + 0.5710670473622114, + 0.650373429927166, + 0.4609151747901368, + 0.5932869125996934, + 0.6578585809987704, + 0.5710324484801889, + 0.4977916340571564, + 0.5494036682714517, + 0.5335856058822706, + 0.5332363891898495, + 0.6419471451310421, + 0.5905225172360283, + 0.6189834624372395, + 0.6429282151366019, + 0.4648705931817338, + 0.4502387823728122, + 0.5214573165678819, + 0.6315379748247014, + 0.45264483129833566, + 0.4928953950519291, + 0.5224823675949615, + 0.5404922085273672, + 0.4944266886074341, + 0.5207051482013256, + 0.560772290698775, + 0.5436508766539484, + 0.4881722901603142, + 0.5527112966258244, + 0.5177671758320254, + 0.5946428876314663, + 0.5938811885150271, + 0.48637450281803263, + 0.5536062009312114, + 0.48585645204871447, + 0.5814070639799787, + 0.5386558216654445, + 0.6371140031375921, + 0.5485171851304155, + 0.6193364723264174, + 0.5060645838808097, + 0.6544143171255272, + 0.5790360756435216, + 0.6443265571557864, + 0.53578054300436, + 0.568643614508813, + 0.5416236903494775, + 0.4685956367080625, + 0.5119818723027355, + 0.6224868768354261, + 0.46073792697852706, + 0.46848864141114177, + 0.5338850250341416, + 0.4883879063615012, + 0.4645684899136797, + 0.5853332053296874, + 0.6521802181224414, + 0.5308117574572698, + 0.49488592143883675, + 0.45409501934835916, + 0.6528681079675999, + 0.6030493015935778, + 0.6107375775969428, + 0.5197949992789009, + 0.617793962472035, + 0.44652925671896454, + 0.47551483626191327, + 0.5615461557877105, + 0.5690840909566475, + 0.5723733152503158, + 0.6621522983476402, + 0.6352790756218946, + 0.5739389777361676, + 0.6342754992944779, + 0.5671663843659809, + 0.5775070292578922, + 0.5228244418338164, + 0.5546849321409015, + 0.6361805102596221, + 0.6405905104536298, + 0.6462493897454781, + 0.5288032465247304, + 0.6458590785840647, + 0.5715693385406039, + 0.5839561276988029, + 0.49133334393357225, + 0.46988945312511543, + 0.4914593809375865, + 0.6102928299007527, + 0.5668166085785759, + 0.562168290579512, + 0.5891589661922534, + 0.5129965699397484, + 0.5598081098072141, + 0.6627154445451214, + 0.5608084377087084, + 0.6152771896539693, + 0.48164617849555, + 0.5336264187066465, + 0.5818928478135942, + 0.6007462482107707, + 0.4783700487045091, + 0.47373771876548454, + 0.5626566817833839, + 0.5162153308178679, + 0.5797657297808009, + 0.4605993023104847, + 0.5086414337399571, + 0.51298243428798, + 0.621254259910546, + 0.6611145733120302, + 0.5215276316542885, + 0.5389733577686314, + 0.5911896787401294, + 0.4618765681873196, + 0.46752059246987937, + 0.5643080489820481, + 0.6220497624160777, + 0.5137667520536466, + 0.5071787073747709, + 0.4564189388262528, + 0.45996374152531005, + 0.4527963910294846, + 0.5411298482817113, + 0.4663850707811351, + 0.588737145288359, + 0.4568199051852399, + 0.6077992502158993, + 0.5733261212404059, + 0.5736842992606543, + 0.4624960284999269, + 0.642172893588695, + 0.44946699598368106, + 0.46599441046652545, + 0.5450496766240644, + 0.6225475173408443, + 0.6557915641481267, + 0.44560956846420513, + 0.5230914354272375, + 0.6328379464094734, + 0.5985049675682865, + 0.49090857897056955, + 0.5676333397500618, + 0.6071794099442095, + 0.5062690501587317, + 0.4687593402693735, + 0.5845366681914945, + 0.45158340384418877, + 0.5918388766495675, + 0.5129446751333335, + 0.5757994483368793, + 0.49790149679412565, + 0.4597786882450119, + 0.64541938820969, + 0.4952151201976618, + 0.5866405216565903, + 0.5101568047646915, + 0.589438810492763, + 0.47892983949371304, + 0.4530856928650305, + 0.46380203066437836, + 0.5265161565217664, + 0.5423658284656355, + 0.5882331315002318, + 0.5468243214993546, + 0.6318662337996335, + 0.5518845495468349, + 0.5180386517144263, + 0.6604635297834276, + 0.5450497336323765, + 0.5833098416850572, + 0.5293667390510404, + 0.6297314881094571, + 0.5405750119958725, + 0.4924530721843322, + 0.47743282745927684, + 0.635728064873122, + 0.4518836369596041, + 0.5618297020679751, + 0.447633595606244, + 0.5795072330210478, + 0.6173227215789759, + 0.5279200607841191, + 0.48320899989854915, + 0.6374518640272036, + 0.5543471869820374, + 0.5257047270101608, + 0.5170014761140584, + 0.5162372640015471, + 0.4802059204717278, + 0.5799769954089931, + 0.47208638041901035, + 0.6152940082014116, + 0.6477030557909423, + 0.48600714479751683, + 0.5847955006814404, + 0.5705455705783334, + 0.4774182578570689, + 0.5280905429622818, + 0.5847038575800094, + 0.4654946532122812, + 0.5965548186333411, + 0.44727891115364377, + 0.5066285133633229, + 0.5094812072722323, + 0.4907875239461229, + 0.6630004013564228, + 0.6107931837537192, + 0.4470303151119168, + 0.6553289384147221, + 0.48154330948953705, + 0.5109063839895849, + 0.6191629597549515, + 0.6344072560112016, + 0.5490494484904718, + 0.6437246977823571, + 0.4640117482256221, + 0.46713594022399646, + 0.4711077864352812, + 0.6034901821685688, + 0.46659164439827394, + 0.6212814440752833, + 0.48313970248470384, + 0.5392598134320163, + 0.6196572371542486, + 0.6052696403162995, + 0.6490814844912799, + 0.6324345576280335, + 0.5451030707818959, + 0.6398688382657369, + 0.5905999252647394, + 0.5420881208935937, + 0.49521161289595494, + 0.4423300033995132, + 0.45872680841821417, + 0.491366233907669, + 0.4611180663838801, + 0.5441636716382939, + 0.5795265796485288, + 0.609248192763629, + 0.5093649571692975, + 0.4584403753208447, + 0.6139625431971638, + 0.5529524960135062, + 0.5783248090807025, + 0.6446807241616371, + 0.4887397880672523, + 0.6264396717965408, + 0.45377087062106564, + 0.6171576240251606, + 0.5232190810460352, + 0.583393763694933, + 0.47272593361211507, + 0.6470323036981246, + 0.5633853119820394, + 0.622881640205239, + 0.5950547418122702, + 0.5423709558514926, + 0.5239135377919436, + 0.5492275486353166, + 0.6575526355073653, + 0.510472441452732, + 0.4445682461510064, + 0.5350510229343044, + 0.6444885257593718, + 0.595573142979184, + 0.5735995246448302, + 0.6219572066392471, + 0.6496848028680846, + 0.6593419018388134, + 0.5315643796083035, + 0.5927984144786713, + 0.5463298270929748, + 0.6089914778400026, + 0.6124493933559263, + 0.4590786871435691, + 0.5974749151724774, + 0.5767609580778283, + 0.5279124388432257, + 0.592884405271666, + 0.4471496292271653, + 0.5965236730798473, + 0.44975166253017074, + 0.6112755466821064, + 0.5522601635584856, + 0.5919760307196884, + 0.6405264411088, + 0.5694469976982259, + 0.5419252415616576, + 0.5708846128180357, + 0.5146939403738285, + 0.6220218318525398, + 0.6371780576465078, + 0.5937887551728463, + 0.560245088077235, + 0.593034490154041, + 0.5206360288586488, + 0.6468918462277442, + 0.5689976105000591, + 0.5641680751047967, + 0.6482179775708792, + 0.5855824955765643, + 0.5560693640402147, + 0.5296251871393013, + 0.5761576135589073, + 0.6307657709045413, + 0.6441441159884069, + 0.5921190784294292, + 0.49240251091558446, + 0.5981045271853277, + 0.5265146150737515, + 0.6194283333033443, + 0.5356333288363961, + 0.5025679793757448, + 0.4726632281740474, + 0.4422887404725629, + 0.4673911585777075, + 0.6131439016647235, + 0.5226309585066504, + 0.6400727591242701, + 0.5656420829009082, + 0.6063379442264413, + 0.5823855152650018, + 0.5736331539073558, + 0.5841439665293211, + 0.5158213801529613, + 0.44410255818965316, + 0.5552858886864318, + 0.6096111535950959, + 0.6305484334911977, + 0.6166365754806213, + 0.5367972043939236, + 0.5280390915794005, + 0.4917002402124853, + 0.6554308918026238, + 0.5270829600896932, + 0.5915740607772215, + 0.5101985858450836, + 0.47636545938372515, + 0.45578157671571223, + 0.6339013710002354, + 0.5694046510756335, + 0.5353541857896266, + 0.6252438268502594, + 0.5760974212348409, + 0.529640434377717, + 0.597007207154925, + 0.6595150492357988, + 0.6197231801892785, + 0.5415796543353106, + 0.5688731903674952, + 0.5004459598983578, + 0.6274863400708898, + 0.48468017400916147, + 0.4796398056850334, + 0.5590969843067648, + 0.5263898920183112, + 0.5026499476171926, + 0.49187096930705587, + 0.5953325530177285, + 0.5010294787378323, + 0.4802479839226425, + 0.5512106742972323, + 0.5204647916973749, + 0.549509681661157, + 0.5804658226033317, + 0.5259514413612058, + 0.5380127702660731, + 0.5823509771216702, + 0.6485356519869048, + 0.5636437097800002, + 0.6498369101288373, + 0.5763847577111025, + 0.5204148785752255, + 0.44369659088835234, + 0.6544385900167123, + 0.5899516946901628, + 0.4778545600047648, + 0.47525710372523217, + 0.6063591314277964, + 0.5422010700124389, + 0.491454289403681, + 0.634404138423917, + 0.532275440541597, + 0.6315614270861067, + 0.46038409563319327, + 0.5594911485274211, + 0.5263967917294945, + 0.4746575216226371, + 0.47532639041949265, + 0.5469245970110151, + 0.549459488078008, + 0.47325830516558093, + 0.5892196436737562, + 0.6369768631956112, + 0.5352329268554391, + 0.6573306435115699, + 0.6283824229400751, + 0.5223379354126755, + 0.4993976521999684, + 0.49415337801190734, + 0.47218644639386675, + 0.6257249242964915, + 0.4485524183948477, + 0.5479712414393609, + 0.5987246351951313, + 0.5399357515135761, + 0.484431095172232, + 0.5560158833212305, + 0.4854922231896715, + 0.5555115137813609, + 0.4618995054798819, + 0.4752606387539206, + 0.5908901295807387, + 0.5932524488612914, + 0.5759919974289607, + 0.5557290857418079, + 0.4924200735891474, + 0.44157625528115524, + 0.6152409107509031, + 0.45992693792451406, + 0.6402702636295917, + 0.6033393433026081, + 0.6172155891431319, + 0.49911366205352087, + 0.5895204414390645, + 0.629698441103386, + 0.5951074853371419, + 0.5311156555865789, + 0.61206411856271, + 0.579954543602695, + 0.5103917850345905, + 0.6198164430495239, + 0.5489638527402142, + 0.4436362867768971, + 0.6524406363354298, + 0.5374507486228752, + 0.4546184573143441, + 0.5777639295659301, + 0.6030173451643548, + 0.5673312608913869, + 0.5917137080560041, + 0.504850718422277, + 0.5045487993434375, + 0.5695153800308608, + 0.6131964779641121, + 0.5955099125734425, + 0.5382873867947946, + 0.44893140793408, + 0.6627416656740861, + 0.6282656646670481, + 0.46821031463113816, + 0.6057380703226926, + 0.6482134885971091, + 0.4663717159705027, + 0.45779924347950973, + 0.5444999452928938, + 0.5417995113317696, + 0.5932670243424576, + 0.5514542609784188, + 0.498979372976281, + 0.5658525753267639, + 0.5139123928024829, + 0.6420711741613182, + 0.45827770316306515, + 0.5283765912964754, + 0.5829326004443689, + 0.562158490909068, + 0.5603911532503824, + 0.6131178443700257, + 0.6464623647942829, + 0.47427759605845954, + 0.5700978002693623, + 0.4742591811792927, + 0.5280971824512306, + 0.5715306438971319, + 0.6607805942233611, + 0.5951228312099706, + 0.45523537131852065, + 0.5271059874866768, + 0.47852952513576963, + 0.49684007550870063, + 0.44075940052000456, + 0.4931827309043814, + 0.4609262116178457, + 0.5295721529587214, + 0.4910306220897516, + 0.5495846983170736, + 0.6017488001875654, + 0.5660786543942764, + 0.48286848950510375, + 0.6106039343795643, + 0.5871417750741138, + 0.5905552601784935, + 0.4759677767335193, + 0.5502879531952424, + 0.44124800391566105, + 0.5181161344891103, + 0.4769790369021981, + 0.5034351850639527, + 0.47398433097387804, + 0.5047751430729752, + 0.6033911248732726, + 0.5838404222410155, + 0.49069097748221135, + 0.49643228731691047, + 0.4983960790512128, + 0.6039367806558154, + 0.5263973469103135, + 0.6170675257603335, + 0.4465549281412054, + 0.6488353282499527, + 0.6402171729636037, + 0.5925041943796093, + 0.5396052150815809, + 0.6340898188718463, + 0.6522930560591196, + 0.6432547990487465, + 0.6310625624404811, + 0.5705512807914708, + 0.5782577678375276, + 0.6287030310150256, + 0.47800431528091764, + 0.4671679128662468, + 0.598035534743157, + 0.6108645742935928, + 0.45604877066553, + 0.6157728564772569, + 0.5554833218423358, + 0.5687715171706538, + 0.6261196127845134, + 0.4863213288987924, + 0.48555658593853007, + 0.5998751001205475, + 0.5960838517717643, + 0.4914301258833425, + 0.4841269014498236, + 0.6224141640460443, + 0.650935306113029, + 0.5392214960694902, + 0.6116030351762977, + 0.5992808186068687, + 0.6268220627256134, + 0.4900886039022405, + 0.5512882177212071, + 0.4965751886147183, + 0.5051332663090943, + 0.6196515769776535, + 0.5675735113569549, + 0.5602269929730872, + 0.5684329401048633, + 0.6241154252625922, + 0.59060401748968, + 0.5958513220600758, + 0.5252688190940605, + 0.4815715629495454, + 0.5450184528013915, + 0.5839396495483783, + 0.5144580207285758, + 0.4795102549389405, + 0.5500961022922686, + 0.4777102126448724, + 0.6106425012839043, + 0.50385867051939, + 0.6178047380041978, + 0.5204250780870274, + 0.6438817863748303, + 0.5798740540898724, + 0.6410861781677828, + 0.4925718304064529, + 0.6043592449688995, + 0.6224196647266205, + 0.5899407271366337, + 0.4871012636644787, + 0.6115637457308909, + 0.5355333663333504, + 0.5459955642320808, + 0.4548210281254913, + 0.4668174649392271, + 0.5755687488430193, + 0.45957538650544005, + 0.6272955122539615, + 0.6182445163210737, + 0.5155358365434146, + 0.5469407170429106, + 0.45083072689478837, + 0.5213981672929938, + 0.5441147558626797, + 0.44230448172902126, + 0.44198480303079385, + 0.5913217972468479, + 0.5541281189696381, + 0.483267782978438, + 0.5615881149493298, + 0.6272425830053541, + 0.6237397769772729, + 0.6065377505139147, + 0.5968679122297349, + 0.5486371938099007, + 0.6460841749849702, + 0.5892187377357053, + 0.6562242614873901, + 0.5335836027228262, + 0.5202691548757744, + 0.566739089915941, + 0.6080759794580755, + 0.6572615969721993, + 0.6217576702629706, + 0.6513874192748924, + 0.5025489428189885, + 0.4962516455633073, + 0.5647415734313436, + 0.5672596362873215, + 0.45585805894868275, + 0.5923657759423293, + 0.5967276189183864, + 0.4736283637269939, + 0.6619550466557595, + 0.5045146243860151, + 0.5218002545013155, + 0.644946269367848, + 0.5742958493153111, + 0.4959338227438429, + 0.6444375522898889, + 0.48168876187893805, + 0.5975822796900339, + 0.5040392358085382, + 0.580521721261853, + 0.6568954565614262, + 0.4996946339686394, + 0.5486349375784707, + 0.5040831238159268, + 0.5081296184020507, + 0.5846141918122287, + 0.4883775397853155, + 0.4654172645190959, + 0.4566086662894613, + 0.4439228268014822, + 0.6151855653268015, + 0.6029194533757709, + 0.5912969871002439, + 0.4992546756347684, + 0.6532455462725439, + 0.5309685285257727, + 0.6057209451725882, + 0.6337869167261997, + 0.6296690388296212, + 0.5659281671723434, + 0.526212578301812, + 0.6358361681031579, + 0.5242244408865967, + 0.5159134811461762, + 0.5424646544257996, + 0.49939822876154094, + 0.5728881472573404, + 0.5269638720408611, + 0.45635618477351786, + 0.5206554765360614, + 0.6246080445335515, + 0.6555762666500689, + 0.6303272566999542, + 0.6122645802286093, + 0.5770156679324062, + 0.543850720176267, + 0.4830569219472776, + 0.5956959714845421, + 0.5813148593320332, + 0.5008505145752997, + 0.5878814099122175, + 0.6269890066616665, + 0.5141769647198211, + 0.6021714373324348, + 0.45261561632405894, + 0.6512389566190696, + 0.5940645491906182, + 0.5682165152356994, + 0.658853118945776, + 0.47513410017297025, + 0.5640706325258198, + 0.6444329864791787, + 0.4441101279266843, + 0.5301669396115938, + 0.6292551018930491, + 0.5790230009628275, + 0.5468233791775257, + 0.46408824785027797, + 0.45166692432733707, + 0.4432649432401232, + 0.5358003267379892, + 0.6004317584470789, + 0.44283726632437953, + 0.6220759660782722, + 0.46037960580946613, + 0.6415417998116074, + 0.5122638881228853, + 0.647088199391292, + 0.47258544724208706, + 0.6114480983589075, + 0.5042211840344232, + 0.46387684531898543, + 0.4683790023707964, + 0.6537408151001834, + 0.4718130109490031, + 0.4991568779591651, + 0.4942913599582826, + 0.6583758390833363, + 0.658979553064881, + 0.6018763655783078, + 0.588881159001478, + 0.603522666789551, + 0.5817272008425913, + 0.44454147519384946, + 0.6144323791897065, + 0.605883068756049, + 0.518452031236688, + 0.6528305972314489, + 0.44999005324910013, + 0.44311933494997097, + 0.4770140795341103, + 0.5788431424019036, + 0.5151074538159648, + 0.632042157400355, + 0.6080453896075653, + 0.4665401230052134, + 0.5315616287100452, + 0.5339621508532416, + 0.5602499202327745, + 0.49271791048663044, + 0.5254132138481367, + 0.5971412296566359, + 0.6214831363226837, + 0.5337434374221849, + 0.6402533762408551, + 0.5712892818494857, + 0.49022057184571605, + 0.46940380990458175, + 0.5570674883985869, + 0.5337682639522661, + 0.5453327067337047, + 0.5524417758705297, + 0.6480183112209046, + 0.4802558521274828, + 0.49519838027580854, + 0.4405453356340962, + 0.5444165025759315, + 0.4811088719956291, + 0.5348845653757933, + 0.46345020382256225, + 0.45493415971784085, + 0.62893126867925, + 0.6449102725359779, + 0.5687886015601502, + 0.4412226960282998, + 0.539455806404417, + 0.5552709341992711, + 0.4583666871848123, + 0.5540846409656824, + 0.6272416338105251, + 0.5023617000498979, + 0.5533111472369594, + 0.47507681451809575, + 0.4682252435571955, + 0.6556105416082475, + 0.5444999336090008, + 0.5065894767831122, + 0.5239194663990885, + 0.6420171788678706, + 0.6263341439967567, + 0.47628097480476694, + 0.47918727354314805, + 0.46841000936108407, + 0.5084785713761769, + 0.6404906288522201, + 0.6285546983591839, + 0.5314779245075554, + 0.49348865058215435, + 0.6034754917484064, + 0.6024349697559951, + 0.5609057745387657, + 0.52971588102951, + 0.576305424856531, + 0.5864004740174408, + 0.6594995296796766, + 0.612035179205245, + 0.6233465584588511, + 0.5704456361324032, + 0.5330760088124564, + 0.516274016305236, + 0.6006801305611391, + 0.46637767321315343, + 0.5665214666931209, + 0.4894139372590041, + 0.4797273840349814, + 0.649044626868058, + 0.590203616039256, + 0.5257425165079348, + 0.5688170691776, + 0.5151476180647182, + 0.6197160634803975, + 0.6323953042112546, + 0.5459218685288358, + 0.4485688405533153, + 0.4969762821034176, + 0.60045456831404, + 0.5919379026842253, + 0.6165783562687849, + 0.6318935796951656, + 0.4664911650870921, + 0.5947921298435035, + 0.5226671153051496, + 0.6146185811206382, + 0.6487562351074109, + 0.6262595197017742, + 0.456973526994908, + 0.597694451102209, + 0.5138625014337165, + 0.6018169162206719, + 0.582829788929152, + 0.6294668716240636, + 0.5518472866221459, + 0.5841749096795126, + 0.650542708701191, + 0.5131571263836645, + 0.5063167710256521, + 0.5768061407512677, + 0.6406806299304084, + 0.5865626826119303, + 0.6436253604480281, + 0.44042750277195586, + 0.5378251404171261, + 0.45676946644006283, + 0.6007943886988956, + 0.6097418180188833, + 0.5067746938406766, + 0.5969585471986976, + 0.5841008609832814, + 0.5338830097048338, + 0.5124296266207745, + 0.6554959049797292, + 0.5996396081422544, + 0.5051878190259123, + 0.6289299076384158, + 0.44388175891215975, + 0.5221919734147621, + 0.5789782972048172, + 0.6222895899657475, + 0.5681464945845147, + 0.5079171818453359, + 0.6020252575250682, + 0.5437207211236403, + 0.46382532008763044, + 0.6334174972764904, + 0.5205129612499428, + 0.6412998597076712, + 0.4801123759184433, + 0.5345158562200776, + 0.5626284560944269, + 0.5777141599082698, + 0.5467803056768954, + 0.5350418646949517, + 0.6626905166024751, + 0.46107004644293414, + 0.5204048791055695, + 0.4990115876058973, + 0.46676759759140735, + 0.5125305204143282, + 0.5343163856600126, + 0.4628429290992125, + 0.6606017062451137, + 0.49569985041647185, + 0.603770105778569, + 0.44784024121802374, + 0.5831230841504125, + 0.4441579959308629, + 0.5415557185316072, + 0.49846008678487475, + 0.486112544656727, + 0.5177383617681899, + 0.505484287003496, + 0.5086826630344325, + 0.5851441798671196, + 0.6244722997378519, + 0.6211620333628405, + 0.6089495699670673, + 0.5525334662234563, + 0.5427615258411588, + 0.5342321970706494, + 0.47621653302948563, + 0.655138145564674, + 0.4821136515844728, + 0.5708734405679023, + 0.6122894084564448, + 0.6580462841587617, + 0.483817395049366, + 0.5622627945471949, + 0.6422942204870988, + 0.5802033005396019, + 0.5007484342940474, + 0.48148344100782503, + 0.5348023789904648, + 0.5386071406721472, + 0.6429804862885135, + 0.5219711854924349, + 0.5385257618205667, + 0.4766161233721402, + 0.6474852712430456, + 0.5643789822107229, + 0.4713506609827226, + 0.5382668763763581, + 0.6529339386031496, + 0.6028143324066415, + 0.6446716701415232, + 0.6244983199185179, + 0.5752181095817759, + 0.5593088634233236, + 0.4456333415245058, + 0.4821505807859139, + 0.5369074716730385, + 0.47459699924816734, + 0.5343559738679361, + 0.5677445605522174, + 0.6603994213843654, + 0.5289525230819249, + 0.5064724469849655, + 0.6471005287091863, + 0.5634139187862995, + 0.6046441241189668, + 0.5695862009376401, + 0.5644778001711926, + 0.5037407435873807, + 0.5397915099267734, + 0.6286486663008016, + 0.537870794478115, + 0.4717454054538763, + 0.5036253660459813, + 0.6253715351784906, + 0.497905470987521, + 0.5699710102495075, + 0.5335659137767805, + 0.5233495103777505, + 0.5784089253845907, + 0.5141583785850722, + 0.561193992362913, + 0.6591227436319621, + 0.5457559499819828, + 0.6462580310711963, + 0.6091701094571749, + 0.5062781444019873, + 0.47676310376523445, + 0.5545309001823433, + 0.6210062869023867, + 0.5446037214980778, + 0.5309898693288063, + 0.6606758819323166, + 0.6469078743726004, + 0.4728739581570522, + 0.5700501448718095, + 0.6466262061483994, + 0.46964333270570435, + 0.5065987188193997, + 0.5228321279265609, + 0.5843477551683605, + 0.5040370056047073, + 0.6398391568534983, + 0.6305385723178303, + 0.5943092567930266, + 0.6438830540154532, + 0.6215625541570944, + 0.5392629159135656, + 0.5474983444690628, + 0.6537695482365408, + 0.5845585615681514, + 0.45409812377346936, + 0.6042094341260486, + 0.6414609638454367, + 0.5108425066584653, + 0.6480904352188939, + 0.5921596825774829, + 0.5175963537192374, + 0.6116991884715421, + 0.4779515151660467, + 0.44938761585110987, + 0.462911110192633, + 0.4563080106243879, + 0.48107252277083473, + 0.5362619828862096, + 0.5229044831222576, + 0.5239611251766856, + 0.47885636501767576, + 0.533763458666634, + 0.46215761352924145, + 0.546760071854423, + 0.5211531578603885, + 0.450746464492405, + 0.45067767673575027, + 0.44705425673154786, + 0.48603282259070396, + 0.44002841461609266, + 0.526598414033105, + 0.5502207369446479, + 0.5135731123233551, + 0.5296051364904825, + 0.45745140209722496, + 0.5368671153929743, + 0.4625893585981875, + 0.5121653815522942, + 0.497761468988845, + 0.4459132115143539, + 0.4998924636236082, + 0.5175405332059352, + 0.44965503334915047, + 0.46650458969208153, + 0.4790284368427222, + 0.45994162081196005, + 0.447783579747223, + 0.49992704188433507, + 0.4590385848580455, + 0.5210296431070495, + 0.5463085263756771, + 0.5108878122376033, + 0.48748512062063165, + 0.5253554628242325, + 0.5192354268503, + 0.5147806619318216, + 0.521451339765208, + 0.44166244692086193, + 0.5083067493631628, + 0.534945907008597, + 0.4646270370329289, + 0.46192639615663694, + 0.5015122314725056, + 0.48374928124569205, + 0.5377155259587866, + 0.4974930783234369, + 0.5475234350258965, + 0.4566305227893087, + 0.48078503003838075, + 0.5453099344011437, + 0.5218338110335202, + 0.4806423964177092, + 0.4889315667330145, + 0.4405370028020923, + 0.5480480025571413, + 0.5472566047292625, + 0.4788238363330264, + 0.4714556534545457, + 0.5003897993665635, + 0.44481630332575095, + 0.48426282405171883, + 0.5000478764235377, + 0.46759782133763383, + 0.4910699837696759, + 0.5443905676531134, + 0.5022186307827335, + 0.48684406880916087, + 0.5313672263696252, + 0.48984055428177875, + 0.4788386975058849, + 0.5025616431445954, + 0.517504191548617, + 0.4997002797852144, + 0.4682657557772974, + 0.5031624741380548, + 0.4460935714067617, + 0.5443728372032599, + 0.4924426801193217, + 0.45818347882487204, + 0.5473740539600478, + 0.4572557404910296, + 0.46226059067816216, + 0.5098914244967012, + 0.4899412212271815, + 0.5403879262632095, + 0.5257640624652672, + 0.4923361336458026, + 0.4707073620192267, + 0.45492848445895084, + 0.5020841210964045, + 0.449124392881784, + 0.5299673027289001, + 0.485901484530853, + 0.5191658634088191, + 0.5481914444254975, + 0.5402121602626762, + 0.4909649323074542, + 0.4431710040228994, + 0.518409182311388, + 0.5246677491818067, + 0.5508824248364158, + 0.5259076306113466, + 0.4421046208219581, + 0.5390650255115803, + 0.5345603519848843, + 0.4982715856794865, + 0.4946764590250501, + 0.5079329120778403, + 0.48652752190969484, + 0.5007504112032415, + 0.5220843135700487, + 0.47346414313809426, + 0.5279936278525559, + 0.5464299633887214, + 0.5007980579763358, + 0.5217469873686531, + 0.48645631818746016, + 0.5093200395018589, + 0.5095694325275899, + 0.4565512949422361, + 0.4941260295151863, + 0.5435101222924519, + 0.49930779542220843, + 0.5297491017566093, + 0.5320265676845953, + 0.5263503087661392, + 0.5002926083339357, + 0.5175322163633126, + 0.49533391234937474, + 0.46178708799484847, + 0.48242291650151964, + 0.5363325252811623, + 0.5467678445025547, + 0.5073155983594969, + 0.5303521353436152, + 0.4840950640279553, + 0.46658382780549873, + 0.4629987292665493, + 0.4862672938388731, + 0.5355278554088189, + 0.5323737491686743, + 0.4993197635327316, + 0.5146321071141229, + 0.4563442394196472, + 0.517517612960158, + 0.4536132988918578, + 0.5026677128630891, + 0.45122285261963363, + 0.5339645888631674, + 0.44350036916156144, + 0.4535705778811892, + 0.5004441386574914, + 0.5021481839107926, + 0.5032747209723456, + 0.4471294108126076, + 0.504936298390065, + 0.5495164647342335, + 0.4925325947809809, + 0.5408292886745945, + 0.4572410730997889, + 0.4809202661070691, + 0.45726053513083503, + 0.5391645535593442, + 0.5219773305015949, + 0.4721770496214336, + 0.47323964763579845, + 0.46511035322515254, + 0.4583667518697029, + 0.47711113840334185, + 0.4670405706560235, + 0.5107063710838278, + 0.5444969818433723, + 0.5433954920026887, + 0.5437530373087541, + 0.5029742686909884, + 0.4908900535782552, + 0.5505550677267828, + 0.49058741411092555, + 0.5403517628392998, + 0.49792039503951685, + 0.46797813479441863, + 0.4424283173514819, + 0.5299969370250625, + 0.47977680048802906, + 0.46174868101946814, + 0.45807211226989686, + 0.48522751411735077, + 0.47465793970031994, + 0.548997797022595, + 0.45168037674426764, + 0.5231327580225373, + 0.552578199872215, + 0.5506113044810136, + 0.4605386313208377, + 0.5328140039878324, + 0.5369471100026542, + 0.5122201654792792, + 0.4428008844367746, + 0.48169414586530374, + 0.48196597853446943, + 0.5511886685469572, + 0.46599573196954985, + 0.4912121853392228, + 0.46929916424859774, + 0.5442116340800611, + 0.4435064662033388, + 0.4778789923213032, + 0.4823025879948802, + 0.512387955100536, + 0.5036108023584304, + 0.5422217812818584, + 0.550316721058889, + 0.4531273282675673, + 0.4820368921438827, + 0.5446916432698791, + 0.4401583829498117, + 0.5202797983337846, + 0.46721826911559466, + 0.4818513525198108, + 0.502295880247652, + 0.5261856037653357, + 0.5099702893609099, + 0.5417046562360849, + 0.46025247347428955, + 0.5322746805695373, + 0.5271248695125625, + 0.5300790746415558, + 0.46595248313638815, + 0.4978458605683531, + 0.455039972858799, + 0.49538910626266547, + 0.5490159373692401, + 0.5123631962573527, + 0.4558917504977572, + 0.5035802817995109, + 0.4520026037519931, + 0.5509629997596902, + 0.546340800228662, + 0.48553634701300663, + 0.4403797581724139, + 0.45408328440454626, + 0.5527290750513354, + 0.4664234663862078, + 0.47828958662202464, + 0.5388653404409051, + 0.5272276680998217, + 0.525204169396334, + 0.46332163889139305, + 0.44835569555221944, + 0.47241775118786694, + 0.5042288258559819, + 0.4619781469531728, + 0.49526908720160834, + 0.507677128624789, + 0.4986285514285781, + 0.5379345404802417, + 0.5025613734036029, + 0.5067057044579115, + 0.45393540636926705, + 0.5219736471694149, + 0.4889623126061655, + 0.4542574842854277, + 0.48092409095456207, + 0.5363391457934567, + 0.44943474537600603, + 0.44740464140633057, + 0.47189563372753923, + 0.47953038126468944, + 0.5461312436913969, + 0.4698664990845312, + 0.4709006521051946, + 0.5185331397990933, + 0.44131257446710753, + 0.55324372802346, + 0.5166050519150517, + 0.4951112657248874, + 0.5145927680224582, + 0.5331498489426274, + 0.5349951268444707, + 0.5200794986358326, + 0.5414697069925833, + 0.5353456737504952, + 0.5510913030346523, + 0.44654638925719403, + 0.5029706319942161, + 0.4753285025592933, + 0.4403563209137715, + 0.4602890594657261, + 0.4935202676503201, + 0.47084637640303495, + 0.481758419388865, + 0.5477451170677488, + 0.5192010137273964, + 0.48270861949888144, + 0.44538264190523824, + 0.4840813606998736, + 0.453808328771069, + 0.5073067331863319, + 0.48743097733343693, + 0.46723248912006704, + 0.5068642240681684, + 0.4933743823924902, + 0.44168776766835655, + 0.5355165793476518, + 0.4651107542696686, + 0.4535172007902023, + 0.5048392187352013, + 0.5300512719364976, + 0.4590951499137685, + 0.5235430422894845, + 0.5016322629829356, + 0.47850976821845076, + 0.4825889161797091, + 0.5417545228889756, + 0.5020463159359633, + 0.4733512165347729, + 0.4788751427992347, + 0.5079570619372276, + 0.45557344420623086, + 0.49860482441927484, + 0.47853333136469695, + 0.4630444627274992, + 0.46789544451492715, + 0.4728896915125145, + 0.4968147713813522, + 0.4989623214999106, + 0.5459362648040386, + 0.514194916049787, + 0.4794434026629243, + 0.5168859615181041, + 0.5302714944190517, + 0.4815273178862476, + 0.5509836671832962, + 0.47776278028442143, + 0.4457307928862806, + 0.5335787285642646, + 0.5525586912960719, + 0.4951647960223211, + 0.4489057645942433, + 0.5020612662328023, + 0.5422018989471856, + 0.4673091075809664, + 0.526502069960038, + 0.5364601489781403, + 0.47671054812538793, + 0.541234087972872, + 0.4896628937640873, + 0.449105102168695, + 0.4469436080644785, + 0.4475025926073451, + 0.4730425554780745, + 0.5077794179386329, + 0.5427742310489462, + 0.5457772546519686, + 0.4621533127948775, + 0.4788745542573978, + 0.49769017840479346, + 0.5015376517318516, + 0.5217942168692028, + 0.4967834453543757, + 0.45185068499539294, + 0.4591440159041572, + 0.5235841169392541, + 0.5063764015731761, + 0.522670153635166, + 0.5374619266511503, + 0.45174962577158106, + 0.4455650207175721, + 0.4721540662099931, + 0.5105521446167013, + 0.47628163480603825, + 0.5383533577407129, + 0.4671001818941347, + 0.4813956201389645, + 0.5067589546492673, + 0.45868840168445907, + 0.4510120246783962, + 0.4605364438614253, + 0.5027388997662727, + 0.463021253765109, + 0.4701676836929815, + 0.4687795718084852, + 0.4785297760647492, + 0.5300120103644423, + 0.5202452497785532, + 0.4662442063187078, + 0.4801641418911408, + 0.5453911937883829, + 0.5512614564629349, + 0.45893276160006136, + 0.5521702459416883, + 0.44759129595714486, + 0.4757001153983449, + 0.5150013829740698, + 0.530772695701723, + 0.4865015666965814, + 0.5108006484481005, + 0.5351453221808341, + 0.440948190750314, + 0.474841134468187, + 0.48704669619841684, + 0.4837230303274437, + 0.49753012312770284, + 0.5271734961876385, + 0.48101216511312483, + 0.48564567810959663, + 0.46513188791059124, + 0.44239815336317106, + 0.47486357629989223, + 0.5103133959741393, + 0.5076078322677531, + 0.45771458094002193, + 0.522106709954659, + 0.44985717929884167, + 0.4654783565358801, + 0.5345194895171855, + 0.5384566561533041, + 0.45639749856618517, + 0.5159885110354646, + 0.47122806917955345, + 0.49139580288420065, + 0.4842264777224117, + 0.5323867062752629, + 0.4417368711548055, + 0.5418900133442175, + 0.4630548285351318, + 0.47652584496764444, + 0.46911177626053063, + 0.500006205405925, + 0.5522723134543562, + 0.502089506444127, + 0.44607224267130274, + 0.46532762400767474, + 0.5175775786456223, + 0.5289836034520852, + 0.44143918364700657, + 0.4668457259153231, + 0.45759233091497936, + 0.46357417408692425, + 0.4750953709117337, + 0.49873656682137857, + 0.47562832536384037, + 0.4509183182410935, + 0.4502499161091297, + 0.4613633562086863, + 0.46825653619667934, + 0.5218723054540533, + 0.446541577841261, + 0.44276344886866886, + 0.4627541287342283, + 0.48836527957797304, + 0.500015815179826, + 0.4815388079373886, + 0.5159208361064009, + 0.4617205734645964, + 0.4912100843931819, + 0.48396192269853144, + 0.4959691624147033, + 0.5121459866128932, + 0.5518113889508504, + 0.49556974461569553, + 0.4539704845785117, + 0.4626329329184366, + 0.4921435325272624, + 0.45404330014773353, + 0.4998963265646167, + 0.5132881654078496, + 0.47615809001277887, + 0.4910797091724631, + 0.4584832321274609, + 0.5515752141328351, + 0.5109893955668225, + 0.45737855034390523, + 0.541993821434818, + 0.4519511593033392, + 0.4823277996929634, + 0.5000030855654043, + 0.5296412599182709, + 0.46639135609133536, + 0.4530225708271324, + 0.5156086099752867, + 0.5046157824746257, + 0.5114570082559318, + 0.5478914722501212, + 0.5463789093433056, + 0.4984939207278336, + 0.46021823278141083, + 0.48743798209137024, + 0.4785735660514743, + 0.5513267204850484, + 0.5084921871537009, + 0.4421530896541187, + 0.5259788999369474, + 0.5368589256066334, + 0.44086662164879276, + 0.47033531898009623, + 0.4457181080854798, + 0.5153847063088709, + 0.4506838385727391, + 0.47031726129069934, + 0.506384427457336, + 0.5456818430579751, + 0.45529155793340015, + 0.507416673741163, + 0.53274890440812, + 0.46034368892799216, + 0.5092695837488931, + 0.4467615439227067, + 0.4466210409220705, + 0.47093903242101365, + 0.4828689866560092, + 0.4998280861664851, + 0.5010008360589852, + 0.45239782359771713, + 0.5467718493310956, + 0.45462564300157393, + 0.48181580126723234, + 0.5057982032800061, + 0.5052964651645784, + 0.5126345155559717, + 0.4541662946826917, + 0.4538935398865571, + 0.5011442946458606, + 0.4910839933881806, + 0.49539319578806384, + 0.5423756941808072, + 0.5228512857534042, + 0.5467328810630565, + 0.45617355751081373, + 0.46093992644963605, + 0.44166295027847685, + 0.48740990180719573, + 0.4451842383673549, + 0.5164563788944292, + 0.5106594995356926, + 0.5445585782030533, + 0.5070593528514863, + 0.48236494190431034, + 0.47826297960554337, + 0.5406366984809535, + 0.5131618731178538, + 0.546491039550791, + 0.5457440903614441, + 0.5076896615138708, + 0.4913668151553753, + 0.4544864315018098, + 0.4917195130288148, + 0.5210773850663668, + 0.4533765985564488, + 0.5387598910844058, + 0.46375097022584144, + 0.4939139857155669, + 0.4738614667603051, + 0.48223066895365213, + 0.5481624546378039, + 0.45121406901466493, + 0.5046509105533664, + 0.5428593650346907, + 0.5377734076574995, + 0.532686341065169, + 0.4989088496178363, + 0.44992023555512234, + 0.4725921752797091, + 0.4744161046903463, + 0.4650205830312435, + 0.5008563755670546, + 0.5249060450851248, + 0.4675598434880448, + 0.4414574265072676, + 0.5221004252865693, + 0.5368830957620438, + 0.5250274341986604, + 0.5132930993670766, + 0.44793299331686226, + 0.45720525628330877, + 0.5485614256996251, + 0.4710418990158193, + 0.5290332577960132, + 0.44901353172439773, + 0.5417414035620551, + 0.47608177119393924, + 0.44445065024844793, + 0.5078737405905928, + 0.5270850892028363, + 0.5110057320748058, + 0.548786627276374, + 0.5049939868490348, + 0.48742033596091766, + 0.5167074171103884, + 0.5127561370900736, + 0.5332572496444233, + 0.4411179568225041, + 0.49204856381066847, + 0.49762434811008316, + 0.4987959347200178, + 0.4585905797681445, + 0.535529150910604, + 0.462107382014067, + 0.4592087358946877, + 0.5349876227735795, + 0.5243555840996619, + 0.5197337179154131, + 0.44575171144998005, + 0.5033728607810628, + 0.5053794636105378, + 0.5010892574601941, + 0.4429187197832827, + 0.4493194073839649, + 0.5476339752037618, + 0.4990044570460863, + 0.4590409102354493, + 0.4546875345277549, + 0.4538187883858361, + 0.5412637571567273, + 0.48591756451181667, + 0.4907711765086819, + 0.5533189694831956, + 0.4603706668658596, + 0.5153463794852624, + 0.47596767441015764, + 0.4672744113427578, + 0.5370785265386098, + 0.47149302121469205, + 0.44239464655377436, + 0.5501899767084522, + 0.4436830073864848, + 0.551066852963243, + 0.5349905912180943, + 0.5528656207744774, + 0.4552980201906272, + 0.4846277831487615, + 0.5309661139032322, + 0.5305115838658034, + 0.5169500586097333, + 0.48657457434750084, + 0.5310391810455939, + 0.47993559278975034, + 0.5225582988791954, + 0.45582408210239894, + 0.503784398656077, + 0.4559625880993094, + 0.475237429819579, + 0.45968761364214444, + 0.514687381475134, + 0.46807940666615666, + 0.4552782027549243, + 0.52377173986203, + 0.5190937717200438, + 0.5232417775397883, + 0.5376195859974419, + 0.5101975228769575, + 0.46189112286913275, + 0.5409418925781326, + 0.47832564092094354, + 0.4675260332657397, + 0.4467475139041063, + 0.5466712570948692, + 0.5255720074323038, + 0.5373131222954796, + 0.49473489155970785, + 0.5277232172064109, + 0.5348705469053461, + 0.5234609518923833, + 0.4925409918182786, + 0.4463980076851703, + 0.4452021253933797, + 0.457094713411212, + 0.5390482821869671, + 0.442091852287482, + 0.5015069927647505, + 0.5055795276662466, + 0.4871579207642571, + 0.4787272333014726, + 0.4697212665554169, + 0.549317972793842, + 0.5258560956317291, + 0.5407733071835003, + 0.5125685574572524, + 0.48029488371205814, + 0.5402611162283056, + 0.4811192611360284, + 0.5104993983831588, + 0.5103139267524675, + 0.5215850640099329, + 0.5135851612298221, + 0.4528419423427511, + 0.46041718594522707, + 0.45560815386108744, + 0.5411062991168208, + 0.4892819663717165, + 0.4863505361359645, + 0.4658015411505831, + 0.5265327355272612, + 0.447399260033877, + 0.4421679468748482, + 0.45308250566597175, + 0.44912077995493754, + 0.4701422720166558, + 0.5034356688898316, + 0.5143872981788751, + 0.5355402688633852, + 0.500482275128798, + 0.5281562110469555, + 0.5136693179224251, + 0.5317688160409614, + 0.45374328929378327, + 0.4808293842246736, + 0.4413493675565063, + 0.5091341265226429, + 0.5505863957372679, + 0.5512069221962359, + 0.46182323972702666, + 0.5379791189475073, + 0.4969703640451069, + 0.4520325321586253, + 0.516540765821514, + 0.45452352687806186, + 0.4771408773186752, + 0.44429756758251077, + 0.539371668830732, + 0.5156936985213147, + 0.4929343938787932, + 0.44434612766721204, + 0.5106507154355794, + 0.5307152085597312, + 0.4804816070923549, + 0.5208600376777535, + 0.47520798069201503, + 0.5297308556286909, + 0.4796610943266165, + 0.547781902148371, + 0.47950078885514524, + 0.4776719720124711, + 0.5216018675386163, + 0.48889436846165035, + 0.4841616237883435, + 0.47447245040130814, + 0.4624381704635183, + 0.5480825684133458, + 0.44342220281740047, + 0.47943550925699246, + 0.5310105424934201, + 0.5055035005640872, + 0.49146479512106156, + 0.4803968055559209, + 0.5534189756052006, + 0.4461767454410557, + 0.4808803516257766, + 0.49133937884409906, + 0.511039186990897, + 0.5457031007572569, + 0.44699034690417994, + 0.5050491994089897, + 0.5025165447445437, + 0.4943942054099541, + 0.5321930609918629, + 0.5105405463789405, + 0.5414158563732695, + 0.5265997187961963, + 0.526487584742934, + 0.4491918431876195, + 0.4432276025074855, + 0.5160557438399503, + 0.5169006446622898, + 0.4631706819907446, + 0.5143538414568325, + 0.45573205267024297, + 0.46924520021629196, + 0.5022477344657738, + 0.45181851387383004, + 0.4403930625707694, + 0.5446300814175196, + 0.4508400900096651, + 0.49765311691473446, + 0.47540030688369556, + 0.47090447051009515, + 0.5260366250130509, + 0.45538361175653586, + 0.4560938164543154, + 0.5058479543163334, + 0.4470360447776797, + 0.5509673166489288, + 0.5229401815851451, + 0.5367670244737311, + 0.5529195564499607, + 0.5036326593375595, + 0.4608729613125435, + 0.46076780450888255, + 0.4552574971587883, + 0.5110103808529872, + 0.549630236224851, + 0.49725323479750116, + 0.469544138513334, + 0.45710593820842177, + 0.5418536328446193, + 0.45500125033388883, + 0.5502996612429033, + 0.5283716523882835, + 0.4453074947587272, + 0.5227289666832792, + 0.5304582496977208, + 0.44666489384510166, + 0.4912792525036186, + 0.4946502321774491, + 0.5001260734588265, + 0.5042046019932855, + 0.47499917256243906, + 0.5250760350830503, + 0.4934522511217839, + 0.47924208642792976, + 0.4487549202636265, + 0.526923410518135, + 0.44358609664152954, + 0.5004549462216699, + 0.47469086191859533, + 0.5454956961206777, + 0.4905046878388103, + 0.5143547884442125, + 0.5510485191585832, + 0.4629743145381516, + 0.4970177103290863, + 0.4663127746021906, + 0.48012531794864827, + 0.44149661711764476, + 0.5297608856128495, + 0.4521572331107762, + 0.5361842282265815, + 0.51376006869797, + 0.4464887287953578, + 0.5002034477010708, + 0.44710908170391894, + 0.502820414514233, + 0.5332518360848747, + 0.5132058233511357, + 0.5154857977362195, + 0.4445929264504716, + 0.4479031789390023, + 0.458236750239433, + 0.4899320835634953, + 0.5434904219547608, + 0.5295625371903081, + 0.4678756188691911, + 0.4415219357677384, + 0.5152982972880799, + 0.5443984478417179, + 0.4616438482180163, + 0.4467289805898012, + 0.4549911985667051, + 0.48170678382142884, + 0.49798110156103736, + 0.44087485893840495, + 0.4916983037190902, + 0.44172227792007773, + 0.5113323309326967, + 0.5256467670232251, + 0.539846167400816, + 0.4910884829065345, + 0.4930500439172758, + 0.532894423669495, + 0.5432342247033063, + 0.5067554760719893, + 0.5122767883610125, + 0.5373453932460163, + 0.5337247806409201, + 0.5242428616848301, + 0.446631605668007, + 0.5265933313710164, + 0.4499953884348078, + 0.5403719394823583, + 0.47243157515010414, + 0.48486403031277603, + 0.486324899596646, + 0.5528366945252511, + 0.4492765140434767, + 0.4982874119738987, + 0.5377993054234241, + 0.5383525823587335, + 0.5300386464425273, + 0.5166099826909274, + 0.4572268336073937, + 0.5189473721806308, + 0.47949643629933075, + 0.5026354131682594, + 0.5352061235861053, + 0.5107336691332633, + 0.4846590486781145, + 0.49378753654287144, + 0.4789019831948677, + 0.49447059447778374, + 0.5291326976839306, + 0.5333949291827702, + 0.44921958665675316, + 0.44334953866882615, + 0.5339301131793522, + 0.44810305041567555, + 0.4519962984696866, + 0.5012990685970427, + 0.5203957336512022, + 0.5471943573081114, + 0.48121909639217636, + 0.5307547945606108, + 0.5154275535232132, + 0.5530688881869443, + 0.44067684689577447, + 0.5073809083116458, + 0.4713698311414736, + 0.5482854250330547, + 0.45115945239840805, + 0.4517148714678872, + 0.4915908717718096, + 0.4668638767789661, + 0.5276106849053377, + 0.4849986100950562, + 0.46097343405053154, + 0.46781735337951225, + 0.5499903646480734, + 0.48457472995966616, + 0.5029710720443011, + 0.46332896399562656, + 0.513569128773052, + 0.4623127039816655, + 0.5424388736269014, + 0.46956005926913125, + 0.44922938569774995, + 0.5003248382854477, + 0.5190452672173378, + 0.49507927842500116, + 0.4489611941876066, + 0.4678946192858283, + 0.5036951511647517, + 0.539307172819995, + 0.5432864861065136, + 0.5470784547677895, + 0.5401992629154225, + 0.4965038198402175, + 0.5003642998500335, + 0.5069803695662246, + 0.5364028196229667, + 0.5330268648749421, + 0.4406944178699931, + 0.4546006201759097, + 0.4886364315107116, + 0.46798953166787, + 0.4880293206478107, + 0.49219409043822726, + 0.5483093694644429, + 0.49829705505326, + 0.4906532697712913, + 0.5293594380876822, + 0.47896830440181404, + 0.5159878533820229, + 0.4632048402222659, + 0.4671730730510926, + 0.5271148785681365, + 0.5191236887917348, + 0.4688365375414827, + 0.5048934601125359, + 0.4702627730799759, + 0.4679122978565587, + 0.4579859708968586, + 0.45468409448799213, + 0.4547375423442659, + 0.5014583974679948, + 0.4755342350517367, + 0.5501998652257157, + 0.4471019855841126, + 0.48107289738846293, + 0.4661318688246098, + 0.5064585446012317, + 0.4433801572402066, + 0.5346749702400588, + 0.5036174803257399, + 0.5482323016059815, + 0.4992264502952363, + 0.4875437143651878, + 0.4416498834813909, + 0.4950647724027781, + 0.546240993298694, + 0.45790400470845855, + 0.5530704929002845, + 0.5191818560602143, + 0.48667903348055547, + 0.5516487527657697, + 0.4919994885042355, + 0.46376459472402676, + 0.5303138008550918, + 0.5304612473452238, + 0.5175627627513973, + 0.488040376761444, + 0.5075954759047477, + 0.44414941739393976, + 0.49144214882599396, + 0.5469263406207248, + 0.5521609411340809, + 0.5437400083781558, + 0.4961812208304578, + 0.4917366205990187, + 0.506894242312347, + 0.5443261828471464, + 0.47613855100075947, + 0.548306620387643, + 0.4459190521451631, + 0.45338281304001393, + 0.4793482914296241, + 0.550244523758478, + 0.50161367141672, + 0.4643431407550042, + 0.5081089093695307, + 0.46616870402181165, + 0.5263904226716384, + 0.5123802017538529, + 0.5051554201237162, + 0.4534534341260816, + 0.4751965052618189, + 0.5008320943323015, + 0.5149747980535236, + 0.49860519869292697, + 0.5398018898924527, + 0.48053503811721576, + 0.44290301459373105, + 0.5012968063142275, + 0.4847467168551127, + 0.4418813836464243, + 0.502108008317298, + 0.4707178616149799, + 0.4515208221447101, + 0.5480171332648236, + 0.5074661980819748, + 0.523045894525048, + 0.5314587229393163, + 0.48893974683486824, + 0.4771350252103715, + 0.5020235312932626, + 0.5460380955025493, + 0.4494975066497413, + 0.4616079314135315, + 0.4861072224200993, + 0.5446748648200749, + 0.5192815099787836, + 0.4789710290165945, + 0.5270319960332845, + 0.44635226564275676, + 0.46956187019185314, + 0.49663724123747144, + 0.47316964801412065, + 0.5186355267689801, + 0.4849205750082371, + 0.47477428130521726, + 0.5241255546264043, + 0.44203763264012974, + 0.5289825815265561, + 0.49346311618955213, + 0.45669775904382276, + 0.4432966235555716, + 0.5119893705247172, + 0.4662041920664602, + 0.5118600883986756, + 0.46185207954421414, + 0.532784665421828, + 0.45613775015095787, + 0.5335331238923945, + 0.4774842275620574, + 0.45675513894077563, + 0.5017534038768106, + 0.45103110405277413, + 0.44094419247064204, + 0.5295325147329069, + 0.5029943232932422, + 0.47277929520198436, + 0.47590261196920086, + 0.494349177989466, + 0.5309214241673685, + 0.4468108738729687, + 0.4465820114184036, + 0.47297949485148155, + 0.5301528460916047, + 0.46599191152695457, + 0.44028291683418425, + 0.5305989884825816, + 0.5211075017418028, + 0.4552858281686318, + 0.5332691647917254, + 0.5520215652961308, + 0.46126034482229683, + 0.4549289035060767, + 0.5173255612405041, + 0.4608469954701173, + 0.5267575546698593, + 0.4832928533632398, + 0.4830493261216277, + 0.5061901332905884, + 0.48964632090721866, + 0.4459940528555494, + 0.5009427977615182, + 0.4951581974675898, + 0.4484530406418354, + 0.5342103213376296, + 0.5185523969272089, + 0.5320298260552798, + 0.5071025120796921, + 0.5027771723839407, + 0.4583833698636522, + 0.4823122997533228, + 0.44116272451394134, + 0.46535665757743166, + 0.5283811652584431, + 0.5140974944387031, + 0.5320357645408036, + 0.524268753193475, + 0.546969599056871, + 0.5050412213554192, + 0.5388781762861101, + 0.5027794718521297, + 0.45074271372603847, + 0.5450469422689722, + 0.4677914550790257, + 0.4464944230401873, + 0.4933052736980481, + 0.5218958606611134, + 0.5312506195643989, + 0.5467237173732243, + 0.4430017878793317, + 0.5462491366984001, + 0.4885018776765826, + 0.5094129776272089, + 0.4482008052564541, + 0.46714455995613335, + 0.518097666367832, + 0.4544714124860733, + 0.5158212100742421, + 0.5381229351010351, + 0.4847653100853379, + 0.5406962236736547, + 0.5516867694655906, + 0.5081701822156369, + 0.44917375555247635, + 0.552206630197514, + 0.5379236128381756, + 0.4472932295673548, + 0.46702293831442854, + 0.5306122085402483, + 0.5498943066198502, + 0.4446806075592518, + 0.4599785119129316, + 0.5076275699248226, + 0.47800100039092513, + 0.460388930224422, + 0.5154465825312976, + 0.49859219761269447, + 0.5192946587039377, + 0.5066821995117871, + 0.46617431038595664, + 0.4583425967742644, + 0.4832248754876481, + 0.5156176308925695, + 0.45672762322433924, + 0.46692400008505386, + 0.5094700202742256, + 0.44746802562223875, + 0.5324329308488497, + 0.4552030745742683, + 0.5069040132805985, + 0.5036629388682207, + 0.5443416626770786, + 0.4447265204408574, + 0.5234280859411982, + 0.5432986235290292, + 0.5264400258646774, + 0.4487463530975136, + 0.4750528889329342, + 0.5153639700201968, + 0.5452356869817088, + 0.5105547986303212, + 0.5280969671148599, + 0.512918728227619, + 0.48060751218491554, + 0.45246132122145016, + 0.5147355958473846, + 0.5453638272997836, + 0.44417638191877906, + 0.4781526791971333, + 0.47486016776322393, + 0.4563742154378906, + 0.5274638811268246, + 0.45960459076039456, + 0.5328974683781041, + 0.5157375281254828, + 0.49996299558878066, + 0.496541620120387, + 0.5100184500831642, + 0.4903004489860588, + 0.4615033024840659, + 0.4430297804152742, + 0.5203935428400672, + 0.44461209383441863, + 0.4509940357251125, + 0.4617160753503343, + 0.5430656249366109, + 0.5334532086768957, + 0.5372325421038235, + 0.4901893859643443, + 0.4494908491734759, + 0.46814148403680733, + 0.4654125119676598, + 0.48058485603226486, + 0.49229431144701497, + 0.4588458150802379, + 0.4860017962343945, + 0.5237635889451376, + 0.44726819954254976, + 0.4788263333516783, + 0.5397114075061935, + 0.5242432370792873, + 0.5067556447030681, + 0.5014521114188255, + 0.49582281424107916, + 0.529744761954119, + 0.47506686409669546, + 0.5130254981547309, + 0.5475972764652667, + 0.49309114663607523, + 0.44842839358535613, + 0.5409352338509593, + 0.46729805687175435, + 0.4738599386564965, + 0.46753704123267525, + 0.46411722964623625, + 0.4538739600100913, + 0.535151593110296, + 0.5241716312413662, + 0.5296286564235096, + 0.49011397440742865, + 0.4653762495174707, + 0.5271564296682635, + 0.5387264775961049, + 0.4684239405512661, + 0.5443625367444644, + 0.5108203886253626, + 0.5300439537113296, + 0.4519266408959544, + 0.5437854489497662, + 0.4625993465685969, + 0.5405214014492219, + 0.5325499966531769, + 0.5446674653565458, + 0.5198419215422815, + 0.4845758763231344, + 0.47301269753193365, + 0.4508565650341526, + 0.4502210776044697, + 0.45069243604758114, + 0.5512935916972337, + 0.5005800008580662, + 0.5243086534852252, + 0.5165474354666498, + 0.5084725882933403, + 0.46190038386536947, + 0.5478441756333154, + 0.44066774582535795, + 0.5354638813110831, + 0.46325220405032974, + 0.497938364040164, + 0.4606319178766538, + 0.4478367632328056, + 0.44322144373021527, + 0.4517226004352327, + 0.49733635046222513, + 0.5333343757744493, + 0.4531360481444345, + 0.49101085207374096, + 0.5365672072458925, + 0.4789953727212264, + 0.4590468663867284, + 0.5249656728097299, + 0.5159390331779541, + 0.4870829564777227, + 0.5383197719435922, + 0.5069254427342442, + 0.4729705731838629, + 0.48108558688058983, + 0.5364745589340477, + 0.49674684269361824, + 0.5460184097185247, + 0.5423945585959032, + 0.5456715383028027, + 0.4805316800195723, + 0.46199223107934495, + 0.5011487836553764, + 0.45244312774426954, + 0.5157534041733747, + 0.48504603706831767, + 0.5261429917763164, + 0.49693331511852906, + 0.480204784317094, + 0.48085568618467633, + 0.47906301325196676, + 0.48862160001475374, + 0.5079591893820599, + 0.4755837481100354, + 0.5495526479781047, + 0.4972803324649533, + 0.4722698107393224, + 0.4817867144648583, + 0.5368352399414733, + 0.5116040053940484, + 0.5019971795448482, + 0.5514696331288484, + 0.5187472258258977, + 0.4702672920214145, + 0.484433213453397, + 0.5056035006763899, + 0.46193919968737235, + 0.4794313831800915, + 0.5194297245617107, + 0.4873218854445327, + 0.5253021081767355, + 0.4970054564035638, + 0.5017746252521208, + 0.4699354984988603, + 0.5015869097578934, + 0.4730067750924821, + 0.5333464025243904, + 0.5437208209103795, + 0.5528109099883967, + 0.4757408569893929, + 0.49374958522707346, + 0.48691141873913985, + 0.49980616975654923, + 0.5314694969251379, + 0.5521967236204901, + 0.4807849011962033, + 0.45811661614719684, + 0.4831239516156174, + 0.5418280063598604, + 0.5259214770981423, + 0.5381861489480628, + 0.5161856535968452, + 0.44015633778887847, + 0.5280128480081128, + 0.485092049325427, + 0.5151765178749639, + 0.501325122914442, + 0.5328490639402064, + 0.44006713268217934, + 0.5243412980642084, + 0.5105738103399142, + 0.506221383011969, + 0.46694789849202, + 0.4623909245768868, + 0.4980203415106383, + 0.47666687097016447, + 0.5447298787879546, + 0.45343338968810704, + 0.5060311061763887, + 0.5095883202892385, + 0.5165059001088457, + 0.5022793888509088, + 0.5370299297776853, + 0.5453770397693822, + 0.44340455075509483, + 0.5124847049637019, + 0.5098531850280912, + 0.5086751271155578, + 0.5102549239937544, + 0.45270105671710514, + 0.480568962528218, + 0.45964150889794625, + 0.5464360377474282, + 0.4900691771131225, + 0.507320082681845, + 0.5301969006913286, + 0.5193770442865873, + 0.505403959693892, + 0.4604584515764735, + 0.5432334450138312, + 0.5092065416599147, + 0.48960089645425897, + 0.442803969010633, + 0.5309952067513715, + 0.47034399769443813, + 0.5306627703978996, + 0.5133886394964058, + 0.5125771160430307, + 0.5022138101549647, + 0.4968194800380454, + 0.5429446021087878, + 0.4674405546806191, + 0.5312834951843005, + 0.5493108589880927, + 0.5466088261406132, + 0.49843137716550173, + 0.5232370481689891, + 0.5101884109298276, + 0.4435297859284207, + 0.49164605714726306, + 0.50107282401424, + 0.45437650540762786, + 0.48432565442119413, + 0.4990130382917627, + 0.457435321055733, + 0.47344838772276443, + 0.5461096822176705, + 0.4839149332419697, + 0.48946780123760136, + 0.46458254928090403, + 0.44635896973621264, + 0.4724286678486628, + 0.5039499170585952, + 0.5395037354148615, + 0.5233609658502799, + 0.48399501049991084, + 0.45951809612559, + 0.5048139924658714, + 0.5263076511351072, + 0.5419074677849566, + 0.4889574286201239, + 0.5502337769056302, + 0.4953515832064734, + 0.518623764973478, + 0.5371953119910509, + 0.5387731774281754, + 0.5324763431460008, + 0.4952412432298074, + 0.5287966435816176, + 0.5267486086659434, + 0.4972704027544774, + 0.49778490906264466, + 0.550999831072219, + 0.544153136677973, + 0.49027119295493515, + 0.5163848821428202, + 0.49182684084825096, + 0.5450288361821898, + 0.45858030514945186, + 0.537580607280582, + 0.5514214729193034, + 0.5426994770367901, + 0.486731104538965, + 0.5325853875993151, + 0.44602345640111807, + 0.5075374157380916, + 0.4852049537518027, + 0.47758812957544083, + 0.4804949352345807, + 0.5083880388918152, + 0.4855283116766912, + 0.5410735131659439, + 0.4437043915401175, + 0.4575284212892631, + 0.5128333183177478, + 0.4520950298178065, + 0.45830692446308136, + 0.5032555249724819, + 0.5157840873836536, + 0.5361033202220022, + 0.5413597739454974, + 0.5050473272894825, + 0.5048364125666189, + 0.510815224685285, + 0.4618009055900819, + 0.527394973182295, + 0.46489682636469865, + 0.5267262958400412, + 0.48844810817178375, + 0.5076401602601615, + 0.4851796814325862, + 0.5488914035140267, + 0.488789520609771, + 0.5058882662934556, + 0.5167213354490097, + 0.5342584702696291, + 0.44183654813889717, + 0.5515689084066324, + 0.444317595175212, + 0.4616581853363521, + 0.49304144517624804, + 0.5033940578885173, + 0.5346656292938698, + 0.44679700183579546, + 0.44608379753808064, + 0.4539412629955789, + 0.5469383281740241, + 0.44059891962320225, + 0.5456041784778148, + 0.5319943228128267, + 0.49667300153938765, + 0.4863348318446412, + 0.4621270495146784, + 0.46963825429565254, + 0.49336370254434453, + 0.548793526068379, + 0.5196135244985227, + 0.525053993890254, + 0.5105320304543862, + 0.546941610930436, + 0.44509327054482856, + 0.4721416001353115, + 0.444470719103569, + 0.47030356118199945, + 0.49562890377735874, + 0.513684384046535, + 0.45598605402313674, + 0.5534343285081059, + 0.49004289613681556, + 0.46459712076469095, + 0.5427563935011184, + 0.49508392176680605, + 0.4441521664201505, + 0.5183330696867833, + 0.5010052532769761, + 0.4833178567181273, + 0.45578772457318567, + 0.44109198065178135, + 0.545020014783491, + 0.5504999549896962, + 0.4907164311601893, + 0.5436282196803198, + 0.5157090843812179, + 0.5048197244506879, + 0.4859640005870544, + 0.4620338008481399, + 0.4958471266084517, + 0.4806088647664765, + 0.4602409043088068, + 0.44753786213380053, + 0.4471882709968754, + 0.5451884503549318, + 0.46611994587544625, + 0.48348721034624914, + 0.5096513456114391, + 0.45683080965051165, + 0.543396436617825, + 0.46117420845556456, + 0.5318470671935385, + 0.5096356592195326, + 0.4517088349418612, + 0.4716584454319964, + 0.549459865874414, + 0.46866892696995904, + 0.4872190106712515, + 0.5335589969300423, + 0.44830460748424755, + 0.529499694730307, + 0.447340223850716, + 0.5423308613546949, + 0.5044542551488971, + 0.5233552881835286, + 0.5503268389409359, + 0.5384543607509125, + 0.44990735856011366, + 0.5195904414695889, + 0.5000149633339458, + 0.45635427598395, + 0.5489332366951806, + 0.535525184512137, + 0.4423798977825255, + 0.4910821746698986, + 0.44558763818550623, + 0.4652676916751222, + 0.4545888460800088, + 0.47113716520004356, + 0.47729010894835355, + 0.5351714444914265, + 0.5422795564756224, + 0.4497796983959006, + 0.5140827093481741, + 0.5483904807021865, + 0.4994383462670028, + 0.4900830340924063, + 0.5341986461948024, + 0.5429310401960679, + 0.533681247840101, + 0.532431172621701, + 0.5455706787950352, + 0.4634439313128956, + 0.4971061799193746, + 0.5350062644610544, + 0.5183120325233794, + 0.4814438776946617, + 0.5270406230363252, + 0.4975482138092503, + 0.5319450109405951, + 0.4862168219745583, + 0.5172511715180287, + 0.47801843384402454, + 0.5308705817091913, + 0.5482303219700663, + 0.49030505815374514, + 0.5438292766031639, + 0.4599721018497812, + 0.47837578181517454, + 0.5042187727777778, + 0.45192749559766265, + 0.4704129836010993, + 0.49268132079471283, + 0.4882578258056005, + 0.47941833502236053, + 0.5505100818659281, + 0.4910518426532234, + 0.501752572414556, + 0.5012865842176092, + 0.4731466744397388, + 0.463425270300923, + 0.5157244481066056, + 0.5034916475389876, + 0.5315986402947277, + 0.5060684112219911, + 0.4524566180664896, + 0.4957228971539362, + 0.491233222182925, + 0.5094343316069827, + 0.5079483904061188, + 0.539991912799589, + 0.4497470494360594, + 0.4969113647991615, + 0.47842255326647115, + 0.47823637105625105, + 0.5310019998635432, + 0.4509705276294815, + 0.450116864761496, + 0.5041088934386859, + 0.4940843568317277, + 0.5487621206356995, + 0.45710476379947973, + 0.5104894255110819, + 0.4680010238941056, + 0.4633163868647723, + 0.5395553820391381, + 0.48144703061573835, + 0.5030207919408705, + 0.5074262943146478, + 0.44837067901387695, + 0.5287697754073852, + 0.5119835293818694, + 0.4589302008555962, + 0.457483919253918, + 0.5530521514629825, + 0.4851490714684783, + 0.4806168874032344, + 0.4429764565795546, + 0.5195215379515985, + 0.47596739143508143, + 0.5160439271149626, + 0.4766190893572023, + 0.5493051875569751, + 0.443081051167442, + 0.5498935888504649, + 0.4799739036143562, + 0.46505292398732717, + 0.45227114442876976, + 0.4619902427644081, + 0.47878740432186473, + 0.47951330391240105, + 0.4508374972173599, + 0.5322604046097068, + 0.48692015140144657, + 0.44589118878769196, + 0.4957172652125736, + 0.4822924768279617, + 0.46059190042755127, + 0.45223588794877273, + 0.47067957650179576, + 0.49122588341749057, + 0.5350493918093794, + 0.5418236942737616, + 0.509665684394355, + 0.44735138062929913, + 0.5335430553499962, + 0.45635309198584684, + 0.47973270836727955, + 0.5360730963499952, + 0.5371815991265003, + 0.5086203475284568, + 0.5434279727959479, + 0.48604487112395744, + 0.5053174789370474, + 0.5329891168812134, + 0.5481309069784515, + 0.4405171262669118, + 0.48180534036990996, + 0.5268622922849143, + 0.5230682678553852, + 0.5168221501182532, + 0.45771342582152375, + 0.503094810015974, + 0.5321545831249596, + 0.531812128464478, + 0.5093581154282532, + 0.5079649530465087, + 0.4518864921912359, + 0.5230351801137897, + 0.5411023196106397, + 0.5372860996488291, + 0.523739741820909, + 0.5498119578355719, + 0.5482362123588953, + 0.4819829635242672, + 0.4432036095283536, + 0.5504192790401939, + 0.44664036717682204, + 0.5238698357057009, + 0.4414795772675521, + 0.4903010289558375, + 0.5079346277895141, + 0.5391235032155154, + 0.5363248666485857, + 0.45516818348960436, + 0.5442449530485653, + 0.5385050270766008, + 0.48864678486877594, + 0.44002388166093653, + 0.45866729170920967, + 0.44219862552005934, + 0.5188511083870305, + 0.5482142591825072, + 0.44199457644306916, + 0.47718134536551016, + 0.5189474810016099, + 0.4925123897117636, + 0.44111623729143173, + 0.45387400835883457, + 0.5335217143729948, + 0.45465193061477815, + 0.4571193898870802, + 0.4807406715561094, + 0.5491063097639924, + 0.4613347709442926, + 0.5445077958684232, + 0.457641970683243, + 0.48216354127298405, + 0.4966239373542392, + 0.4411183396115584, + 0.5483837291909318, + 0.49354012275150055, + 0.4666373139532217, + 0.5117926380876113, + 0.5140545766953135, + 0.49104351871885615, + 0.5448340060632225, + 0.4573438836223842, + 0.5418021804117191, + 0.4435888368051842, + 0.5055608126384828, + 0.5119896772814707, + 0.5519528371173769, + 0.46712524621240126, + 0.5095143040338311, + 0.5244032247040804, + 0.508021804636702, + 0.5519986256793902, + 0.44277729762639795, + 0.5081239805006906, + 0.4778022248902097, + 0.4741459206672787, + 0.5261687369321055, + 0.5501950007240795, + 0.5355294324889266, + 0.5160874420022421, + 0.5147935952405853, + 0.4681470163927913, + 0.4870186939900394, + 0.45043501005716186, + 0.5155648257782606, + 0.49446026836554374, + 0.47996444266348626, + 0.5351610800255984, + 0.46831259593917174, + 0.48540396398357927, + 0.5403830008032882, + 0.5193057642968153, + 0.4692869055955966, + 0.5372747168506324, + 0.5093389687132814, + 0.5373252100523167, + 0.5273320204564803, + 0.5346433682114686, + 0.4591093767632141, + 0.5165328982034377, + 0.4921751581787868, + 0.4984386068736154, + 0.4753233521397704, + 0.4522540711959321, + 0.49157005990759944, + 0.5251212566506703, + 0.46262654166491485, + 0.5006550915914544, + 0.5436465651391724, + 0.47410224361645015, + 0.46664834178537967, + 0.5179816857318394, + 0.45511477318428356, + 0.5223862287316959, + 0.456763181919643, + 0.5134006073199406, + 0.49915005065187523, + 0.517695866813784, + 0.4779348706263414, + 0.509314044482189, + 0.45099319347536554, + 0.4884041137122358, + 0.5305351161445514, + 0.5350845245413441, + 0.457918033093942, + 0.467640879806544, + 0.4737397345151282, + 0.5403966140760506, + 0.48386855691966063, + 0.5322328886314546, + 0.5174371637430711, + 0.5011641494857392, + 0.5475550146587499, + 0.4846573256526714, + 0.47477992817038317, + 0.4963075207425974, + 0.5322111044558804, + 0.5354360401009193, + 0.45574409646963276, + 0.45160311090586114, + 0.4528830294908986, + 0.5346052364231253, + 0.4454303123596849, + 0.4851554788230875, + 0.5049649208581555, + 0.45437395542985615, + 0.5084505349625794, + 0.4968482850768335, + 0.455416449507977, + 0.5355914637119905, + 0.4591679012582008, + 0.5387933730808036, + 0.46225702930141344, + 0.5304376297434239, + 0.47753136816160446, + 0.5031142592494904, + 0.5427158059485686, + 0.4567821897103461, + 0.5354618325759841, + 0.5450172523207727, + 0.4839007224750504, + 0.4831352101005972, + 0.5052018768916776, + 0.48113492506678635, + 0.5167149927842631, + 0.4422135675235022, + 0.4551689181366713, + 0.5295131820919736, + 0.4876419038302507, + 0.45292812453739406, + 0.4717544468075724, + 0.49358029176227314, + 0.44962902677309835, + 0.5058294619176974, + 0.4928293677597785, + 0.5106708830758048, + 0.47466373604290724, + 0.519341837844961, + 0.5042633991446686, + 0.45872651758338406, + 0.5333377207871395, + 0.5122993243242949, + 0.46575871203105423, + 0.52459054927003, + 0.5433668951234547, + 0.5016708445549627, + 0.5103544076107847, + 0.49653618690387796, + 0.47030075953035105, + 0.5229786043891167, + 0.4490229182516422, + 0.4915047990674398, + 0.543870055389204, + 0.5178023592315658, + 0.5036210056808561, + 0.5195805279297785, + 0.5471169311790629, + 0.55295943824205, + 0.4675832046120239, + 0.5021630184130779, + 0.4573279502809836, + 0.4803844980313016, + 0.5365880436125715, + 0.49354694022295287, + 0.5175082718561442, + 0.4940081277161223, + 0.44412185141766153, + 0.46824850676086777, + 0.5413791362530747, + 0.5277410967130627, + 0.46695716997663494, + 0.46009714930498147, + 0.4523297918418629, + 0.5200461536722337, + 0.550207292234168, + 0.5377127637540643, + 0.502211924007159, + 0.4729903036323002, + 0.5470115233699702, + 0.5461964653869991, + 0.5348110479520313, + 0.5357399494106869, + 0.5111960102278816, + 0.4950918968680071, + 0.4476260398320017, + 0.45290749356588533, + 0.5081411991234438, + 0.5124618176403843, + 0.4613412746525475, + 0.5438340644381673, + 0.5523932107236297, + 0.517689498151181, + 0.5478294747579303, + 0.4806494244935603, + 0.5423551348651094, + 0.4766250588208707, + 0.4404988760101469, + 0.5233032082363418, + 0.4818167599392931, + 0.5070993459091313, + 0.5013772390954181, + 0.4816277195955149, + 0.47030470030073573, + 0.45104348519130416, + 0.5265526645505121, + 0.515677991668896, + 0.48928738388636733, + 0.5148592474396262, + 0.4556423131478119, + 0.5044783473003479, + 0.5031406143935703, + 0.5333203481359144, + 0.4674874424137923, + 0.44739178839215404, + 0.5310438159772812, + 0.4788732660633662, + 0.5412668229558761, + 0.5236717354617694, + 0.5457904938549094, + 0.5516276864184184, + 0.4743564802559072, + 0.45029908289446596, + 0.4628226586985427, + 0.49659614408467806, + 0.5289966612041788, + 0.4854246845698435, + 0.464260022098271, + 0.5216160132386239, + 0.46210239877195225, + 0.46426234569133157, + 0.4891292056828672, + 0.5082290965957491, + 0.5393936392866054, + 0.5120276389406444, + 0.4731854192582958, + 0.46922933558560853, + 0.5244615905883708, + 0.5073131270174155, + 0.5465974371307761, + 0.4492553938911763, + 0.45150727170539867, + 0.49176955743208184, + 0.5445762232767685, + 0.4439879686047917, + 0.4770823570993184, + 0.5389752243503222, + 0.4779734367202759, + 0.4745552001696044, + 0.44365894646826826, + 0.4600099244259736, + 0.5522454295280248, + 0.528446781323649, + 0.46799455184312616, + 0.4805535866028231, + 0.5407146643259719, + 0.5249101837504178, + 0.49826211342903415, + 0.5523576394188892, + 0.5445792790478049, + 0.5261231551636398, + 0.4575196233678574, + 0.47506596083999736, + 0.5220293393795983, + 0.49498392474534175, + 0.5014363197317365, + 0.5039121329427522, + 0.5506202953859224, + 0.45272783464807315, + 0.4940086708165929, + 0.5417740052853435, + 0.4956878595465703, + 0.5174935338369353, + 0.5410481691348099, + 0.47423970182193476, + 0.5239310169947955, + 0.5178355269779793, + 0.5078500163469254, + 0.5382156690283552, + 0.4651136987381, + 0.44318001660295897, + 0.517967518764415, + 0.4489898920182634, + 0.4823451401564358, + 0.5340688103300767, + 0.46209364210058235, + 0.5195840494009112, + 0.5095773387389141, + 0.44379738137869584, + 0.5164791415458176, + 0.45986446158247674, + 0.4914960495792694, + 0.47534542946106123, + 0.44163114790080754, + 0.5197933258211177, + 0.5455289443917992, + 0.49536707370044464, + 0.4674075738468274, + 0.5136007526227369, + 0.4642637652780939, + 0.44407437312661957, + 0.4828423790331744, + 0.4949664983398338, + 0.5010555667067211, + 0.5105325548058796, + 0.5252369063061624, + 0.45358537212640215, + 0.4417621103283898, + 0.4552530492508831, + 0.4875023417253113, + 0.504429450432551, + 0.4607366961223264, + 0.5120288381464381, + 0.5446000879543458, + 0.5438652841365869, + 0.4943514135242846, + 0.5047482119776977, + 0.4752666534486843, + 0.5277048098183363, + 0.5102420030370676, + 0.5505467324224924, + 0.46103252836166253, + 0.5399536182725838, + 0.44905396277395204, + 0.4827685582187117, + 0.5074370957929605, + 0.5248119584514711, + 0.4941988872242729, + 0.5486180166915255, + 0.5397156983806143, + 0.5305275172028412, + 0.5274746256434522, + 0.4506816228154093, + 0.4631379343835678, + 0.47731314191174806, + 0.4979833869632962, + 0.5175829490727902, + 0.4784879317076122, + 0.46765975159972645, + 0.46594537717062456, + 0.4831602543263648, + 0.4552416826351042, + 0.4816748943503433, + 0.498339294967086, + 0.5383770443063525, + 0.4911842661739461, + 0.5212848369084148, + 0.48841276127384875 ], "y": [ - -0.22160811627060384, - -0.20396133366088043, - -0.24800461689923653, - -0.2785571646911139, - -0.2010014478668365, - -0.16469850968357752, - -0.17572536189386284, - -0.19206239392557084, - -0.2946710998038715, - -0.18758298681189406, - -0.2605674934827026, - -0.2550368735422324, - -0.18044557357425708, - -0.2796317849260713, - -0.18523610963529377, - -0.2613129035832916, - -0.1666240202347511, - -0.1976282579812477, - -0.24018135426306264, - -0.21051611084785232, - -0.21702236028515587, - -0.2934520892644191, - -0.24742899191852377, - -0.22647339256854707, - -0.27548454098797287, - -0.17399093776167357, - -0.26497429316268245, - -0.15771709344990298, - -0.2787566886198316, - -0.21893407913922147, - -0.2524524943001722, - -0.1770787369734375, - -0.2668477547674016, - -0.23829022335991568, - -0.2696624230287358, - -0.195825877586688, - -0.20878158302562197, - -0.23107717848309942, - -0.29744499548522313, - -0.23747176982885956, - -0.16611682235286793, - -0.20608707010299865, - -0.2330184906521059, - -0.18972097155028234, - -0.17718848412187801, - -0.2742825927852023, - -0.23400928518633524, - -0.262008381787691, - -0.23014766748924298, - -0.2586982441178777, - -0.19112173221406717, - -0.21561300407760703, - -0.2695362394027705, - -0.2436506169405447, - -0.220773771400821, - -0.17979698508588285, - -0.15454634340692205, - -0.20297697992526126, - -0.19493129807461784, - -0.17865526791544428, - -0.22343165727121875, - -0.1743981185176352, - -0.21087365367927385, - -0.205635625379986, - -0.2843852834030462, - -0.24189934594152204, - -0.25969120353238534, - -0.27813462962957375, - -0.18186472651609886, - -0.2728753316157477, - -0.23818899011102576, - -0.2775434634542214, - -0.2516708355851365, - -0.20065961986288747, - -0.2768479108313611, - -0.25721217819947656, - -0.26693501393236985, - -0.19923270836116425, - -0.2919462540663527, - -0.23528099306756178, - -0.23198726733286226, - -0.22563575222149543, - -0.2155422044150262, - -0.2978119468332068, - -0.15939761007347042, - -0.19591349250641069, - -0.1982718803694354, - -0.22021849468374133, - -0.23749946524299068, - -0.15583809223023135, - -0.21794784804651704, - -0.2746879085945761, - -0.22425377188298004, - -0.24233334477459684, - -0.2861478166650862, - -0.25190588925469504, - -0.28951394436736877, - -0.27575828393413104, - -0.2636000245305068, - -0.22288815273555376, - -0.1937108680682587, - -0.28172430786460234, - -0.22679016394596457, - -0.18574458381894454, - -0.2532079095590062, - -0.2495942620956211, - -0.2541274194571035, - -0.26642661742891827, - -0.1643800985845383, - -0.25835302762906864, - -0.2565080697176225, - -0.23691326755166747, - -0.26379248941307015, - -0.2263839442557593, - -0.15526489109625996, - -0.1842048721122234, - -0.2663134681655525, - -0.21937852853185105, - -0.25309171849773293, - -0.29461151505376665, - -0.29552426276169, - -0.29193009259425856, - -0.2853548774344806, - -0.26259750904135004, - -0.25546125867565456, - -0.16786799268746494, - -0.16738389495870307, - -0.16762166364423872, - -0.25483248763720573, - -0.24442797826258866, - -0.24960099647691014, - -0.2349182651029945, - -0.2492950743110808, - -0.1635332857260371, - -0.27052309888871556, - -0.2819586670139416, - -0.2654168664166021, - -0.20417944511844283, - -0.24549874938745037, - -0.20488562197792964, - -0.2611157865937863, - -0.2596200952538608, - -0.2845680546608331, - -0.20853724315602873, - -0.27932121091721296, - -0.2837427898077954, - -0.20279712101187933, - -0.24033865237519186, - -0.2725835880645367, - -0.1636572914396454, - -0.21157134940414993, - -0.22440114667217037, - -0.2512138393405343, - -0.17935162021050483, - -0.1990408251406594, - -0.20285097357167947, - -0.256439379283971, - -0.2646049751814286, - -0.23454668717900867, - -0.21574232135359728, - -0.1848669930994554, - -0.24186788036457085, - -0.2660166589077526, - -0.2793787651739304, - -0.2786809157760641, - -0.20616623997424885, - -0.2674391895065514, - -0.23240190892281193, - -0.23583576375749082, - -0.2687992763050407, - -0.22955828353688562, - -0.2798036012004468, - -0.28595330382615125, - -0.16869394799926368, - -0.20541897528978575, - -0.15769606204812175, - -0.28603883845445593, - -0.16590650918994942, - -0.15928571494102808, - -0.2365466702273016, - -0.19677337986462995, - -0.2015795052678937, - -0.17997830270759496, - -0.17870749643236777, - -0.24864480554111032, - -0.2669696712864314, - -0.17264105168228014, - -0.17129618063308572, - -0.23299620162814003, - -0.25368153532277204, - -0.2579839403399419, - -0.18557182026637653, - -0.29617897052903086, - -0.16851193336355244, - -0.24874952192975758, - -0.2873397124483686, - -0.1770241035588819, - -0.26563290735578515, - -0.2181397943243435, - -0.18397335826384115, - -0.2641887778641382, - -0.18254225811938238, - -0.1797218358662131, - -0.28669593320999254, - -0.19861719026989352, - -0.1840225219682311, - -0.18807603246927873, - -0.281008974561277, - -0.2343194575472608, - -0.2554996649016901, - -0.16736155861425955, - -0.23104938675704867, - -0.21591783148588534, - -0.28998841626543476, - -0.27624477711452955, - -0.2500036612310293, - -0.1622274136984239, - -0.251932355352656, - -0.28778692791231836, - -0.2280731633976531, - -0.26670292098456294, - -0.2464209651839712, - -0.2604347072482591, - -0.2847860646359536, - -0.18356288968807938, - -0.2647057630125449, - -0.1922005582328803, - -0.16616123880967018, - -0.26808074375626795, - -0.1891204087223447, - -0.195385268901201, - -0.2530034528210566, - -0.20651490880888035, - -0.270704866718222, - -0.2456538052141114, - -0.24051720407816457, - -0.20155871018964017, - -0.15904544962606065, - -0.19110944757799017, - -0.20482662040561286, - -0.2518634861572583, - -0.2411073026116492, - -0.22391046442698043, - -0.21201928951298732, - -0.21505402329917123, - -0.17682358442147633, - -0.19994454760839975, - -0.15646639159979325, - -0.1829055735245813, - -0.16388120919342078, - -0.2613399594043352, - -0.18610550385176017, - -0.20807037964492964, - -0.17141645686081844, - -0.2677262285265698, - -0.2679543032730256, - -0.204076763674651, - -0.23346292886199183, - -0.29166313411481926, - -0.22864156723228463, - -0.21242785163750333, - -0.16013117724123152, - -0.17081098028444547, - -0.1812352599097345, - -0.25257434018356034, - -0.2439434162682617, - -0.2846613234007872, - -0.2937828092453605, - -0.1639071886776602, - -0.2021544013250393, - -0.17146837865499698, - -0.28469591508375963, - -0.2955206690175275, - -0.2620750467559404, - -0.2915582077309616, - -0.2718480659352325, - -0.23739519263577347, - -0.2476637662561863, - -0.19700472231342409, - -0.18391115962759072, - -0.26916794449226966, - -0.1650504165063395, - -0.22806341380370743, - -0.2863447308376166, - -0.22941498552123424, - -0.16150822781374288, - -0.2370218975333469, - -0.20374415408215452, - -0.17533863157200008, - -0.1625986846005882, - -0.27856185389082366, - -0.1753641189719727, - -0.23526101144670597, - -0.17331529975771937, - -0.16805614334006969, - -0.29169971190096305, - -0.2479226869453789, - -0.2586125802023047, - -0.2749429698799857, - -0.2901797548174578, - -0.1791059820231929, - -0.22354202830227538, - -0.15892566100071823, - -0.19358757890079076, - -0.18008742343530268, - -0.16282355568335424, - -0.28364957889916265, - -0.2145989441975631, - -0.2413519771565246, - -0.27676389785767486, - -0.26819261242201425, - -0.27558463308569997, - -0.2626723036594105, - -0.28775950101316017, - -0.183267162284736, - -0.2845782217097617, - -0.17151186021469753, - -0.1762036517534181, - -0.20705276775758213, - -0.18773065950690188, - -0.25904417646517164, - -0.2340620318673532, - -0.1884169410960087, - -0.19216583242007185, - -0.22911020830913167, - -0.1932465479535294, - -0.29755685701541834, - -0.2256331031665449, - -0.15852939134285585, - -0.1754156176324358, - -0.2683402540023179, - -0.20386371288755292, - -0.22212017477818713, - -0.19160055494603734, - -0.2117670354849313, - -0.2787411816999199, - -0.2539149151943866, - -0.19496274151554283, - -0.21822792081824055, - -0.21034732403342254, - -0.2652358900313419, - -0.2956339838188836, - -0.2652591279796069, - -0.18499004147540865, - -0.254564274225162, - -0.2385318426140473, - -0.19651796212881834, - -0.16941952397025023, - -0.1689685654646083, - -0.22553241123682435, - -0.2254308792013373, - -0.20634966461387533, - -0.28821755940526833, - -0.1851667916921975, - -0.19587331680264491, - -0.23733859406856345, - -0.16009498329334476, - -0.17402391275626689, - -0.2197902817511581, - -0.2880510930420782, - -0.2494420223806581, - -0.2399133399826054, - -0.24105151856509127, - -0.1850167227642927, - -0.22369040848565258, - -0.27704525327955126, - -0.15681061313724304, - -0.20772932561248394, - -0.16738444458157314, - -0.26081328910249413, - -0.25581887259699787, - -0.16444036398576553, - -0.18634282457637913, - -0.23771204750117414, - -0.23067914994312916, - -0.22857706721093046, - -0.2841046488045218, - -0.2199569680227676, - -0.22138325312754858, - -0.2781123773434677, - -0.26541926176022024, - -0.20191759726123948, - -0.19108092739886456, - -0.2443626253904356, - -0.25105861440474864, - -0.2888132662431997, - -0.2676373543318611, - -0.25237979634613705, - -0.2618521711489758, - -0.2022918858361647, - -0.26755470798665915, - -0.24864648507936715, - -0.2204697088505041, - -0.29447939452900074, - -0.2896615584695347, - -0.15925559066839753, - -0.2511602138811019, - -0.22754873533134579, - -0.2901994178788573, - -0.2803818362389028, - -0.19448113713075357, - -0.16938675637410108, - -0.18286571050948483, - -0.1876126055494136, - -0.20954950550683032, - -0.21095283733380787, - -0.15766453073573714, - -0.16213918890512902, - -0.22356179316276326, - -0.1976655861959395, - -0.15661533430742822, - -0.1792118296926307, - -0.2986799631530271, - -0.2748086894999963, - -0.18275832738420017, - -0.1557637203771567, - -0.18914884565877566, - -0.2916579580242493, - -0.1862389660272002, - -0.2859155790416171, - -0.1937986059653467, - -0.2826087840157017, - -0.1660540960720017, - -0.22614360118363225, - -0.1583382293370175, - -0.27666782921537963, - -0.29065371953547986, - -0.21201258011391405, - -0.22735505265886993, - -0.1868058690415183, - -0.15767675581015406, - -0.15971633011207062, - -0.19383538060170352, - -0.19205898148496975, - -0.192981949443053, - -0.18376959397374748, - -0.19038643421267704, - -0.167373443086927, - -0.24657755444471263, - -0.2954925115485918, - -0.17284599134398845, - -0.2198347258276105, - -0.16233069088940733, - -0.27122366586107854, - -0.27982613096198483, - -0.2120377572879043, - -0.2958708902872357, - -0.2744914761368636, - -0.20284460683203132, - -0.1642522202396043, - -0.1972720110928522, - -0.1901469745318904, - -0.19052231507999404, - -0.28032071770626116, - -0.2494008298945832, - -0.19782117645927025, - -0.2530701920340634, - -0.18883042642438824, - -0.15942790155863953, - -0.1805843645870029, - -0.2140460351310921, - -0.29541783013302086, - -0.1888523426728364, - -0.16734080000748994, - -0.27369232205907823, - -0.20547703821858926, - -0.21439524273064103, - -0.2206461778722264, - -0.2317659153333395, - -0.22048599400260505, - -0.17606963380029056, - -0.21035444453881003, - -0.28501610279654227, - -0.1604730484349601, - -0.1997486746778252, - -0.259432880936164, - -0.2189717309319348, - -0.15893277276312862, - -0.262689036579682, - -0.22830481481581116, - -0.23201373096857683, - -0.15838406838897062, - -0.2964856485081622, - -0.2531639216858122, - -0.280760103284727, - -0.18899092178681182, - -0.27757238689780417, - -0.1639633354769148, - -0.29593911657038185, - -0.29874741344563416, - -0.2561314869980799, - -0.19842874072473748, - -0.1935506530179034, - -0.23411545926952626, - -0.18684777681064305, - -0.2585911902013475, - -0.2355477485064399, - -0.1871816384400159, - -0.2921040051026406, - -0.2341006509246591, - -0.2800113720815368, - -0.1831585224522435, - -0.1853750398232072, - -0.16027584464304162, - -0.2635429846156068, - -0.16637599340203985, - -0.17122996562110468, - -0.16301731068532424, - -0.18881398051100517, - -0.2585266068393618, - -0.19600943745161797, - -0.24891923294049328, - -0.2766880695588587, - -0.27553794817221766, - -0.2893021619882542, - -0.20808196241483934, - -0.23600068687573067, - -0.1746433015762783, - -0.2193734788383026, - -0.16374037814902578, - -0.18927064474017416, - -0.17382074864633534, - -0.15591380020824155, - -0.1685680382279765, - -0.28668034602201414, - -0.2707787868143984, - -0.24421869900794338, - -0.22461978645143357, - -0.18956135279181138, - -0.17111779509078967, - -0.29868325136455076, - -0.250228116482467, - -0.28345363013941915, - -0.23588094771545548, - -0.15971680936817734, - -0.2698671428063414, - -0.2793645132043731, - -0.2854920629418811, - -0.2230308538098569, - -0.22520793194457206, - -0.2825467840583292, - -0.21560700112589806, - -0.2068374621826793, - -0.2803296600579356, - -0.1960185236109028, - -0.21353956178340133, - -0.23995410920022153, - -0.19481102563238314, - -0.23994377847721018, - -0.2610246775216167, - -0.20280467529743557, - -0.2840712391959363, - -0.2574550534699691, - -0.15720978016386744, - -0.19669979709031904, - -0.19021105765727028, - -0.1685331229205439, - -0.1851128687710038, - -0.15580787281655092, - -0.2190567149788818, - -0.2653103186025117, - -0.2057150862189806, - -0.2654755737745282, - -0.2494248246943091, - -0.26742130923509555, - -0.2558913450518523, - -0.2512993495173208, - -0.19572545288522122, - -0.18442763538456863, - -0.24685092315260165, - -0.2578982389612003, - -0.20051462118628066, - -0.1549560468935557, - -0.21609645179063405, - -0.2525140911635431, - -0.2962465312240354, - -0.176646536513261, - -0.17401039151692804, - -0.21005981519867623, - -0.23842822722981222, - -0.16942626026130456, - -0.1771085153130442, - -0.18581374786500388, - -0.2118657060685725, - -0.18178632864800603, - -0.2702611109815558, - -0.23421481427870228, - -0.16637788207971535, - -0.25025492390467075, - -0.22281903829179012, - -0.23517244468714732, - -0.15894903720818349, - -0.27854675657416456, - -0.2110898085052576, - -0.22237360456221433, - -0.2607755117421269, - -0.21459308502204577, - -0.21376496817502405, - -0.2770159068128744, - -0.16181816569348376, - -0.16313043333413801, - -0.15605255254056732, - -0.2767921125535408, - -0.19497594929987072, - -0.2426899954782576, - -0.1702528295184088, - -0.2607915202134281, - -0.2645501069233995, - -0.18980904444219315, - -0.2283333739059787, - -0.25248958986229697, - -0.289728351472599, - -0.2781804618026803, - -0.22160611324573615, - -0.19373666003753298, - -0.19838870897255906, - -0.2169832302417192, - -0.2550316184502576, - -0.25702821740665716, - -0.17681774551314836, - -0.23546190342439272, - -0.16972072126244975, - -0.2886042790378306, - -0.16721341746097354, - -0.2598340130676424, - -0.22374376886969632, - -0.1604957263668808, - -0.20689864875416103, - -0.2330116287299622, - -0.15935933051901857, - -0.2963711075708382, - -0.29578696602382604, - -0.16160990912606552, - -0.2550364196749895, - -0.24497701555713913, - -0.2588838331142244, - -0.2855314076706687, - -0.20936361954988786, - -0.1989736537218746, - -0.19585498687742153, - -0.27176186496234533, - -0.2087665513192142, - -0.25833473865718953, - -0.1560608160142971, - -0.2041125872337457, - -0.22654989472040393, - -0.17443073573334777, - -0.24652224838874448, - -0.17486184586441283, - -0.25424908070784064, - -0.15955767712335817, - -0.15563623023784773, - -0.2257496273217922, - -0.1753092331826997, - -0.2943844901226865, - -0.2638205130606731, - -0.24772684970262768, - -0.20795946454281905, - -0.15719079763808036, - -0.17345903563134632, - -0.29206051397383437, - -0.1683705772763208, - -0.1626826463186901, - -0.24417141026460537, - -0.17891784438512182, - -0.19452249644802405, - -0.2544702450489521, - -0.26533508078566415, - -0.18061390639251346, - -0.2590224366174638, - -0.24588091608495047, - -0.2000159090361825, - -0.29383561042808676, - -0.20691677189945362, - -0.15961521936782697, - -0.23210899902954873, - -0.2985706168784768, - -0.23323341446456541, - -0.20587386546040565, - -0.2219446345502734, - -0.25210046030790134, - -0.2858357518942137, - -0.24828799796359935, - -0.23759231579493703, - -0.22478322050339128, - -0.17749183152113263, - -0.2361365104656357, - -0.1910225561117497, - -0.28055523680190003, - -0.19459084612272615, - -0.2942322894519158, - -0.2660677335112149, - -0.255762641080788, - -0.24844982826559983, - -0.1826856026286381, - -0.21191829330499684, - -0.17967986218758442, - -0.24997745895729534, - -0.2407785800054686, - -0.26971263011845453, - -0.2635403797527595, - -0.19106456575398217, - -0.19028406479304055, - -0.18487996368695564, - -0.21597055932221332, - -0.1910243021216615, - -0.21662696225478034, - -0.17631240521145958, - -0.2842195184345411, - -0.28131016943118126, - -0.2575084618801715, - -0.24479174579765353, - -0.25290710507270214, - -0.20944277378284454, - -0.242917428932306, - -0.17405304781784725, - -0.21993448461695386, - -0.24931981187919722, - -0.18137911096177137, - -0.2795478448654952, - -0.24721735133089418, - -0.28274633917082126, - -0.2039894245397724, - -0.23977604992195914, - -0.26273511249135656, - -0.23428024627862298, - -0.23109798924853733, - -0.16246444345022926, - -0.19210518800618437, - -0.21580687018504416, - -0.17340135166884382, - -0.29592073924302525, - -0.23570025872181188, - -0.2032261960136021, - -0.27151104662236203, - -0.18003543084908616, - -0.22623516199536178, - -0.2233805215248978, - -0.15709792743504658, - -0.22265911164263275, - -0.18642679218399089, - -0.16737888663073944, - -0.22492476230143646, - -0.23232237231552766, - -0.23971793024771246, - -0.25120477807295766, - -0.2844618835773707, - -0.2976267232982882, - -0.22985313809447352, - -0.23396270653843537, - -0.2846166376529963, - -0.1903570915854811, - -0.19403953658764864, - -0.16444669806961706, - -0.19793202552603195, - -0.2952395471870622, - -0.24477925123897643, - -0.2329603300638003, - -0.21391105453650952, - -0.2910338105118854, - -0.2865104723992927, - -0.1840263585035849, - -0.28589857640470984, - -0.19994455881929635, - -0.21137147423641722, - -0.24901043500475534, - -0.2668168567146942, - -0.22108627682618676, - -0.27996746534877504, - -0.19135617736470847, - -0.18449875603544094, - -0.25988035812847693, - -0.20794735457061936, - -0.2689876314632867, - -0.25949982387081477, - -0.24325187581959518, - -0.2862951379394128, - -0.25927949499921216, - -0.29677068784229294, - -0.20812904671964622, - -0.2788418810619412, - -0.23264075487502214, - -0.19461902548071208, - -0.28483299400678674, - -0.18065915266110494, - -0.1685850354666685, - -0.15518928411768598, - -0.2608745751028097, - -0.2280137509480966, - -0.21998484801816282, - -0.21832931575972586, - -0.22758635476600406, - -0.24833129894071312, - -0.255830742906508, - -0.18535555009210603, - -0.16909963792686797, - -0.198454998617013, - -0.1792716172785875, - -0.19963034686845446, - -0.29537746411331584, - -0.28543463330580676, - -0.25093789019990903, - -0.22870419572184747, - -0.20464996802018953, - -0.1826492866847973, - -0.24449754640125645, - -0.2734200188483607, - -0.17621269194925754, - -0.16318348677568212, - -0.2937681114733244, - -0.22384717460736983, - -0.15565875894824835, - -0.15727000345574474, - -0.23174328741608785, - -0.24860916899237429, - -0.15906967162717345, - -0.2417645695162036, - -0.2812472061104348, - -0.24954241553266077, - -0.2493606613771724, - -0.2725891395860234, - -0.2786311376676288, - -0.17539751273878873, - -0.24145676998890236, - -0.27122387321353253, - -0.21610032957279068, - -0.2595751034208605, - -0.28008710051694247, - -0.2683476707097988, - -0.27618839526573324, - -0.21774856688627794, - -0.19337011777612975, - -0.24516506154843504, - -0.24810520233564962, - -0.19820154204426277, - -0.1989369645646879, - -0.2856127110946626, - -0.17478337570553998, - -0.28159941934197114, - -0.21942390844329812, - -0.241353453503342, - -0.26169080832973285, - -0.26536750152254207, - -0.23152643248002786, - -0.25434101923046026, - -0.19664161594948995, - -0.22962927195403693, - -0.2695772973508224, - -0.22552467535411164, - -0.250224907637835, - -0.19384409301274072, - -0.1558407394839137, - -0.28803026871443155, - -0.16657505494784827, - -0.23404118356568485, - -0.16874425726599998, - -0.2424622497728519, - -0.23801640946391517, - -0.21551731004601943, - -0.16706074323951392, - -0.22388447783434684, - -0.2979233834292279, - -0.2483672670949115, - -0.23119071054029125, - -0.17343297879128913, - -0.17690638949181642, - -0.27898050059833673, - -0.2278476907811059, - -0.23977750455377408, - -0.2513902765685849, - -0.276988993564827, - -0.18012259587244675, - -0.15663203403278492, - -0.24418001318864951, - -0.24438293937080446, - -0.1595648869787379, - -0.2910048024613481, - -0.28165946849840195, - -0.18451584113416364, - -0.20890033480006331, - -0.29574190895426244, - -0.2841338666698158, - -0.28899811700616235, - -0.18040013427898888, - -0.2375579979480809, - -0.2420742728752484, - -0.26235406111312837, - -0.23934003908020413, - -0.24886318137344177, - -0.198445388922752, - -0.15867644767709807, - -0.23163154684490264, - -0.2707275126788202, - -0.2860660966644758, - -0.24332067453711934, - -0.23719238873503393, - -0.17459805817268584, - -0.29355209923933867, - -0.21245287997347795, - -0.15800037394181923, - -0.26754955551895887, - -0.2916085688284379, - -0.22456811641585928, - -0.18422095513544168, - -0.2795259424154374, - -0.2566331591089511, - -0.19788073359245661, - -0.16584998149156743, - -0.22620035105344186, - -0.1930919696421594, - -0.18773001706832176, - -0.2952536681409196, - -0.2069836262311996, - -0.18420709540015168, - -0.28625164737072833, - -0.19599314494057402, - -0.2347405601600579, - -0.25582192737826404, - -0.2042656141910491, - -0.1802100954910813, - -0.25372929327018634, - -0.23279725660031975, - -0.2336680032551317, - -0.19105580245455206, - -0.28414212021517843, - -0.2696394725398971, - -0.26582830254876183, - -0.21620422179729873, - -0.18704075559462624, - -0.19969879161218473, - -0.1855828458848549, - -0.2276041446538421, - -0.21367205147644175, - -0.2510065337511376, - -0.21510474828103984, - -0.2063373337703015, - -0.22047458610457898, - -0.2520424392736561, - -0.275592452596733, - -0.2724831426069585, - -0.24421279648508648, - -0.245521148796207, - -0.29771417831657754, - -0.29610438199819106, - -0.17585907375969384, - -0.1763836119042237, - -0.28797668274345345, - -0.1933241840581664, - -0.1754652572596997, - -0.2013818505744103, - -0.2725058967534035, - -0.19316212441475333, - -0.20559181435590934, - -0.1950849550882635, - -0.21218119829198215, - -0.27608133862967027, - -0.27454108465209776, - -0.16187918456636563, - -0.27545700468171086, - -0.27663239582199095, - -0.2867805440560359, - -0.21376853196292567, - -0.255800784248003, - -0.1550421892348865, - -0.2525061892780387, - -0.27361803466998746, - -0.2908136388978073, - -0.2068083471538017, - -0.29043925216921795, - -0.24386804273561816, - -0.1982202584425829, - -0.16264497186467203, - -0.22426584406018077, - -0.24252392043467172, - -0.2303742619490328, - -0.15709116977793325, - -0.15827137895129495, - -0.16381875520713082, - -0.2890399698582178, - -0.20079584017132013, - -0.2810696898836195, - -0.28621299208811396, - -0.2745283549479036, - -0.19856315072907166, - -0.2095379411925002, - -0.1623996423496077, - -0.16510735360475787, - -0.1835756146196395, - -0.21511401239519784, - -0.29394974087465287, - -0.16829237082908305, - -0.16136839167350253, - -0.22227165316518177, - -0.19819743530520068, - -0.2444242210242495, - -0.2372006701357196, - -0.21616930930328718, - -0.20111490290036638, - -0.2478843043024613, - -0.2908437272982311, - -0.29683661647562903, - -0.2793134764579664, - -0.22466075755078319, - -0.293331259292317, - -0.28401949945693944, - -0.2690069253194499, - -0.20227457902061238, - -0.2587583322176276, - -0.22012066662650387, - -0.17805806838096708, - -0.298560530363381, - -0.2512547984897224, - -0.22478729463773428, - -0.24439790571304973, - -0.23565573563148604, - -0.263034357115182, - -0.2921634993731733, - -0.17949544527284414, - -0.17559209895900488, - -0.16283709981810118, - -0.2783200127323097, - -0.15964752465433676, - -0.22069610301660697, - -0.207035355088666, - -0.24619528935993745, - -0.21417377828887665, - -0.18365156766196097, - -0.23914187590400904, - -0.22923135320841745, - -0.1581679513896314, - -0.24191430204153458, - -0.2021097061797727, - -0.25423450819775056, - -0.21354518256138, - -0.229589180909478, - -0.1988687121302734, - -0.2984177254965442, - -0.17580588166827782, - -0.28115335719535184, - -0.1702284592786391, - -0.16976349800954793, - -0.24881630983708644, - -0.23668059965966567, - -0.1912828475552104, - -0.2530581341583995, - -0.277435293924346, - -0.17167078045136255, - -0.244857169803819, - -0.2312027069459569, - -0.29019498113213016, - -0.2521571675556203, - -0.16204712592578477, - -0.24267700576183843, - -0.16719926562778858, - -0.27219232127978993, - -0.28551639423890074, - -0.2825989731920497, - -0.20652127707922946, - -0.2960960648161283, - -0.19669579476609345, - -0.23592645054685168, - -0.16097985702366827, - -0.21536290763021904, - -0.18082002866070002, - -0.2688813716761823, - -0.2011806787949204, - -0.19076242227792578, - -0.2265237955429995, - -0.25663801772212314, - -0.20980680042185615, - -0.2081424363676763, - -0.1785326056015366, - -0.2111507378970007, - -0.2751421587525989, - -0.18144353210453557, - -0.2194045512872025, - -0.21849232473748098, - -0.22861389601298818, - -0.22464068684869015, - -0.28447920841342206, - -0.255064357580336, - -0.25661338718829846, - -0.25906668080344475, - -0.19726102703060827, - -0.16653095466923365, - -0.1582285367452612, - -0.17272999881138568, - -0.19924589386397734, - -0.1925848641164637, - -0.23731792021401746, - -0.20743500908828771, - -0.22489912810926072, - -0.17110160718583547, - -0.2051744596555738, - -0.1877622132515197, - -0.18450123861578482, - -0.2969114083619441, - -0.17389506522577022, - -0.2037801570789807, - -0.21495495560449682, - -0.16046484993312826, - -0.2163874475280489, - -0.21325875746954256, - -0.20354575965367122, - -0.20371931285136224, - -0.2665182870858924, - -0.17667665308396463, - -0.17515430807655774, - -0.21870574555865918, - -0.26062588544676407, - -0.16049009547524368, - -0.21636193499801104, - -0.1763121749395311, - -0.15542402306627892, - -0.1701713990544425, - -0.2555971078893739, - -0.2146756774173251, - -0.2956406062247066, - -0.15467813525563354, - -0.2845599343808933, - -0.20673916956302318, - -0.2647615487052413, - -0.1607759503950977, - -0.2648213485441305, - -0.2432278254648077, - -0.2070048428375036, - -0.28623786996410056, - -0.2444842594959351, - -0.1927197493061839, - -0.16049174920855688, - -0.25290755739379267, - -0.2250280537871422, - -0.24740533079167712, - -0.2578517487309576, - -0.18482371255232596, - -0.29127547499875095, - -0.24763958930625413, - -0.19237490352426712, - -0.21099639672178022, - -0.15474327835281879, - -0.16349273176941997, - -0.2832405118333811, - -0.23076007434504944, - -0.23739175600139895, - -0.23138171249633532, - -0.29774968881508584, - -0.23631773916569476, - -0.1961105552875336, - -0.1707991766101992, - -0.18332333901239967, - -0.26167016078431093, - -0.21730934514862477, - -0.2533219586314155, - -0.21652362448071574, - -0.24948694642937821, - -0.20857953784812255, - -0.19479013515159826, - -0.2260823398429041, - -0.1881439436041617, - -0.2607833963682765, - -0.20095363655608678, - -0.17396970292012742, - -0.23136831880627245, - -0.22975352567751867, - -0.19206770417518704, - -0.1635200891289396, - -0.2231391073931359, - -0.21568929808624737, - -0.23271810136786378, - -0.29221832850930163, - -0.22606025785475448, - -0.2931047334687098, - -0.18050925482405927, - -0.19250429633469823, - -0.24200648031879124, - -0.2801550966845365, - -0.24209045473458146, - -0.1950857664653354, - -0.17756850625383075, - -0.20092180133301507, - -0.2598783571273595, - -0.17122835404845196, - -0.1875815814266345, - -0.20314220124516275, - -0.20652066850524178, - -0.2440958637208267, - -0.18499886634150747, - -0.2958556817263826, - -0.21267780247727736, - -0.2645184379938195, - -0.25469438261930244, - -0.2541687695964797, - -0.19842985960868764, - -0.17983554283417336, - -0.19592381667205902, - -0.23725883721278107, - -0.16544326575885626, - -0.1661120704335101, - -0.2029243389361008, - -0.2702545664556363, - -0.2913771636387334, - -0.21502504783323287, - -0.17382266481126918, - -0.20146910944630378, - -0.24678091091876744, - -0.2766110889679373, - -0.2473976611178914, - -0.24686548335385408, - -0.16642913444542118, - -0.23250330823262755, - -0.2865183825073381, - -0.25697979858488573, - -0.25343138065846654, - -0.15933834077554537, - -0.20623082032176826, - -0.24208309696800542, - -0.27917034291934584, - -0.22811804081750162, - -0.22805108435854765, - -0.22082378258751617, - -0.253600803196119, - -0.2802834995770681, - -0.21557349544904147, - -0.2622301525462879, - -0.20057929318660417, - -0.17877778723862542, - -0.28920959027423765, - -0.19486765289978328, - -0.18900689893048456, - -0.22641972514907632, - -0.19494558265384598, - -0.23722209440422, - -0.16308529788282328, - -0.24997364806087474, - -0.2355668514507484, - -0.19819167930690354, - -0.2936567578395754, - -0.18873610257101892, - -0.2688387489962838, - -0.16979998860505793, - -0.2510176744117002, - -0.18852555080125588, - -0.1907720319290602, - -0.1958423657418738, - -0.2537990721461713, - -0.2507706769800539, - -0.2748532228762707, - -0.18555811406488174, - -0.21820286800059596, - -0.27271956380768286, - -0.2151920196342082, - -0.1598877711229105, - -0.27594215447784814, - -0.24599254835061685, - -0.2686636525257214, - -0.1845616720621251, - -0.2368474216458597, - -0.24666310249930823, - -0.2590390871600753, - -0.29230481830992416, - -0.226093087095583, - -0.1764757161385102, - -0.2533068777059564, - -0.2116025987930088, - -0.2818422854958231, - -0.2127380381475799, - -0.17564589689026844, - -0.23150633656221817, - -0.18849021601296784, - -0.25635523175441205, - -0.2723690535140038, - -0.27993134236422107, - -0.23534678345180093, - -0.18694353137590555, - -0.28988926740232307, - -0.21933488085807956, - -0.2777466823425524, - -0.2651130934292225, - -0.2895061956612312, - -0.256400827829076, - -0.28831362011516976, - -0.2815915458895187, - -0.1997875009423217, - -0.22325112204921368, - -0.2071976923930741, - -0.20432330187909414, - -0.29365805337492196, - -0.19146285862428303, - -0.17346547615458519, - -0.2574178771353096, - -0.21820080201106434, - -0.1824641980064981, - -0.1939772368952432, - -0.2627659272671784, - -0.21820827975067691, - -0.25864055864143226, - -0.16627668199388523, - -0.29163361093629314, - -0.22292026212143246, - -0.156716730256965, - -0.16779640156006626, - -0.26248506355250595, - -0.2755320731051857, - -0.2771862995193589, - -0.24751337919582556, - -0.23454506924223695, - -0.20481628004835928, - -0.18575118558724604, - -0.27131496650867903, - -0.2449766632883624, - -0.23297314962616628, - -0.17480956850180432, - -0.21269628646995617, - -0.24241161585961055, - -0.2240060269069806, - -0.22647349612965123, - -0.21304918738070394, - -0.22234927957229855, - -0.19748967885022842, - -0.20901135807233479, - -0.18426552235938215, - -0.22724639911609684, - -0.15910404053588817, - -0.22290448171659372, - -0.23850281697856163, - -0.254347813146387, - -0.25168412573761545, - -0.20957148160713132, - -0.2308237216335551, - -0.28907095024620955, - -0.18522215453780494, - -0.26185721822244856, - -0.28125026829318056, - -0.2408064075799767, - -0.2633634232800175, - -0.2367331402687562, - -0.23688775818989866, - -0.20754611416155355, - -0.24544764475412845, - -0.1721419882294708, - -0.2338429503580401, - -0.28235564147028414, - -0.16148856672253814, - -0.16221266707805138, - -0.241771022969841, - -0.18205458714606151, - -0.1878978504647889, - -0.2027916049180597, - -0.2513980890912902, - -0.2408987565801033, - -0.22105815602819617, - -0.19359326660337953, - -0.1610814397082065, - -0.21111688362002967, - -0.23786314680620277, - -0.21257650518116591, - -0.18292622857686344, - -0.22666872137563016, - -0.2569330601659605, - -0.23934737869058412, - -0.26696541867644824, - -0.2841203789667926, - -0.21034899462559664, - -0.28032068159632334, - -0.21556111627179014, - -0.18958528591461465, - -0.2333591425275566, - -0.1832021546341266, - -0.23166637447009603, - -0.23886786678947736, - -0.17735828661273978, - -0.18479737942696745, - -0.27356632884918924, - -0.2454106705763343, - -0.16575504745098113, - -0.1955792332938458, - -0.19333297722613124, - -0.2729433575264106, - -0.2939246285381669, - -0.2501535459352161, - -0.2582243828304896, - -0.21187076633086108, - -0.1577342840557121, - -0.19807273202446007, - -0.21344013556164831, - -0.24515885769752854, - -0.22165381074361315, - -0.1724311338000965, - -0.19356598707721157, - -0.17779565086228488, - -0.15870899185636397, - -0.16703062889103343, - -0.1578371618681679, - -0.18943932933257257, - -0.22915070544550048, - -0.25259195560396325, - -0.2789400944822567, - -0.25404286187758046, - -0.27316917381366684, - -0.28151742328695606, - -0.28532647069518535, - -0.27914637265641495, - -0.27856375840916603, - -0.26854174285962484, - -0.27945237962683384, - -0.27898280728287755, - -0.1665898765491227, - -0.2579493005135958, - -0.24722247988415846, - -0.2964123313764723, - -0.18676794012993247, - -0.26499469453280483, - -0.17375263163492366, - -0.21649487399428788, - -0.23928670689901377, - -0.1605134178306489, - -0.2378958814644771, - -0.2968997848931132, - -0.2777313978308892, - -0.22830734139993392, - -0.2947780589170834, - -0.166581643186107, - -0.17273187471009277, - -0.2731831864417645, - -0.1786905460919844, - -0.17265039844915364, - -0.27711553615139795, - -0.17437085528648982, - -0.27985491651276156, - -0.24355066210475032, - -0.25505485097876557, - -0.261805545873871, - -0.26765796124071656, - -0.2763429947479614, - -0.27347467833220046, - -0.193241659824826, - -0.23892948086408317, - -0.2650660427843298, - -0.19845190002134913, - -0.26400551042272136, - -0.26736130081319365, - -0.17465072556109532, - -0.29592972070948254, - -0.2363519916182759, - -0.16012805675936492, - -0.25197729070285546, - -0.23237080912205105, - -0.28460953610430434, - -0.2363843051408607, - -0.1793368699566245, - -0.17671595735202994, - -0.28295669596104833, - -0.29195578050792864, - -0.23827613240098586, - -0.18275881522914048, - -0.24196963851811867, - -0.28469726993398037, - -0.2534581960880323, - -0.20199866036876207, - -0.23187813787008793, - -0.1987931366941093, - -0.20827348410444466, - -0.20160398774994795, - -0.2120257563907174, - -0.253193521262969, - -0.162684627490784, - -0.25253187023154133, - -0.2982556848344328, - -0.17499301510072932, - -0.1579471870058362, - -0.26678019001788583, - -0.1724101672826353, - -0.21434188354007677, - -0.1993507877428777, - -0.23478060175805854, - -0.23559259704399121, - -0.25015138509114704, - -0.2930825796822048, - -0.17960275977523765, - -0.211345364368152, - -0.17657551841836427, - -0.2877023055125895, - -0.19937614711416413, - -0.25170141416177727, - -0.23209127199372964, - -0.23926193418160938, - -0.2502972583904214, - -0.16124610673510034, - -0.24661449157413545, - -0.28442704790093626, - -0.17775824942720508, - -0.15800444695963195, - -0.21574246675770317, - -0.182683161040636, - -0.26578561322240446, - -0.2674201281242001, - -0.25709324887659357, - -0.27814830023124565, - -0.18014424387429157, - -0.2382609898131816, - -0.21241218604544476, - -0.16222672892585643, - -0.23746537786559357, - -0.24327914290790936, - -0.28651061619006823, - -0.1562049534138234, - -0.19642933710446306, - -0.19991488539966323, - -0.20858017318109853, - -0.2210392554958917, - -0.2650455164784736, - -0.2857540895619538, - -0.2611046004137951, - -0.20777992080883323, - -0.19700168003241536, - -0.22304928556055703, - -0.2817244625792822, - -0.16577450276415193, - -0.20524790091778522, - -0.18319791931008528, - -0.20435435052431575, - -0.16484224293793753, - -0.28472848311908466, - -0.16121433281736783, - -0.28092279758839866, - -0.2605657803639215, - -0.21178752423847513, - -0.2289553384541101, - -0.21769183758415106, - -0.2443664413900288, - -0.18125334534358198, - -0.2342976911286791, - -0.21482435172014136, - -0.2729557948853808, - -0.1685753398531657, - -0.28341963480500976, - -0.25594806209778365, - -0.24874727426369822, - -0.27768491364644726, - -0.28227321542918493, - -0.2555866616372137, - -0.15627778414945415, - -0.2824933703981514, - -0.27061919775824467, - -0.19653760884085783, - -0.28470656416869145, - -0.27615782458926075, - -0.2801720501677333, - -0.18730739795282653, - -0.2061967426577481, - -0.17477503495089652, - -0.18128317878585276, - -0.20568868844952096, - -0.298532227124465, - -0.27354471113086914, - -0.2758991184438265, - -0.20542985639837363, - -0.22401888605487214, - -0.1764793128959386, - -0.24007949037420856, - -0.2853136548582389, - -0.21828568468456944, - -0.2015477745051686, - -0.1687685958203118, - -0.19725253449817554, - -0.19727443508428416, - -0.1807144971906592, - -0.19542807277131935, - -0.282800021013917, - -0.22324342053698104, - -0.19987013604794443, - -0.19034946228716412, - -0.2634881618647184, - -0.25635730939668966, - -0.24823235403301194, - -0.2496552127746631, - -0.15765529702696024, - -0.28617215817662206, - -0.18860241928975996, - -0.28550483652854486, - -0.23298134727604952, - -0.2880168130177248, - -0.20295116649528777, - -0.2175883273143776, - -0.2212305029219869, - -0.18540975571903384, - -0.2139612808339677, - -0.2931129020819199, - -0.23824913780640355, - -0.166260961258371, - -0.17084855758952167, - -0.23354756154965026, - -0.17903549098290228, - -0.29637509050095734, - -0.15635791043976102, - -0.19612143137105403, - -0.2378287341430949, - -0.2776576993156972, - -0.1901270529375125, - -0.24316980447728626, - -0.19307478971954162, - -0.1709230205629746, - -0.17944561312644014, - -0.17149852592789996, - -0.23085457866268289, - -0.22602423627653376, - -0.1797460061354233, - -0.20891280481442492, - -0.2248400840758969, - -0.24341242961237233, - -0.21323598687997763, - -0.2224832385216494, - -0.2594740422462156, - -0.18937154854847693, - -0.2701494859002583, - -0.27145432460023655, - -0.24654249011314033, - -0.2509230395968229, - -0.2768539966905871, - -0.18815122917843619, - -0.20681819553398756, - -0.25280237084623947, - -0.18871488059669017, - -0.19366028061069052, - -0.28163096382828473, - -0.2717279029987593, - -0.21919728112838036, - -0.18201656191152693, - -0.23648695744688442, - -0.21353208614803074, - -0.2907804421537365, - -0.2363227920496125, - -0.2256699480625991, - -0.27153654829362345, - -0.28303559499243236, - -0.1814648380916036, - -0.22989382341738068, - -0.2870480622092615, - -0.29174200619372864, - -0.2846539956251041, - -0.24990738455557193, - -0.27895316581894775, - -0.2684345223868372, - -0.2735166104922693, - -0.24847269894828083, - -0.23336031755477182, - -0.20038487300935415, - -0.23350514624642682, - -0.23197757423042364, - -0.1691767334293418, - -0.21786095873592923, - -0.16892742997405844, - -0.27557893955938295, - -0.27620206211130444, - -0.24514791044035963, - -0.16575232153081917, - -0.2688640197411254, - -0.1741229078370824, - -0.2712441264846264, - -0.2314178501100193, - -0.17761813427443274, - -0.20240484137017634, - -0.23594865359983422, - -0.1721712014941937, - -0.2477277059025543, - -0.18331985928372632, - -0.24941407646890387, - -0.21274668494395477, - -0.26677648789742564, - -0.2774454304487285, - -0.2577847026738529, - -0.17268506847148707, - -0.2774511959807017, - -0.22106601231747003, - -0.19214855994053043, - -0.26441532316655464, - -0.2564682521192658, - -0.1655461868712191, - -0.2674252461804113, - -0.15623133984865012, - -0.17315107506865032, - -0.2335679861586748, - -0.17617261871323173, - -0.1779547713986382, - -0.19295950969278428, - -0.20752081208318998, - -0.2114659622552718, - -0.2741587693118505, - -0.24081950921085862, - -0.27028981497767, - -0.20524738592284542, - -0.29479559443260683, - -0.2519588975747065, - -0.19519534348111645, - -0.24983894913880916, - -0.21562163310417237, - -0.2765679511018976, - -0.2729392928076577, - -0.2028441571968892, - -0.16668980306770634, - -0.19249023348837624, - -0.293911768681869, - -0.2216563149357233, - -0.18788559563955448, - -0.18102231827959336, - -0.27156359525003987, - -0.19062301690211825, - -0.26637809523078043, - -0.23400947131740027, - -0.26261872559909033, - -0.24851634935582897, - -0.2331210925197257, - -0.2755941218472654, - -0.17044194169040344, - -0.20879182128920268, - -0.2703166607928549, - -0.21845777435284025, - -0.26345923069671984, - -0.18542100248124477, - -0.2258850233970784, - -0.20801557673650878, - -0.23428891803306606, - -0.18550964507879653, - -0.2557860275326834, - -0.2812851287530719, - -0.26906096984371486, - -0.17610261580775943, - -0.25161913785396783, - -0.22689359756232783, - -0.2953818073724636, - -0.26397563625362847, - -0.24066638912185187, - -0.1817068508534887, - -0.15550555331682236, - -0.19044218312901978, - -0.29730726878474945, - -0.22714056463845272, - -0.26578576815537247, - -0.2392392222898208, - -0.22565057898167545, - -0.16044342035458303, - -0.16948659842525654, - -0.25334642852681327, - -0.29436759102687987, - -0.2481903887595758, - -0.24844711148018017, - -0.2259338463296609, - -0.2138212548550695, - -0.21265430257418122, - -0.172821891356335, - -0.1568999868909966, - -0.25118679139940414, - -0.2431972315606672, - -0.1555133311560963, - -0.23778557248278206, - -0.26570747125334093, - -0.2855606538101744, - -0.27674339150200755, - -0.2474991447666769, - -0.2731523490799625, - -0.24484499195601664, - -0.29053209910008965, - -0.1930749239265442, - -0.16867075465152337, - -0.26977228598153125, - -0.24791304208921272, - -0.17741522652022712, - -0.2764414461783437, - -0.2393201530565466, - -0.2377433568569574, - -0.18999239484299063, - -0.2013194645566891, - -0.1624731431688929, - -0.2597725639079552, - -0.25753297125031466, - -0.24496890537845714, - -0.25805982022089197, - -0.2898502070924052, - -0.1707100449612092, - -0.21156099141343546, - -0.2600720455601629, - -0.17547909471863782, - -0.2890310734641859, - -0.27312861581658154, - -0.22330436689538646, - -0.28753146883700237, - -0.291227603751941, - -0.21049298250998794, - -0.29542583059013683, - -0.21405399440957237, - -0.2985101231974064, - -0.23243186336611837, - -0.26575945704043563, - -0.16121581769589927, - -0.19201527884157116, - -0.1753921096978599, - -0.26842710748955534, - -0.22293560819914468, - -0.15923763538307872, - -0.2817148715590365, - -0.2365148020443637, - -0.29301840702286575, - -0.27916525912082296, - -0.2691659121535141, - -0.26159556422528585, - -0.26694901470601584, - -0.282119633383547, - -0.29687889923592825, - -0.2376756542085307, - -0.25615983759012595, - -0.21566819810828827, - -0.22701247497138632, - -0.2770909164687673, - -0.17088868335017204, - -0.1680201957915767, - -0.27530489536311775, - -0.16941281865554753, - -0.17843840651201792, - -0.21737021027799655, - -0.25852391507831846, - -0.21346488901028984, - -0.27367613427379817, - -0.17287986966956212, - -0.2921530060979388, - -0.28971295284956494, - -0.2502005124569125, - -0.24123720816729596, - -0.20236263505300597, - -0.22349422513183556, - -0.2641118425279603, - -0.2825203507628241, - -0.27346903221827157, - -0.16241455065135063, - -0.27797246382465923, - -0.28614873979933564, - -0.25895263249637546, - -0.19090004371050906, - -0.26784963182544325, - -0.24931778665838022, - -0.19999247746509557, - -0.2793598855858929, - -0.23905077588304352, - -0.2665991137982808, - -0.16710390932075325, - -0.286699075328447, - -0.255337230618967, - -0.22828573495936272, - -0.21211177536505837, - -0.29764502669891124, - -0.1987840384803214, - -0.2447489663735714, - -0.27673208204379923, - -0.19476620373666373, - -0.18133643401044058, - -0.2938622796572171, - -0.21982271770885292, - -0.22403179104475882, - -0.19062472442673206, - -0.21931306137245163, - -0.27239662966279593, - -0.2115087521892412, - -0.17966396451148178, - -0.27608051155142127, - -0.24014196973446567, - -0.2301147370517329, - -0.17894635703575057, - -0.23289418591852906, - -0.24974278762639657, - -0.23445444658945913, - -0.22810991387777035, - -0.16485990845329695, - -0.1803918030092428, - -0.2560018602847043, - -0.2775947357939713, - -0.2269390041738522, - -0.2931997728560894, - -0.17114951895821942, - -0.27018062354356454, - -0.1663437355167024, - -0.24136408760607758, - -0.2772171547172126, - -0.159848890773304, - -0.1638547267032229, - -0.26389446584389065, - -0.2744089390802424, - -0.1824111500535116, - -0.1934702112607668, - -0.24633816950565707, - -0.19547860722585259, - -0.2821103986660084, - -0.28629253635893465, - -0.20906230300757586, - -0.2531602163332487, - -0.275294019573299, - -0.2038374389364725, - -0.23078398926340993, - -0.2173516639426891, - -0.23455134577077505, - -0.2214716359352235, - -0.26795469097504326, - -0.23254160299885882, - -0.2694627348119418, - -0.29116329029532756, - -0.1679081644337697, - -0.20703321778776093, - -0.17775810973870898, - -0.28398947033007826, - -0.21595934080584653, - -0.2203886813533668, - -0.21513164065307494, - -0.1770799855560225, - -0.17280946599736394, - -0.17632798001325756, - -0.22197264542778317, - -0.17472899617016716, - -0.28574096389187814, - -0.15632685290370896, - -0.22364994377654396, - -0.16899623066799058, - -0.23741423845469092, - -0.22276639239392293, - -0.20310413959409895, - -0.1843256625744619, - -0.21238588937368125, - -0.2827823807172241, - -0.2682789864535664, - -0.282381388633539, - -0.17238178634280635, - -0.18637749377184568, - -0.2818473910224497, - -0.2811264556400659, - -0.2892267453216237, - -0.21229391491278904, - -0.255910070250455, - -0.16211586725831062, - -0.2507844650501776, - -0.19106535344809664, - -0.26319582648771256, - -0.1723995040748813, - -0.17056897805538979, - -0.24328534884466724, - -0.2055432389732073, - -0.27883942951424917, - -0.16784184351308548, - -0.28361635079923253, - -0.18074946598171243, - -0.16676161816784704, - -0.2077623545023429, - -0.23130917520387223, - -0.174460272462858, - -0.2754036405932848, - -0.22473317208793503, - -0.2821317227983766, - -0.20268300764830682, - -0.2803985124078378, - -0.290351895262486, - -0.2330112765376981, - -0.25589725862069823, - -0.1901573772226877, - -0.20422240906737482, - -0.22178115956542804, - -0.24653173863584976, - -0.276499569541854, - -0.16309095905298307, - -0.21716866086440412, - -0.16651810844725473, - -0.1546348481803859, - -0.23831285937870253, - -0.27260439675766934, - -0.2434808965804809, - -0.19107442345714337, - -0.254502453466823, - -0.22284289783213446, - -0.2287906576385347, - -0.21401078814672825, - -0.2555169216802665, - -0.19193867447747678, - -0.21297909410500576, - -0.1865197822306711, - -0.28014939758919016, - -0.18200609157583614, - -0.15576862798004376, - -0.22757360513956212, - -0.1550830594757684, - -0.1893105253397453, - -0.21722040348787675, - -0.18038031898337206, - -0.2646590351309917, - -0.1608925933081407, - -0.2850362235633672, - -0.23596295964986796, - -0.17991929502891563, - -0.26607267958345154, - -0.19588562539082643, - -0.22027993364239065, - -0.1993292792133023, - -0.22330731543823729, - -0.16036458991408684, - -0.2889540036350388, - -0.29612817575300304, - -0.26931840254492917, - -0.19293865079465788, - -0.18523441497358545, - -0.17271141748300692, - -0.18024810406108902, - -0.29376763760475827, - -0.2490734468650882, - -0.23398840023957462, - -0.18591406637589797, - -0.2190581640714021, - -0.2161706710938432, - -0.26718959847504137, - -0.26414357259355564, - -0.205140694617168, - -0.19031731101846372, - -0.17626779406848914, - -0.2696665798354657, - -0.2670130584702524, - -0.22425273177206909, - -0.18316913504033738, - -0.23971321413351582, - -0.19140912376119504, - -0.20435351149870734, - -0.24089619810102825, - -0.2786008631453943, - -0.24608785638160802, - -0.2514472371929018, - -0.17590882152010467, - -0.2129620612555993, - -0.2155917470348733, - -0.2684989306656945, - -0.2840750582314362, - -0.22510426704207637, - -0.22615845669080914, - -0.18798052041408864, - -0.27355296958541997, - -0.24938687567079684, - -0.26418867752637837, - -0.23571276035826355, - -0.2766886062564294, - -0.18886715406921548, - -0.2968475943894624, - -0.2897877455972622, - -0.18192580049247073, - -0.19472142882565904, - -0.2538390943197133, - -0.1894086152588312, - -0.15939271601049462, - -0.28594965619958856, - -0.24509299808094454, - -0.24337108238886979, - -0.28158138097529833, - -0.1809536389666238, - -0.2937102306971206, - -0.27652014344793774, - -0.23303518838286058, - -0.2717309956239828, - -0.2559733070781941, - -0.1615270107484701, - -0.1881122722323938, - -0.2607398690472073, - -0.17913612020026193, - -0.2882669534409732, - -0.2309562415739692, - -0.2913619044055153, - -0.2962511452498487, - -0.1771514837069556, - -0.27302489822405795, - -0.22562400397229912, - -0.20844921097208458, - -0.16175446318064082, - -0.28402533651780604, - -0.2361469636980904, - -0.24739768857681765, - -0.26694688690225366, - -0.23387962612541224, - -0.2338676285552711, - -0.2619381900051078, - -0.27503963282601085, - -0.2642716658508544, - -0.28388479271369893, - -0.24331622243068043, - -0.27287352744828514, - -0.283799043192353, - -0.1549105410656849, - -0.2524263772211466, - -0.2721889384872949, - -0.2459164772531565, - -0.2673415038674908, - -0.16995790611948278, - -0.15896020518993365, - -0.22452005099117878, - -0.18201775181519514, - -0.2082070626583784, - -0.24149142685584782, - -0.22907716278687848, - -0.16818089698015454, - -0.18086722502332472, - -0.1588881908698404, - -0.27574554930180434, - -0.18476972202819997, - -0.1579282889857057, - -0.21097144152723094, - -0.2383835264375776, - -0.23761492392009284, - -0.2607028820813014, - -0.2582816391584286, - -0.2014190508717403, - -0.1848870594292383, - -0.24200430762087344, - -0.17353928259200538, - -0.1598684893838471, - -0.2784946812475443, - -0.2774811851507823, - -0.2888555118032504, - -0.22649255604099638, - -0.26703363993417106, - -0.21021201577031912, - -0.170447386069685, - -0.18208809253448943, - -0.22737021696120446, - -0.19009794070835923, - -0.18386996621113968, - -0.19160490972953798, - -0.2919608903361222, - -0.16330883024900025, - -0.24274889470983668, - -0.23610246134301818, - -0.2216029105285937, - -0.18974493484119256, - -0.2937326076735185, - -0.2294104129427879, - -0.27846552793949486, - -0.1898443976339229, - -0.2539249317306671, - -0.19332500315052675, - -0.24673389623228312, - -0.25091459058318066, - -0.257058248357978, - -0.26053314500909613, - -0.1959028876536349, - -0.2505280908928854, - -0.2959683759511429, - -0.19636963054915288, - -0.21569214740194861, - -0.22573601989976183, - -0.24747363451572899, - -0.1596555083503319, - -0.2833648211755428, - -0.1957899675098851, - -0.17358351581362746, - -0.2984728529013744, - -0.2538749532912662, - -0.21696934225877118, - -0.1665824057091451, - -0.21747646459924552, - -0.2904808698821975, - -0.1996083562377019, - -0.2081087768978131, - -0.2545023874337851, - -0.25569449018029156, - -0.2937569675930053, - -0.1745414820318376, - -0.24102558124013737, - -0.23145398667041717, - -0.20653841282299965, - -0.2782876434943574, - -0.24602477698859604, - -0.16336808894320276, - -0.2306804863588077, - -0.26312619744684634, - -0.29099740135145047, - -0.261324943118799, - -0.23161941908346514, - -0.15864941353825163, - -0.23610380934276454, - -0.21987416368953655, - -0.26997467595678626, - -0.17765803146656362, - -0.20038188045687572, - -0.18870650793961596, - -0.2943714468181862, - -0.26186203416544895, - -0.22610612376953754, - -0.15591553131315058, - -0.21129187868714766, - -0.20536455534626763, - -0.19905639144364382, - -0.246275128494031, - -0.29069080893035953, - -0.2202054226307801, - -0.27588181794395505, - -0.1957467968593346, - -0.2045518609957509, - -0.2585748587042647, - -0.2601904526183994, - -0.29160989887900796, - -0.16427129356455095, - -0.18666951951116373, - -0.17491260226500932, - -0.158335585172892, - -0.2883974013613693, - -0.17176539310885738, - -0.2154876108941412, - -0.22326329852623839, - -0.1619564015553239, - -0.22218369047954867, - -0.24905125210558784, - -0.20139034631334218, - -0.23964142176828368, - -0.1945056542049139, - -0.24186140727298702, - -0.26984955296356355, - -0.2576019101298893, - -0.21694124964728523, - -0.26821023854022946, - -0.2791551237693377, - -0.1883166380082637, - -0.23758733716585448, - -0.17829024937518229, - -0.20826542901789466, - -0.19341856154045206, - -0.1715409113301429, - -0.2639173657147058, - -0.22477800678255774, - -0.15537135047963985, - -0.16572976169794143, - -0.2127699463973023, - -0.26056757925530405, - -0.15500530726317624, - -0.24919226698800787, - -0.2673333272031764, - -0.22116216055498383, - -0.2386009405974308, - -0.19054561567930062, - -0.17228185080107944, - -0.23852172253835338, - -0.23062944449573175, - -0.19005529451928294, - -0.2489227701738831, - -0.16076727999503795, - -0.24949615518427268, - -0.2762882382952504, - -0.22935845727807283, - -0.2856443846600259, - -0.21479877966158212, - -0.22377484049188284, - -0.2672019316842947, - -0.1917990635810035, - -0.2294073613195231, - -0.2161455461170646, - -0.18377576792624953, - -0.2754796380817055, - -0.21514264767730346, - -0.1558318181537742, - -0.19327605172387569, - -0.19653772894666066, - -0.22325746538369912, - -0.1934511084232432, - -0.2744706644460483, - -0.27514386051164924, - -0.16234045579423909, - -0.25231373444670596, - -0.20292378628542912, - -0.27593604536283983, - -0.16204298800042696, - -0.2833966693960411, - -0.19853041799541393, - -0.19551279389288978, - -0.2930891090813815, - -0.2395633974124808, - -0.18797387819376032, - -0.27476043586037174, - -0.19149823486266762, - -0.21697001515744352, - -0.19011920430950902, - -0.19225915441886027, - -0.17894269591158335, - -0.2187373243158423, - -0.21758510983160564, - -0.26739388406183107, - -0.17500048657144635, - -0.19022710882996507, - -0.2187488786730789, - -0.2220010476131335, - -0.1730891754527691, - -0.24661674004740997, - -0.2032804987140588, - -0.22698922809305747, - -0.2234495829825084, - -0.21808097800295398, - -0.25122901166956285, - -0.23851502465808871, - -0.16845217455725023, - -0.22055751250022482, - -0.22961498578798878, - -0.25835470007258915, - -0.18588471435420606, - -0.23559399223960376, - -0.15632483562500465, - -0.1588609544200318, - -0.24720376809660094, - -0.2889878054605122, - -0.18606411011657098, - -0.28686286235533326, - -0.2533383804469974, - -0.26688744277856785, - -0.2200323903582918, - -0.28489476534704883, - -0.1576911715217735, - -0.24556301841005826, - -0.20570571889360062, - -0.29858268648218145, - -0.27671201724453126, - -0.20715772564497387, - -0.1592650410974372, - -0.1573272364696465, - -0.27474157388338427, - -0.2584440108004965, - -0.22796951675675928, - -0.259417756303958, - -0.1778428770446251, - -0.21832346171058514, - -0.21216104645971162, - -0.17320484126165098, - -0.25946820012679794, - -0.23584541126262343, - -0.17499184695539788, - -0.24442544870663263, - -0.18204681036139397, - -0.29807743579139595, - -0.16211039956212256, - -0.269714823449896, - -0.21925975389582225, - -0.253838585071268, - -0.2763459648935104, - -0.21340852181288525, - -0.16699038727514803, - -0.1615213630998241, - -0.19586020851365188, - -0.2955017988999464, - -0.1671829686278697, - -0.21778882543503864, - -0.2975565381890079, - -0.20422420834147875, - -0.236191679973218, - -0.18484919618457074, - -0.2591303935932557, - -0.23231661147404087, - -0.29323888201291437, - -0.21244765701930873, - -0.20572713474622323, - -0.2712792866381345, - -0.24327380209872637, - -0.266255284226829, - -0.18494296045121528, - -0.21742211421003055, - -0.19331985231061719, - -0.20499763697348433, - -0.2955602489485276, - -0.17863198147051776, - -0.2767093307442339, - -0.24796805804720443, - -0.2046323306782078, - -0.2134626250082255, - -0.27718174590752676, - -0.17239928830259685, - -0.15877765007500746, - -0.24349385011187624, - -0.1850209699688385, - -0.1836489640512366, - -0.19758610928608544, - -0.2638597339911734, - -0.2691773423362487, - -0.15821789308403647, - -0.20872804977131154, - -0.2391556671478564, - -0.2282627797679093, - -0.21952598095620957, - -0.17512038294103094, - -0.16783468915191146, - -0.2761593026437872, - -0.23288747724616787, - -0.27104856399355937, - -0.25796709620808916, - -0.21465721332537513, - -0.2885921474602799, - -0.27943069396583603, - -0.2062868511197592, - -0.18104138260117592, - -0.22155636837569015, - -0.2837120375993513, - -0.19984747549474974, - -0.23974531737550248, - -0.24727166914999016, - -0.24898384799569578, - -0.27992966366752964, - -0.22101219030763042, - -0.21096822138863075, - -0.2344039786573008, - -0.21942502506991268, - -0.17518385203350206, - -0.17077702398791111, - -0.17649644419412447, - -0.18703407523363527, - -0.18006807951302484, - -0.22504022726549022, - -0.23886408295719339, - -0.1642849656516848, - -0.26120532137642016, - -0.22854698222885683, - -0.2887809455042552, - -0.289854321747655, - -0.18005027131907614, - -0.2534001509662349, - -0.24764260870261598, - -0.16086606450380556, - -0.27265056786339165, - -0.24494143580504707, - -0.2985820614462208, - -0.24997272266331103, - -0.2480044720457666, - -0.29138819663363935, - -0.22418772916126695, - -0.1990710573078016, - -0.23370678475977788, - -0.23995978959275485, - -0.2378197884258798, - -0.21780974434913364, - -0.2605579139783315, - -0.2870432772733906, - -0.2111172925297018, - -0.20027543837759684, - -0.2093964013222702, - -0.24257167294619214, - -0.279228234618587, - -0.273870539154731, - -0.2934182632476438, - -0.20840231542599735, - -0.28054014110107095, - -0.23630472423125426, - -0.18579724737589567, - -0.263776685754733, - -0.27490382971868516, - -0.22471315368240583, - -0.2125077632570391, - -0.23987498499577609, - -0.24189522144562464, - -0.2610078899843657, - -0.2965894476768638, - -0.2452858092322912, - -0.28053852988276484, - -0.27438323511128954, - -0.22193951295340325, - -0.15527927825854015, - -0.24178934668698607, - -0.16915964221712174, - -0.18358844979978026, - -0.24948462196234436, - -0.2880034120946917, - -0.1810549753181893, - -0.2523508939089492, - -0.19073458284287453, - -0.26128274999473394, - -0.2556119505428832, - -0.25098323615773094, - -0.2597112213406069, - -0.24307176753798881, - -0.28382090078524963, - -0.22784531127447105, - -0.23269008320717866, - -0.20801273394741027, - -0.2635769802606836, - -0.16760810459808484, - -0.16279048401461704, - -0.2969364891479866, - -0.2152686635471679, - -0.2416052495199128, - -0.18725960250017465, - -0.1812515980537126, - -0.2571484424603848, - -0.2412062988311953, - -0.2853706003831876, - -0.2413040506579559, - -0.22225280518464482, - -0.21559632507269688, - -0.1895903131498698, - -0.179266615789329, - -0.2128407657956819, - -0.2859003268139915, - -0.24219060480123414, - -0.26276760847077407, - -0.23436475145778818, - -0.27796377550213414, - -0.2937589558532296, - -0.28822534839371555, - -0.1563872113663553, - -0.20399548662480127, - -0.18296974396754173, - -0.17269641490857526, - -0.22697330382012204, - -0.1774502189623679, - -0.19506749293941944, - -0.26472130032202407, - -0.2191206568488157, - -0.2949531397520033, - -0.25818965377328895, - -0.23756460861638454, - -0.2852751200970768, - -0.2725649217436478, - -0.22001214764454427, - -0.1672463371350618, - -0.20442793185219396, - -0.2587252675273864, - -0.2898655343431341, - -0.2976130451181993, - -0.17217350808749296, - -0.165849643892281, - -0.19903558255154252, - -0.26382290738541647, - -0.2670503372822436, - -0.21659637731538633, - -0.240907285246011, - -0.2315208463802523, - -0.2292090835004631, - -0.22600407227198682, - -0.2214644566102421, - -0.21697759587256582, - -0.23752802199496548, - -0.2254713079352322, - -0.24400783916229057, - -0.287263090506811, - -0.18630871078437583, - -0.1861856444482184, - -0.1652378945060516, - -0.24453295727511695, - -0.16719203850271513, - -0.25650707156368, - -0.2034842009768791, - -0.2754579858991448, - -0.2494751082111738, - -0.20024957202517957, - -0.20058028215138812, - -0.18811394922134544, - -0.23909876005868264, - -0.2262025671504696, - -0.28085516846887854, - -0.25382613815714744, - -0.2807847925749782, - -0.17353908735161358, - -0.28890170968050743, - -0.28313630095303594, - -0.22862013438090106, - -0.2384425171574816, - -0.191695444127936, - -0.2967503382452959, - -0.16840063182774892, - -0.2577533120588091, - -0.1826711664852519, - -0.21056365136596505, - -0.17587451520805236, - -0.2795127896004062, - -0.23890452533170972, - -0.23162409971267695, - -0.2440625249329826, - -0.17727942068241162, - -0.16566491073899065, - -0.26896383431457566, - -0.2131334504967585, - -0.15844058495695543, - -0.2600263317754857, - -0.23286734760425962, - -0.1583469077496504, - -0.21922593532465698, - -0.19864641168849162, - -0.19622076544681596, - -0.15528102942263466, - -0.25977012050039705, - -0.2521140477029987, - -0.15549711910216565, - -0.1648376331262265, - -0.20419145455527798, - -0.21368395213959665, - -0.2096320720389569, - -0.2035284797162529, - -0.22370887377565202, - -0.2518847778653112, - -0.28937854214815645, - -0.19291558700201306, - -0.23448557956064303, - -0.16808392453627224, - -0.24890199147814282, - -0.2914873858565758, - -0.18172669296808122, - -0.21746227872621732, - -0.2782617057538976, - -0.22800012140514345, - -0.21409833435262843, - -0.1894707667688364, - -0.24925746042942906, - -0.19223743393381748, - -0.2727272245763237, - -0.26133206856457325, - -0.2435541386238948, - -0.2623681638571767, - -0.24186234701496895, - -0.2755134837359545, - -0.23279360671999239, - -0.2789507870421103, - -0.16402499361386236, - -0.2329961344247146, - -0.2507089533105581, - -0.216905884840929, - -0.2549503964216452, - -0.18231558302799933, - -0.22430968865243867, - -0.2550930722175073, - -0.17767221087440777, - -0.1783820379746917, - -0.19861952864178595, - -0.16687058699753446, - -0.2559291281620262, - -0.18818559365543397, - -0.22333887962448812, - -0.18320018097124707, - -0.29696618824279947, - -0.170068302645858, - -0.1981167457751296, - -0.26892951224722716, - -0.24847291861140663, - -0.18279703724094887, - -0.17693171087715387, - -0.2048143861608573, - -0.261922359304832, - -0.2848784599421413, - -0.16773772586973051, - -0.2196821894410103, - -0.2241198900620682, - -0.2316088281355334, - -0.2690381180607891, - -0.1683845980367056, - -0.29229356883424373, - -0.22958175708625755, - -0.2636833431569756, - -0.23735410031314366, - -0.29229152945369574, - -0.22900275709148013, - -0.2176934687491176, - -0.15486195920660895, - -0.26245764807411726, - -0.2334451576364588, - -0.23793647788345262, - -0.29712037020490467, - -0.20135792880872957, - -0.20766219589644502, - -0.22420989180979897, - -0.21010708084229363, - -0.16811432983564065, - -0.2482424902399811, - -0.18510523326720602, - -0.17594428214761082, - -0.27612747350717953, - -0.23721606412647245, - -0.2192860227894205, - -0.20481915745055423, - -0.25001629591689106, - -0.1821520208754482, - -0.21850269651526028, - -0.20797392025660028, - -0.2768080736777292, - -0.25326152904437454, - -0.25997603357361904, - -0.15883504779095337, - -0.24433314365638972, - -0.2719556093994741, - -0.25594924645883277, - -0.17500026635032923, - -0.2688488224533984, - -0.23389885744043784, - -0.16708527156806188, - -0.1914132888380505, - -0.22226768843966244, - -0.19004982227333667, - -0.20610386533242014, - -0.26530680918838634, - -0.23127376107411457, - -0.21101574730201067, - -0.2856254721901746, - -0.16359243260908432, - -0.19513434939442575, - -0.16730273239018958, - -0.2546387817994095, - -0.2117753844755616, - -0.27195837577786336, - -0.217111567720557, - -0.26502998185061416, - -0.18986724636914482, - -0.22221724099894127, - -0.15896523014177338, - -0.29007108760584227, - -0.2720530243689101, - -0.2929352656088545, - -0.2684014765229072, - -0.26963807708336546, - -0.2857120178681325, - -0.17240402644845176, - -0.20785551559774956, - -0.21053034954614935, - -0.2629312270376132, - -0.17362109720673946, - -0.1552566640531796, - -0.2656076748955861, - -0.1809460868144971, - -0.23900927510723904, - -0.25003015446089294, - -0.26229800978725587, - -0.25231535863373206, - -0.2275017965638857, - -0.2756442273573148, - -0.16971721948320212, - -0.15572025829358008, - -0.2944743231439736, - -0.26369379968343465, - -0.19591062470075435, - -0.26033653649008803, - -0.24385816527077703, - -0.24492945667024035, - -0.1673114137841258, - -0.27905739836051074, - -0.24357540938898, - -0.17895622281172768, - -0.2518035712986715, - -0.27393296160702507, - -0.24961317454725768, - -0.17176630955892583, - -0.25354295084420553, - -0.2067765705932494, - -0.21012899398025908, - -0.20193719451177788, - -0.22932358049869098, - -0.16771342361994943, - -0.22012515093621599, - -0.20237597640235652, - -0.27782149332180245, - -0.18396340187231836, - -0.23547469806828109, - -0.24325191857660944, - -0.2725404081481422, - -0.2317096930798231, - -0.2506011202676573, - -0.20513038328023248, - -0.292726737007625, - -0.18358645676595886, - -0.23024747480753732, - -0.17864927399984348, - -0.19782176223495052, - -0.24758877641764523, - -0.2648471900648179, - -0.2565872766978404, - -0.15868805370618985, - -0.1919406354180727, - -0.20500308054594082, - -0.17904337441529572, - -0.16132980184715456, - -0.16218653603087865, - -0.18678170542324674, - -0.23833831759088514, - -0.19319035704831666, - -0.22958289626529382, - -0.1691596465133634, - -0.16490833298897742, - -0.15465928618931568, - -0.18146759961809678, - -0.19840897469392083, - -0.2773148272539505, - -0.16813715259803652, - -0.1878758230867048, - -0.2651932182863337, - -0.19610903841310412, - -0.18111860302892258, - -0.2452366731354278, - -0.2379924749365086, - -0.24877372600609024, - -0.24405861835393294, - -0.26594939338796947, - -0.2711896834905621, - -0.17447856954820856, - -0.17512123036584593, - -0.2488369493607888, - -0.20247355741325684, - -0.15545905019897804, - -0.2007512040923866, - -0.23422451902423966, - -0.17802089614686017, - -0.15787794906248928, - -0.2699578175294132, - -0.20049860807967407, - -0.22333039592398876, - -0.2949665304656134, - -0.20285194774504509, - -0.16338979269835283, - -0.2207508100879708, - -0.17056452061827834, - -0.17507670811145395, - -0.19573154934746945, - -0.27855123545240235, - -0.1611673460515911, - -0.20799917778253268, - -0.28227726248033874, - -0.27915993369516956, - -0.15564957547952385, - -0.26552694724680825, - -0.28725251609285607, - -0.25733976862519775, - -0.18180278200559064, - -0.27244463439624017, - -0.25941147997895236, - -0.23285830269415048, - -0.22134504210735534, - -0.1829752232723271, - -0.23227296926221608, - -0.25108783337415574, - -0.2766845929627024, - -0.1915783727730428, - -0.288053514454794, - -0.1775906366222621, - -0.23523780454114301, - -0.27694353940562927, - -0.2230587760351826, - -0.29553061077712733, - -0.16618052573635125, - -0.2076854427365474, - -0.2569370336444386, - -0.23226497670309426, - -0.2322099411775153, - -0.297664303134563, - -0.20059726877474127, - -0.2033766284426347, - -0.18472815189932168, - -0.16181266406798026, - -0.27568257743264646, - -0.22789342647496555, - -0.27860149546701196, - -0.29822908141993637, - -0.24754774973226445, - -0.19296682719841668, - -0.18622045142330226, - -0.29141256504394253, - -0.1971904044021896, - -0.2592912982067644, - -0.16209024243435463, - -0.1548407258230557, - -0.18479599782751077, - -0.2403059948623341, - -0.23753964732564492, - -0.23843974104264784, - -0.18286297056643147, - -0.24903937457335518, - -0.22828368450907693, - -0.23674536308957564, - -0.16708828514863064, - -0.284253213817348, - -0.27321208862893265, - -0.2671135858107202, - -0.23974436550941144, - -0.21277690233404364, - -0.295534816532208, - -0.23348141162702407, - -0.20204168257733982, - -0.18071057212097957, - -0.2532546032403388, - -0.24915745102181497, - -0.15558540097772108, - -0.16838975352543825, - -0.2310606047127317, - -0.23334606922520207, - -0.19304870510290867, - -0.2852867184672493, - -0.2470742097983294, - -0.26651853167602113, - -0.28371680586413445, - -0.24082499512183822, - -0.16974770190905392, - -0.24057466465660193, - -0.1961371766144143, - -0.192123720645962, - -0.16106443397931736, - -0.27539997071146793, - -0.20952115324046422, - -0.23151894012390634, - -0.23929124945431712, - -0.17912424406610333, - -0.2451822686018142, - -0.2630364740451083, - -0.22212710372449443, - -0.1894674842159296, - -0.25976650101881177, - -0.21667256333620652, - -0.27960247507674124, - -0.18133728662745596, - -0.2685732506335126, - -0.19228677249666648, - -0.2638513446572185, - -0.18180573149569024, - -0.22746834333593552, - -0.23545871269582797, - -0.21961288991266065, - -0.29337460699738427, - -0.24761642218388133, - -0.21335933662388668, - -0.16548433200062332, - -0.22406374096380466, - -0.20860972753854307, - -0.2219345241775244, - -0.2026019119273032, - -0.21165498676035738, - -0.274200530447442, - -0.22450285504769218, - -0.2111510948358047, - -0.22458285705532044, - -0.19962520768467612, - -0.21197058607941954, - -0.24366934567854007, - -0.1707970105858408, - -0.23607394914077312, - -0.2538548234354848, - -0.2026333061914838, - -0.2563308967995872, - -0.1918512891159142, - -0.20997147899176072, - -0.24479929440945872, - -0.2651032525815804, - -0.2730195763386181, - -0.18062575034869272, - -0.234704071780557, - -0.1916612351521187, - -0.2106741082507685, - -0.21973200682801491, - -0.21745640987392462, - -0.2144062820856143, - -0.25358799371646656, - -0.23915087425914083, - -0.1792313805284606, - -0.15510342888449635, - -0.21199692596125314, - -0.16536665528149838, - -0.24073357109558982, - -0.2601977607341164, - -0.20563614523257548, - -0.1835385832768765, - -0.21183313499860976, - -0.17730433411875937, - -0.2668858874894081, - -0.19501281172741558, - -0.24777300744202715, - -0.1842848429242723, - -0.2976010940727367, - -0.27362660351199586, - -0.25957966999284204, - -0.22298682562973654, - -0.2521242294658149, - -0.23398854210394016, - -0.29152562388977726, - -0.18438287855967267, - -0.24620609404394173, - -0.16870065639379578, - -0.19101765703821727, - -0.17126072594999664, - -0.2195959968036631, - -0.18545831416668904, - -0.2064060998112513, - -0.16730964617661498, - -0.24296356220668885, - -0.2659942246783509, - -0.1818828719577113, - -0.25831933153127745, - -0.22440656179424168, - -0.22134477455206314, - -0.26726152300810235, - -0.22445765094982945, - -0.20783098251942425, - -0.19913035243849542, - -0.19132330315295737, - -0.24422129838960116, - -0.277190894080872, - -0.2651305826189883, - -0.22519780437142015, - -0.2462983512215357, - -0.29782023085760617, - -0.22547034862403276, - -0.2663414461115074, - -0.16152181678333077, - -0.2931599010575257, - -0.2335871368356397, - -0.16208638926770597, - -0.29399942182341726, - -0.1789375347570375, - -0.24182673589335207, - -0.20496503108330466, - -0.19708708831654176, - -0.27497438821994163, - -0.2482322193996485, - -0.1821481513597294, - -0.19396462304475373, - -0.19154645957883, - -0.22301569773930507, - -0.2783048755542714, - -0.2277065088718463, - -0.25667687102272796, - -0.23014078972427482, - -0.29562718749531103, - -0.20258579198004492, - -0.23220684814234963, - -0.16142808182696453, - -0.16417886216365274, - -0.29721889066197144, - -0.2729402292335602, - -0.18848370051228439, - -0.2843227003824646, - -0.20462520103025802, - -0.18005211937546967, - -0.17189909641804874, - -0.26125958091226903, - -0.2938545611827767, - -0.2632537634274426, - -0.2782703962351983, - -0.15515457926522064, - -0.16337879473302286, - -0.19295317653936467, - -0.1935911778664101, - -0.2313529412292919, - -0.24779557565382826, - -0.2863153583849467, - -0.16238253205864314, - -0.25324467776848797, - -0.29738640436335206, - -0.17379522573041659, - -0.21292742547254762, - -0.28924291430393073, - -0.2882474729535906, - -0.29348927959372767, - -0.22349227678417394, - -0.27155365993557923, - -0.18095906852089583, - -0.2709486400854469, - -0.20041968686750344, - -0.2917854227545754, - -0.20606211464255575, - -0.19188669769199096, - -0.24582229070133566, - -0.26531648711079914, - -0.190054893034234, - -0.24929086052650798, - -0.1939453287279405, - -0.1619412807391406, - -0.2495335275158314, - -0.198061852961109, - -0.239470335810762, - -0.2670862172944309, - -0.2237991432571804, - -0.22157535297653583, - -0.2715744992052974, - -0.2221837961159709, - -0.1746244056730292, - -0.1909464469675996, - -0.2723188191398491, - -0.18448523447890747, - -0.2196740812720665, - -0.23555023164910233, - -0.25883190291039004, - -0.2879123969077365, - -0.23618952452257908, - -0.19877452076469815, - -0.23796638196960296, - -0.2721888834022584, - -0.27938625907591286, - -0.18029024696508134, - -0.24286023836425713, - -0.2611717511168136, - -0.2703947818725325, - -0.2870428898959045, - -0.27669384385946494, - -0.21214175982495687, - -0.17210122089264768, - -0.25771386539714874, - -0.16144006550193402, - -0.2566979011303446, - -0.18926037473683016, - -0.21930176748626903, - -0.17741083093893173, - -0.24995991087503214, - -0.2475604205283633, - -0.24945260352213797, - -0.2278950453949383, - -0.2874399300988727, - -0.21378988785028719, - -0.17405437277929284, - -0.19524403314463556, - -0.25200259314583706, - -0.18161011602243904, - -0.24828351633044507, - -0.18668888548241247, - -0.26753421953754525, - -0.23355115363699142, - -0.1884688045001399, - -0.15716948386777785, - -0.22063198449819463, - -0.24705527970821992, - -0.21588936923066798, - -0.23046857858460212, - -0.15486566057431925, - -0.1743919885679352, - -0.26466737865383905, - -0.2682651666400864, - -0.15547411091016614, - -0.23073836574748108, - -0.20641214749308243, - -0.2299224059294182, - -0.19624904505367813, - -0.24065073313288987, - -0.2864048209042344, - -0.27258149142108096, - -0.22649258365097164, - -0.23085075890436402, - -0.18705861473233526, - -0.2882163957362829, - -0.28440868051355034, - -0.2517371452831022, - -0.23768525983171992, - -0.2776452145033096, - -0.18536394868032213, - -0.25324391059793155, - -0.1933485112603081, - -0.16716795254150577, - -0.1810543684850848, - -0.2680605399527975, - -0.2403662094455844, - -0.24308763270981018, - -0.2193714750571475, - -0.2703227960107798, - -0.2720576116366699, - -0.25278284453859357, - -0.26718601062429875, - -0.23428720260757258, - -0.2320055751843, - -0.2781576707281481, - -0.15512248905970852, - -0.22310022803120555, - -0.2598890623221637, - -0.2850257101296204, - -0.2953161682658717, - -0.25088413666681575, - -0.2966290453486931, - -0.2185194845165465, - -0.272033447197828, - -0.2745505469053829, - -0.2743358056252761, - -0.15913577856674171, - -0.26365676848517705, - -0.22689334239978493, - -0.23245429450043084, - -0.2986074454724565, - -0.29095673782771675, - -0.2715437167675001, - -0.16693232316772683, - -0.22002134494042005, - -0.18105833428311968, - -0.1864952119360132, - -0.2876893767096255, - -0.27002402415790927, - -0.16567875661938888, - -0.158218480629074, - -0.28694730488665726, - -0.16020946330857722, - -0.26642754520175155, - -0.27940124432106445, - -0.29856180133178273, - -0.26138817766511413, - -0.2719662352908059, - -0.29501811356930246, - -0.23375933622888814, - -0.22196869115282114, - -0.2787291519005569, - -0.24636205419229654, - -0.19152068536419237, - -0.2388813667935988, - -0.2135988111573987, - -0.19176643142308317, - -0.25931162633885124, - -0.23535781951662185, - -0.2757581831586758, - -0.225722506487122, - -0.17810645485606874, - -0.21586825163584158, - -0.28187822107642396, - -0.25843022241825186, - -0.22287664686001402, - -0.22763378609416912, - -0.2768013810174655, - -0.22039356977836128, - -0.1737412049836372, - -0.2429901750487649, - -0.2304752933663951, - -0.2665110737968123, - -0.16910031541284115, - -0.26808325878059347, - -0.2723732672035766, - -0.24313747054253002, - -0.2086794346900669, - -0.20480821313381903, - -0.2986758313857103, - -0.25326168919580005, - -0.2532169756180104, - -0.26595668290173324, - -0.16761605520320016, - -0.2785679046709057, - -0.28610390114455636, - -0.18276773619491032, - -0.2846818359490919, - -0.15463506091907608, - -0.2716664409909939, - -0.167186508789419, - -0.23417529885724675, - -0.2467715185674105, - -0.21515480050536234, - -0.15790190900241388, - -0.22237198095558267, - -0.23200830055672378, - -0.175085471707514, - -0.24248800256338943, - -0.247843741659896, - -0.1882534824374767, - -0.17000516450235537, - -0.2938979311956551, - -0.24003860752362538, - -0.22336486011706122, - -0.21789369129422054, - -0.265335771472063, - -0.28624766377653726, - -0.23631108909881976, - -0.19858374777355997, - -0.25429517144132235, - -0.2726170799619092, - -0.1889738522886239, - -0.29468686345143474, - -0.15640335417915543, - -0.22541673235335646, - -0.22470218946444886, - -0.2001344704766348, - -0.20328225471871625, - -0.20130605279110644, - -0.23059547111824555, - -0.21425587466578125, - -0.28186125264772294, - -0.22758013616823786, - -0.198179302945611, - -0.2444783609234615, - -0.20824667613063158, - -0.1815509153820079, - -0.290370150377934, - -0.15750202241626063, - -0.29580610643803423, - -0.21620394034159693, - -0.23009238955311392, - -0.25040514796299695, - -0.22818865035168134, - -0.2333120205696128, - -0.26900105222769816, - -0.2840911427771365, - -0.21572591474418573, - -0.2922585685023924, - -0.23432931314986463, - -0.17116420562533202, - -0.1948810359489077, - -0.21563041754298315, - -0.2535220048490605, - -0.23666840380765905, - -0.2546969998339898, - -0.2808201145826171, - -0.2421034593231789, - -0.22278956154232704, - -0.2748487751222153, - -0.15504245962966617, - -0.22210400665817256, - -0.20788004775099186, - -0.18760594369159622, - -0.15807595658353923, - -0.28547488499249296, - -0.234917724649018, - -0.2661701277868722, - -0.2826550043618697, - -0.27177728756495106, - -0.18906172079861877, - -0.2807111016133405, - -0.2774787271838607, - -0.19386400513868354, - -0.1597817670871697, - -0.2043210899609167, - -0.2346532971904574, - -0.2558519117506681, - -0.25361441312686867, - -0.17497813642015458, - -0.29472030379162356, - -0.25407684709705713, - -0.2729991515825917, - -0.2918758033535547, - -0.20884555071510147, - -0.232655484449201, - -0.1635913945990338, - -0.1662976532451329, - -0.2748573458400242, - -0.20434220837514333, - -0.18783462937213766, - -0.20565893909853583, - -0.19332320358512148, - -0.16550193887480202, - -0.20858689926352733, - -0.28187577129986663, - -0.24961759967618113, - -0.2572973735005518, - -0.23701293244588445, - -0.21877895379408807, - -0.2070216258757283, - -0.16586224910739703, - -0.21793008001519693, - -0.18081941871730578, - -0.23658414309762718, - -0.17701794954104094, - -0.23164122357879252, - -0.21328769781805074, - -0.25075081811289723, - -0.23172370085838856, - -0.25737413058711456, - -0.25486771390411267, - -0.26819299840841326, - -0.28149585690225487, - -0.27260070437682893, - -0.23592386674432658, - -0.27600518794881534, - -0.2249235361652208, - -0.20563377126489654, - -0.268370444592518, - -0.20476136761489233, - -0.28017892817404655, - -0.19907655117340187, - -0.2875241879376347, - -0.1910132171218104, - -0.22271669577645992, - -0.1964045937187444, - -0.28057174792817147, - -0.2819308952531678, - -0.18036269008753902, - -0.17121091440000713, - -0.2731254977042324, - -0.1992891758495326, - -0.24767573753017072, - -0.24226505753393351, - -0.2127956245972677, - -0.15681722462377717, - -0.2144279019324416, - -0.25683400007894186, - -0.2920458584676462, - -0.18892182839248647, - -0.2421738057623001, - -0.277492821364758, - -0.27795895815336796, - -0.15750950494813776, - -0.2140428967807665, - -0.2428033993210357, - -0.2933869625960949, - -0.24733303923485345, - -0.1756684782211207, - -0.16814085568641518, - -0.20869476611762477, - -0.2935929589583401, - -0.18963355536712023, - -0.24270972081144254, - -0.2681065252998808, - -0.17011090820958644, - -0.2526908934888434, - -0.28664337168393045, - -0.24055941753998605, - -0.16791283138581697, - -0.2516419452680482, - -0.2079464916466402, - -0.19874735731634588, - -0.19811124275134462, - -0.24667781892993199, - -0.267458908426194, - -0.2943634558945611, - -0.2906569948747615, - -0.15556867026328028, - -0.23306322542776214, - -0.21360357157720233, - -0.225599033288883, - -0.24561973381226615, - -0.20947977255900752, - -0.1729889199882773, - -0.2576719239665102, - -0.2674926528035442, - -0.17676805605591783, - -0.16387580598915769, - -0.2634247674772295, - -0.214557792720527, - -0.17353436725174703, - -0.20203120426030535, - -0.22724968294588674, - -0.1571170736567819, - -0.2938638500307179, - -0.18644762435226608, - -0.17047110137048405, - -0.16180593552045097, - -0.23644818272044982, - -0.16676089427532692, - -0.2778681586857383, - -0.29784367574660797, - -0.24203817077585316, - -0.1837479299006942, - -0.24820630879981903, - -0.188861624315952, - -0.2711713567344128, - -0.163755590076462, - -0.24841674947925685, - -0.2919693041045338, - -0.1669663314498562, - -0.25608280848471515, - -0.2897452332539818, - -0.2322823016221192, - -0.2752914578596975, - -0.21033168818853049, - -0.25652233123808593, - -0.21969629805881122, - -0.24436382969068926, - -0.26249390162769537, - -0.292630569530194, - -0.21220039525953566, - -0.27729200122004455, - -0.2365117273113576, - -0.16576034040640905, - -0.21940012979819007, - -0.29761037783910094, - -0.25393193245919893, - -0.22447266551382533, - -0.2553732839335421, - -0.20215018445234967, - -0.1955600611131864, - -0.21458577257161185, - -0.25640016788633324, - -0.24019848364266658, - -0.2515666994344108, - -0.18053753683031007, - -0.2970123248147782, - -0.2985788945270083, - -0.17155961645536486, - -0.29780259905167955, - -0.24322393982857973, - -0.27934588595880333, - -0.2892461591407426, - -0.2120477934776786, - -0.2567302880869156, - -0.2899145817661041, - -0.1779409134980089, - -0.20680915238779424, - -0.19841500656172245, - -0.24046368194899947, - -0.2377273280301917, - -0.27704731755002804, - -0.16126282032270106, - -0.1643810902233841, - -0.19072657983267, - -0.17421741395785537, - -0.18033466127658682, - -0.1665050639951311, - -0.27906362128612566, - -0.29826992136890207, - -0.25056395856243596, - -0.28270663660758094, - -0.23355182369205885, - -0.2282081378780822, - -0.175707762532832, - -0.290551974777713, - -0.15492729546312217, - -0.19331148823208277, - -0.18020106340451103, - -0.19431829326539518, - -0.2004054928197152, - -0.2301270188366818, - -0.20812425449498034, - -0.19821710019010874, - -0.23046527944430012, - -0.20882762772442304, - -0.244145804914832, - -0.16549829410709105, - -0.23091954943378293, - -0.15952326369084108, - -0.25336954392073724, - -0.29131589652724305, - -0.23500059277381852, - -0.2827416631877927, - -0.1592097505057558, - -0.289307914573287, - -0.18400643970120079, - -0.26573081118141845, - -0.264400963020222, - -0.16065042033159138, - -0.26052033720278783, - -0.16623860589418352, - -0.22968258918259715, - -0.18735653546141542, - -0.2092079789555933, - -0.2954246395246143, - -0.229564713610747, - -0.2891197380528369, - -0.2450912250664056, - -0.23585922738138665, - -0.2818527351213236, - -0.2715781219743653, - -0.2227420539300183, - -0.289093891636458, - -0.19745060521415636, - -0.17891363776542618, - -0.15968594147183088, - -0.2172007352409075, - -0.15557443284402867, - -0.2796631167640418, - -0.2834106620395686, - -0.21100329738985096, - -0.1797604524390526, - -0.25958584387594485, - -0.28451374020362435, - -0.29072644831719724, - -0.27540284855830255, - -0.28761792509052864, - -0.28859049182595486, - -0.1932883672001402, - -0.1706022868352063, - -0.233529056359273, - -0.22132383564876412, - -0.2930815571596483, - -0.1943928264148378, - -0.1582452040727294, - -0.29587914884966865, - -0.1831173023325771, - -0.19547394861232292, - -0.19004345384881877, - -0.18291985503454344, - -0.22082315468819996, - -0.19436751062354107, - -0.1769950686962306, - -0.24183308453669902, - -0.29822002863536456, - -0.20523522281748163, - -0.2679771046436125, - -0.19725863242177083, - -0.23624028703820005, - -0.21674166747495413, - -0.1954462023292562, - -0.26726646186091474, - -0.25399100916616335, - -0.1849701910302542, - -0.27118664029689465, - -0.20806159302619764, - -0.2881471053964293, - -0.29099650569862945, - -0.26537898359431206, - -0.23976015118510013, - -0.2909912748644976, - -0.2694175934397559, - -0.23038335461268647, - -0.28981713250728297, - -0.16010035140598453, - -0.2831777100360077, - -0.20131132317229666, - -0.1764221025168481, - -0.2156041134543885, - -0.16454816066393768, - -0.17585954695094996, - -0.2385258053213341, - -0.2805866544291171, - -0.2396526153871255, - -0.275012197995089, - -0.1693850610124275, - -0.2814619586326509, - -0.2310712993225686, - -0.2110899835733674, - -0.20884705451370866, - -0.21786013555058753, - -0.2853842687443575, - -0.28514872263884067, - -0.27520062401845774, - -0.2383862650264175, - -0.17137275091835893, - -0.26956212906114385, - -0.16633906184677694, - -0.20947310852485046, - -0.29232296675203434, - -0.26975458362601323, - -0.284411028064552, - -0.26449370754856394, - -0.18355040693206298, - -0.2942730618679205, - -0.2561858294859592, - -0.1715920027153733, - -0.24842960983978776, - -0.24709253622155125, - -0.22202154091146017, - -0.286689514797608, - -0.19476926268342443, - -0.18036238070274194, - -0.19641226879620938, - -0.19777336206245422, - -0.25236520435591775, - -0.23948091255077344, - -0.20213956437077174, - -0.26783994934073174, - -0.1881943508246951, - -0.2911918259205574, - -0.1693203626894783, - -0.2907168159950706, - -0.29324598811147384, - -0.26813599944561906, - -0.2962195433651182, - -0.17738975963131454, - -0.22937399926952043, - -0.15634290805128478, - -0.23316559922283198, - -0.17953263596014774, - -0.2430668653848808, - -0.1708072157903067, - -0.2771152192133732, - -0.26617823602423024, - -0.2040023572440402, - -0.23333981165438084, - -0.29780842189646367, - -0.2708566633538235, - -0.1915755481175339, - -0.27827345568516454, - -0.16461683990699194, - -0.18654995282905432, - -0.15914607932534228, - -0.19362907313018804, - -0.15931617680021656, - -0.17112279417403295, - -0.16444742948588437, - -0.23667818631486467, - -0.18412854703671194, - -0.16342623408669416, - -0.2011591439774313, - -0.24195681300923821, - -0.1971016358688314, - -0.22495937560052048, - -0.19736245093693938, - -0.21369481184274797, - -0.16613568187852326, - -0.1676589986764459, - -0.25511750938646693, - -0.27141024491703236, - -0.2693098162750775, - -0.19744159382423537, - -0.25276101535891715, - -0.16928894106329795, - -0.2962013906000088, - -0.23886965979920347, - -0.19208333221179913, - -0.16527224481515873, - -0.29500077783871, - -0.24696059735245846, - -0.287467709021018, - -0.20624326842460522, - -0.1610296078062, - -0.2704561429821393, - -0.27646561527532837, - -0.19753124018677848, - -0.2766682285552032, - -0.1720100376837751, - -0.2551754873855757, - -0.2260070034078511, - -0.1977277625865595, - -0.21351928801676184, - -0.20611893084898147, - -0.27512791627317723, - -0.22188859142877887, - -0.28358844227491226, - -0.17034428770273857, - -0.20536008955593105, - -0.17772618959134817, - -0.28703956136371156, - -0.29360826453617866, - -0.2734957185010581, - -0.25314627223243835, - -0.18602686205102775, - -0.20074597973894506, - -0.21053401453954437, - -0.29420532659636217, - -0.2846744594814058, - -0.22366037898629465, - -0.15658538539261405, - -0.17139421379601527, - -0.24209061552836808, - -0.19740304030006955, - -0.23290840240814734, - -0.2734281428083904, - -0.28293179725298323, - -0.20290236709552154, - -0.19115228930946282, - -0.28700139436181615, - -0.2414385103196055, - -0.24961862992934533, - -0.23697237252923692, - -0.27146593798529084, - -0.1823390996227468, - -0.156158914831719, - -0.19132430121473848, - -0.21109851371761185, - -0.23500317460211553, - -0.28612729506175016, - -0.21475288514772806, - -0.16701998826643982, - -0.2474190937399698, - -0.20417648175063904, - -0.17834280440687866, - -0.15594216261063906, - -0.25619958472508125, - -0.20191640538440753, - -0.19514978374234215, - -0.2306700026356498, - -0.16829002419785694, - -0.19731234895121103, - -0.19172410899436687, - -0.2570408457982584, - -0.1744188106884827, - -0.19459732603663588, - -0.2747535954494389, - -0.25731793587684754, - -0.2312796150863363, - -0.18285671361770403, - -0.16646026951440446, - -0.21655052610343029, - -0.260654296530895, - -0.2554144510399435, - -0.26720227228454696, - -0.1696434105458705, - -0.25565234768424533, - -0.1881026930743782, - -0.2683283256547844, - -0.24824780919232417, - -0.1675352814121954, - -0.26559823416899253, - -0.2244128955139572, - -0.21512625475257607, - -0.2855442368030223, - -0.2875769259393953, - -0.2828814129314643, - -0.2349578795510782, - -0.21940019330349364, - -0.2743263166742408, - -0.17861612534892202, - -0.17167385278904904, - -0.2846086804109812, - -0.18901230095804822, - -0.2353703559958778, - -0.2310098476025113, - -0.2779048363753017, - -0.22664129731095242, - -0.15685321708474068, - -0.16941971903453526, - -0.23568055066720028, - -0.29125723532718756, - -0.16257992167743643, - -0.1573674579989456, - -0.20521474718760208, - -0.2351488419698169, - -0.19840337694619048, - -0.28043820050145224, - -0.26454266993947445, - -0.16511998299510094, - -0.27416814254372435, - -0.16022032892762783, - -0.16386088442476782, - -0.2176963537562213, - -0.23957928245461857, - -0.19830938188978475, - -0.20427599971344917, - -0.2435606366257964, - -0.16373006113225513, - -0.21304003038111002, - -0.25719177340530275, - -0.16096160350549743, - -0.29555707384647184, - -0.25736175901807845, - -0.19442137370311235, - -0.16750199854469494, - -0.23895369822535495, - -0.1901176614932354, - -0.25212860889772537, - -0.21139143449875458, - -0.1828221126037219, - -0.17279735417927916, - -0.2363336213769771, - -0.254618548274193, - -0.22644362381209862, - -0.243850494928331, - -0.2551525027605032, - -0.2867233706607813, - -0.2323595668784747, - -0.2629528530107486, - -0.23558761254983518, - -0.28697250827861587, - -0.29485963832833895, - -0.23877978247511383, - -0.1731332930370038, - -0.2137181057219601, - -0.2256366604870414, - -0.15598532518826116, - -0.2442591541593605, - -0.23905159587022112, - -0.22099856870321122, - -0.16511332276403057, - -0.28957691215507037, - -0.2603946440597147, - -0.23765282341487634, - -0.24735394352612036, - -0.2445541718041462, - -0.2747241363846801, - -0.2535186967489731, - -0.19675319506623246, - -0.18121281218943103, - -0.19101468505420557, - -0.2935702580041241, - -0.21905218790294573, - -0.183026249761918, - -0.2918527977226828, - -0.16291709511246977, - -0.17492938083769377, - -0.29618971212346196, - -0.2360423428534321, - -0.2641648684643624, - -0.20694266603996575, - -0.22470159217355165, - -0.2707512328266898, - -0.2580520229536113, - -0.2795654726448582, - -0.226707234270897, - -0.21522808983645086, - -0.18738568556386626, - -0.17365911237556708, - -0.24165396175295345, - -0.29441103748156494, - -0.20754243722722027, - -0.20266166795053464, - -0.24844416772896194, - -0.176723457086031, - -0.23604428165854535, - -0.22338278408341172, - -0.1630491103421096, - -0.15558952339110643, - -0.17007168029384614, - -0.27752901653692535, - -0.16997050682403037, - -0.22724205513261264, - -0.21626119521094156, - -0.29762567068804857, - -0.24015047805711354, - -0.18448918864687497, - -0.27262333519195814, - -0.15701903027146352, - -0.2019106226815418, - -0.16699539940800154, - -0.25784290370826585, - -0.2561210080775735, - -0.18518064809400947, - -0.2756991252390322, - -0.25551760442420907, - -0.28088511763229296, - -0.16542439010409649, - -0.21198218715446668, - -0.2177142691814481, - -0.2802862166789981, - -0.2929209619970901, - -0.2962209441857187, - -0.17184626252170637, - -0.18015488547126202, - -0.18138567338194816, - -0.28394427959916696, - -0.20900400714946032, - -0.23031790090080972, - -0.20221581083819143, - -0.23884247275174644, - -0.17211081094079844, - -0.27408707804557586, - -0.17042373722667772, - -0.23399884492400302, - -0.25339113558230886, - -0.28904585823694445, - -0.17729893189905593, - -0.18647519435054416, - -0.21818932671844016, - -0.17637621143350404, - -0.1967302514681325, - -0.2891874755674843, - -0.24331332292644225, - -0.18090212023328564, - -0.19002651132478354, - -0.20086993827744692, - -0.2900143721155275, - -0.19143919202646978, - -0.1739312213968322, - -0.24529400477501384, - -0.17435424074695338, - -0.18610581245578128, - -0.24105553929265502, - -0.18934575434328238, - -0.18058735547998334, - -0.28436390801380285, - -0.2531617628941006, - -0.24578832943253248, - -0.19557964594556035, - -0.23983021341054328, - -0.27683525939159387, - -0.18320919904053537, - -0.2812658608517574, - -0.22607345273787766, - -0.2542201585613711, - -0.15848876765917003, - -0.23427019687089418, - -0.1889912284094718, - -0.15703526321840233, - -0.1762874377497065, - -0.20584730439606985, - -0.24172320927093727, - -0.23036213009383882, - -0.17796416901976667, - -0.27135914808031825, - -0.1946771362756378, - -0.2914367060191126, - -0.2280102194192697, - -0.16998570150319456, - -0.2518769609786485, - -0.18374921365038657, - -0.22356616499017323, - -0.2802830943934591, - -0.23891474408038355, - -0.17959631057167819, - -0.16833481112980034, - -0.245776609952894, - -0.16132934178413055, - -0.2609064106360666, - -0.2368340092983608, - -0.1787487440679128, - -0.2693868154334281, - -0.2087727350647959, - -0.28357028275124313, - -0.17363312416986368, - -0.2987998372135368, - -0.16724686491495375, - -0.25946127389033863, - -0.2136734733491549, - -0.24876971783236723, - -0.29286819157735633, - -0.1931398231236298, - -0.18975206036189426, - -0.28176528681727014, - -0.2983147633173229, - -0.1580847845564298, - -0.20833154294872275, - -0.22109480441607787, - -0.2919516404285861, - -0.23812614469686386, - -0.22289627808498724, - -0.24048036344788093, - -0.2938372220271892, - -0.16873674441012118, - -0.16578065796670907, - -0.2629564327505306, - -0.1730846878974077, - -0.16427282071564284, - -0.27493312143731163, - -0.2203989726059496, - -0.2725923095927339, - -0.19015049366933132, - -0.1578623166984013, - -0.2894980602913705, - -0.2964976284620615, - -0.22608204277594485, - -0.2720998352297286, - -0.19433234259230042, - -0.22445643392139342, - -0.16352290327286817, - -0.28614077940417637, - -0.24923216968695314, - -0.22761383168487942, - -0.18944778862077144, - -0.2043261575365241, - -0.2916804476163479, - -0.252374812643334, - -0.16058033584209666, - -0.28264889890249845, - -0.24541146732339805, - -0.2860565478602965, - -0.22612731315964854, - -0.2789252342532694, - -0.1963488777309264, - -0.16325739847667145, - -0.15682402794672484, - -0.18655395367905092, - -0.2322358761885671, - -0.17408217362932304, - -0.23401764522413418, - -0.16376542963838572, - -0.1816597566722039, - -0.2822923258505757, - -0.15826790482721378, - -0.24267822947283557, - -0.23603984243020248, - -0.28537038102488715, - -0.17001460683382932, - -0.2863970352018663, - -0.28864853260085954, - -0.24486374793134766, - -0.18457776406059861, - -0.16792791902111778, - -0.26314519321057384, - -0.15869682863861118, - -0.16295710063146449, - -0.22609208547835896, - -0.21302749189745185, - -0.17977988705459563, - -0.20189150564946615, - -0.1860543559729589, - -0.22184543005207155, - -0.1619284933897675, - -0.2168899466377976, - -0.19844690443969892, - -0.2628602301810491, - -0.18005454183223965, - -0.16524815119307268, - -0.26413326792601327, - -0.2653593609906151, - -0.27755760244999506, - -0.2806854329981446, - -0.2375669493390042, - -0.23921054874098932, - -0.1601662961665772, - -0.2539629907748288, - -0.21240585354878033, - -0.2683228225719431, - -0.2808346001867846, - -0.18618600423441903, - -0.28659405195808324, - -0.19848654762916618, - -0.24528044101550825, - -0.21237011418170523, - -0.16787577546703067, - -0.20836331606626735, - -0.22809745228503467, - -0.23167771712409413, - -0.2369628912106292, - -0.2832937321990772, - -0.2011223641090497, - -0.1734153336091827, - -0.248063874407113, - -0.1605597610930305, - -0.21010893111012496, - -0.29586335314393875, - -0.29344194560212356, - -0.26811470128846215, - -0.2799835862150989, - -0.26860890820245326, - -0.18899587818779973, - -0.17415603770666732, - -0.29761458980128286, - -0.22495527899840212, - -0.2689497604700062, - -0.2726457056608248, - -0.18667198502172552, - -0.2004573247265634, - -0.21493485630810505, - -0.19174780946210127, - -0.21437690379193652, - -0.1640140108319958, - -0.21996897168342205, - -0.1637189916362054, - -0.23571021676354878, - -0.15744271990868608, - -0.21492244270464497, - -0.23289885062903243, - -0.16976622438784397, - -0.29534131324985197, - -0.2891296130681822, - -0.218803107519001, - -0.22728297262340855, - -0.20444467910932873, - -0.22354909250745644, - -0.21712134235669245, - -0.2738088485243505, - -0.2568273033643611, - -0.27567184595306915, - -0.24842531010687527, - -0.19392806233774199, - -0.2943869537909535, - -0.26476618510406474, - -0.22276649840902824, - -0.2544136663397825, - -0.27922354992949144, - -0.20379617176852477, - -0.23751825808199806, - -0.1641315627980659, - -0.20391123724629612, - -0.24798169416660615, - -0.23313630034610297, - -0.27845540573018646, - -0.17320660859349182, - -0.19601136607110722, - -0.241431985009883, - -0.29608031619615793, - -0.16103169945392956, - -0.17212085393151597, - -0.269463902541192, - -0.2715837549593379, - -0.16537510624915702, - -0.2548359067034175, - -0.20592628823454923, - -0.18680596981867786, - -0.16392063053580525, - -0.21744058825147156, - -0.2359290636610658, - -0.23301300310031203, - -0.29261034123843355, - -0.29136532732835857, - -0.2911449343468013, - -0.27373378996514647, - -0.21147989118824229, - -0.2452596669449463, - -0.17959299762125897, - -0.2737927972126932, - -0.28146517532823834, - -0.22786547113202044, - -0.2768516433969177, - -0.17084419001225554, - -0.27799898952027285, - -0.2563155203101846, - -0.18310462750043088, - -0.24003421997768257, - -0.16351608610535487, - -0.26467466097852466, - -0.25640884225956073, - -0.21046041849788058, - -0.1908426519568816, - -0.2637444602073828, - -0.22722925535024874, - -0.17981206933673216, - -0.1904994708034364, - -0.2943137790159001, - -0.2741540680189174, - -0.2526621645045205, - -0.2779657464642563, - -0.2590081547494608, - -0.2516746539242725, - -0.266555680008303, - -0.21317092893525413, - -0.16321091247863487, - -0.17516756450434035, - -0.24473724212318348, - -0.1688142112714669, - -0.22516917557598334, - -0.276927362827408, - -0.2160473985589473, - -0.21178730443841637, - -0.2617174223045378, - -0.19316645702597007, - -0.26413890591483885, - -0.15862932212324066, - -0.28724964215613014, - -0.1635738222436822, - -0.29505862042276, - -0.1580986436824303, - -0.25075799483863426, - -0.21937307736473285, - -0.24585870947389152, - -0.20083024106189717, - -0.1807313504887853, - -0.24054313118565612, - -0.180046199805208, - -0.217224074853673, - -0.18991122381842285, - -0.1956649783238498, - -0.17586703456089914, - -0.29320321675305294, - -0.2478932620757336, - -0.23201963503686435, - -0.25298747195164734, - -0.2622390777848309, - -0.16502591360905478, - -0.1670668173592407, - -0.16719692708715997, - -0.2443059335589659, - -0.18596536149305937, - -0.17556729528999793, - -0.2762096394400966, - -0.157183031607924, - -0.25797094614371063, - -0.28190870221967357, - -0.2702414987256002, - -0.18421919203123333, - -0.2077553827183032, - -0.2418134378335353, - -0.18706656006319503, - -0.218346820517994, - -0.16031389687807512, - -0.23935683579251008, - -0.1644134178313641, - -0.2424458683503447, - -0.23845723051020237, - -0.2773793406285009, - -0.29705852845387104, - -0.15471464748635375, - -0.17513137762388398, - -0.22973770978513813, - -0.28155549101865884, - -0.2616877050440426, - -0.2066125139610795, - -0.17062753538836511, - -0.2534231150015268, - -0.24165614478971317, - -0.2957282633320616, - -0.23959591723271811, - -0.17618119737944066, - -0.2890634941395467, - -0.18586176073832597, - -0.28600206720571614, - -0.23012314166357922, - -0.23356575108139147, - -0.2921855532731104, - -0.16800589078360637, - -0.1590446431947371, - -0.23713997950353247, - -0.23638250418273246, - -0.2126036576209025, - -0.18515290379778648, - -0.2829010514797878, - -0.2953284155609896, - -0.22253789257804002, - -0.15585958100375064, - -0.2503244844992744, - -0.29802385488588967, - -0.2692254571025656, - -0.15744615202994866, - -0.24070477664354942, - -0.22097172217580419, - -0.2641842050363157, - -0.2615711156734569, - -0.28973770508188146, - -0.26362471033732976, - -0.2970132703844088, - -0.18114910695568642, - -0.28756347388012543, - -0.20041220103667523, - -0.22012560326452704, - -0.28681393148080314, - -0.2283020815657058, - -0.20822257265109578, - -0.24721145779265352, - -0.22139966744671796, - -0.27467568484006355, - -0.2963026033790749, - -0.2287586653740878, - -0.268235319237686, - -0.17064417101949333, - -0.1683219182206369, - -0.17260175286837554, - -0.1789866606227276, - -0.2212456629611024, - -0.29189840437520265, - -0.20539794960854907, - -0.2594189861992811, - -0.18604899704660255, - -0.22604308076024437, - -0.21183071193382302, - -0.2964337328069762, - -0.20032861367721078, - -0.16230480619252102, - -0.2428539759025069, - -0.26591652493566253, - -0.20019075237943867, - -0.19688670759201282, - -0.1628231556674187, - -0.1987440408355521, - -0.29833724948379786, - -0.1702173432794904, - -0.18953847284789951, - -0.15608213886337793, - -0.24841020446437465, - -0.1907926914664833, - -0.20683211002707103, - -0.24647186438660257, - -0.281210744589254, - -0.29238830755247897, - -0.20757856917526718, - -0.20968337468813314, - -0.24427745696284076, - -0.2863228643546992, - -0.25846526941256115, - -0.17687745421768827, - -0.22177823540747185, - -0.2218124458268952, - -0.23012079774320512, - -0.26580359136149884, - -0.28987824573168414, - -0.2754693165755468, - -0.23695473530164016, - -0.2737032986283498, - -0.25816429061950036, - -0.21297738274851086, - -0.1944934182240206, - -0.2295643339038133, - -0.2539208048092406, - -0.29074101527193125, - -0.27954251779880934, - -0.23486191079166882, - -0.28157783491868743, - -0.2922235548212341, - -0.2747416828607271, - -0.206524131966214, - -0.2833340115763244, - -0.2489650618740813, - -0.1652905186463871, - -0.16312642374148098, - -0.19631446778020983, - -0.25598790595846976, - -0.1589095542682768, - -0.2862072671388742, - -0.15452887986004796, - -0.18375326763013333, - -0.16462432702324772, - -0.20113350346577752, - -0.1940891916393216, - -0.2862764230664602, - -0.15795724316193394, - -0.2581262805962352, - -0.24275670337170382, - -0.2792690142849098, - -0.19595979659281115, - -0.2530816765215147, - -0.23857448393462954, - -0.28777026668154415, - -0.28964677865906957, - -0.23011297525269736, - -0.19617019541150194, - -0.2802746853019511, - -0.1637298190012136, - -0.2773080026793279, - -0.18107900132273838, - -0.26185656398952506, - -0.21260672975392236, - -0.208116566316812, - -0.2169054884041861, - -0.2550473236949125, - -0.2971528980133395, - -0.1749402561382663, - -0.18884217054461994, - -0.2536214385220338, - -0.25496763216692814, - -0.1984368214145485, - -0.21864744806719932, - -0.29874652981212996, - -0.29182606735419053, - -0.29583148084413324, - -0.2835596538430153, - -0.2269411600869889, - -0.2682216260758429, - -0.20277998347833542, - -0.296158559347545, - -0.1707874851764039, - -0.16259391773132806, - -0.2260845218492757, - -0.20506142603420163, - -0.21000838284184387, - -0.27250449461984166, - -0.15762906007301528, - -0.18273490966077793, - -0.23466987553000068, - -0.1998879434339509, - -0.2774541022801565, - -0.23789681662175235, - -0.26294959346910546, - -0.26237431376302367, - -0.17892181329892415, - -0.193968532546561, - -0.2901410560561762, - -0.20882950580868842, - -0.1760537515384596, - -0.2766656867889314, - -0.24804915687148604, - -0.15881908219481927, - -0.1853028578798265, - -0.22999631152701905, - -0.2144065461126561, - -0.29331152783559844, - -0.17940907459186908, - -0.2984863661171396, - -0.24146951920504656, - -0.28577749549806347, - -0.19945405100342806, - -0.27254242432727754, - -0.26190352011917234, - -0.2342790646425416, - -0.2667880564882266, - -0.19549788526099302, - -0.16827495826958191, - -0.16118100424229354, - -0.2618711861540247, - -0.16696320231239742, - -0.19499803378550684, - -0.28869742341881927, - -0.24298006182381005, - -0.1960726980689857, - -0.2593287436277685, - -0.24648376002601577, - -0.18024751997589172, - -0.2659372420443854, - -0.20502557043987812, - -0.24967851696954635, - -0.2859594849631587, - -0.2688280738917871, - -0.20995169312594467, - -0.1815102381618877, - -0.27976483573742816, - -0.22147667521081033, - -0.228935602531111, - -0.2328212619384521, - -0.23907264344738138, - -0.18468088464881116, - -0.20807480675310136, - -0.22549208302986562, - -0.15586347151110544, - -0.18698680190343714, - -0.237628281980655, - -0.2925627679999972, - -0.2676661207398447, - -0.20980427407026586, - -0.29370967436652984, - -0.22103533620912458, - -0.2803200827330844, - -0.21588598898645558, - -0.2037099931908252, - -0.15956665970339, - -0.1741133089483292, - -0.21967397622581358, - -0.19472336284748445, - -0.18786014196777118, - -0.28880030253510774, - -0.27055638896192497, - -0.2959214571949956, - -0.18576616660151696, - -0.279849015998232, - -0.2129256584930713, - -0.16819075472755218, - -0.27886434871673105, - -0.20383734933063552, - -0.15787353660655645, - -0.2872107307935387, - -0.15620675569085263, - -0.18273187794440998, - -0.21465664024035747, - -0.22317586683368168, - -0.21539621902518583, - -0.2605953231291759, - -0.20466362514387104, - -0.280504093199458, - -0.2551794892667101, - -0.19047473885541794, - -0.2506700192250768, - -0.28396115666860994, - -0.1766484980630214, - -0.27352179329338805, - -0.16675981856199135, - -0.18784895029601356, - -0.19995130078199091, - -0.274501279935957, - -0.2222835447910766, - -0.19770572697964883, - -0.2630720452333958, - -0.260074573478333, - -0.2653376195178805, - -0.21172144239967555, - -0.2735549794298465, - -0.24816877146155436, - -0.25427941175671875, - -0.20085528022392152, - -0.2149197639548167, - -0.24175730771504816, - -0.2848978035872134, - -0.19179477230675418, - -0.25755682001103775, - -0.251205780945615, - -0.20646211950461574, - -0.22115470552390704, - -0.2584929959666634, - -0.2063975100251368, - -0.2608987901184431, - -0.2266883470675961, - -0.1791757789136993, - -0.1781518332511936, - -0.16652889175131147, - -0.2972572534594199, - -0.25871832205509, - -0.2843837478773163, - -0.26150077984967623, - -0.18894992569927477, - -0.21345153341258535, - -0.19636767833120883, - -0.19400235336567004, - -0.18234509199544197, - -0.26643198092385106, - -0.20081866056723313, - -0.17567952437694853, - -0.18899696192878118, - -0.22694102350926906, - -0.2697498050538324, - -0.21826540994897964, - -0.23878157332246158, - -0.29822816528486923, - -0.26640190425476373, - -0.24443623401755088, - -0.17904855737441777, - -0.18534572445520014, - -0.191723778038435, - -0.23031264231727983, - -0.23830269316542535, - -0.21962337301038048, - -0.23882059627541127, - -0.22038878189451333, - -0.28656519327167324, - -0.2744915960417352, - -0.17495750328556703, - -0.26375998253858746, - -0.21051743709961493, - -0.2803719347126216, - -0.2026677001560363, - -0.2928360379110007, - -0.22217904348870032, - -0.28722047318496974, - -0.1896517788604573, - -0.23563421649491828, - -0.27088438765406, - -0.2835340428695661, - -0.21117777778679214, - -0.20043817967437172, - -0.17049527351860486, - -0.27674263654216547, - -0.15533115116871063, - -0.2531141337336552, - -0.23866591900442968, - -0.227586865292223, - -0.26872635323769084, - -0.1855218132179844, - -0.18395900460155665, - -0.1595685877569377, - -0.27149754212249055, - -0.27512185715440385, - -0.26573708032469034, - -0.22067809676273017, - -0.20861335747985849, - -0.28429608510217175, - -0.18819524874400317, - -0.21953748906889597, - -0.2652440927756281, - -0.19491202219247533, - -0.2409219642315064, - -0.22458426889674135, - -0.28169183618243726, - -0.16682070348718817, - -0.24543304093199717, - -0.17539250205149598, - -0.1548983317618587, - -0.28735835029185475, - -0.18992394801565596, - -0.2844983882109146, - -0.18223372187328518, - -0.26860632134420775, - -0.16654771041997085, - -0.24707603649834717, - -0.19627976684731563, - -0.20573871669465713, - -0.22123393334633173, - -0.2751332206436687, - -0.22855376845262007, - -0.16641321707892662, - -0.20728635126152287, - -0.17818660997427538, - -0.2700001665810981, - -0.22924370482546808, - -0.2905183181472083, - -0.2705244235479682, - -0.1713794629707514, - -0.25638438201047054, - -0.18097604840364256, - -0.16392865132938614, - -0.27563694247065373, - -0.26674003685973335, - -0.2115918336153511, - -0.1733950123625703, - -0.19196894285149357, - -0.2946062293610254, - -0.24299472362097768, - -0.1577789829285967, - -0.22564447190282055, - -0.22085682056589043, - -0.16871552030469134, - -0.2043656136468362, - -0.17420177581491678, - -0.21174887805885673, - -0.22088505229254968, - -0.16324127295339314, - -0.2860050483254116, - -0.2784176448847399, - -0.25292127637354395, - -0.2977638119362483, - -0.16253845826308833, - -0.28997051109433475, - -0.20358409577751824, - -0.19131431137033164, - -0.16873096908421187, - -0.28341891114954276, - -0.25562137882826774, - -0.16636441163289936, - -0.2362133536120075, - -0.26790735648284203, - -0.19663413866139198, - -0.220017191368229, - -0.16289284918171051, - -0.18103334106402133, - -0.29065898439433857, - -0.20428100807690297, - -0.23248721622146584, - -0.2216727217885182, - -0.1649545064474274, - -0.18598806971927892, - -0.18346748737574764, - -0.2457751945397286, - -0.20008616970697934, - -0.24634455161456936, - -0.16789688716891377, - -0.21149241135270191, - -0.270509418954598, - -0.24280921436010622, - -0.23755153247052452, - -0.2500787633472482, - -0.19611095564525832, - -0.19137830880094708, - -0.21948999646332157, - -0.2871240066479833, - -0.2562355962791679, - -0.19716749300513778, - -0.19363481607906108, - -0.1780779317682635, - -0.21012422190664798, - -0.22199924877887273, - -0.2465344708215496, - -0.29662421433406855, - -0.2722668900865061, - -0.24756869442020177, - -0.23502104297413035, - -0.18484931618214215, - -0.27900983492761555, - -0.2081804299180139, - -0.16929123817936126, - -0.26774073596165665, - -0.16285639687766862, - -0.16421458377535184, - -0.291784737629482, - -0.2363485867022783, - -0.15767730514807826, - -0.17325392935020603, - -0.28951202161623446, - -0.236643570557353, - -0.1748013966570252, - -0.229205561626264, - -0.2782920926542291, - -0.2512305375082128, - -0.28991286895718515, - -0.2459247903948331, - -0.29049317338375713, - -0.23866505599020413, - -0.18851769260521656, - -0.16988832365862302, - -0.26855170820185265, - -0.23746706438651982, - -0.24639616131685743, - -0.2671739111402751, - -0.2797764471680275, - -0.2345356570178352, - -0.22519685482708662, - -0.28857374404306235, - -0.2079019765183016, - -0.21776223331672923, - -0.2920302310142925, - -0.21689587846578218, - -0.22196318821643013, - -0.2809208237675298, - -0.25549306434457864, - -0.17684958698288666, - -0.1852887389473722, - -0.18981651366624458, - -0.1957752938265911, - -0.2692311056648166, - -0.1957334894170748, - -0.21027198177879183, - -0.154450481283206, - -0.16609774846589903, - -0.29073680247048866, - -0.2466983306614845, - -0.18174828579891156, - -0.24380624257109373, - -0.2678954031787995, - -0.2966481558732616, - -0.2629789498653186, - -0.28607374993852935, - -0.2268117526157551, - -0.21352340499911482, - -0.18528634655127602, - -0.2688749953798047, - -0.2383767154752709, - -0.23126786514065759, - -0.23305072408173377, - -0.18946313077688004, - -0.2937636175560277, - -0.21491530310942014, - -0.19606226091522838, - -0.19848629825823333, - -0.22504042708414507, - -0.2661752609417053, - -0.2507147675997562, - -0.16218601902211896, - -0.2802521747158863, - -0.22465027386215425, - -0.17858197935229214, - -0.1763878727221363, - -0.18143769043544183, - -0.17386704132412106, - -0.20067264067448165, - -0.17855757218713586, - -0.22636877039119, - -0.26005205357887473, - -0.24167228662769577, - -0.2330756252277103, - -0.286957642409853, - -0.2694405524149722, - -0.2790292524988708, - -0.20526330170211274, - -0.1777286969618031, - -0.22583951553959128, - -0.2561955216022013, - -0.2875503419209421, - -0.20923114188418068, - -0.15797389208279267, - -0.23697562268406616, - -0.2216592538198719, - -0.29104531613335066, - -0.21638542281531506, - -0.2283662106922416, - -0.23886606900659704, - -0.2119591057600717, - -0.17358264493169934, - -0.29342716124479545, - -0.1990725004090924, - -0.2699993956397127, - -0.1634032108647618, - -0.19549342991844146, - -0.29498582372076415, - -0.16226751456908198, - -0.27647054818084893, - -0.29607864940681333, - -0.21363969304766928, - -0.24493422662622596, - -0.19757043581531006, - -0.27985552273175274, - -0.2980796822388472, - -0.2186329009172883, - -0.17234728020604853, - -0.2171709969769139, - -0.19671386517359438, - -0.17216734335461858, - -0.19848403996504857, - -0.18533362966308964, - -0.19301238009264232, - -0.24465047888994018, - -0.20938761602459882, - -0.23763180185145708, - -0.2269669461539407, - -0.2846055394407672, - -0.19682339672683083, - -0.17404763766179415, - -0.17602221737966656, - -0.274831002413918, - -0.21533069057386173, - -0.16691100418227614, - -0.17886195170354216, - -0.23862918520268558, - -0.26267833866812884, - -0.19794156988041448, - -0.17091911215991418, - -0.18942618138060976, - -0.23580669716677705, - -0.15968401558024678, - -0.18786433749793596, - -0.17679448747019844, - -0.28397307354564305, - -0.21306856337785776, - -0.2532482122451402, - -0.22852579971839992, - -0.2387268278421135, - -0.19210228969535892, - -0.2833245277202519, - -0.20103633586719047, - -0.19163708429449583, - -0.2481960445795351, - -0.22653993903260117, - -0.273063590214065, - -0.15773934103185142, - -0.18033574572138175, - -0.24961070201373553, - -0.21227432038204952, - -0.20778349979639607, - -0.28266807254445325, - -0.17484265217452744, - -0.25661162254568304, - -0.19613740123391987, - -0.21791400712036005, - -0.17163169247573287, - -0.25061251573213617, - -0.26862398336387405, - -0.19123328090427183, - -0.27338332500672685, - -0.29216428867140615, - -0.19738365210946174, - -0.19890088773097336, - -0.24916643952418055, - -0.19981312222971184, - -0.2871348173238268, - -0.2746500465710294, - -0.2694200517017492, - -0.24195161321592207, - -0.24973047557481384, - -0.18159314444966534, - -0.169170180275518, - -0.15640734803205666, - -0.2611384044002388, - -0.2729186593258271, - -0.2780260285599955, - -0.16681341017144377, - -0.22034732504749177, - -0.23993495279511878, - -0.2585583313747446, - -0.22759936479519732, - -0.15563397425040393, - -0.2543890098111428, - -0.2365082128317653, - -0.20171658081866323, - -0.23324506059424638, - -0.18183595258683677, - -0.25193441549062634, - -0.18624574754158563, - -0.29651015575733325, - -0.2754494544034242, - -0.17798972042589561, - -0.2310239993738774, - -0.18792991662608116, - -0.2884344450707471, - -0.18961409670910628, - -0.17912670688270327, - -0.2695306307549618, - -0.1919054118447618, - -0.22873252475455597, - -0.22216696224980625, - -0.2322285474434013, - -0.2381962686494289, - -0.18659757650300715, - -0.18685406446187908, - -0.16632660499649055, - -0.2965869300392804, - -0.175304930085718, - -0.22067696415332938, - -0.28376458066316973, - -0.27741529860444963, - -0.2907779659665044, - -0.20716396953949814, - -0.21699831561831526, - -0.2863002245688904, - -0.267407372658206, - -0.27436951093095097, - -0.23498682998077391, - -0.2929708658314244, - -0.2680324137183877, - -0.17845982124474893, - -0.23456957955520136, - -0.26006494874698466, - -0.1751520364746808, - -0.16032870426823342, - -0.16675420183974513, - -0.23854271706209554, - -0.2424103908285697, - -0.17265590461391236, - -0.25706158664240447, - -0.27492306551394935, - -0.26084627505402225, - -0.19606714347124876, - -0.17711282863646807, - -0.22477522829839922, - -0.286033099301357, - -0.21388133750524468, - -0.2566256006760476, - -0.24448457280064462, - -0.1828661943481933, - -0.2880479952419772, - -0.16374978208912205, - -0.15741106071703162, - -0.28147937790985034, - -0.27675242797098687, - -0.2777063830439838, - -0.2432792833129352, - -0.16222419050285003, - -0.18358346086365546, - -0.2432651949410701, - -0.18378808331940705, - -0.2896501396897709, - -0.24628974193526854, - -0.2510990756519034, - -0.1711318016248657, - -0.16094659588952306, - -0.2116554886987025, - -0.1809967934014865, - -0.23341918475662882, - -0.2537897856027739, - -0.20839799160835162, - -0.22983087772972288, - -0.15443319927506988, - -0.24901234840369307, - -0.18670869152711628, - -0.21597104795385236, - -0.17257852342724928, - -0.21260042977463905, - -0.1925952001912487, - -0.22815031209105308, - -0.17218039587499054, - -0.16977721991494432, - -0.18770979118876313, - -0.23163876867333838, - -0.2698165947360169, - -0.15959797935932563, - -0.28180476481174715, - -0.28138530456585703, - -0.24075458262386365, - -0.2774993670931506, - -0.21600608160823237, - -0.25595839246260066, - -0.29205674765853185, - -0.1740633658678382, - -0.25319881603025834, - -0.2887777335397084, - -0.17887195330634245, - -0.17202985387116254, - -0.28968802105406377, - -0.17755487221042243, - -0.2583843299887278, - -0.25919066544072933, - -0.23756083442617382, - -0.21085511459416423, - -0.18109554451244497, - -0.2417061880890793, - -0.2544026386414949, - -0.2060356520904071, - -0.2641777382324544, - -0.252087872575116, - -0.18750357854303362, - -0.19076089979027128, - -0.21619739237817392, - -0.22715145762253092, - -0.17845666598891807, - -0.1917479776999727, - -0.18116311286634917, - -0.2781249626600089, - -0.15652634472671648, - -0.17462407869363522, - -0.23972849506180702, - -0.22943805734117925, - -0.1881749443029256, - -0.24556949324071883, - -0.21423448536665896, - -0.2987985850965366, - -0.2506173551362635, - -0.2510074054915423, - -0.26247746841338143, - -0.27088678723294435, - -0.288447485225916, - -0.24005711803824414, - -0.22501590231711613, - -0.15473210142910881, - -0.24502545778280366, - -0.26607525452302494 + 0.8327792199010597, + 0.842165513546451, + 0.8436336956688811, + 0.8375806986990764, + 0.8440556119926065, + 0.8316424345593194, + 0.8301736779976755, + 0.8390281513961286, + 0.8479125952111829, + 0.836974286272967, + 0.8231808736518638, + 0.8444651041225978, + 0.8563348657693687, + 0.8325071025583624, + 0.8347290462839712, + 0.8246561378691087, + 0.8515170917905176, + 0.8233723838652922, + 0.8501024368451667, + 0.8530103608075055, + 0.8410744660268898, + 0.8387762845502543, + 0.8436833143541571, + 0.837878398958661, + 0.8212752740819541, + 0.8345471132860642, + 0.8267657000272743, + 0.8478322269740088, + 0.837850787204643, + 0.820034393391647, + 0.8486164521012235, + 0.8492158952809298, + 0.8278311021250901, + 0.8393594785971319, + 0.8446434729372418, + 0.832070158532396, + 0.8480791315931384, + 0.8514673318243295, + 0.8504893651082784, + 0.8435621020400943, + 0.8225015796207323, + 0.8513620216276446, + 0.8517576058421537, + 0.840487829110072, + 0.8449043062902718, + 0.8233306505174446, + 0.8233540129789705, + 0.8569705709356759, + 0.8415728484593088, + 0.8250174407220172, + 0.8208449658562015, + 0.8414877402161995, + 0.8293556939538771, + 0.8408927523538102, + 0.8250552100711683, + 0.8418001767233182, + 0.8541731301881036, + 0.8335539435559275, + 0.8462282279199426, + 0.8277984632494545, + 0.8320094601793414, + 0.8495628428750641, + 0.8322106564323799, + 0.8226082140368741, + 0.8551709333197791, + 0.8424153445827497, + 0.8562391242122903, + 0.8493563665331109, + 0.8437902329269884, + 0.8308313231460094, + 0.8294705628038663, + 0.8547741979222903, + 0.831498845691094, + 0.8231036381325553, + 0.8352821502905443, + 0.8526164371820409, + 0.842023901363802, + 0.851278788380954, + 0.8200922087173594, + 0.8245544791841062, + 0.8472771962587229, + 0.8355238881751981, + 0.8412737119332165, + 0.8374918628601691, + 0.8423056969264816, + 0.8521412173549062, + 0.8451564194474431, + 0.8271345969651037, + 0.8239077363382353, + 0.8540771441587254, + 0.8493097463370366, + 0.8505861175538263, + 0.8262386753053781, + 0.8510964833903409, + 0.8250356139853249, + 0.8476943752484948, + 0.8201871067157416, + 0.8509067450525435, + 0.855810543985663, + 0.8364690417822097, + 0.8573082158058601, + 0.8525686739692074, + 0.8235555688374464, + 0.8354328783363192, + 0.8412566132004926, + 0.8524528080575293, + 0.840253537118215, + 0.8513871744301099, + 0.8483938636174913, + 0.8405306185080881, + 0.8210908179423076, + 0.8238690775404326, + 0.8225182712005162, + 0.848422030232458, + 0.8320177424480698, + 0.8316325154232896, + 0.825682184401799, + 0.8512751046549235, + 0.8414435280921922, + 0.8544287845947169, + 0.8494292185896131, + 0.832529883363757, + 0.8518243407421124, + 0.8490640845579615, + 0.844762764778147, + 0.8530992876505815, + 0.8512944941086587, + 0.8456051704731866, + 0.8441033963986884, + 0.8221524010940301, + 0.8340941845655443, + 0.8244285572066351, + 0.8247024778966785, + 0.8456916929441908, + 0.8483109584371334, + 0.8276817475802386, + 0.837952590336012, + 0.8200443860812293, + 0.8576205347186361, + 0.8289066003406015, + 0.8496525712777753, + 0.8450040409246046, + 0.8496674398737446, + 0.8374340819449515, + 0.8445068507339881, + 0.8376107041113094, + 0.8444902975694013, + 0.8228972347677658, + 0.8234893571372253, + 0.8336435484625643, + 0.846295918259877, + 0.8382852520294265, + 0.8473660008766075, + 0.8259195624674821, + 0.8223714767320477, + 0.8202278958883689, + 0.8405999860478615, + 0.847266699259346, + 0.8211116243568297, + 0.8523925640536769, + 0.8543744794304159, + 0.8325428132080491, + 0.8383813573925697, + 0.8274553190698549, + 0.8408068170429434, + 0.8235490098318009, + 0.8355337449756938, + 0.8484200242865865, + 0.8575809992411432, + 0.8560226311883449, + 0.8563906665995805, + 0.8472562653569814, + 0.8242537416143707, + 0.8530804425576703, + 0.84601506835703, + 0.8227296612089574, + 0.8224311932690079, + 0.845195857759586, + 0.8461131538833053, + 0.8212048892689925, + 0.8510901969041355, + 0.836935546440685, + 0.8489273504005511, + 0.8444973066370244, + 0.8223393783068419, + 0.8374220433466085, + 0.8573765569470924, + 0.8471833229459362, + 0.8250599727316987, + 0.8562361707907257, + 0.826793793224879, + 0.8569773201611217, + 0.8488078420364431, + 0.8419547170731478, + 0.8464971122569582, + 0.8493568977587999, + 0.8296800905186162, + 0.8325740344191067, + 0.8306650837175107, + 0.8298613325025934, + 0.8504230983176487, + 0.8299786925141083, + 0.8367674969974175, + 0.8260741929612028, + 0.8559372684620017, + 0.8527195440739253, + 0.8301653328027946, + 0.8547760517603271, + 0.8412249314523135, + 0.8448032476681571, + 0.8485094674526993, + 0.8278761792058, + 0.8480654791368547, + 0.8355572892436053, + 0.845511056710237, + 0.8540713274674167, + 0.8231431467661573, + 0.8380183601588906, + 0.8438527139100261, + 0.8332106236315399, + 0.8325132915041001, + 0.837256296121305, + 0.8478173752385969, + 0.849984280854329, + 0.8313433499973488, + 0.8357865861165323, + 0.8207890396142096, + 0.855409261832983, + 0.8216663491001948, + 0.8417134610748357, + 0.8360265372870216, + 0.8463604184442005, + 0.8365403606304866, + 0.8436223333420795, + 0.8458010537006937, + 0.8302413761539043, + 0.8256325894783731, + 0.8297349815932031, + 0.8564419030323089, + 0.8371531231130604, + 0.8359693576746645, + 0.8406378123427183, + 0.834765589522533, + 0.8384135147021642, + 0.8346309684771434, + 0.8527147431959028, + 0.8291614074001308, + 0.823796200104185, + 0.8267957971982753, + 0.8506483805063293, + 0.8466195726762347, + 0.8340029819794866, + 0.8459091853904225, + 0.8353878361822358, + 0.8346222092587884, + 0.8514878408702279, + 0.830186273935078, + 0.8327842265355451, + 0.8440171364107238, + 0.8360384552442401, + 0.8387506563634664, + 0.8367046792154438, + 0.8265707880121927, + 0.8487376311359695, + 0.8333917712784698, + 0.8243569177774148, + 0.8349197232629598, + 0.8358478738631235, + 0.8286284063545728, + 0.8364173240037458, + 0.851431270435986, + 0.8404209029992831, + 0.8500201200948073, + 0.8283080756946137, + 0.8574575371163948, + 0.837314725908941, + 0.8392412314206764, + 0.8376091078344146, + 0.8286533077230515, + 0.8323146995473157, + 0.8326827520030973, + 0.8281131541660445, + 0.828913020139969, + 0.8280198089043879, + 0.8541712674257933, + 0.8360258777185574, + 0.8329777331625391, + 0.8246983896979496, + 0.8545192076413715, + 0.8532942528818377, + 0.8456520733223043, + 0.8243752740176801, + 0.836274310405278, + 0.8493159622834172, + 0.8381945710851636, + 0.8514614827363006, + 0.8370820538010211, + 0.8560781205707473, + 0.8372980477525578, + 0.8343141280348665, + 0.8530544111321884, + 0.829182095992117, + 0.8507546661835804, + 0.8427025862086772, + 0.8340124482496379, + 0.8311759212699006, + 0.8556517896580198, + 0.8429815756559071, + 0.8394775874150803, + 0.8382967137561828, + 0.8247819408443607, + 0.853320394016968, + 0.8326988400660391, + 0.8333935370470561, + 0.8328601285856772, + 0.8275328751803093, + 0.8337898897097242, + 0.8220707017506212, + 0.827788859350335, + 0.8420141714310637, + 0.8280906407298795, + 0.8425139321063823, + 0.8497755661891426, + 0.8501992270988545, + 0.8407347400160364, + 0.8404098314880682, + 0.8515783742385603, + 0.8206040032673009, + 0.8272662438274407, + 0.8415774894149713, + 0.833937339034836, + 0.8402171518095916, + 0.8518245971089855, + 0.8219735284050381, + 0.8364700990428275, + 0.8367838248436407, + 0.8259883750494282, + 0.8573789503502598, + 0.8403657568588738, + 0.840881056255322, + 0.8556437506610051, + 0.8353654167557081, + 0.8453307518343753, + 0.8534531653136812, + 0.8481280564673529, + 0.8299803506751042, + 0.8407686111686701, + 0.8419470206846535, + 0.8557346617667513, + 0.8349862269978245, + 0.8538515966399336, + 0.8455224674208248, + 0.8375365067820918, + 0.843148823769496, + 0.85634409666153, + 0.8563073280237261, + 0.8478589451248195, + 0.8305227054203539, + 0.847642890442281, + 0.8287455298817924, + 0.8352244337373693, + 0.8524019829142435, + 0.8305969606862357, + 0.856688386947487, + 0.8572211942335836, + 0.8438808381861409, + 0.8511669191645148, + 0.8524485824457423, + 0.8488246463403564, + 0.8507026389626556, + 0.8555004136920078, + 0.8331510404868687, + 0.8369888819223278, + 0.8403240207237838, + 0.8545324178701628, + 0.8350237079710456, + 0.8452673777749645, + 0.8331380926632437, + 0.8234329104608294, + 0.8377228782792061, + 0.8242393532057031, + 0.8278542549465968, + 0.8416032049645185, + 0.8382225881425928, + 0.8507378255585987, + 0.8542707835510063, + 0.8475087825807386, + 0.8576488275393757, + 0.8461582528115847, + 0.8299240347876391, + 0.8355084774159297, + 0.8206531799174017, + 0.8249012411241602, + 0.8469144246337297, + 0.8556898547976901, + 0.8551066392955863, + 0.8408253372240796, + 0.8211269346540238, + 0.8373887772603145, + 0.8331816660293632, + 0.8450959371083563, + 0.8352877027626864, + 0.8501911451785606, + 0.8268356562062746, + 0.8263714092392479, + 0.8353006905298618, + 0.8527676238608929, + 0.8340090278042395, + 0.8321633312203979, + 0.8463779224444841, + 0.8528629423620453, + 0.8271916592733703, + 0.8496795561882593, + 0.8507186978455973, + 0.8463742270789189, + 0.8417040682838087, + 0.8518766832531273, + 0.8271523785837234, + 0.8478865469690274, + 0.8256370552811243, + 0.8573480647368588, + 0.8468810179950597, + 0.8432829944224447, + 0.8457901903475185, + 0.8268362047121826, + 0.8344724254357133, + 0.8449004017387942, + 0.8542788632593161, + 0.8201921669251103, + 0.822326124392429, + 0.8510179798388245, + 0.8540956705371011, + 0.8447813614129562, + 0.8315154122036016, + 0.8295365657743721, + 0.8573187879889846, + 0.830837209033064, + 0.8514783863274668, + 0.8441033291118173, + 0.8379098569922048, + 0.8418854231627948, + 0.8485055615275912, + 0.8538665307065083, + 0.8414201763485724, + 0.8289784211192692, + 0.826361534105745, + 0.8254828419350343, + 0.8361543653788232, + 0.8377685501279716, + 0.8552837918546035, + 0.8530909243374034, + 0.8541534263488518, + 0.8371783783515303, + 0.8492434587603874, + 0.8342020277182821, + 0.8475542654527162, + 0.8414777834532248, + 0.8301313365603281, + 0.8203299861655624, + 0.8223176976057828, + 0.8435414731870217, + 0.8394061029338394, + 0.8478111816916145, + 0.8411344365139194, + 0.8504902587713412, + 0.8501000493171106, + 0.8228629027717467, + 0.8263725003753212, + 0.8544325659886033, + 0.8534777854650987, + 0.8363842272236723, + 0.8219464018810463, + 0.8231582139757092, + 0.8397602063069305, + 0.8226850201900179, + 0.8455995588256067, + 0.8440036233612924, + 0.849532345175299, + 0.8543418994025157, + 0.834662608336817, + 0.8396327549752536, + 0.8371745989199674, + 0.8477135851362451, + 0.8487662984356128, + 0.8456251699068852, + 0.8522810214133225, + 0.8338053209704176, + 0.8515386154432695, + 0.8506938177413894, + 0.8413671229039024, + 0.8348291652609059, + 0.8501143354462227, + 0.8447432588942643, + 0.8467752170401025, + 0.8308691684085912, + 0.8338736747576282, + 0.8529145927104944, + 0.8565049352191231, + 0.828623144091728, + 0.8262200046153966, + 0.8485875032796831, + 0.8530454762153853, + 0.8248877980785648, + 0.8262079480595821, + 0.8553145484133124, + 0.8219014843901631, + 0.8442047196526562, + 0.8564350303372319, + 0.8479440977271664, + 0.8551161361986355, + 0.8244907438299929, + 0.8489481681589415, + 0.852346139419085, + 0.8245201922210769, + 0.8294542031416957, + 0.8269681522829435, + 0.826893669656617, + 0.8388335952617951, + 0.8344785723157107, + 0.8226897235293169, + 0.8441846300811521, + 0.8568839528876675, + 0.8318610075950574, + 0.8293401563649958, + 0.8535512093344743, + 0.8356986440333407, + 0.8511005541646102, + 0.8373114456341729, + 0.8520855224705249, + 0.8353742680666588, + 0.8368962789738018, + 0.8459315812191177, + 0.8420982541345665, + 0.8422672542142747, + 0.8254563102688319, + 0.8440577934094093, + 0.8275820163377591, + 0.8559854783094765, + 0.8329739416388575, + 0.8425142419056451, + 0.8494322806404306, + 0.8408898636249027, + 0.8263064560440464, + 0.8442265904667396, + 0.8225943648647841, + 0.8496668439910784, + 0.844065001497163, + 0.8461501048782966, + 0.8254608572385487, + 0.847301478322485, + 0.8545954692805761, + 0.848940452053928, + 0.8530400477771846, + 0.8436972863683602, + 0.8281932141506183, + 0.8475784701901155, + 0.8310361712108648, + 0.835441653182416, + 0.8278400379303277, + 0.8311239902033704, + 0.8247705581628516, + 0.8477409884046685, + 0.8401082514780275, + 0.8392935343203092, + 0.8268252408374341, + 0.8389288540754637, + 0.8344130769511651, + 0.8394815618737828, + 0.8278150261438111, + 0.8315816946553873, + 0.8518797610175314, + 0.8243000054891796, + 0.8236442232608963, + 0.8358069678652574, + 0.8329925395092904, + 0.845546201399697, + 0.8386073337428397, + 0.8326591671801518, + 0.8541416494971209, + 0.8389197385518168, + 0.8206349416576809, + 0.8285396406550667, + 0.8222906710877075, + 0.8335660569932882, + 0.828163408922224, + 0.8345541204712754, + 0.8213169029283776, + 0.8434401963376581, + 0.8535953660650746, + 0.8416372330765867, + 0.8265623395103339, + 0.8486336013784641, + 0.8416602314653064, + 0.850426914472643, + 0.8518381923613169, + 0.8298104512883826, + 0.822535368641852, + 0.8248701238260381, + 0.8293535718365893, + 0.8369114510253264, + 0.8536890304072213, + 0.8249104719244704, + 0.8455077361736493, + 0.8340661453893226, + 0.8489165852854462, + 0.8233474030204142, + 0.8317601772815473, + 0.8303321811074995, + 0.8473577591609022, + 0.8231884419757883, + 0.85037869394875, + 0.850822168295755, + 0.8266711451099213, + 0.8388037096597897, + 0.8265639892277005, + 0.8544192231046773, + 0.8545091895232584, + 0.8440126908952026, + 0.8560416353284271, + 0.8241359058361105, + 0.8469534089881693, + 0.8429282823731385, + 0.8380350065377995, + 0.8392691389360817, + 0.8421128255674114, + 0.8254749148753976, + 0.8545499738670825, + 0.8232228957189398, + 0.8393338267767632, + 0.8468873522423845, + 0.8542269809607809, + 0.8332227981474107, + 0.8350831404176999, + 0.8376912387978102, + 0.8514811077979703, + 0.8379357344848892, + 0.8241178760193191, + 0.8254538703464217, + 0.8222422329016229, + 0.8376068470618123, + 0.8255244115233975, + 0.8242379875395547, + 0.8201788154602228, + 0.8451628560207388, + 0.8328942106513563, + 0.8532173334086768, + 0.8426117459490775, + 0.8351045832810488, + 0.8364583148332783, + 0.8299283095881224, + 0.8291930283922937, + 0.8223252060990303, + 0.8209506072897172, + 0.8433503721151837, + 0.8374974392874758, + 0.8269793054419988, + 0.82718445694594, + 0.831259042025343, + 0.8538421201002043, + 0.8447910275281477, + 0.8300192617754871, + 0.8486782046005873, + 0.8221033869256181, + 0.8205093641780216, + 0.8477729581761964, + 0.828564125383811, + 0.8331238142668844, + 0.8496273778075072, + 0.8575034163379485, + 0.8501632791130984, + 0.833443662927811, + 0.8266480525572595, + 0.850495495140187, + 0.8254664952466179, + 0.8454944094627443, + 0.849412058521563, + 0.8464043632358788, + 0.8360101674882451, + 0.8459368002951497, + 0.8203722189009666, + 0.8479069117576504, + 0.857031574951588, + 0.8482123221074668, + 0.8422184137093099, + 0.8305136518099642, + 0.8337983164088084, + 0.8357081174094458, + 0.8575583893655497, + 0.8204989645901692, + 0.8293936197103932, + 0.826335047674606, + 0.8455714385336033, + 0.8504385336748003, + 0.8271097941793039, + 0.8283629872569437, + 0.8464988795817782, + 0.825838686481245, + 0.8392367769545064, + 0.848609056445434, + 0.8352778052958135, + 0.8422597373049574, + 0.8453146328173198, + 0.8239288750968636, + 0.8461882746482341, + 0.853981742655983, + 0.8507482815520401, + 0.8486683689193341, + 0.8256167166211379, + 0.8571063259475891, + 0.8520036591632791, + 0.8447818989996827, + 0.8270167106520838, + 0.8513295729525726, + 0.8258308604065727, + 0.8465367615471642, + 0.8416562201871196, + 0.8298366454229371, + 0.8201957414093577, + 0.8564239552195679, + 0.8306759641690279, + 0.832688592176159, + 0.8514279465468626, + 0.8203870954956829, + 0.8416661464586523, + 0.8427819343915549, + 0.8413041389266143, + 0.8276366767493613, + 0.84538174541406, + 0.8454999522868257, + 0.8300591695312738, + 0.8216514934769513, + 0.8213577116622994, + 0.8528579480753175, + 0.8391061099105118, + 0.8433055992412916, + 0.834640312537545, + 0.8485198637163927, + 0.8202541669829904, + 0.8373070763750062, + 0.8217321207442609, + 0.8396668665988446, + 0.83345647929676, + 0.8256235766998898, + 0.8281655341663094, + 0.828144215923423, + 0.8423943663088496, + 0.8340174618074554, + 0.8278835114990782, + 0.8309695751398167, + 0.8252306593806458, + 0.8390177798516019, + 0.8234313381641675, + 0.8344730310599267, + 0.8411428380158416, + 0.8307365566257662, + 0.8374912517601126, + 0.8279541172730284, + 0.8209617959608793, + 0.8345337032373988, + 0.8251061716515639, + 0.8398490069456074, + 0.8333274461744509, + 0.8330150833017103, + 0.8418573504199955, + 0.820488869246317, + 0.8214255927122351, + 0.8397636037922744, + 0.8331429469843882, + 0.8385238764374346, + 0.8233028533004584, + 0.8203664715297204, + 0.8257543834619913, + 0.8207367973956945, + 0.8429645266197286, + 0.8359118395712779, + 0.8367125631678021, + 0.8399222223753195, + 0.8396609671344817, + 0.8388569173031686, + 0.8411920398538624, + 0.826335937818682, + 0.8408901802374393, + 0.827526196594845, + 0.834128842580507, + 0.8366758791261285, + 0.833417594220333, + 0.8295461513225217, + 0.8217190521539469, + 0.835015783845235, + 0.8280337130147924, + 0.8408311786862923, + 0.8376272337971202, + 0.8313909658925093, + 0.8277482093850574, + 0.8424109183610122, + 0.8250199101264317, + 0.8266525703962393, + 0.8218634173769775, + 0.8338153053179229, + 0.8364867838423445, + 0.8375526831980726, + 0.8406857824501057, + 0.8310688232203179, + 0.8218519478398939, + 0.8344759727619272, + 0.8363232328527964, + 0.8387601925403404, + 0.8404525432241888, + 0.8289229210204411, + 0.8279127849513137, + 0.8260870895305779, + 0.8316879337652326, + 0.8385301112915671, + 0.8303698164484973, + 0.8284706758493533, + 0.8243750941297372, + 0.84061846673062, + 0.8369763338339121, + 0.8338042114643794, + 0.8408484498210772, + 0.8345634425736469, + 0.8336056135837595, + 0.823497060862309, + 0.8316951449657002, + 0.8249135237762101, + 0.8390947229876918, + 0.8384337971958206, + 0.837958984805766, + 0.8406690238974809, + 0.8225198694823469, + 0.8259065540061471, + 0.8295678251136468, + 0.8345728092787262, + 0.8283746789215236, + 0.8413395477882557, + 0.8240474042073929, + 0.8424507402122674, + 0.8299971819634043, + 0.8398222643286954, + 0.8314236650138851, + 0.8264866310940773, + 0.8409068251960432, + 0.8204733552486908, + 0.8299645343753971, + 0.8267881338916837, + 0.8234701704595954, + 0.8426745049751128, + 0.8257484462965073, + 0.8215312407094463, + 0.839690227203571, + 0.8230934267996654, + 0.8404125693683662, + 0.8313110592932041, + 0.8326949744506025, + 0.841691526504661, + 0.8388400741323953, + 0.838945831000366, + 0.835441272563023, + 0.8350014149074889, + 0.8324816650120073, + 0.820260715488867, + 0.8365913042350249, + 0.8360516171459611, + 0.8256851806826327, + 0.8337329218150181, + 0.8362884647236994, + 0.8234620108852162, + 0.8300074112794722, + 0.8242547953854634, + 0.8346752142842829, + 0.8402955051131922, + 0.8417871874030352, + 0.8307211550319995, + 0.8331270503181285, + 0.8290162483940273, + 0.833268715185625, + 0.8254641737040838, + 0.8258524697070906, + 0.8406243551939547, + 0.8410225854734398, + 0.8203234751345101, + 0.8397065681072124, + 0.8214324478072628, + 0.8260094994348787, + 0.8439474022332479, + 0.8412262382284419, + 0.8201635528672605, + 0.8405041939145063, + 0.8412190319711038, + 0.8286993130580677, + 0.8236608298457736, + 0.8269940845973918, + 0.8210552929131261, + 0.8234099864618273, + 0.8403993140543524, + 0.8235184331989595, + 0.8358147558395421, + 0.8327610240705039, + 0.8437205098607792, + 0.8334482108837709, + 0.8306511575615089, + 0.8218458610015935, + 0.8207943003631795, + 0.8311075327393236, + 0.8320145535606343, + 0.8258901423516022, + 0.8282167585536525, + 0.8420392844014327, + 0.8311675974540675, + 0.830039433125957, + 0.8283894752236285, + 0.8386124413619115, + 0.8291775627173377, + 0.825072425797893, + 0.8298862693754818, + 0.8412757443925303, + 0.842836516335511, + 0.8421672819789703, + 0.8419668129500006, + 0.8284434137750312, + 0.8350819329106152, + 0.8296015328403168, + 0.8381173595971488, + 0.8239284540287359, + 0.8426712736838663, + 0.838457709442622, + 0.8276563011859063, + 0.8371300792125157, + 0.831973723145571, + 0.8349880043006047, + 0.8349216081422545, + 0.8282986607240702, + 0.827686889011057, + 0.8256522793613469, + 0.8341154944650002, + 0.8414775608759443, + 0.8281603127127278, + 0.8354300957540152, + 0.820311295696552, + 0.8279085546952006, + 0.8213224921641612, + 0.8280029895729057, + 0.83406082573596, + 0.839224945957998, + 0.8298854532327744, + 0.8322469093428858, + 0.822496624693834, + 0.8300510597322929, + 0.8253238990763798, + 0.824241842900498, + 0.8255835597494054, + 0.8225448297884371, + 0.841460268065877, + 0.8373444612873422, + 0.8425132105644692, + 0.8339695673323875, + 0.8411167998077578, + 0.8364949861181995, + 0.8268820330317806, + 0.8335426657792481, + 0.8308852566349599, + 0.8385840538584498, + 0.8263722897988987, + 0.8255574040113182, + 0.8272324972531483, + 0.8325029035642711, + 0.8297813016612221, + 0.8338498729958582, + 0.8299087274488284, + 0.8437749867038556, + 0.8286284088186597, + 0.829043193004968, + 0.8360659817517385, + 0.8343760965040711, + 0.8413410306533008, + 0.8334869088684066, + 0.8384728483912189, + 0.840955691927196, + 0.8311020681044271, + 0.8205232369375192, + 0.8247978883023992, + 0.8304229140222193, + 0.829390242928918, + 0.8358607538312985, + 0.8203164501028822, + 0.8421009462020761, + 0.8203964590080646, + 0.8264045795682747, + 0.8290574299422677, + 0.8404442968910519, + 0.8222409804271585, + 0.8228321249444656, + 0.8268454173676001, + 0.8271458681000243, + 0.8339171847715888, + 0.8419351474086726, + 0.8300147059150268, + 0.8251195646013754, + 0.8242047797829075, + 0.8308213404135617, + 0.8352408640702416, + 0.8425650771088161, + 0.8208327648639644, + 0.83062023390406, + 0.8213794884908783, + 0.8202615018884869, + 0.8252181002172879, + 0.8420108313905698, + 0.8329121624466912, + 0.8348334977053828, + -0.6746141840785174, + -0.6886284765161518, + -0.6601040188768568, + -0.6655967348076679, + -0.6940409469739117, + -0.687455710582586, + -0.6745841574310276, + -0.6802424913903562, + -0.6788869778572966, + -0.6719371602015586, + -0.6699791544149387, + -0.6908070117658702, + -0.6930627788224111, + -0.6920528352604609, + -0.6613786416956481, + -0.6692206710409371, + -0.6942914952825258, + -0.6898026180708242, + -0.6791365734568852, + -0.6899642191497567, + -0.6715804410083333, + -0.6812903981860591, + -0.674591683548175, + -0.6972110935112932, + -0.683945085735822, + -0.6762502934078075, + -0.6973058956481382, + -0.6741865540931916, + -0.6860077587034613, + -0.6819701566948445, + -0.6667340495592315, + -0.6711914399502821, + -0.663710094676848, + -0.6955342294800742, + -0.6659717206277096, + -0.6876458889121088, + -0.6829550093007313, + -0.6960715771874232, + -0.6775303726150119, + -0.678368637165803, + -0.6932966334474095, + -0.6917399952013681, + -0.6864093778496579, + -0.6914893690122369, + -0.6977401662042911, + -0.6787370440849035, + -0.6888429902281146, + -0.6930263238837162, + -0.6672854406335794, + -0.6951963831888156, + -0.6694261112593567, + -0.6715003266575331, + -0.6873968971651537, + -0.6942096850416324, + -0.6937378424149452, + -0.6617493169902309, + -0.6754594657213264, + -0.6780017039243544, + -0.6747329556340319, + -0.6683002001522719, + -0.6651501711312592, + -0.6928774315932067, + -0.6703526712758717, + -0.6755407982273284, + -0.6708668912250719, + -0.6827522128150574, + -0.6667795747534927, + -0.6678491471767756, + -0.6962228836774962, + -0.6681336983404802, + -0.6670646368761041, + -0.6869537098598495, + -0.6735327896917102, + -0.6749161042536174, + -0.6607609925144794, + -0.6824391043422964, + -0.6814727636691921, + -0.6939686217301894, + -0.6934855029415801, + -0.6959686148640771, + -0.6732482009704546, + -0.6801764811788376, + -0.6663226957138189, + -0.6802820481779657, + -0.6653978592492075, + -0.6953870917152366, + -0.6759398443040056, + -0.6945392966875719, + -0.6949581526205741, + -0.6708794955173274, + -0.6730907250607087, + -0.6667113716499671, + -0.6713415550773809, + -0.6960388414938202, + -0.6640126052842721, + -0.6906810808505668, + -0.6798644003274743, + -0.6887513251705029, + -0.6952192099010965, + -0.6609861597647275, + -0.6864347920726361, + -0.6778850938651649, + -0.678253581972582, + -0.6892106710289049, + -0.6971311569796488, + -0.6656448031257765, + -0.694563259057485, + -0.6952098359062748, + -0.6948857728076272, + -0.6911667726852665, + -0.6622860682756938, + -0.6937249590455887, + -0.6700966937930312, + -0.665298358170495, + -0.6813846562562297, + -0.66144504711305, + -0.6632451455814717, + -0.6673705666927828, + -0.6947589631921681, + -0.6930855218100677, + -0.683585632695927, + -0.6772942311350535, + -0.6650686494049545, + -0.6739474884455319, + -0.6840132497431871, + -0.690031146752834, + -0.6669212180006778, + -0.6934592790849192, + -0.6652779914567487, + -0.6941656426276396, + -0.6688316606277314, + -0.6607716232467629, + -0.6894880164489943, + -0.6646797943780495, + -0.670760786003949, + -0.6858583181097863, + -0.6974211678267301, + -0.6760562367738313, + -0.6933939815112516, + -0.697581141837333, + -0.6887615133432778, + -0.6600069225816003, + -0.663923953099917, + -0.6704867607310226, + -0.6970625917876369, + -0.670772565767838, + -0.6607231354214145, + -0.6921814946230959, + -0.66793551537241, + -0.6654112221346467, + -0.6726985358797045, + -0.6687532036080519, + -0.6699503930002195, + -0.6634026389435991, + -0.6819784578105069, + -0.691326938462314, + -0.682732086699986, + -0.6700805533580487, + -0.6888021111618905, + -0.6748813927069008, + -0.6829504808560811, + -0.6951221306688757, + -0.6957729202986209, + -0.6712416695390037, + -0.6790242840366107, + -0.6736547929288142, + -0.6966711585093713, + -0.6933624338616954, + -0.6820460816255794, + -0.6652339559274938, + -0.677344350041237, + -0.6764599422983517, + -0.667608598461279, + -0.6668326318614972, + -0.6824601636498356, + -0.6783781235486522, + -0.6900296408450133, + -0.6930484758719688, + -0.6777421068380083, + -0.6668064338032343, + -0.6816281379919223, + -0.6965114695725022, + -0.6725418738033794, + -0.6616198503155789, + -0.6923671231549478, + -0.6762229005550496, + -0.6613827231074759, + -0.6660288937383735, + -0.683246446506367, + -0.6767804109831066, + -0.6977257421066394, + -0.6668256810138676, + -0.6689043736986101, + -0.6738656984864401, + -0.6641466587165921, + -0.6614201709461075, + -0.6807273301173363, + -0.6737070190222737, + -0.6814187871451918, + -0.6790739511156232, + -0.6777392982896252, + -0.6885633914579151, + -0.6946670881492347, + -0.6814411332622994, + -0.6952166563661799, + -0.6770274856921616, + -0.6885669516772127, + -0.6944584701738877, + -0.6659285140876098, + -0.6946296561877678, + -0.6694683472293828, + -0.6957724301121598, + -0.6933042340458916, + -0.6662246306548055, + -0.6933320635778694, + -0.6851745901220025, + -0.6851008516738358, + -0.6664773613105298, + -0.6889140745342193, + -0.6619753816748079, + -0.6844776420978537, + -0.6820975752364891, + -0.6853234386749736, + -0.6941313730669997, + -0.6666404813153626, + -0.6771601991413763, + -0.6907557133346961, + -0.6816598944248002, + -0.6725414181155871, + -0.6753715993655398, + -0.6753588067653471, + -0.686363042566137, + -0.6692428542343192, + -0.6673577696239847, + -0.6815819848529493, + -0.6843322284898764, + -0.6955484649810205, + -0.6611740114732744, + -0.6697971615331532, + -0.6686201988492472, + -0.6715785703430595, + -0.6619378300060514, + -0.6800727705492728, + -0.6610395491170569, + -0.683022201263447, + -0.6910534430997515, + -0.6947971116226088, + -0.6693475777179481, + -0.6825558239092868, + -0.6704474739784368, + -0.6807515204691592, + -0.6932702843455287, + -0.6862270644643407, + -0.6826705798708743, + -0.6911769569962792, + -0.6649239653096749, + -0.6675965457497756, + -0.6692675011724754, + -0.6795311260172137, + -0.6903068658536712, + -0.6782632556885907, + -0.6789022256242505, + -0.6919469409684276, + -0.6975792298339692, + -0.6787719366861165, + -0.6803267400976987, + -0.6895497052956906, + -0.6697803922099581, + -0.6802284970819463, + -0.6713286445393906, + -0.661542921979802, + -0.6721423809671493, + -0.6715952835941091, + -0.6606422824527411, + -0.681086503680562, + -0.6809674575087514, + -0.668132615011977, + -0.6725826088559591, + -0.6691576234048412, + -0.6964313122792681, + -0.671561501757517, + -0.6839006519665206, + -0.6672648702484053, + -0.6956961594746738, + -0.6914054559209156, + -0.675598256812254, + -0.6761303623245282, + -0.6649259307273713, + -0.6622675330094479, + -0.6825825922218365, + -0.6620365690877199, + -0.6754453006110023, + -0.6629611575447288, + -0.6906087288733064, + -0.6929299442865553, + -0.6795212377294962, + -0.6734584657805814, + -0.6957309166094032, + -0.6941780914640323, + -0.6810208380025617, + -0.6635121058639575, + -0.678575337056153, + -0.6849556292128414, + -0.6685061988289451, + -0.6708898447178794, + -0.6623101669062174, + -0.6603842641863717, + -0.6912105355625384, + -0.6642963125385545, + -0.6920701816067335, + -0.6638275786918244, + -0.6621570598730788, + -0.6965554701977301, + -0.6621366257161929, + -0.6773069803872079, + -0.6713947605745646, + -0.6638094923585318, + -0.6953156502459316, + -0.6946292293181813, + -0.6926457786525416, + -0.6837948677251265, + -0.6836342473171184, + -0.6664274577915912, + -0.6675997143653187, + -0.6854268497267045, + -0.6819101821298482, + -0.6654142347055736, + -0.6624069109656958, + -0.6971332742505527, + -0.6793531990989536, + -0.6930574787170009, + -0.6842272122392853, + -0.6866122088473987, + -0.6601214779469657, + -0.6788431266838921, + -0.6807493636356386, + -0.6772510599851753, + -0.6670054547463979, + -0.6647846718033822, + -0.6742356010200281, + -0.6761561525793798, + -0.6907887971386057, + -0.6879072400453848, + -0.6627368837672113, + -0.6862344087647868, + -0.6719191074186022, + -0.6733913574131228, + -0.6878054702640402, + -0.6610240860754436, + -0.6754944012153229, + -0.6813467800807157, + -0.685192613144929, + -0.6869348894818763, + -0.6708838335721231, + -0.696041650664229, + -0.6903872900345278, + -0.6795416480443517, + -0.6831301719275387, + -0.6822391249246678, + -0.6977063564904373, + -0.68696011316178, + -0.6602418778884843, + -0.6758956558490061, + -0.6621982462511796, + -0.6752588922290702, + -0.6691199693575786, + -0.6626592933842332, + -0.6933649102836178, + -0.6839984763903686, + -0.6754760538164711, + -0.6710543820853578, + -0.6741162409048135, + -0.6785339335453852, + -0.6634411906372406, + -0.6747870211877897, + -0.6845907304903196, + -0.6951478152868003, + -0.6807633520786521, + -0.683463227651484, + -0.6688857339812069, + -0.6676197635664105, + -0.6852240841214505, + -0.6945284822136585, + -0.6933375688804698, + -0.6604520834576711, + -0.6667821100751983, + -0.69479002224664, + -0.6664465025841261, + -0.6859813537064171, + -0.6956525297910844, + -0.669752994698008, + -0.6761195891152739, + -0.6905058407689199, + -0.6887493354798598, + -0.6768133761896861, + -0.6904502304704636, + -0.6878943439604596, + -0.6800099668244156, + -0.6972171482399235, + -0.6727137333072158, + -0.6601472122738065, + -0.660249325345894, + -0.6722134694452813, + -0.6653713441706426, + -0.6697240275195547, + -0.6659848524433125, + -0.6733428836419079, + -0.6743824484684026, + -0.6836778731244544, + -0.6617475439708467, + -0.6883397983860362, + -0.671940351636465, + -0.679769445052373, + -0.6764666963726652, + -0.6817960285379824, + -0.6963406627558634, + -0.6864595129484394, + -0.6661140540521318, + -0.6600362696923529, + -0.6908275271901851, + -0.6887856655886246, + -0.6603758816813177, + -0.6918215724431288, + -0.6844975326130331, + -0.6603461296233962, + -0.6766294718437241, + -0.6684390880771633, + -0.6743845995477578, + -0.6974341118120094, + -0.6954564616238984, + -0.6783526080899775, + -0.6762087583444282, + -0.6747526284975439, + -0.6947920292971516, + -0.6910100211457635, + -0.6888423277062988, + -0.6602724862543715, + -0.6609333740732911, + -0.6935898415780253, + -0.6829184421340371, + -0.6883963214704134, + -0.6888769194822435, + -0.6732894892885142, + -0.6828596698063102, + -0.6644884041859759, + -0.6852535616833239, + -0.6744848518137354, + -0.6873026588341064, + -0.6883579398896497, + -0.6802240188477496, + -0.6970741312231162, + -0.6880300780236311, + -0.688552569049997, + -0.661626536729126, + -0.6787633640995725, + -0.695510576520576, + -0.6651090243441025, + -0.6752980939362537, + -0.6647891146010826, + -0.6913832360519615, + -0.6655759068266525, + -0.6639875283844118, + -0.6813761431997847, + -0.6820909975409589, + -0.6847637871348109, + -0.6651087378988025, + -0.6862356409060374, + -0.6718306268634103, + -0.6905912890122553, + -0.6941922277033447, + -0.6888709416104346, + -0.6733367153466117, + -0.6825986756718786, + -0.6970634007583321, + -0.6816588218774726, + -0.6686995531136737, + -0.6853314852253869, + -0.6895677346532545, + -0.688350924823682, + -0.6806328752108978, + -0.6966626623408988, + -0.6775906902067996, + -0.6644980844404059, + -0.6684409343848937, + -0.6947698611696231, + -0.6908816080086646, + -0.6776951249001967, + -0.666364873444987, + -0.6816272729110479, + -0.6641777899346701, + -0.6868490926653473, + -0.6624768589609384, + -0.6736743765025385, + -0.6932647658735291, + -0.6719444060631047, + -0.6809871438903407, + -0.6763549666302989, + -0.6889813684215885, + -0.6845573831203583, + -0.6958444033531709, + -0.6692296940606933, + -0.6625232600331735, + -0.6623611206674921, + -0.6878204228735931, + -0.6869339586779344, + -0.6958788889250089, + -0.6897351845493644, + -0.678504924546521, + -0.6626662046885975, + -0.6844330108257274, + -0.6649357885016501, + -0.6645257980386753, + -0.6903893042670357, + -0.696191034505454, + -0.6976482411335778, + -0.6763717307867539, + -0.6891929704171622, + -0.6732414490513808, + -0.682936501277053, + -0.6652547068675356, + -0.689624855653104, + -0.6656552904604697, + -0.6699937343396408, + -0.6646656963012861, + -0.6838269807953417, + -0.6892510924545528, + -0.6942689656104019, + -0.665335397503783, + -0.6927003712264327, + -0.6605484999333536, + -0.6636130118941415, + -0.672383200104287, + -0.664294927401748, + -0.6760564644537552, + -0.6795078674625501, + -0.6809274571763406, + -0.661784496247274, + -0.6754102951815901, + -0.6908137737782103, + -0.6638941879513804, + -0.6622239371990131, + -0.6954314617042157, + -0.6633761339245652, + -0.6858118030451135, + -0.6948745809619966, + -0.6949805433491383, + -0.6857023852694862, + -0.6862450407016696, + -0.6942938737861815, + -0.66461334520863, + -0.6697463781645258, + -0.668068528227637, + -0.6795183422747151, + -0.6744814676780488, + -0.6829616235627527, + -0.687309237802271, + -0.6849899065456878, + -0.6836624271084395, + -0.6745587191361917, + -0.6658444017672613, + -0.6810493281926067, + -0.6799830577750451, + -0.6813081088870694, + -0.6840167630780499, + -0.6625601857884025, + -0.6814702977218634, + -0.6816239516152831, + -0.6786264186540882, + -0.6754693943678026, + -0.6895112702757065, + -0.6733713571492133, + -0.6689016865905588, + -0.6800297515290823, + -0.6710604278257589, + -0.6684504912085033, + -0.6701171185277435, + -0.6619591799905795, + -0.6825874927841656, + -0.6735858980255431, + -0.6644335346788923, + -0.6603918374273736, + -0.6964703399864449, + -0.6947222059891012, + -0.6781182709092023, + -0.6946082843105266, + -0.6855714109165199, + -0.6850442966636229, + -0.6748307566090712, + -0.6754149349158436, + -0.6757658449348143, + -0.6905031829496779, + -0.6913187561945626, + -0.6602547232747428, + -0.6872273250814173, + -0.6700107301301448, + -0.695400733546086, + -0.6867866623609156, + -0.664112197785645, + -0.6884921328659229, + -0.6949699478246412, + -0.683854498185014, + -0.691697501483643, + -0.6665531424108867, + -0.6802027097082193, + -0.6761793669764123, + -0.6870740099225621, + -0.6706541381164306, + -0.6839066421783172, + -0.6858873006585079, + -0.6725156554675198, + -0.6705503801087667, + -0.6698915716994726, + -0.6925354683007977, + -0.6741714840980962, + -0.6772726372412409, + -0.6852406522898356, + -0.6976847475060071, + -0.6738357288795459, + -0.6601373467435034, + -0.6746001057589305, + -0.6836878983229883, + -0.6682379828951184, + -0.678960724666767, + -0.6616558415992683, + -0.6846068006490835, + -0.6934396073421979, + -0.6827305560558085, + -0.6923322166640623, + -0.6688064525288602, + -0.6703313038690305, + -0.6675214810046828, + -0.6723702583799247, + -0.6697850856620029, + -0.6605195435661257, + -0.6951364117678613, + -0.6944020308132371, + -0.6877394615641371, + -0.6774306186565501, + -0.6933654907772052, + -0.6780060208332929, + -0.6637410819393393, + -0.6638759111373009, + -0.6607208672625781, + -0.6856352593658654, + -0.6901594942858211, + -0.6959958145787476, + -0.6819895896039675, + -0.6855910611737636, + -0.681248886252476, + -0.6777335539608192, + -0.6690264393927152, + -0.6696969682850866, + -0.682682136774839, + -0.6603114375893356, + -0.6881324685111765, + -0.6862188873119885, + -0.6643933467188025, + -0.6765936720306495, + -0.678679400991603, + -0.6856758656173493, + -0.6888645339935718, + -0.692241119391915, + -0.6798390361659148, + -0.6942458522663006, + -0.6646479166179272, + -0.6622496504873908, + -0.6694063579766252, + -0.6678516848510522, + -0.6973814891542861, + -0.6948155688138594, + -0.6838323199728185, + -0.6625997793805041, + -0.6696542036011097, + -0.6703737689475311, + -0.6850400660213888, + -0.6959769438815648, + -0.6828997168731955, + -0.6821704137678539, + -0.6778978803230582, + -0.6977254311519504, + -0.6623797867724716, + -0.6652219157091247, + -0.6725389554125811, + -0.6653641329602328, + -0.682044624529532, + -0.6838587996103385, + -0.6698697289384384, + -0.6970724915126271, + -0.6875605057611888, + -0.670478371857921, + -0.6724209148214719, + -0.6625832565154621, + -0.6745714968314281, + -0.6615885762622472, + -0.6859228020221907, + -0.681187669617963, + -0.6717719206252293, + -0.6694422455638718, + -0.6783815035367479, + -0.6859314084755539, + -0.686017135477061, + -0.6701822214645149, + -0.6609154926810725, + -0.6811874673653049, + -0.662285909696503, + -0.6904468411253498, + -0.6791717183606816, + -0.6830582546443873, + -0.6641657152218704, + -0.6610232381952378, + -0.6705472324260547, + -0.676661226343928, + -0.6859871198196634, + -0.6713136895728434, + -0.6730549815074504, + -0.6667408984642558, + -0.6745878347239797, + -0.6784331833201561, + -0.6900845649417741, + -0.6859831765278893, + -0.6954897987610792, + -0.6932867771445437, + -0.6668757097387835, + -0.6755249182678071, + -0.6668847044295517, + -0.6956985624758185, + -0.6670918049247632, + -0.6615935843782369, + -0.6902290211836317, + -0.6601001698882334, + -0.6659691978194161, + -0.6893559616002148, + -0.660739522085578, + -0.6874020691902292, + -0.6899601753282918, + -0.6839259121936698, + -0.6890878910457464, + -0.6904603345372745, + -0.6972870639294911, + -0.6782903391050586, + -0.6847334188544274, + -0.6763369356568024, + -0.6619466063398434, + -0.6767883978749699, + -0.6743381100746154, + -0.6950058698041798, + -0.6870753617998904, + -0.6791378130951656, + -0.6601967499766616, + -0.6910270233624053, + -0.675301116961508, + -0.6936568406862873, + -0.6803480285979479, + -0.6688627099299547, + -0.6737909932897717, + -0.678630921360456, + -0.6701342754219256, + -0.6724162381896679, + -0.6848711422896, + -0.6852964572105767, + -0.6896178519760607, + -0.6777663364481377, + -0.6683655002100122, + -0.6799240365920958, + -0.6713278405467107, + -0.6625519859468975, + -0.6872513588445184, + -0.6693464403031315, + -0.6718638412703386, + -0.6885284509673647, + -0.6816599452683172, + -0.6628323730682397, + -0.6912220970633121, + -0.6783280899083165, + -0.6635939361451534, + -0.6939254696089828, + -0.6942307909189023, + -0.6670308412075271, + -0.6825540752703775, + -0.6647294585651986, + -0.6628672667014036, + -0.6836366283354437, + -0.663770200783864, + -0.6738180544526224, + -0.6890813731897523, + -0.6772425773877552, + -0.6901249056972775, + -0.6773247076528338, + -0.6641586465622358, + -0.6850239764102113, + -0.6782886552849731, + -0.6967168054394723, + -0.6825011765142329, + -0.6887224847590199, + -0.664756462834594, + -0.6760562781558382, + -0.684979777649574, + -0.6823221244882101, + -0.691421284087173, + -0.6742092732627272, + -0.6687937084864094, + -0.6922075425609912, + -0.6652635704372011, + -0.6843393791149299, + -0.6700184700228072, + -0.6908146169898945, + -0.6679234446804524, + -0.6859957319993504, + -0.6653103727857191, + -0.6960148387884658, + -0.6724412773300604, + -0.6847063931892795, + -0.6608503308904085, + -0.6928329137383004, + -0.6790514509415956, + -0.696960934202054, + -0.6760461714800856, + -0.6886966089228946, + -0.6697228943301874, + -0.6930658817302809, + -0.6943070824374076, + -0.6759522949742962, + -0.6677075479388989, + -0.6895672069859192, + -0.6679689652850607, + -0.6660663931348076, + -0.6713434188627301, + -0.6660041352966444, + -0.6890792224034312, + -0.6644636353906871, + -0.6763208933712171, + -0.6934358673287988, + -0.6915794518062333, + -0.6860917184308937, + -0.6649233797620897, + -0.6763596478230952, + -0.6864826643167306, + -0.6893888172096097, + -0.6607223913405648, + -0.6955186883972332, + -0.6948345235560052, + -0.693296010962844, + -0.6604786353123839, + -0.6747395252753812, + -0.686524544631854, + -0.6857731223012055, + -0.6869429600859279, + -0.6839408645535698, + -0.6841563112510587, + -0.6757315820609576, + -0.6974650300186277, + -0.6745229906185262, + -0.6822790496801544, + -0.6661191091308092, + -0.6714674729403369, + -0.6618356255296656, + -0.6828993726228134, + -0.686170937428217, + -0.6738338758141356, + -0.6651708275987223, + -0.6882754488597818, + -0.6856079183593412, + -0.685247520773029, + -0.6699668771196525, + -0.6945221886170955, + -0.6693050136881674, + -0.6820243554036369, + -0.6647527923065154, + -0.677087476241349, + -0.6754025100209651, + -0.6745524363880929, + -0.6963303834686061, + -0.6655813061817024, + -0.6772369214564768, + -0.6648728942077734, + -0.6660652552306722, + -0.6705996458674133, + -0.6818544527090054, + -0.6920036728547695, + -0.6931148412766018, + -0.6738803291653084, + -0.6638268938681365, + -0.6767801722306475, + -0.669010558351832, + -0.6613693423314899, + -0.683468253225419, + -0.6645566031299482, + -0.6801452398044369, + -0.694515429349326, + -0.660052387011257, + -0.6784695147031921, + -0.6961456090668563, + -0.6839838484101725, + -0.6627275613664478, + -0.6813330863363941, + -0.6941136707094784, + -0.6679123240761775, + -0.6830450686040028, + -0.6656691513291723, + -0.6943126032027759, + -0.686602189600876, + -0.6817093043952506, + -0.6874595015094821, + -0.6839584959081116, + -0.6940422579309925, + -0.6906780756936478, + -0.6905851130205978, + -0.6789317562934533, + -0.6811070804691708, + -0.6616310870862109, + -0.6821171299060822, + -0.6908590818851487, + -0.6876256329538722, + -0.6654304333205089, + -0.6847400373998251, + -0.6977408401010384, + -0.6889336845023554, + -0.6932455137513162, + -0.683328284361242, + -0.6914277986408374, + -0.6859324178987822, + -0.6969696099100924, + -0.6810287809232763, + -0.6820801018128684, + -0.6798546010988465, + -0.6700523014980063, + -0.6868409298942117, + -0.6965499453231757, + -0.6800078504951066, + -0.6675521560220908, + -0.6770717327947787, + -0.6653675034423976, + -0.6795956601258437, + -0.6609207723999184, + -0.668166759043576, + -0.6730436169707711, + -0.6746666538757743, + -0.6719293011524974, + -0.6920111976211792, + -0.6746476440991915, + -0.6948191294878826, + -0.6878956144804721, + -0.6917594470756868, + -0.6869331431380431, + -0.6938764464194677, + -0.683124119215386, + -0.677498570119251, + -0.6696919353535923, + -0.679352397603181, + -0.6840239472957512, + -0.6729361677738068, + -0.6827367682272928, + -0.6671296075431027, + -0.6707791334949472, + -0.6963445845736387, + -0.6628765104000667, + -0.6622219387178705, + -0.6844303062745949, + -0.6824473976318826, + -0.6762335088318554, + -0.6623292802543552, + -0.6602087334948621, + -0.6888502792134712, + -0.6716606893895537, + -0.6617004381145136, + -0.6898489285865764, + -0.6647655599440013, + -0.6969169285852465, + -0.6753182221254993, + -0.6617465746401905, + -0.6937061072687631, + -0.6667400427461521, + -0.6808165580268543, + -0.6813432131519538, + -0.68961287892829, + -0.6673905048727781, + -0.6684850864718914, + -0.6738678556656402, + -0.6730868948792857, + -0.6725265184077892, + -0.6613792960124205, + -0.66638070050897, + -0.6653567776299272, + -0.6803697960461321, + -0.6764130753564633, + -0.6945193307182689, + -0.6659295401308543, + -0.6629695999313524, + -0.6908393760735516, + -0.697043300661734, + -0.6919270372507287, + -0.6941792334563361, + -0.6953521787398947, + -0.679958951811606, + -0.6921690110584846, + -0.6708181503413416, + -0.6791631818032826, + -0.6922058157445945, + -0.6746430876814385, + -0.6601182811795862, + -0.6927650952836475, + -0.6720416495417066, + -0.6942645656740892, + -0.6781186801122433, + -0.6707213665879485, + -0.6783231289258743, + -0.6633816188744308, + -0.695062011991768, + -0.6919167675236934, + -0.6692514329456851, + -0.6949644391451254, + -0.685513256495105, + -0.6801786012199507, + -0.6634104096283345, + -0.6617416221332484, + -0.6904413431151972, + -0.6600739306646641, + -0.6896911970962276, + -0.688087795782958, + -0.6782866687600719, + -0.6832232445787071, + -0.6712923662988849, + -0.6975407001000561, + -0.6906526017455021, + -0.6935892525448508, + -0.6799884554035347, + -0.6878429994557147, + -0.6631482650164132, + -0.6970258519030796, + -0.6898929281506682, + -0.6764921266888652, + -0.6681148363222812, + -0.6743894881485571, + -0.6927695669103751, + -0.668515338590879, + -0.6744742328122286, + -0.6655162971269207, + -0.6928080216142083, + -0.6655525274463691, + -0.6820900482583716, + -0.6898243805272337, + -0.6806382583029438, + -0.6756602471145645, + -0.687773921173952, + -0.677618785233191, + -0.694406735565021, + -0.6702648940631922, + -0.6853298472724901, + -0.6750579456023806, + -0.6653139220400532, + -0.6747777641226399, + -0.6842970140077071, + -0.6726420264589661, + -0.6640728507769519, + -0.6699243068287358, + -0.6963860415699744, + -0.6923238366192136, + -0.6620691054319603, + -0.6775643524906247, + -0.6782130389720502, + -0.6935803859265312, + -0.6629686285489127, + -0.6659309469220408, + -0.6972961362837272, + -0.671655079741274, + -0.6909914479309579, + -0.6667119728493196, + -0.6894763363841971, + -0.6912308655951994, + -0.6945131914049024, + -0.6663494805458908, + -0.6799682057937334, + -0.6662269192817467, + -0.6746583339952683, + -0.6705498461176341, + -0.6765613441600827, + -0.6799779687748003, + -0.6914021516796249, + -0.6776116384915641, + -0.6946430473042029, + -0.6818354534836437, + -0.6896773282293436, + -0.6849956290799664, + -0.6919974433459373, + -0.6646550560700297, + -0.664751748922092, + -0.6874382266588547, + -0.6720106050335631, + -0.689772460025647, + -0.6680734381517003, + -0.6795746716654804, + -0.6650709739025675, + -0.6712999637530539, + -0.662264312073934, + -0.6894489858111559, + -0.6793522991002983, + -0.6702098247686605, + -0.6802932243274833, + -0.6839436841277483, + -0.6937925896030703, + -0.6964764723156407, + -0.6609889837143061, + -0.6882944404916048, + -0.673838279192946, + -0.690967987099381, + -0.6690756636500553, + -0.6958117388539787, + -0.6634487679673438, + -0.6680639078481896, + -0.679157372877377, + -0.6605834861692909, + -0.6907221897627762, + -0.6757099902774428, + -0.6960363819200602, + -0.6878121127325028, + -0.6866403909075348, + -0.6675215966157483, + -0.6913228837808966, + -0.6945581703760393, + -0.6977172535815247, + -0.671416563457728, + -0.697174240214728, + -0.6771386933522396, + -0.6634301987111303, + -0.6721398381726339, + -0.6835678736446186, + -0.688207136926993, + -0.6689332264302391, + -0.6741242868998314, + -0.6710862973474113, + -0.6871103930477438, + -0.6902914424027318, + -0.6687267289537459, + -0.6829311134123511, + -0.6709791037119541, + -0.679478334746567, + -0.6970927685898821, + -0.671953478213447, + -0.6747479201523031, + -0.6674796638624269, + -0.6925129429617366, + -0.6888671718023027, + -0.6648152589334919, + -0.6601053001180852, + -0.6661859541133374, + -0.6623198126896133, + -0.6851023890509369, + -0.6799026882133444, + -0.667561571423204, + -0.661744717756065, + -0.6874414772277379, + -0.675198216881195, + -0.6883606421537922, + -0.6655783384591727, + -0.6629403216726506, + -0.6950294769432056, + -0.6891403552294741, + -0.6768460268466573, + -0.685567686196925, + -0.6859492956858243, + -0.6836719418721492, + -0.6755486349898543, + -0.6672087683811682, + -0.6826752218698353, + -0.6737840337157294, + -0.694360647789233, + -0.6745557062291581, + -0.6641959516707673, + -0.6864249024184453, + -0.6759586392225602, + -0.6870436553340612, + -0.682955709590194, + -0.6767811131179833, + -0.6897621736518913, + -0.6661438764256369, + -0.6819406019764187, + -0.6722185462755829, + -0.6971674394803365, + -0.670588294116879, + -0.6768306378040193, + -0.6630935889931323, + -0.668525272489879, + -0.6763364256437366, + -0.6836810481598791, + -0.6920393082594097, + -0.6964748996772245, + -0.6690731510492179, + -0.6632379599258845, + -0.6734891690241945, + -0.6754065751880853, + -0.6743272843942528, + -0.664687091091521, + -0.6898790084523083, + -0.6645075297658956, + -0.666217802910457, + -0.6905987762213343, + -0.6828866592730235, + -0.6876404656024421, + -0.6827600222129604, + -0.6908356863678654, + -0.6760103063266654, + -0.6942882941560792, + -0.6662668644135894, + -0.6722131681362502, + -0.6642350736189614, + -0.6619201321575426, + -0.6875881004650394, + -0.6609456471736175, + -0.685274249549011, + -0.6890659760631423, + -0.6633777668282899, + -0.6726991512860843, + -0.6838295555527969, + -0.6720744509950455, + -0.661689858179794, + -0.6659505016899365, + -0.6756604787804956, + -0.6950715152857632, + -0.6699637778056466, + -0.6728815612968716, + -0.670065003155151, + -0.6925979498294388, + -0.6808218859648221, + -0.691771365640305, + -0.6805276517366103, + -0.6695536456027104, + -0.6810431256485943, + -0.6722362119803829, + -0.6831805122059486, + -0.6916455653380844, + -0.6697253419730533, + -0.6678749577512987, + -0.6716206424348872, + -0.6927350017195629, + -0.6865887880944194, + -0.6811493519370384, + -0.6963664944121042, + -0.6772756465222945, + -0.679909868866722, + -0.6629532075396997, + -0.6694090196521282, + -0.6957054720095052, + -0.696622427785256, + -0.6634940610277374, + -0.6892388699676688, + -0.6684811644669957, + -0.6834692072095165, + -0.6677356997328431, + -0.67103725624618, + -0.6801350334484382, + -0.671324023266882, + -0.6846367254068946, + -0.6827405967606496, + -0.6773454291833074, + -0.6704254726270799, + -0.6957708221446083, + -0.6723828527134458, + -0.6770379875506429, + -0.6846318328548869, + -0.687027098270678, + -0.6851302156654274, + -0.6931768928065579, + -0.6967855744368786, + -0.6799148686912161, + -0.6681246982997961, + -0.697286411250418, + -0.6872818634933087, + -0.696661304813142, + -0.6925976332833031, + -0.6906497720160092, + -0.6762449151738805, + -0.6818480947834817, + -0.6872809185905433, + -0.6674437611695194, + -0.6726939334620584, + -0.6679654643318679, + -0.6622298254381274, + -0.6604153298929771, + -0.6634232047794218, + -0.6725586122292647, + -0.6937124855677474, + -0.6614064861108531, + -0.6655879818115533, + -0.6807025111389706, + -0.6720194314074666, + -0.6914837928648007, + -0.6783594944161238, + -0.678337591108074, + -0.6810117366020423, + -0.6860878366093911, + -0.6891640616322702, + -0.663289169035579, + -0.6729527542454519, + -0.6686342371691991, + -0.6826695134320471, + -0.6640017906942423, + -0.669872065326235, + -0.6959946779046207, + -0.674983164517916, + -0.6914855624312097, + -0.679221954089955, + -0.6938186589696134, + -0.6740234175753985, + -0.6739844350786226, + -0.6785845690516735, + -0.6831456007236262, + -0.6841388574214696, + -0.6975917917774193, + -0.666056398318824, + -0.6872544264439704, + -0.668189863996715, + -0.66817364387638, + -0.6647663009534135, + -0.6875050456376134, + -0.6652667059221818, + -0.6931420393223273, + -0.6853075078392803, + -0.6760429597070471, + -0.6720936106536758, + -0.6797862288894218, + -0.6684426803828294, + -0.6626771259869222, + -0.6653119147098012, + -0.6950729816504606, + -0.6907935350658361, + -0.6627911414696752, + -0.6899732283582299, + -0.6909849539971739, + -0.6945699928135668, + -0.6850509501194522, + -0.6970912764956406, + -0.6673791629225302, + -0.6929983604306441, + -0.6945695687853825, + -0.6763014401201268, + -0.6842908989792, + -0.6710614903914651, + -0.6602266523828683, + -0.6642028093414887, + -0.6772505759662178, + -0.6963523470139603, + -0.6852331307018932, + -0.6781563329169858, + -0.6838338153461031, + -0.6804833437710189, + -0.6754053571329968, + -0.6624291266449919, + -0.6842084674771782, + -0.6970437333197831, + -0.6961824134608616, + -0.6697989561601823, + -0.6621027358435413, + -0.6740386367700523, + -0.6798056368034838, + -0.6808045708552836, + -0.667825348485461, + -0.6775367106779304, + -0.6887281338805605, + -0.6794494430118139, + -0.6910132022874309, + -0.6914532193011151, + -0.6932101760059879, + -0.6975489237770228, + -0.6738470278319542, + -0.6791504521371138, + -0.6700696151636777, + -0.6609292628121038, + -0.6861577940123793, + -0.6627697680720739, + -0.6611180156837909, + -0.6960725528036611, + -0.6806951082987529, + -0.6863799807414959, + -0.6798283770474095, + -0.6886092970643627, + -0.6687806147207753, + -0.6939886002271214, + -0.6729365071172725, + -0.6920887822917211, + -0.6839292241776387, + -0.6875195602372259, + -0.677294059483719, + -0.6943036152672095, + -0.6677854403555811, + -0.6786799282377324, + -0.6862461237895201, + -0.6764735519681818, + -0.6776477382743485, + -0.6811685761077484, + -0.68658399165484, + -0.6752793364535454, + -0.6888216804068564, + -0.6696712056587935, + -0.6957595786070656, + -0.6757367868829003, + -0.682662263619943, + -0.6925980594710333, + -0.6612475860674104, + -0.6775071963156994, + -0.6602651766696861, + -0.6906164969927041, + -0.6953403367895009, + -0.6712165641768463, + -0.6602692437844891, + -0.6701832583554334, + -0.6948098950596887, + -0.6670570747519119, + -0.6862829939958408, + -0.6871860748868184, + -0.6818359658588492, + -0.6613593830636965, + -0.6768704667796747, + -0.6930935750021043, + -0.6974117471126111, + -0.681718536648049, + -0.6667314386422813, + -0.6945854226105568, + -0.6726031861625789, + -0.68466118862712, + -0.6619971491244699, + -0.6828602997994823, + -0.6976793784597808, + -0.6752348474572178, + -0.6887589995458859, + -0.6783134942502501, + -0.6779461413107882, + -0.6873544644987367, + -0.6758575615293594, + -0.6851955258123734, + -0.6627379496866868, + -0.6869159707906949, + -0.6826329231871908, + -0.6646511087785362, + -0.6690136109288157, + -0.6808618850913944, + -0.6614789225036978, + -0.6920513280966252, + -0.676599525981242, + -0.6952020209914223, + -0.6667309445512932, + -0.6846680323215785, + -0.678029652492314, + -0.6609507473855915, + -0.6944091238738621, + -0.6827604054873095, + -0.6750777979592932, + -0.6956817238177594, + -0.6708041529566309, + -0.6837169116790056, + -0.6758634133139066, + -0.6614266012515118, + -0.6758738157231715, + -0.6833364457973108, + -0.6735256934678312, + -0.6666894874162961, + -0.6770568533242027, + -0.6638495971907764, + -0.6845833959112412, + -0.6959388578618637, + -0.6860060942963059, + -0.6885874338709155, + -0.6631181799002115, + -0.6656198493025697, + -0.6942020733097257, + -0.6627700431527308, + -0.6861002451408925, + -0.6630898460678806, + -0.6708269561138879, + -0.6756396219342691, + -0.6649469291308054, + -0.6875954030168024, + -0.6953559178141927, + -0.6686344731758804, + -0.6836160494949891, + -0.6880623370906888, + -0.6737224493804856, + -0.6602550373383194, + -0.6631134407789977, + -0.6802855717992843, + -0.674654425174489, + -0.6861710555190127, + -0.6707414049904205, + -0.68407592348919, + -0.6728073406483758, + -0.688601585245522, + -0.6735831429133917, + -0.6955779873508309, + -0.683823970614698, + -0.691041802077868, + -0.6798131949630443, + -0.671581389018582, + -0.6887380792220447, + -0.6900380919130021, + -0.6773116151373348, + -0.6819414627315924, + -0.6698002483390159, + -0.693261361463937, + -0.6881782125146657, + -0.684061450381463, + -0.6862889704436388, + -0.6620709113347534, + -0.6777802039469352, + -0.6658986235436495, + -0.6767088279395986, + -0.6677133154561515, + -0.6839047827343512, + -0.6654358932102531, + -0.6807994724800226, + -0.6960031081622761, + -0.6952362964688373, + -0.6870391401379875, + -0.680959324612881, + -0.6864709221941706, + -0.6882155785217433, + -0.6744707433979625, + -0.6750459249836201, + -0.6774061431107924, + -0.6752827472064928, + -0.6617075479159128, + -0.6877772698110782, + -0.6668343143081599, + -0.666876155926276, + -0.6931595319836775, + -0.6655427802525903, + -0.6760825521860171, + -0.6651911081114592, + -0.6825256077405681, + -0.6793655626906279, + -0.6811210771760452, + -0.6928949267387551, + -0.6615197043962133, + -0.6897741811173308, + -0.6918743050934525, + -0.6753530460626138, + -0.6887315930820538, + -0.6730357032385131, + -0.6934645276374823, + -0.6701816624310536, + -0.6665888038786179, + -0.6967796183060665, + -0.6652817694087534, + -0.6942905645427806, + -0.6783268968974103, + -0.6856569615086835, + -0.6897882338603152, + -0.6655473744418994, + -0.6706348932670023, + -0.6685086161076256, + -0.6804675403656918, + -0.6659855222505514, + -0.6856834933909585, + -0.664313568969311, + -0.6608366551882838, + -0.6969616114667475, + -0.6914684216459602, + -0.6633574254905269, + -0.6966135440492925, + -0.6915137433648566, + -0.687713100303803, + -0.6770121865413958, + -0.6684402895423017, + -0.6900186771466346, + -0.6967736647063334, + -0.6607705659330411, + -0.6739468663360825, + -0.6622220213591462, + -0.6694171356987825, + -0.6602631750659941, + -0.6608247007318191, + -0.6609962877580743, + -0.6786883613356934, + -0.6878342177165813, + -0.671727805178135, + -0.6928767924062251, + -0.6757783661881112, + -0.6853872991064788, + -0.6602853014162304, + -0.6904440216470971, + -0.6931908257672079, + -0.691323397951282, + -0.6820011003712735, + -0.6609697793153273, + -0.6638361671423338, + -0.6939424067165783, + -0.6618369103992205, + -0.6689561474958134, + -0.6852019911360918, + -0.6843063839891654, + -0.6974360470643006, + -0.6930764919195065, + -0.6893903880278026, + -0.6742915384756283, + -0.6927634051133017, + -0.6878214114308622, + -0.6675385643952627, + -0.665473326423374, + -0.6722379815487818, + -0.6864586303238495, + -0.6940631233751487, + -0.6800841347654837, + -0.6781355860603744, + -0.6897355771124641, + -0.6782750461828223, + -0.6901219603482708, + -0.6681751461332505, + -0.6913591561754914, + -0.6700759117775952, + -0.6637496791537449, + -0.6736661439253805, + -0.6716299971617692, + -0.6629355385447498, + -0.6626477667199235, + -0.6718101199086317, + -0.6689763440399417, + -0.6855488448342107, + -0.6777880198386262, + -0.6859736021235279, + -0.6674123571423537, + -0.6680259472229403, + -0.6947263416052759, + -0.6668111779410876, + -0.6603948192752008, + -0.6899772334501494, + -0.6612981874087145, + -0.6915281928051303, + -0.6886361261250465, + -0.6693309151333993, + -0.6621867860432537, + -0.6751280098708455, + -0.6887761865023837, + -0.6647603715080921, + -0.6787578579744076, + -0.662170660407926, + -0.6797741549127545, + -0.6618981402861653, + -0.6657404313878066, + -0.6731570794001185, + -0.6789238684212862, + -0.6867863141462432, + -0.6623866476282485, + -0.6810245932989393, + -0.6923379956053464, + -0.6800257891565975, + -0.6897237695276617, + -0.6709644861374151, + -0.6640610388161057, + -0.6869395392388271, + -0.6940107871017819, + -0.681261634245777, + -0.6945613398762703, + -0.6910995335188319, + -0.6684475730628032, + -0.6800940638702028, + -0.6909690285937159, + -0.6902836981947678, + -0.6923242120916643, + -0.6864386562187127, + -0.680394601300569, + -0.6874876321262026, + -0.666982155525292, + -0.6934081536009647, + -0.6870741013238458, + -0.6610756035065875, + -0.6758260703202007, + -0.6954689183397278, + -0.6895550007297366, + -0.684050977780381, + -0.6691919432085031, + -0.6949525215646, + -0.6673338586256298, + -0.6631264512755615, + -0.6740735790072454, + -0.6686136034872043, + -0.6938570103556978, + -0.6698905172102271, + -0.6884851714138002, + -0.6645840730269992, + -0.695405172097749, + -0.6673397357547255, + -0.6969639557589473, + -0.6895750253899385, + -0.6865974771378084, + -0.6968614130667298, + -0.6795772040048131, + -0.6713359545323115, + -0.6888695374693296, + -0.6656528818361287, + -0.6602355266318771, + -0.6950315611902632, + -0.6619463460541736, + -0.6785368266359034, + -0.6933231959108186, + -0.6772100619646573, + -0.6604070588589573, + -0.668643387605257, + -0.6772543415619097, + -0.6940296147272571, + -0.6693026298459428, + -0.6934438402057589, + -0.6889060647839713, + -0.678236474876074, + -0.6963028135284706, + -0.676796774392656, + -0.682310491015884, + -0.6947406903873912, + -0.6902805950590825, + -0.6939818379288455, + -0.6783107488350006, + -0.6689324446815202, + -0.6689863380730167, + -0.6688251816029916, + -0.6720045490299665, + -0.664158661741929, + -0.6734967022168055, + -0.6887327976401898, + -0.6885435846358108, + -0.6919136997051241, + -0.6865448563146183, + -0.6654062000797991, + -0.6656070698185391, + -0.6618134827923989, + -0.6871729465011924, + -0.667088200190356, + -0.6888684651746658, + -0.6857722141150525, + -0.6765402234836546, + -0.6652231023423355, + -0.6741494675783527, + -0.6708406014324094, + -0.6930775702710844, + -0.6765774460203097, + -0.6910023348631881, + -0.684100459191232, + -0.6849764737486642, + -0.662620584683778, + -0.6835973951023421, + -0.6886229305788955, + -0.6928391904785537, + -0.6922643094569537, + -0.6892558070202082, + -0.6956371108127828, + -0.6718129904184356, + -0.6891973561919823, + -0.6866975306727819, + -0.6783188259235202, + -0.6969151517393047, + -0.6759766538750919, + -0.6697124977309957, + -0.684503440419006, + -0.6729044925083957, + -0.6729596250329484, + -0.6717915779906319, + -0.6607745357044513, + -0.6849961710949776, + -0.6864102252298755, + -0.6713387020921092, + -0.68414695927534, + -0.6904736332534671, + -0.685039914727294, + -0.6612107706480245, + -0.6736519130937015, + -0.6928007420636159, + -0.6612433500161976, + -0.6692068452468573, + -0.6692600978794168, + -0.6863449473746487, + -0.668887922586638, + -0.6744696304301374, + -0.6860778614134376, + -0.6847976996975548, + -0.6659076375761189, + -0.6693789786387505, + -0.6749871602288893, + -0.6706925063266258, + -0.6919992532563639, + -0.6932898360084259, + -0.6616486488026565, + -0.6919217240517208, + -0.6953439716014542, + -0.6677644023838503, + -0.6754518364592047, + -0.6937529812973326, + -0.6865327247825164, + -0.6664232785090369, + -0.6850078169011665, + -0.6947233968385566, + -0.6895085643256345, + -0.6665983970554035, + -0.6609041829102352, + -0.6887663454769573, + -0.667775240532318, + -0.6831504079109323, + -0.671001134284783, + -0.6698483176094285, + -0.6775620020122828, + -0.6647065051361573, + -0.6954024103312788, + -0.6800857898276765, + -0.6747559068969391, + -0.6871998876240792, + -0.6788670473463918, + -0.6911664669600909, + -0.663533085271234, + -0.6782490205521178, + -0.6615490744747978, + -0.6738657784032835, + -0.6951522534430712, + -0.6895969832545322, + -0.6827328140279411, + -0.6630709017354147, + -0.6851587715344126, + -0.6662967082687511, + -0.6750548073448224, + -0.6954214997588452, + -0.6971836508146557, + -0.6663007537364207, + -0.6673889085737384, + -0.6725440899571016, + -0.6642170271131129, + -0.6950949791366942, + -0.6880947935783122, + -0.6715436312171733, + -0.6735429675220264, + -0.6834984753720279, + -0.6721369051365197, + -0.6761583810443088, + -0.6803612581554632, + -0.6948980502045984, + -0.6781598897909548, + -0.662596620787512, + -0.6783142760944824, + -0.6862446480217225, + -0.6735534851459501, + -0.679908046424463, + -0.6647607648400234, + -0.6669471358665875, + -0.6958957279036927, + -0.696782580837614, + -0.6675157466051602, + -0.6635107119737745, + -0.663480701810269, + -0.6906537767089471, + -0.6872325662516383, + -0.6709115429666466, + -0.6732821227590878, + -0.6613653819020286, + -0.6977847951350087, + -0.6767792893468727, + -0.6809853803904504, + -0.6863470414068759, + -0.6943916692963243, + -0.6842129025688839, + -0.672223720719469, + -0.6878309192364624, + -0.6642191605949691, + -0.6826951985145107, + -0.6787069484564163, + -0.682023585727884, + -0.6781779702380255, + -0.6854175254115465, + -0.6968694198409265, + -0.6733669207373515, + -0.6949165331112863, + -0.6898735744038513, + -0.6673373934970633, + -0.665147634861431, + -0.6673745565457034, + -0.6855328871865872, + -0.6801602941421095, + -0.6820626509804671, + -0.6747699782709048, + -0.6683914204220394, + -0.6733761102531914, + -0.6829397269378238, + -0.6655914086675134, + -0.6750875382262094, + -0.6786976814929876, + -0.6824105086916041, + -0.6785164007807406, + -0.6794161792715614, + -0.6754351819119847, + -0.661118930579629, + -0.6652466576298275, + -0.6675395631518609, + -0.6618482056253472, + -0.6642968340817074, + -0.6851601579946209, + -0.6815846480314534, + -0.69386531921823, + -0.6776054767421945, + -0.6768473776562575, + -0.669115904755571, + -0.695605535339369, + -0.6845824109061895, + -0.676340151595163, + -0.6931482888691953, + -0.6636157421428805, + -0.6966346163527408, + -0.6661031915846848, + -0.694689689088112, + -0.6954037442928883, + -0.691958913684796, + -0.6683335683546654, + -0.6678395777914916, + -0.6795153634033079, + -0.6837998414602038, + -0.6615486131564381, + -0.6689155820436684, + -0.6799751335612643, + -0.6780021041413088, + -0.6973554960339466, + -0.6645003735006314, + -0.6807820314427774, + -0.6778635539297281, + -0.6813120565615203, + -0.6654537645687179, + -0.6790952775804372, + -0.6874429504744202, + -0.6824835988577211, + -0.8082537854559504, + -0.7809652936675557, + -0.7686186107417998, + -0.7367286006017599, + -0.7083101231982896, + -0.7011198642162784, + -0.7507427721426679, + -0.7733816193332199, + -0.8108085356899118, + -0.7850623663402492, + -0.7381511786753021, + -0.8051124254402168, + -0.7384043589584661, + -0.7244098866860297, + -0.6865579971798647, + -0.7183391099465046, + -0.7023000286111607, + -0.7501574834153549, + -0.7883245409586445, + -0.7648644004633011, + -0.7338123468093993, + -0.8078783844903993, + -0.8129545610217592, + -0.7481888050526007, + -0.6624418145187709, + -0.7483751982931963, + -0.7408063922007615, + -0.6997036695375833, + -0.8151620734055683, + -0.679147255599717, + -0.7055122667289377, + -0.7012072982717966, + -0.6784526969336174, + -0.7163946285279927, + -0.6802708326921996, + -0.7672001955487346, + -0.6929875064451335, + -0.7975780234648948, + -0.7530112910729103, + -0.6953432205199513, + -0.6779045701719233, + -0.6828333848613015, + -0.7077342065451093, + -0.7131962742442496, + -0.7840587986798778, + -0.7201040033078966, + -0.6932434858854518, + -0.7211026589229367, + -0.7518952763861728, + -0.8050339519818339, + -0.7559175531894027, + -0.7815923925415572, + -0.7813990478446698, + -0.7856699507229238, + -0.758673835677503, + -0.7835234973149285, + -0.8064932623547971, + -0.7749171761222516, + -0.7089430608044537, + -0.7014261834869834, + -0.7710455667317335, + -0.7252973810197845, + -0.72405419511947, + -0.7625855025390184, + -0.7789499845927068, + -0.7463836174468936, + -0.6781941171109842, + -0.7975158095614546, + -0.8146024349930661, + -0.6606496418498314, + -0.7159789845648135, + -0.7099923039390789, + -0.6740522123162795, + -0.726440474026224, + -0.6943128691331284, + -0.7342047228771882, + -0.7239539305061962, + -0.6701490073432164, + -0.8026257423559757, + -0.7054228180632809, + -0.7233476676195694, + -0.7109689001677423, + -0.67635589840931, + -0.675925021290397, + -0.6626927757158676, + -0.7492134448301406, + -0.7070476757236973, + -0.7564287391017832, + -0.8098849309496458, + -0.810805137563184, + -0.7641363078151392, + -0.7284504592380547, + -0.7505183193337199, + -0.6712103974338802, + -0.7650108584475936, + -0.7044712313754258, + -0.7113565388494385, + -0.7628493331939756, + -0.6681419802003163, + -0.6877969684813554, + -0.7573098925251769, + -0.8040837943171818, + -0.761462824618976, + -0.7801279201030749, + -0.7444933055696845, + -0.6783993643711261, + -0.8025477686154884, + -0.7320591448948601, + -0.7517031265921671, + -0.7406126396906796, + -0.7415103443238972, + -0.8100629135383143, + -0.7914870549113895, + -0.8112907475989314, + -0.6603091974864932, + -0.6787818938888602, + -0.7077408023337644, + -0.7604659167102941, + -0.7242017310713983, + -0.7269017721419014, + -0.805313947253889, + -0.702283245582013, + -0.6916238772620583, + -0.773890222058508, + -0.7095167889739532, + -0.7733932162477396, + -0.7478430978822835, + -0.6926955970685353, + -0.7684586367533139, + -0.7414082078110309, + -0.811198092002705, + -0.7931805575689981, + -0.6971998679002221, + -0.7427614527411136, + -0.7872591656271013, + -0.7246805377653839, + -0.7995518638108075, + -0.7202337315184324, + -0.7245409908827884, + -0.7096942630362476, + -0.728566397545838, + -0.7517862161539377, + -0.7385935739144583, + -0.6803830910283633, + -0.7766488293064546, + -0.8013666937148393, + -0.6663085400420963, + -0.8154341302053894, + -0.7756792737941908, + -0.6985995817693657, + -0.6799642400723069, + -0.7964497389248135, + -0.6929569978688812, + -0.7394984012088627, + -0.7433783484907506, + -0.7940584001399346, + -0.7777355360642009, + -0.6842300451926169, + -0.7798292919684131, + -0.739583003875077, + -0.7257922425274839, + -0.7151270707384795, + -0.7395313976696307, + -0.738043944084877, + -0.814439127392499, + -0.6983814212276914, + -0.6668536580852866, + -0.7062980809154539, + -0.7340579899501454, + -0.7636590861443354, + -0.7372898599510901, + -0.678732027219667, + -0.8087819695254485, + -0.679413988215789, + -0.754349375247956, + -0.7273276292301765, + -0.6817382897604457, + -0.7745685162108457, + -0.7916079367846374, + -0.7653714813210452, + -0.6826378879677509, + -0.7196650042481163, + -0.6957043119999815, + -0.8046691167799227, + -0.7287078204699089, + -0.7323029696707395, + -0.7020747480397972, + -0.8148313981441138, + -0.6827958638831663, + -0.7299770474948607, + -0.7063859900185623, + -0.7514163729880418, + -0.7377393010685498, + -0.6652619602049115, + -0.7896521360562931, + -0.7995753763497307, + -0.663172165886539, + -0.701417255321219, + -0.7350772672058106, + -0.7890769796082692, + -0.7207858423555501, + -0.7503068410097699, + -0.815425989247594, + -0.75259509903174, + -0.6832941389174174, + -0.7292765630957412, + -0.7232082143328096, + -0.8069069607552171, + -0.7880673373947314, + -0.7061800544539385, + -0.6740036851300922, + -0.6613354681669145, + -0.6843119270640606, + -0.6826107887842577, + -0.6997269779970222, + -0.7193208589463731, + -0.7691226382083544, + -0.6730085810464805, + -0.6807545069623241, + -0.6606828168810279, + -0.709625487766931, + -0.752626597740686, + -0.7620610013797376, + -0.6824404809522949, + -0.8102170785791366, + -0.6964470171237498, + -0.6998388655140427, + -0.7580707025171567, + -0.7613149790589431, + -0.6935584442069949, + -0.6626872995386094, + -0.7690930641292599, + -0.7009815449023018, + -0.6690058990908725, + -0.6882213161887741, + -0.7935694201994627, + -0.798271365948894, + -0.7415187645592832, + -0.7938805586970233, + -0.7724275771190755, + -0.8032376264257073, + -0.7818185430548307, + -0.7359452981969781, + -0.7102188666769571, + -0.6849795218422997, + -0.7925531682678814, + -0.7153367944548678, + -0.722841917764693, + -0.7129548650701383, + -0.7782483560336755, + -0.7701597511379804, + -0.7698006783108916, + -0.7215761683498232, + -0.7028876616155644, + -0.6667661705191923, + -0.7333467979840593, + -0.7793361176880785, + -0.7695489636600328, + -0.6796038250918358, + -0.7453377661474611, + -0.8110392091021217, + -0.7953854471366646, + -0.6651601805298681, + -0.7448873406690434, + -0.7642945362571354, + -0.7749084932957211, + -0.7257095979810816, + -0.6836072528074403, + -0.7444690303533339, + -0.7066186798588145, + -0.6678192960041613, + -0.7137655541549336, + -0.7822313660842676, + -0.780027933322762, + -0.7578853275973024, + -0.8024656274811484, + -0.6736261259642493, + -0.8032408156616507, + -0.759734595338244, + -0.7840832715373334, + -0.7784695023072972, + -0.7526615221309841, + -0.6775125549344729, + -0.7579719110635003, + -0.6732114582500793, + -0.6710471626556314, + -0.7870992688371143, + -0.7664547863417959, + -0.8042627194115393, + -0.6640288186835195, + -0.7708004830239259, + -0.7102531024671752, + -0.772553790033168, + -0.809653330847487, + -0.6940279810455523, + -0.6994463129739498, + -0.6717387716132002, + -0.701879509797213, + -0.7759496380341984, + -0.7001117440062223, + -0.7086474256117086, + -0.6743665336936229, + -0.8052625102500502, + -0.6894083029604956, + -0.8021614104429808, + -0.7068269310943087, + -0.7453172398786513, + -0.7352212326496468, + -0.6768310527448813, + -0.7461268464452655, + -0.7188228198351353, + -0.7310751574764904, + -0.7556393795621187, + -0.6872946320217798, + -0.7780964209039813, + -0.689170275992497, + -0.7079678845886694, + -0.7553187620795873, + -0.8154417018300902, + -0.7736467647078682, + -0.7690778298855347, + -0.7661629167030568, + -0.6927301051027107, + -0.7714542868818768, + -0.7565757102437599, + -0.8017430127881998, + -0.8009257212458369, + -0.8038241332538255, + -0.6603629017328185, + -0.805579700625961, + -0.6749913942932106, + -0.6726279046868531, + -0.6952418071551819, + -0.7627024241194795, + -0.6848091697345668, + -0.7621909192829806, + -0.7937719408755084, + -0.7602248228558792, + -0.6650006191433697, + -0.7064493653900563, + -0.6686199700956689, + -0.7712852894349207, + -0.7449466419994435, + -0.806808641835594, + -0.7375024613921416, + -0.792380266781774, + -0.8029290449633921, + -0.7666236877607284, + -0.7239031793427938, + -0.6906126432244638, + -0.7675839076274538, + -0.792271192562784, + -0.7209869934098567, + -0.6784852614524273, + -0.7210154704320523, + -0.7853006224063994, + -0.6713081461203879, + -0.7911555437103186, + -0.697387086296887, + -0.7926075191530563, + -0.6688151784168688, + -0.7583124929459502, + -0.7557043682892038, + -0.7805434788663742, + -0.7047799305846778, + -0.7220082388488656, + -0.7042754754964511, + -0.7482466352802566, + -0.7040879851261382, + -0.7355651859584685, + -0.6910282211174517, + -0.7158344021501759, + -0.6626693993518713, + -0.7442460206638029, + -0.8015965973092463, + -0.7476953421331541, + -0.765495230205194, + -0.7316009484641326, + -0.7878275219825316, + -0.7494043409005036, + -0.7046225612804555, + -0.8000706791105889, + -0.6655185889724629, + -0.7596683437148162, + -0.7291037257042312, + -0.7710635669716095, + -0.7468944660472785, + -0.7099212566800578, + -0.7464125743570005, + -0.777483385333429, + -0.662274377625539, + -0.7483129306354079, + -0.7521395528614001, + -0.7283466418416331, + -0.7581407553064078, + -0.8064587680099801, + -0.6961922135748526, + -0.7595852946610242, + -0.7610177553518879, + -0.7188879859364492, + -0.7956854565622351, + -0.7706197503465789, + -0.7300718029651299, + -0.6838191032403026, + -0.8040147054535768, + -0.7791456191935986, + -0.7004872048312789, + -0.7508833711504629, + -0.7453804025136574, + -0.6621903015486836, + -0.8056525343272534, + -0.6861773725673814, + -0.757963749191169, + -0.7630420044671244, + -0.7484033719421042, + -0.7829140833917044, + -0.7222278803114853, + -0.6784148867481953, + -0.742640389493095, + -0.7680604812448437, + -0.7843958982257437, + -0.6705311323705361, + -0.7796854312823596, + -0.8124087452206723, + -0.7424341466416957, + -0.7528301141947965, + -0.7436064341406099, + -0.7323884062138931, + -0.7815326256019546, + -0.7592696755702938, + -0.682276826931995, + -0.7277523657323578, + -0.7254880187214432, + -0.7944929808889551, + -0.6925720088923183, + -0.7934333286800869, + -0.6795930759529547, + -0.6619883866408023, + -0.7928080614801968, + -0.7549872903287831, + -0.7014257823915578, + -0.8078351377503764, + -0.7684392706884166, + -0.7428127491621273, + -0.8067543397135565, + -0.7491395595707501, + -0.6730842934837458, + -0.7584594157829575, + -0.7976194544477985, + -0.7072863506980254, + -0.759305126009165, + -0.7569211819906763, + -0.7507799700242404, + -0.7272060147534579, + -0.7765320471245952, + -0.7733744081934936, + -0.71654196382889, + -0.7648270359905373, + -0.8029776827119526, + -0.6978067842364062, + -0.6775138349135559, + -0.7682979722604715, + -0.701454404450971, + -0.7618381619093915, + -0.7035977828629639, + -0.7894779135365255, + -0.7954459757548651, + -0.7795533509385647, + -0.7155004289458575, + -0.8017791073655567, + -0.7236537329826255, + -0.8019940893544314, + -0.7780646349175464, + -0.7385156058536552, + -0.6973869628257656, + -0.7904879170304154, + -0.6987441065736678, + -0.6721944563927442, + -0.7842299891548173, + -0.7604497144451006, + -0.7284352145113691, + -0.7871571595340954, + -0.7076598720817048, + -0.761052758701599, + -0.6688812184208188, + -0.7281414766242302, + -0.7867426770913883, + -0.7828841241074233, + -0.7236732107028466, + -0.7104598646337651, + -0.7299679551040777, + -0.6922837281155474, + -0.8049317196548256, + -0.6750430570470529, + -0.6850018001613705, + -0.7033927762906098, + -0.7065097403567651, + -0.6886471257144453, + -0.7674584856573108, + -0.7714441857548647, + -0.6698171195404731, + -0.6914855714235834, + -0.6976005501625085, + -0.7349842522071324, + -0.6717563644284152, + -0.7249758568553377, + -0.6757409493867058, + -0.6968910010729593, + -0.7474567119746522, + -0.7670321648383452, + -0.8099294696701486, + -0.697776077083007, + -0.8024278050389043, + -0.7204289013853948, + -0.7769346129962941, + -0.6646583094908765, + -0.7465034264001303, + -0.7676632083298711, + -0.7446217306538653, + -0.7663841026777704, + -0.7079992351572881, + -0.7992322403919259, + -0.6680447697897225, + -0.7044657869050779, + -0.6761420289231191, + -0.7806824977857539, + -0.8129914001985269, + -0.6943292996149353, + -0.747765261056524, + -0.6889411950725823, + -0.6668341277070131, + -0.6687889238146889, + -0.7214354846315678, + -0.7805159990214072, + -0.7564685006731054, + -0.8158150220045834, + -0.8105331981822668, + -0.770307040969049, + -0.7461725308048495, + -0.7538086232221337, + -0.6678471846348895, + -0.7443286010371398, + -0.7460735593154385, + -0.6913894447447235, + -0.6947480607615888, + -0.698872558709676, + -0.8020565172914645, + -0.7749707015974194, + -0.8005683362249638, + -0.7473091113857526, + -0.748474264819076, + -0.795590983548681, + -0.7460536319192603, + -0.7429044008703238, + -0.7957863469291557, + -0.7543818362553986, + -0.7757257133946089, + -0.6836284723478581, + -0.7924257399668467, + -0.6772604917674151, + -0.7154195306857789, + -0.7840508109430195, + -0.7451618152250847, + -0.7167076345541363, + -0.7248367361062028, + -0.7511076218624673, + -0.6866638133729026, + -0.7318019759145181, + -0.6894211340666493, + -0.7166698215267282, + -0.7831396638272553, + -0.744306740418474, + -0.7525062179804173, + -0.7189420779662686, + -0.7404294327507748, + -0.7385987073015431, + -0.6950498583975995, + -0.7962393620708337, + -0.8052026066836679, + -0.6644285522045257, + -0.7993703566896092, + -0.7128505231632543, + -0.6922233863397395, + -0.7750092185702481, + -0.6946378207062059, + -0.7935413229571344, + -0.7301308889874755, + -0.7614488554275691, + -0.7508165653499657, + -0.8077206986827458, + -0.7641200887679399, + -0.7527313924350494, + -0.6718645635831095, + -0.7497825769575828, + -0.7289417380632915, + -0.7611827358211086, + -0.6733190254253136, + -0.6641148972963478, + -0.6894030896635515, + -0.773480118446543, + -0.7532423906394918, + -0.7168449885261742, + -0.7297805217111499, + -0.8047642468222276, + -0.6718408379273475, + -0.7550610492296552, + -0.7524145094212453, + -0.7974447552412944, + -0.7620758183715379, + -0.6682249598019396, + -0.7441221157698784, + -0.6995217575776682, + -0.7797159122283784, + -0.671620921005587, + -0.6731083107633816, + -0.7826900853894903, + -0.8027235172979295, + -0.6889355724584141, + -0.7200127449186442, + -0.7724653553358152, + -0.8039219223420013, + -0.7644829967647024, + -0.7100301061909446, + -0.7169764381820867, + -0.7655011942132113, + -0.7345491023597882, + -0.6813726787097941, + -0.755689866354876, + -0.7333876820468981, + -0.785870664418124, + -0.8040057052008431, + -0.8102331343690126, + -0.693550751942431, + -0.7342019857195979, + -0.7721037813772718, + -0.7373508669249541, + -0.7385376752087459, + -0.7335683412867096, + -0.7315121285936504, + -0.7801549009035966, + -0.7916231230195055, + -0.7982134610519361, + -0.7824524383968455, + -0.8123037109732814, + -0.7179061989806503, + -0.6923216261846515, + -0.689691800261539, + -0.7624418256949547, + -0.7433766303948928, + -0.7863147162702566, + -0.7387642466941002, + -0.725576714163906, + -0.7294721556939916, + -0.7326661834471119, + -0.7682649010531349, + -0.7829712916849253, + -0.7488038141146499, + -0.7198106431389065, + -0.7081008326244067, + -0.7559906576080972, + -0.7802394388821213, + -0.7869556970094248, + -0.7808381167845977, + -0.7891377787612494, + -0.8127289573992339, + -0.7345247131185234, + -0.6743365696973702, + -0.778785895749364, + -0.7211256018184269, + -0.7405108407122337, + -0.7279864662138086, + -0.8120772282098246, + -0.7249903380743852, + -0.754649029657757, + -0.7334170548790404, + -0.6877158498326699, + -0.7579026150026225, + -0.7968974412229282, + -0.7966318988546224, + -0.6823420116821588, + -0.765719687529785, + -0.7869670157585561, + -0.6899832144780219, + -0.7238259043560779, + -0.7113637596885162, + -0.7505249358724053, + -0.7122248168367424, + -0.6656705546579331, + -0.7237412015829119, + -0.7891018734030828, + -0.7507297988538327, + -0.782996727905639, + -0.7307539739768847, + -0.802260550780386, + -0.8028266514482325, + -0.7097300906273512, + -0.7453639999675478, + -0.7074160174740493, + -0.7320291935673744, + -0.7029560511028782, + -0.7647679946639261, + -0.6767808763278854, + -0.7138806057596462, + -0.8146692863991232, + -0.6819777720360913, + -0.6785331850372207, + -0.7070226891363003, + -0.7211898087161971, + -0.771662348891635, + -0.6687390258708819, + -0.6976380054315455, + -0.7132221610105157, + -0.6605199894357934, + -0.7056623320568997, + -0.7524324002161714, + -0.7015459131209439, + -0.7359125494017706, + -0.6921202714814172, + -0.666806865220135, + -0.7617011194176485, + -0.7536875847457383, + -0.7608389805101646, + -0.806598830766539, + -0.6733215491980302, + -0.763380180391726, + -0.700388039279875, + -0.6716090635486993, + -0.7890361991716089, + -0.6608574088898438, + -0.6784522273901789, + -0.7849937193264835, + -0.731433858308586, + -0.7178657511316396, + -0.6614971419759234, + -0.7107924162578008, + -0.7469152313451285, + -0.6783644313668784, + -0.7998239179662086, + -0.7384938322762139, + -0.7348611532731724, + -0.7869214794456628, + -0.7707688075295613, + -0.7921005496959647, + -0.6906908695415227, + -0.7843496787602396, + -0.7816413961993969, + -0.7207699719134759, + -0.8001800196798357, + -0.7838841566258118, + -0.7066775429508249, + -0.6604210988719842, + -0.6710247673292424, + -0.696723749583666, + -0.7740304502179406, + -0.7558775397088084, + -0.7036399439613457, + -0.7884837066970947, + -0.6939211314625013, + -0.7531138339322162, + -0.6758092878185594, + -0.7076237010669288, + -0.7275592127025399, + -0.8048883836753767, + -0.712788567014694, + -0.7349222213893829, + -0.7561998811927054, + -0.6606930523970591, + -0.7246217099499804, + -0.8015677485662851, + -0.7232339267988638, + -0.7933904092228733, + -0.7627195924205803, + -0.7986928013110854, + -0.6778755167851274, + -0.6681411605011304, + -0.7469489719966659, + -0.7323177322999942, + -0.6789697905904201, + -0.7146622133207896, + -0.7108037859805426, + -0.6920970729939742, + -0.7856449512314689, + -0.7495044206789842, + -0.7896254841802075, + -0.7345916259252537, + -0.768746716180541, + -0.789611634599668, + -0.7405083804050449, + -0.7913672917063534, + -0.7461761992917445, + -0.7945369024590448, + -0.7071082832606772, + -0.7112348639887496, + -0.7110603332509846, + -0.740790510829605, + -0.7683665066492832, + -0.8125263668700339, + -0.7250307539377775, + -0.6822248887567491, + -0.7822765468341532, + -0.8111152094934997, + -0.778968923071991, + -0.7004086581575973, + -0.7429310373698647, + -0.7774884157066356, + -0.7964091475543824, + -0.7179005113445704, + -0.7833586570972347, + -0.747043387157893, + -0.7415857681470452, + -0.7972799796359424, + -0.7305347171724625, + -0.7002774772123754, + -0.724192596800554, + -0.7297476887080353, + -0.7208429947591797, + -0.6697350509274907, + -0.7918579248904262, + -0.7759468652925904, + -0.7702924626083187, + -0.7755126907917859, + -0.672402999059041, + -0.7831451508237268, + -0.7591132542471709, + -0.7361893768386153, + -0.7411507269950964, + -0.6649230454095933, + -0.7672792930454481, + -0.7292113662921855, + -0.7386161196016824, + -0.8009252558405489, + -0.7177422736769368, + -0.764159548620302, + -0.7013257409351422, + -0.7113824059463504, + -0.6685029252230054, + -0.6986023180674075, + -0.697212794425147, + -0.7339726120514718, + -0.7842878867490071, + -0.7579700178341926, + -0.7781510503463753, + -0.7927146961679632, + -0.7311883390264883, + -0.8081865959233584, + -0.6846188450183727, + -0.7625744731951289, + -0.7221573305091141, + -0.7321771924796582, + -0.8039399713934013, + -0.6654485738443124, + -0.7569655603823341, + -0.6753730700477486, + -0.7569347971121814, + -0.6813504938716443, + -0.6892168814338687, + -0.7621853492000895, + -0.804246103058316, + -0.710417882482629, + -0.7380506788740471, + -0.6772180489616461, + -0.7087796805917684, + -0.6966892937032723, + -0.7049933880547565, + -0.7869222940230993, + -0.6688407894395155, + -0.7911656570753917, + -0.7435910569959452, + -0.6735456630575443, + -0.7110590666199195, + -0.6967676322084624, + -0.758936172300171, + -0.7210418733725021, + -0.7403871904064967, + -0.7359555121480165, + -0.8053870699834335, + -0.7082586083084541, + -0.7256485073514325, + -0.6717555132324282, + -0.7730768936520426, + -0.7123245922120955, + -0.7049236655820224, + -0.7821883945504453, + -0.8055288241030474, + -0.7208218281714355, + -0.6907594933896547, + -0.7615628564166433, + -0.8076290890718094, + -0.6600810349993413, + -0.6765532954169178, + -0.6812052435026779, + -0.7360322663145307, + -0.6774921528301369, + -0.7555402098526205, + -0.7562506985025329, + -0.7481230175679855, + -0.8109352920984156, + -0.809522828434831, + -0.789519636483262, + -0.8018925423115412, + -0.7878626373172004, + -0.6948223600387794, + -0.6629262415491219, + -0.786498492363722, + -0.694148899955676, + -0.6753305377171688, + -0.8101561674406709, + -0.6952168249841544, + -0.744739389196462, + -0.7753519013396009, + -0.6663732825483741, + -0.7109908827986059, + -0.7026720548345043, + -0.7344333618601154, + -0.7192872571629356, + -0.7839663316898323, + -0.7192427693571591, + -0.8084441218276454, + -0.6728631928129464, + -0.8141898044610582, + -0.7123219919169219, + -0.7172850701683341, + -0.7235542117685536, + -0.7453491748306825, + -0.7041066957294684, + -0.738637023734702, + -0.6751117281547816, + -0.7609434079655919, + -0.7733252928294513, + -0.7391946825150553, + -0.7978972554925584, + -0.8085953886387537, + -0.6742706701026637, + -0.6896881779245939, + -0.7567707685593605, + -0.781954730389963, + -0.763860229703268, + -0.6678646609392355, + -0.6751252910144083, + -0.7209659795521649, + -0.7260666938433473, + -0.7084646545427487, + -0.7722920076902159, + -0.7233573165587095, + -0.72114024693462, + -0.811994209769708, + -0.7313138232589913, + -0.685805746827782, + -0.7851581930707766, + -0.7607912431535444, + -0.8090362202677807, + -0.7097133627913706, + -0.7048478282416186, + -0.6921294699345355, + -0.725640208805393, + -0.6814859871425796, + -0.7893744433682931, + -0.7194977601107789, + -0.7202776488844339, + -0.6916927475800733, + -0.6891760429518293, + -0.7969044190549723, + -0.718794720542767, + -0.7957693354397309, + -0.6621416621865994, + -0.7461612928995878, + -0.7854920946605268, + -0.8077673324547844, + -0.6850734702994871, + -0.714412662013507, + -0.6740323507516699, + -0.7849480936198981, + -0.7265748830978288, + -0.7090444429524614, + -0.7225654037060523, + -0.7566535978129802, + -0.7672497251407902, + -0.7229277911442513, + -0.8107799963653843, + -0.7582386200699867, + -0.7891640550778517, + -0.7201379885030019, + -0.7618022000280426, + -0.8151993473682462, + -0.6920207331519646, + -0.702184967024168, + -0.6908188123832469, + -0.762136200446935, + -0.6936629396002046, + -0.6867371859242282, + -0.7123994273740932, + -0.7437898902747795, + -0.7992813264324438, + -0.794317113463664, + -0.7554084578891826, + -0.7479360247131999, + -0.7655476759020474, + -0.7165390224070756, + -0.7350789319616056, + -0.6713018772989634, + -0.7980913118386884, + -0.6742218362866654, + -0.7649398111304642, + -0.7520704144591094, + -0.7403674048044484, + -0.6783058456926958, + -0.8014943544891008, + -0.7437474909887928, + -0.7654698808242418, + -0.7041718401844974, + -0.6875085427028513, + -0.6678152353126059, + -0.7539654282397206, + -0.790921001069685, + -0.7585976010301232, + -0.6710775828226327, + -0.6788265195783298, + -0.7409927380364553, + -0.815534157242014, + -0.7331875395080014, + -0.7770167886650126, + -0.6693749300413788, + -0.7035896695588517, + -0.6860284002638348, + -0.7574713609055982, + -0.7920120509408818, + -0.7669995400701616, + -0.7042899853409208, + -0.6901011052995509, + -0.7375377135233583, + -0.8027171982118326, + -0.7788837355531758, + -0.6699696817765713, + -0.7690737911139892, + -0.6955231574888261, + -0.6759634763740403, + -0.735611721539926, + -0.6908364424816648, + -0.7832622331577449, + -0.6709967569267401, + -0.7162206128385583, + -0.7466991130448464, + -0.6633804996377675, + -0.7777963882716771, + -0.7369799398404155, + -0.7591836224313574, + -0.8006518379809809, + -0.7379865077174657, + -0.7711326427678056, + -0.7092598026120672, + -0.7666906703879091, + -0.6665168105497298, + -0.7711191132153907, + -0.6784813345689484, + -0.7975846945045995, + -0.7531449116939073, + -0.7611621705190522, + -0.7706277204390661, + -0.7382221419063071, + -0.7870496807132917, + -0.6737790761371374, + -0.7479653555316566, + -0.685215924161555, + -0.8006507959129547, + -0.8068174387644529, + -0.7194635196488061, + -0.694035560398018, + -0.7441585545463355, + -0.788825573729653, + -0.6776132462107983, + -0.6974860133229853, + -0.7255887261328248, + -0.7996825434371676, + -0.736528896882477, + -0.7323199222805412, + -0.7163350171160385, + -0.7104282847127971, + -0.8094996829119366, + -0.6718695097575313, + -0.7992548157233764, + -0.7616406208020541, + -0.7638977832560676, + -0.6698461550486514, + -0.7924255651638871, + -0.7853768024460672, + -0.7921298306559548, + -0.6966413577913394, + -0.7453753216540548, + -0.7244536196375524, + -0.8137020273762314, + -0.735039956513422, + -0.7524949266499379, + -0.6688424809166703, + -0.8036644834060788, + -0.7769780031984497, + -0.6985531931786431, + -0.7097846119915452, + -0.8097444116993268, + -0.7941425401452231, + -0.814572822449483, + -0.8074745169998926, + -0.7781138553381195, + -0.7337072292895511, + -0.7309969364605696, + -0.7479692680351608, + -0.7486341995919532, + -0.6616969340104808, + -0.699133795393928, + -0.7479689353375094, + -0.6848521870139657, + -0.798909629291144, + -0.7307129467597174, + -0.6640219850320446, + -0.7486705857810408, + -0.6675553587967697, + -0.7584370595260657, + -0.7358512619760491, + -0.7955014630915743, + -0.6916060045416389, + -0.6707967955405606, + -0.7902021674026173, + -0.7934816362381886, + -0.7375105466772836, + -0.7634567334562574, + -0.719795861153816, + -0.7043086841228582, + -0.7239494323706352, + -0.753318791532073, + -0.7868285248519464, + -0.6994864846674662, + -0.701171326051888, + -0.7074498877339405, + -0.6933984062757104, + -0.7167089910566458, + -0.7150850963197682, + -0.7876736692659748, + -0.6909812294886273, + -0.686292447001898, + -0.7755853978167426, + -0.6816411207039527, + -0.7416134412928547, + -0.7273235871970706, + -0.6856454239779612, + -0.8151957995716588, + -0.7365440974254582, + -0.7597401073917449, + -0.6848491823613744, + -0.7461571103407296, + -0.6803872079574149, + -0.8073105570143347, + -0.7228511038913246, + -0.675374291749858, + -0.7607248994781708, + -0.696104287805668, + -0.7863530211006788, + -0.7673275413709892, + -0.6985830992826282, + -0.6952864144130431, + -0.6609413975378597, + -0.7495513482334252, + -0.7280883899789921, + -0.8038242085216082, + -0.7439918169227219, + -0.6680825037555698, + -0.7535240885403038, + -0.7544054145603613, + -0.7980848693223017, + -0.6682291785116141, + -0.7920982057706376, + -0.7488682930350705, + -0.7662707955445659, + -0.7425320254805948, + -0.7759594179839332, + -0.779921816550078, + -0.7515933863897737, + -0.8101063602113888, + -0.6631203916340819, + -0.7043715852024258, + -0.6709383166384333, + -0.6742771530122732, + -0.6952915324332497, + -0.7517326897259435, + -0.6863629757507564, + -0.8054158817746618, + -0.6657711851319124, + -0.809478285063842, + -0.7945879859409238, + -0.7472267815630131, + -0.7398562906894905, + -0.680602723099934, + -0.69589910564426, + -0.7159386130109966, + -0.7648766309267039, + -0.7228354665440635, + -0.7124712019967713, + -0.674084142871464, + -0.6874740836228741, + -0.7273123575159471, + -0.7480530988558753, + -0.739401153337559, + -0.7917459446911628, + -0.6608669462430015, + -0.7269306436744725, + -0.8059579112793672, + -0.7430948283453122, + -0.6921331414936251, + -0.6680883695432709, + -0.8068276449699763, + -0.7790901742330085, + -0.6779941284059341, + -0.76374330053932, + -0.6749608894421216, + -0.7256674170253076, + -0.8143832303424023, + -0.7842606725529184, + -0.6961665050731126, + -0.7033193968536469, + -0.7665277635100296, + -0.7015714143231429, + -0.7311400945839854, + -0.8006945678488328, + -0.6907831707242142, + -0.7193911769166605, + -0.8084027965901199, + -0.7258540501737034, + -0.799169199255396, + -0.720846182677373, + -0.6940046493519433, + -0.739093677098169, + -0.7332387305063791, + -0.7563100735937504, + -0.789291492552848, + -0.7637660711871789, + -0.7538261803495147, + -0.7897202283086658, + -0.6895146886024994, + -0.6702249360757374, + -0.7397820156293914, + -0.7833294015692143, + -0.7202313957349916, + -0.7588035637801989, + -0.7925573573645549, + -0.7385279280999516, + -0.7616806708296937, + -0.6744819427381095, + -0.8156479834121129, + -0.7652841388220714, + -0.779550034913175, + -0.7759490401063482, + -0.7069167632400244, + -0.7006235855999146, + -0.7471577979537544, + -0.7609676774903695, + -0.7744659003716905, + -0.7512049155863658, + -0.8105902032891801, + -0.7719075378947243, + -0.7289284259271563, + -0.759201676947333, + -0.7979102570741325, + -0.6925943826267034, + -0.6639668410536362, + -0.6922496120135074, + -0.753211792856081, + -0.7003605149225384, + -0.8114725945566976, + -0.7141548686339305, + -0.7859011516838421, + -0.7142914375943187, + -0.7464329873741369, + -0.6966943305471964, + -0.7537626823444261, + -0.8023313622803704, + -0.7397344753990249, + -0.7333027275363782, + -0.7417511929536079, + -0.760245056271606, + -0.7645600082650756, + -0.6676411960405398, + -0.8102276453537338, + -0.815323913916526, + -0.7729895260463084, + -0.7475586591846453, + -0.7269168091336567, + -0.8118066065924378, + -0.7871905452523927, + -0.746322456895828, + -0.7045757878253148, + -0.6715442617646893, + -0.6722881523155182, + -0.6803105644107678, + -0.6641146410487323, + -0.7797820899969509, + -0.6845460604112699, + -0.6616761519297927, + -0.8073332043805855, + -0.7315637034760089, + -0.7718365230418186, + -0.7191397757902757, + -0.7044921911463197, + -0.7570189073235523, + -0.8076048287888096, + -0.6785143952105636, + -0.7227045424538657, + -0.812015316525915, + -0.757215786969652, + -0.6817386742323992, + -0.7416469172249968, + -0.6660711863232678, + -0.7470010324523257, + -0.7525580438148972, + -0.7923666203018562, + -0.7042688267621394, + -0.7898529180874823, + -0.7678223150282001, + -0.664935577830323, + -0.6936748083532766, + -0.7631017621908616, + -0.7473894345010683, + -0.7380275266004227, + -0.7886839720399822, + -0.7378093034782666, + -0.7472376448587381, + -0.8051321031584049, + -0.8110747210319684, + -0.6609821049256829, + -0.7721559031881661, + -0.7893711061469992, + -0.6999006642855621, + -0.7076222407325159, + -0.6685511033267892, + -0.809240161189783, + -0.6655208850866088, + -0.739026411416954, + -0.7963444367956436, + -0.8081164663834056, + -0.72032459768892, + -0.7355274263443945, + -0.6843452267515566, + -0.7990908702421574, + -0.7366853505144904, + -0.715066685888336, + -0.7981727449479343, + -0.6745028752484269, + -0.7082040248305961, + -0.7590333988462072, + -0.7521209445368177, + -0.7530286184999782, + -0.7298481148477911, + -0.669990955587965, + -0.7507983716651775, + -0.6927505596289146, + -0.7482208220478873, + -0.674897801455238, + -0.7873849008776853, + -0.7907391212826408, + -0.7845041825994967, + -0.7225689879537186, + -0.6684478629300616, + -0.7561669176494803, + -0.7028205810621556, + -0.6687744108083195, + -0.799799330236145, + -0.7275423127737011, + -0.7586237645137655, + -0.7609781913118755, + -0.771510299338216, + -0.6748468042892403, + -0.6825076498401257, + -0.6933669223679276, + -0.747146936075497, + -0.772887699227852, + -0.7088680211421045, + -0.6829141117630039, + -0.7085954603803464, + -0.7130120746959817, + -0.7198887547259835, + -0.7064964034347083, + -0.7440791411380815, + -0.6775169028584438, + -0.6613510511352116, + -0.7230236893214413, + -0.7442894293170874, + -0.7593054521278263, + -0.7855545842477533, + -0.7969412733925133, + -0.7673897656272093, + -0.7798318316113466, + -0.7666409966077694, + -0.8038823482078532, + -0.6773810823938471, + -0.6671922426693022, + -0.6967981914705655, + -0.6804669269366902, + -0.721322992449015, + -0.7659174699750609, + -0.7231993070927535, + -0.7294364356297915, + -0.738817039845884, + -0.6716821968060405, + -0.7238464075739066, + -0.7896098973553037, + -0.6873420657074807, + -0.7822499541273014, + -0.7915872070184544, + -0.7562580479588608, + -0.6623073521951508, + -0.6647318697118932, + -0.8020902993376984, + -0.7404520181585241, + -0.7584048388518329, + -0.8108459309306724, + -0.7009851037495519, + -0.702190035229582, + -0.792873387122339, + -0.7334653630639111, + -0.6610109536318165, + -0.7204067375741948, + -0.7527495585362146, + -0.7900942957982375, + -0.7696692096011256, + -0.734559945613857, + -0.7730488926562771, + -0.7696891463396547, + -0.7567200910704783, + -0.7834166172255321, + -0.7736618637799031, + -0.7587407800634497, + -0.7979207779416013, + -0.7245163572926223, + -0.7760765229218346, + -0.7151399876890636, + -0.7853666319058881, + -0.7673072235012707, + -0.7839665843967559, + -0.6868567280070883, + -0.7725946249518111, + -0.7032196371214802, + -0.757434018204111, + -0.7408957401680595, + -0.7160024917088977, + -0.678608593963779, + -0.7661714815078614, + -0.7412330598530315, + -0.7175714293290183, + -0.6962383401998063, + -0.6657412806399113, + -0.6749390733440968, + -0.7732674383544484, + -0.7848380650222793, + -0.7658004336421074, + -0.7385320622257779, + -0.7781441257310848, + -0.7166068932273608, + -0.6762640312119835, + -0.7482922942811147, + -0.694671274557151, + -0.6972165743731179, + -0.7610039666762874, + -0.8029605513163065, + -0.7760317977031234, + -0.6779469470711875, + -0.6837717434897973, + -0.7753611836093476, + -0.7332243448218394, + -0.7823638352954004, + -0.6867010465670567, + -0.6641221986430135, + -0.8035226060729984, + -0.7131209824429312, + -0.7763889777489072, + -0.7959199308472168, + -0.6657335857648137, + -0.7978395910136455, + -0.7569377051935592, + -0.7419108626608997, + -0.6975601743389677, + -0.7144944415360238, + -0.7213179163220133, + -0.7867735257783568, + -0.7738475086638249, + -0.6811973604759036, + -0.6932726313796788, + -0.6839455360698251, + -0.7805623453661955, + -0.8065288669973387, + -0.7374294458033301, + -0.7601267532405971, + -0.7133225712784229, + -0.6840677497190332, + -0.7738821516639494, + -0.69519080529227, + -0.7936905833213058, + -0.7865492155906325, + -0.6775908177302437, + -0.6888585310634245, + -0.7430508488287615, + -0.7176298891023197, + -0.7914495456360096, + -0.7345829949774273, + -0.7058280007457365, + -0.7637949273512119, + -0.6811644337664735, + -0.7862755730959412, + -0.789888837078046, + -0.7501445619009478, + -0.717023938115372, + -0.7564981013555313, + -0.7143889262456586, + -0.7544538555258276, + -0.6841240669820174, + -0.8079282872471086, + -0.7259344733886298, + -0.7871428018392196, + -0.7064052833168326, + -0.7834469134721398, + -0.703299522857611, + -0.77165705268337, + -0.804331176332066, + -0.6758622155910567, + -0.7253439737233871, + -0.7401380157726732, + -0.8090916618726461, + -0.7593050623602496, + -0.7903052189479113, + -0.6723134380994852, + -0.749933018599006, + -0.6740417273858782, + -0.7125048488041164, + -0.7764074326818238, + -0.7275232901501398, + -0.7280347095678024, + -0.7564317773356382, + -0.7876561730283542, + -0.7042709839127806, + -0.698752533500776, + -0.7580849206538925, + -0.6711520026779831, + -0.7316230214275222, + -0.7319371351162093, + -0.8092622986729481, + -0.6813482966302704, + -0.6884375659187809, + -0.7867770834822041, + -0.7967393578702425, + -0.7180084914913767, + -0.6897450624002903, + -0.7035576707850186, + -0.7154045869431749, + -0.8042640116613923, + -0.6709690649392271, + -0.755814751622787, + -0.7325324112173585, + -0.6677280268627298, + -0.7178684328147948, + -0.6960090841273272, + -0.7997727108044017, + -0.7226630170623306, + -0.7494518830991882, + -0.7996661459362268, + -0.811238387929563, + -0.7282261202609472, + -0.8010441580538108, + -0.671618209282425, + -0.6864804879764812, + -0.7170105202128937, + -0.7068376612404297, + -0.716845811303713, + -0.7157044206897659, + -0.7839004145589016, + -0.7704982661152396, + -0.8108533474576174, + -0.773452566326907, + -0.6775618652489764, + -0.8053366747647436, + -0.6705200825585502, + -0.684571675597338, + -0.7740528519616242, + -0.6828552681943351, + -0.8020560738952037, + -0.7719597002084252, + -0.7981800306217254, + -0.6871224475831841, + -0.7403830977652541, + -0.809031287240534, + -0.7787550760527734, + -0.8116432653995357, + -0.6938152714273699, + -0.6693539615313849, + -0.6711228895089083, + -0.8001598298638656, + -0.6800721473502925, + -0.702268545321733, + -0.72839740808505, + -0.7807120972910261, + -0.7906009041781643, + -0.7889812941102624, + -0.7823850949670232, + -0.675441666778349, + -0.745383831375856, + -0.6961982439067094, + -0.7482229753026669, + -0.7391455090713909, + -0.695281098609174, + -0.6761859495237563, + -0.702342690097608, + -0.7521543281012935, + -0.6787606544179371, + -0.6741198908303869, + -0.7771006361752744, + -0.7025269489381344, + -0.7295193554658008, + -0.6827177902237429, + -0.7627060557346143, + -0.6831310295266128, + -0.7642024266741264, + -0.7459952084243345, + -0.7413645972938903, + -0.8059190863032628, + -0.7767740927513767, + -0.7737740299112782, + -0.6747698410293389, + -0.7726760568262148, + -0.7440049767489255, + -0.7145836200462206, + -0.8037060755972474, + -0.8008540869060116, + -0.8103021758083492, + -0.7245239138212888, + -0.7756423269858395, + -0.7165402912537571, + -0.8130520148616087, + -0.7609724512370509, + -0.7671360788665742, + -0.7203957210024812, + -0.7389825221105745, + -0.7754924865822498, + -0.7116616464966546, + -0.7113317467240474, + -0.7441400933063106, + -0.7929971099172384, + -0.7049709766937762, + -0.7498007815719786, + -0.8011603928000367, + -0.72820607511402, + -0.6711779495395445, + -0.7833686904958705, + -0.7683669675481856, + -0.7237157143618207, + -0.6858889672005607, + -0.7779314008339426, + -0.7539070079629705, + -0.664749787594006, + -0.8010774850781952, + -0.6862611987729618, + -0.6986222620279169, + -0.7414651135448379, + -0.6960040394248774, + -0.6767214103331891, + -0.7873875041333842, + -0.7523184647161997, + -0.7326670067739, + -0.805860594989696, + -0.6961290229295439, + -0.7554130548278765, + -0.779637179429998, + -0.6698506755168634, + -0.7036138553968223, + -0.7531952794860022, + -0.7361185324016352, + -0.6842620279474738, + -0.7874692886435567, + -0.688506548016679, + -0.7267685852223045, + -0.6788548077470175, + -0.752070426083661, + -0.8076633350999096, + -0.7453281029638801, + -0.7539901981904893, + -0.690981322899291, + -0.8107074735491978, + -0.7216253490826241, + -0.7826894505478006, + -0.7109696766917752, + -0.7026192763057685, + -0.6751304026735714, + -0.7958810141812896, + -0.6845028449832584, + -0.7691422566675149, + -0.6832338633569981, + -0.6810636205676004, + -0.7677169475134674, + -0.6608167911050804, + -0.7598632578561842, + -0.7118618359915722, + -0.6681982889206732, + -0.7583992720528402, + -0.7510639918157515, + -0.6621945685774276, + -0.7180329380540053, + -0.8028193065951913, + -0.6858100923592535, + -0.7409985694428425, + -0.6914386293463477, + -0.674048889017738, + -0.7134579577455108, + -0.8140423410608525, + -0.755984836656482, + -0.8143172487124404, + -0.7079966111565369, + -0.784054084593132, + -0.675355925440501, + -0.7031664503907998, + -0.7564669070808995, + -0.8045173513382066, + -0.8101826537582486, + -0.6779381788727005, + -0.7206160086949251, + -0.8142293905909775, + -0.6666509209761522, + -0.7290592399426231, + -0.782725684071632, + -0.7364193181588419, + -0.6752434039498209, + -0.715605606576967, + -0.7815648962046593, + -0.7244500207686173, + -0.6854656183210095, + -0.81497956132002, + -0.7498672885960397, + -0.692740349892571, + -0.747437022371706, + -0.7098854733011941, + -0.8029561571617029, + -0.7434536112407483, + -0.7532551242735857, + -0.6920722363354338, + -0.7864599740753615, + -0.661115929108175, + -0.7766139770549453, + -0.8101091945477459, + -0.6891476356631573, + -0.7763250837495732, + -0.7953153483598608, + -0.7012227615337543, + -0.6804537196974064, + -0.8054602121621078, + -0.7062535434468625, + -0.7443174048340138, + -0.673511510845869, + -0.7555132907156367, + -0.6762995750703592, + -0.6679076963901314, + -0.6855513054900837, + -0.685821056653808, + -0.7205667202341297, + -0.6687442766029219, + -0.7419288711922405, + -0.765337126932476, + -0.7480448514849999, + -0.7499925537725918, + -0.7307831766199997, + -0.762187835124605, + -0.7455103959959638, + -0.8017247868890359, + -0.6987894299159023, + -0.660622986800712, + -0.7129013483721469, + -0.7030085834353939, + -0.8059414101422538, + -0.7801367607980806, + -0.6788055915429384, + -0.7219989260967355, + -0.7132406037232293, + -0.6851236252754729, + -0.8153083129657929, + -0.7221936398058819, + -0.8127507429087598, + -0.802007907445374, + -0.6734118162868469, + -0.7757462320007334, + -0.7679475158118978, + -0.739546768170424, + -0.7473674110391431, + -0.7926445179045324, + -0.7441136971752165, + -0.7642226410556974, + -0.8131041084512959, + -0.8093113350113457, + -0.7160144377001774, + -0.6876783292412365, + -0.6920045201653402, + -0.6842827352948712, + -0.6666392787951295, + -0.713488720202082, + -0.8024561366262903, + -0.687175941006638, + -0.7131388269099054, + -0.6804266143309616, + -0.6829575157976688, + -0.7423246449576596, + -0.7296825625367235, + -0.7927371931181114, + -0.8085887985228225, + -0.8034847574729669, + -0.7985423384711645, + -0.6823699689474295, + -0.7892755811317151, + -0.7562244986804998, + -0.8099485428036278, + -0.7186009825581647, + -0.7136113690539936, + -0.8073775819393868, + -0.7600002119066649, + -0.7366694521936535, + -0.769404638369748, + -0.746059260286872, + -0.6967389411336404, + -0.7678713902090439, + -0.7868009177694555, + -0.756207589341713, + -0.7367987324984208, + -0.6912330854053816, + -0.6728876397258114, + -0.7906249879053281, + -0.7644026910972239, + -0.6747643631005855, + -0.6769183443031411, + -0.7830655655868142, + -0.7137735480365666, + -0.8045989320955504, + -0.6762204512284646, + -0.7527225304484844, + -0.6959232064556172, + -0.7963634319717626, + -0.7204928920867572, + -0.7063702051909156, + -0.8104213483342828, + -0.6714200035592418, + -0.8006343315005244, + -0.808707419438853, + -0.7590459998119148, + -0.6665546199275185, + -0.7141860183893198, + -0.6676582573856752, + -0.8003892645013453, + -0.7759177146697375, + -0.754975988964665, + -0.7941869567729821, + -0.7673063505837635, + -0.7018730612466306, + -0.8015427913816999, + -0.662272527410531, + -0.7335811638141178, + -0.7304331378121316, + -0.6978670139538683, + -0.7623375949475877, + -0.6881653581368559, + -0.7106299094863013, + -0.7145345887761397, + -0.7935052508939953, + -0.8093496326564182, + -0.7633843842236946, + -0.6693179124680024, + -0.8039930642667963, + -0.7429160242517123, + -0.7920449985178777, + -0.7907591595110737, + -0.6782604049343581, + -0.7822601339074485, + -0.7856459158676546, + -0.6615406230849472, + -0.6701567779313664, + -0.7363718886269895, + -0.8013817808424463, + -0.7424964812580268, + -0.7996502830926292, + -0.7100161598251998, + -0.7848851874066466, + -0.6622447726078309, + -0.7971196112676326, + -0.6609526793018816, + -0.7359812190823524, + -0.7850344510449447, + -0.6635048318245536, + -0.6722700809946347, + -0.8097259922504443, + -0.7506643302069209, + -0.7729687105384623, + -0.7390314855238237, + -0.6859633146135523, + -0.6618127118689163, + -0.7772857691994737, + -0.7727658161085331, + -0.6740742388989777, + -0.7008853674319984, + -0.6966010409403499, + -0.763983089659523, + -0.7378223000987226, + -0.7054242673542576, + -0.7557792486763717, + -0.721853628259479, + -0.7958138071197088, + -0.7357987842195075, + -0.7266877361589086, + -0.7549400846771759, + -0.7080779995565673, + -0.7295138030353974, + -0.7757584284568817, + -0.6866992483865932, + -0.7290313103403723, + -0.6744983646377556, + -0.666172485417819, + -0.6612567083427433, + -0.7406440723111533, + -0.6758680448785717, + -0.6918495354980925, + -0.8076518919846918, + -0.784507147159672, + -0.7789566705116933, + -0.7773618516234327, + -0.7531562981376219, + -0.776158108952197, + -0.7309644692944952, + -0.796191709522725, + -0.7616099586722763, + -0.7980055886974053, + -0.7081575859953537, + -0.7484416429391999, + -0.7815527537261716, + -0.7655814921764652, + -0.7866134959206026, + -0.8107477958579912, + -0.7501626737680764, + -0.6883558364186203, + -0.6994897119696472, + -0.66680926210344, + -0.7514115049539742, + -0.7309307888212475, + -0.7729907382777383, + -0.6708650673155354, + -0.7260682588516252, + -0.7272801078294147, + -0.6631185868352933, + -0.7386489737797718, + -0.7979358084142633, + -0.8014336742211753, + -0.7716773817414699, + -0.8142323140845713, + -0.7231408703074783, + -0.6992796539674507, + -0.7699571879773831, + -0.69325386961385, + -0.7894601271801788, + -0.6946696233558793, + -0.6727967939360586, + -0.6875497177696569, + -0.7199656516662891, + -0.7063950755221037, + -0.748085020631708, + -0.7325977012472661, + -0.781023431156203, + -0.8050114451523405, + -0.6899891968222074, + -0.7406432095639056, + -0.7893626094789421, + -0.7934848637023069, + -0.7696451441957809, + -0.7927098527064251, + -0.702960794978946, + -0.7965294235483429, + -0.660118736071805, + -0.7153833349077348, + -0.6725938724685712, + -0.6944540354294951, + -0.7137370490293121, + -0.7207599353873562, + -0.7175642536968843, + -0.666228803028104, + -0.719286403293628, + -0.7025013984383981, + -0.6613760074732262, + -0.7150227635655038, + -0.7552480952207332, + -0.8085579829625927, + -0.7356572456803975, + -0.7445934402203505, + -0.7023527516230365, + -0.6685850170966552, + -0.6920209377690447, + -0.7380014917174742, + -0.7983431790106115, + -0.6620122691448233, + -0.8053791804359826, + -0.737012318538733, + -0.7849181056442979, + -0.725274496741997, + -0.7292988135941106, + -0.7743018452164439, + -0.7358113156607451, + -0.6699871993860849, + -0.679515569171744, + -0.7356845546935682, + -0.7172469395407431, + -0.8062696489615516, + -0.7525120143265247, + -0.7522565430677777, + -0.6719264039115227, + -0.7964764492854703, + -0.7642495664950247, + -0.8037767748800273, + -0.7371417433749333, + -0.750835466377189, + -0.7301750674208866, + -0.7576343266395776, + -0.7917476658408721, + -0.7470482662109825, + -0.7403291794762553, + -0.7422629139591508, + -0.7769799568263306, + -0.6843647951219842, + -0.7019607746121618, + -0.7246957745778003, + -0.7098207061931783, + -0.8085593882723588, + -0.7742835409446713, + -0.7281573592228834, + -0.7379156372740419, + -0.7955396508668157, + -0.7562549952716436, + -0.6653449669022728, + -0.7725992463388142, + -0.81146325108019, + -0.812460430477791, + -0.7038101948684662, + -0.6716640734570533, + -0.7511494031359737, + -0.7228655454311872, + -0.676071001595464, + -0.81345080240042, + -0.663801165194905, + -0.728884376197255, + -0.7448639995875606, + -0.8047400130681377, + -0.751277408507601, + -0.7853287619045813, + -0.6975898987920988, + -0.7597326984569063, + -0.6844266233033187, + -0.7762014801731147, + -0.6940209198273313, + -0.7949919942573866, + -0.7273384493099005, + -0.7008160184000447, + -0.7509066049791655, + -0.7660565896268249, + -0.7396186333658159, + -0.6881714376138341, + -0.8022502364082656, + -0.6695327623443953, + -0.8144778087486102, + -0.6896977096404038, + -0.7390048876158067, + -0.6708348042329467, + -0.6614345917495255, + -0.7873591817749991, + -0.7991454711513853, + -0.7692413833624735, + -0.6690214736166991, + -0.7294434142587649, + -0.6821440060867868 ], "type": "scatter" }, @@ -62139,10 +62369,10 @@ "mode": "markers", "name": "Expectation", "x": [ - 0.4741729497909546 + 0.5159507647804554 ], "y": [ - -0.22661489248275757 + -0.3701098465795569 ], "type": "scatter" }, @@ -62151,31 +62381,31 @@ "mode": "lines+markers", "name": "Mode", "x": [ - 0.3408585786819458, - 0.6074873208999634, - 0.6074873208999634, - 0.3408585786819458, - 0.3408585786819458, + 0.44, + 0.6633025782322575, + 0.6633025782322575, + 0.44, + 0.44, null, - 0.3408585786819458, - 0.6074873208999634, - 0.6074873208999634, - 0.3408585786819458, - 0.3408585786819458, + 0.44, + 0.6633025782322575, + 0.6633025782322575, + 0.44, + 0.44, null ], "y": [ - -0.29881715774536133, - -0.29881715774536133, - -0.1544126272201538, - -0.1544126272201538, - -0.29881715774536133, + -0.697788532493164, + -0.697788532493164, + -0.66, + -0.66, + -0.697788532493164, null, - -0.29881715774536133, - -0.29881715774536133, - -0.1544126272201538, - -0.1544126272201538, - -0.29881715774536133, + -0.697788532493164, + -0.697788532493164, + -0.66, + -0.66, + -0.697788532493164, null ], "type": "scatter" @@ -62183,17 +62413,25 @@ ], "layout": { "title": { - "text": "JPT" + "text": "Marginal View of relative x and y position with respect to the milk" }, "xaxis": { "title": { "text": "relative_x" - } + }, + "range": [ + -1, + 1 + ] }, "yaxis": { "title": { "text": "relative_y" - } + }, + "range": [ + -1, + 1 + ] }, "template": { "data": { @@ -63025,21145 +63263,69 @@ "plotlyServerURL": "https://plot.ly" } }, - "text/html": "
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" } ], "source": [ - "modes, likelihood = model.mode()\n", - "mode = modes[0]\n", - "mode_model, _ = model.conditional(mode)\n", - "mode_xy = mode_model.marginal([relative_x, relative_y])\n", - "fig = go.Figure(mode_xy.root.plot_2d(), mode_xy.root.plotly_layout())\n", - "fig.show()" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-12T16:15:43.819932Z", - "start_time": "2024-03-12T16:15:43.324066Z" - } - }, - "id": "eac2e7e063da5b10", - "execution_count": 8 - }, - { - "cell_type": "code", - "outputs": [], - "source": [ - "# fpa.policy = mode_model\n", - "# fpa.sample_amount = 500\n", - "# with simulated_robot:\n", - "# fpa.try_out_policy()" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-12T16:15:43.822414Z", - "start_time": "2024-03-12T16:15:43.820834Z" - } - }, - "id": "1217769a7ed0ab5b", - "execution_count": 9 - }, - { - "cell_type": "code", - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n", - "Unknown tag \"material\" in /robot[@name='apartment']/link[@name='coffe_machine']/collision[1]\n" - ] - } - ], - "source": [ - "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"apartment.urdf\")\n", - "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", - "model.root.update_variables({relative_x: relative_y, relative_y: relative_x})\n", - "\n", - "# milk.set_pose(Pose([3.2, 3.15, 1.04], [0, 0, 1, 1]))" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-12T16:15:46.316401Z", - "start_time": "2024-03-12T16:15:43.823070Z" - } - }, - "id": "90d7cb5e1e1cc7fd", - "execution_count": 10 - }, - { - "cell_type": "code", - "outputs": [], - "source": [ - "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", - "fpa = FunkyPickUpAction(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value], policy=model)\n", - "fpa.sample_amount = 200" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-12T16:15:46.320004Z", - "start_time": "2024-03-12T16:15:46.317282Z" - } - }, - "id": "ea11db8c3db4075e", - "execution_count": 11 - }, - { - "cell_type": "code", - "outputs": [ - { - "data": { - "application/vnd.plotly.v1+json": { - "data": [ - { - "hovertext": [ - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 5.963717193567754", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 5.963717193567754", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 8.805685480602348", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 8.805685480602348", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 21.567555592524567", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 15.603838398956814", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 21.567555592524567", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 15.603838398956814", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 15.603838398956814", - "Likelihood: 30.373241073126916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 50.9631055879433", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 56.92682278151106", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 50.9631055879433", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 30.373241073126916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916", - "Likelihood: 24.40952387955916" - ], - "marker": { - "color": [ - 56.92682278151106, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 56.92682278151106, - 56.92682278151106, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 56.92682278151106, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 56.92682278151106, - 56.92682278151106, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 56.92682278151106, - 56.92682278151106, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 56.92682278151106, - 56.92682278151106, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 56.92682278151106, - 30.373241073126916, - 30.373241073126916, - 56.92682278151106, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 56.92682278151106, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 56.92682278151106, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 56.92682278151106, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 56.92682278151106, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 56.92682278151106, - 5.963717193567754, - 5.963717193567754, - 56.92682278151106, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 5.963717193567754, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 5.963717193567754, - 30.373241073126916, - 56.92682278151106, - 56.92682278151106, - 5.963717193567754, - 30.373241073126916, - 56.92682278151106, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 5.963717193567754, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 56.92682278151106, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 56.92682278151106, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 30.373241073126916, - 50.9631055879433, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 56.92682278151106, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 50.9631055879433, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 50.9631055879433, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 50.9631055879433, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 30.373241073126916, - 8.805685480602348, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 8.805685480602348, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 8.805685480602348, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 21.567555592524567, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 15.603838398956814, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 15.603838398956814, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 21.567555592524567, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 15.603838398956814, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 15.603838398956814, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 15.603838398956814, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 15.603838398956814, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 15.603838398956814, - 30.373241073126916, - 56.92682278151106, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 50.9631055879433, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 30.373241073126916, - 24.40952387955916, - 56.92682278151106, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 50.9631055879433, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 30.373241073126916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916, - 24.40952387955916 - ] - }, - "mode": "markers", - "name": "Samples", - "x": [ - 0.45915172942014404, - 0.5474996426980006, - 0.5491974909294062, - 0.49038497469498227, - 0.5279689831728162, - 0.7030391939757641, - 0.759680234047925, - 0.6479476081440215, - 0.7237797408089242, - 0.5894109231015993, - 0.7719438843109594, - 0.576461957925967, - 0.8065781003289041, - 0.5550819457863128, - 0.5044674182217166, - 0.48186732833458834, - 0.6715370858541645, - 0.5750425529677408, - 0.6506834234232752, - 0.4676445092230069, - 0.610430494489527, - 0.5027172422472963, - 0.600478408058785, - 0.6524530415346526, - 0.742621773863327, - 0.4523068549090507, - 0.4543529843468379, - 0.5847415238520016, - 0.7415030467913204, - 0.5004822417760282, - 0.6162129313205793, - 0.5971915123122298, - 0.776362461311499, - 0.49587766351711404, - 0.5110378646169509, - 0.7620443082464161, - 0.4579965870077458, - 0.5534580408537453, - 0.7745760139616513, - 0.5379501298065366, - 0.5740798217927998, - 0.6924137164558318, - 0.4702367645606388, - 0.7093579578254097, - 0.7044635983762502, - 0.6128903517060786, - 0.4448302214095761, - 0.44372310927534075, - 0.7064843930454545, - 0.5438948403394119, - 0.5785273313286909, - 0.5024063915428711, - 0.5707072455614297, - 0.4538377396840833, - 0.45517608648228086, - 0.7811137452370926, - 0.6595261302383874, - 0.757524082539657, - 0.7816859211845498, - 0.6549073863868689, - 0.5839372389955572, - 0.5931531999624207, - 0.5047436617952118, - 0.6926425050605554, - 0.7486580415943709, - 0.6675618490346937, - 0.8079523836120788, - 0.8059621124183991, - 0.7732445322846089, - 0.48846627363865325, - 0.45070148977928576, - 0.4455966796203828, - 0.760965635451365, - 0.7647234684089693, - 0.7248928319836295, - 0.698277426442458, - 0.49898372853343, - 0.7329972417642002, - 0.5729445473174256, - 0.7543221841829479, - 0.5588383559881107, - 0.4486438691604228, - 0.5849465719958549, - 0.4720804565919624, - 0.4587176130050891, - 0.6225117031981043, - 0.7208039279689673, - 0.5368010021047627, - 0.7785092733162661, - 0.5734391861669699, - 0.7476080542538643, - 0.6932889373127942, - 0.5995720914630349, - 0.48860277312825384, - 0.6619678966965956, - 0.7273043097332906, - 0.48465530611651747, - 0.6751359006912228, - 0.6686502117411932, - 0.4737746803893892, - 0.5820942353835656, - 0.5218684296704388, - 0.7045792317280195, - 0.49241387531621905, - 0.5846871266004925, - 0.6536239197490125, - 0.4828802903306827, - 0.6335339744287175, - 0.6787110603199681, - 0.6701160766443937, - 0.47483638134876616, - 0.5629960900408019, - 0.6990784672034445, - 0.4847090819899131, - 0.792598668596941, - 0.45298756034555115, - 0.7529084232409268, - 0.4892408060250163, - 0.5807892237856797, - 0.5880678715866807, - 0.759754863366052, - 0.7718471443839194, - 0.7153970809924197, - 0.5112722711198183, - 0.7012410825143068, - 0.4559926985590271, - 0.7728801621351752, - 0.7042440548614342, - 0.8018969006787677, - 0.4647635723616219, - 0.80346176296344, - 0.761272756378317, - 0.5234792834484003, - 0.7800773525210534, - 0.5544152747598988, - 0.6959074213108739, - 0.667215609108354, - 0.7795268818934666, - 0.7372947615156666, - 0.7812394866183572, - 0.5839035853384069, - 0.5046707851772894, - 0.7519356964234671, - 0.578294753039893, - 0.5233705349594879, - 0.7875688924346962, - 0.5893688228863219, - 0.8094432005735951, - 0.7935884632626597, - 0.49276635127015467, - 0.5042019865685257, - 0.7551273602697519, - 0.48145566756046376, - 0.6062646617853498, - 0.5211932679557031, - 0.5792574047935624, - 0.5854149458887994, - 0.5989701502220779, - 0.7676355059957471, - 0.6402170365632303, - 0.5297721011115936, - 0.5112840533387845, - 0.5827809152599129, - 0.47996813978242614, - 0.7000626876932636, - 0.7990890854303743, - 0.8004964617763388, - 0.5630029918667978, - 0.573488001894978, - 0.757671074026981, - 0.5858144992919604, - 0.693851626241013, - 0.7366567560673933, - 0.48920868436769904, - 0.6694390088323926, - 0.6606040256843997, - 0.5578357314536906, - 0.6007839941609416, - 0.7177044383889928, - 0.4604384510211469, - 0.7973740131405158, - 0.7693324177676449, - 0.5224752111951413, - 0.5103232376996193, - 0.6248277298986886, - 0.6818946746657637, - 0.5094063506026164, - 0.5278839244631531, - 0.48967109524252156, - 0.45678779866963604, - 0.5585078167542308, - 0.6824438472327676, - 0.4711431954053256, - 0.5423148930511887, - 0.8106743292948408, - 0.5868498282565582, - 0.58404619163873, - 0.5191346948786933, - 0.5542930039676826, - 0.6413822090306387, - 0.6757954877655398, - 0.7439135456483905, - 0.7534778748139308, - 0.539315966519224, - 0.6038889685452483, - 0.7706925679485126, - 0.6844618828123, - 0.46545028167518854, - 0.5422205694285763, - 0.45141188318918773, - 0.7121137505453047, - 0.7047224865752487, - 0.4541747227612868, - 0.7196227230488328, - 0.5767420359755995, - 0.6737472798263112, - 0.6117750470795489, - 0.6306599433380427, - 0.794474400328349, - 0.6815694381503548, - 0.7498601912525553, - 0.5356883163228262, - 0.5032732996692326, - 0.7291990212918573, - 0.7584491093541543, - 0.5335621364458878, - 0.45273470248091763, - 0.46354984550350337, - 0.7325965282092202, - 0.5405344935309341, - 0.4501729329666017, - 0.5135637191389945, - 0.552080814762125, - 0.6039429417037339, - 0.7455635232489911, - 0.5068172696444593, - 0.5294362176372115, - 0.5088538176979888, - 0.6661785991579204, - 0.6817748702636058, - 0.5878470447913309, - 0.45633853181533385, - 0.505337402549344, - 0.6363590359971558, - 0.6296220464968598, - 0.5598957608305999, - 0.6118663268007817, - 0.6310153300153312, - 0.44121190919021436, - 0.6573426763655302, - 0.5843240268345018, - 0.5449404670042817, - 0.4789725049283129, - 0.6579695117703075, - 0.609721697712851, - 0.6156954578488913, - 0.5811570745025254, - 0.5233140541165554, - 0.5575846437174007, - 0.4995345174783796, - 0.5433183193388017, - 0.645931519521048, - 0.5398275838431909, - 0.6652492567977284, - 0.45662271624723844, - 0.5617353855038281, - 0.5238278806017145, - 0.6652013717936065, - 0.46385783218387927, - 0.5209661704630084, - 0.6072618340423501, - 0.6179422061324842, - 0.5685167273270858, - 0.4904155586915656, - 0.5716975251581004, - 0.5238995606607026, - 0.6160647983683756, - 0.6013271437420604, - 0.657694988939556, - 0.5750511943248195, - 0.6722790504467915, - 0.5852420074723219, - 0.6854195616667168, - 0.4926382164178246, - 0.46708265397682536, - 0.612264438269355, - 0.5736732891282674, - 0.6336610289032865, - 0.6596796061940504, - 0.5670262823746751, - 0.6466868704508378, - 0.6544807370114499, - 0.45780999581582776, - 0.5491151877244871, - 0.6208416390694778, - 0.6358562726476993, - 0.5131232677800712, - 0.6800655160526135, - 0.5307285494583514, - 0.5042608257681752, - 0.603634515098952, - 0.6297488706919772, - 0.47484816308921696, - 0.474821241716898, - 0.4703656547424043, - 0.6791579816357203, - 0.5162989725898646, - 0.5570085516491315, - 0.6035978748978841, - 0.5188062057350731, - 0.5296864553798523, - 0.5421311891751994, - 0.5243153122572657, - 0.4537942547721684, - 0.4461895700204479, - 0.44192876028947287, - 0.5361050221067057, - 0.6424898110590134, - 0.5487530154421144, - 0.4618429793820026, - 0.5787271667068007, - 0.6548543731553197, - 0.5859152452690455, - 0.49653468676589313, - 0.48490332517029, - 0.5983633869618261, - 0.6526169176257269, - 0.6491541569938721, - 0.6032098086470528, - 0.5441825106195066, - 0.5308395691381967, - 0.5210412863140177, - 0.6335948970020726, - 0.4944558681124176, - 0.6366226038282652, - 0.46427549839815613, - 0.5571969010221178, - 0.5398139040476315, - 0.5506658807813277, - 0.6050092315934628, - 0.5788649437202739, - 0.5226529392084179, - 0.6286241013277931, - 0.588003312704813, - 0.4486770966035396, - 0.5667917106785645, - 0.4936212959739395, - 0.5661503415906751, - 0.522724755383124, - 0.6476471001523708, - 0.4470794618909071, - 0.49917576067422703, - 0.5252556738832481, - 0.488797991377646, - 0.5789110235280346, - 0.5903471247103962, - 0.48589504865263977, - 0.5038324823196635, - 0.5359986372308144, - 0.46604578678262515, - 0.5815126685818451, - 0.4694984811899454, - 0.6447062990483557, - 0.5119992307222365, - 0.5442000400538582, - 0.6166925620287249, - 0.4716262400744912, - 0.51206033049888, - 0.49894725676112295, - 0.4839048349129577, - 0.44932030477905766, - 0.4544753310750908, - 0.44887359523547604, - 0.5263625973226296, - 0.6722009695832565, - 0.5270100072880094, - 0.5579620447961853, - 0.4429910547192217, - 0.452417121460591, - 0.6419009043595539, - 0.5075193888895917, - 0.5912735176706783, - 0.6503615291381155, - 0.5770648513330329, - 0.4590945329030214, - 0.5803493356352327, - 0.47203348083854674, - 0.6656581763314497, - 0.6056195514389977, - 0.6712207748634114, - 0.6797550473224221, - 0.49621144724111954, - 0.6162151590613919, - 0.6516596948739951, - 0.6808995826583819, - 0.6781471078548328, - 0.5117357205992917, - 0.4768552755513267, - 0.61179228613164, - 0.6172319697568311, - 0.536452532244017, - 0.656524893601108, - 0.671712087453995, - 0.6502675268992315, - 0.5316515665979553, - 0.4680842588631032, - 0.5153554525496266, - 0.5785154399993737, - 0.48567212234528595, - 0.6336133534633105, - 0.5342029505656524, - 0.4436780322079759, - 0.5447546555281627, - 0.586506305623054, - 0.6316227183213287, - 0.6832432688482626, - 0.6191520048725369, - 0.6301842861440817, - 0.6101238137265299, - 0.5781762431668918, - 0.46086025429558153, - 0.6496466525032448, - 0.6539973796298889, - 0.5681698246853439, - 0.4411763050961333, - 0.6780267106573348, - 0.6771259152174947, - 0.5383947524536469, - 0.6511108501924449, - 0.6573532368039743, - 0.5506605742693781, - 0.45403320454561796, - 0.6438026607516811, - 0.47557457034793565, - 0.5205190020798709, - 0.5867068636178728, - 0.4520272440333092, - 0.6402002807357408, - 0.5403161767037703, - 0.49211279523688933, - 0.6508747103483519, - 0.46468172049522216, - 0.4675114401473938, - 0.46178999836312445, - 0.642601349058965, - 0.6541161506774332, - 0.57190310074535, - 0.5375625399702294, - 0.45706949601822366, - 0.5880290092719884, - 0.5497896676108512, - 0.48796557526715345, - 0.4426996938855564, - 0.6101132871591015, - 0.6555824405857356, - 0.6702530938147537, - 0.5345028608104949, - 0.6330749196774288, - 0.6758895963688675, - 0.5316461267384336, - 0.506498534528388, - 0.6252560643606015, - 0.5337485800360251, - 0.6348058294100782, - 0.5037366872592618, - 0.44468995272896455, - 0.48858564465121296, - 0.4530961234096509, - 0.5488796749236826, - 0.6726669981135666, - 0.4598342151390969, - 0.5572281968844113, - 0.5812058871833963, - 0.5057396193905109, - 0.45117999922093693, - 0.4815620867015693, - 0.5604351785224723, - 0.6020575723899375, - 0.5358383230673486, - 0.6408729587898907, - 0.5493988331599142, - 0.6626152291736805, - 0.47117832557175887, - 0.4822843825773301, - 0.4577561985438559, - 0.4663335859127113, - 0.45594408776672457, - 0.45637994616580213, - 0.4478806374390009, - 0.6457435616114326, - 0.5982067630819705, - 0.6833062404308481, - 0.49779303012096343, - 0.5706370715045204, - 0.6794993617312257, - 0.4573182567036695, - 0.511020441402287, - 0.6171618389951848, - 0.6410190671108749, - 0.5874337324057297, - 0.6228135990340863, - 0.5686067400986963, - 0.517026757313386, - 0.6289887161590083, - 0.444363573067023, - 0.6230267566097041, - 0.6382050461789572, - 0.6713523398027876, - 0.5181661051041869, - 0.5647788817991077, - 0.6815413034459699, - 0.6197387045109748, - 0.6714489482698456, - 0.4632008053341787, - 0.5672227354471147, - 0.49372986755264087, - 0.654860178305893, - 0.5941604449270447, - 0.47882312466579374, - 0.4471852237559099, - 0.6804863601508508, - 0.4879223954178973, - 0.4619235649993174, - 0.6144054361211998, - 0.4773217614902493, - 0.6190807132661252, - 0.4557983487446129, - 0.5832836109936314, - 0.5107149860560749, - 0.49720532905988274, - 0.6455481204494731, - 0.6019443532632821, - 0.6292690398553569, - 0.508259164232367, - 0.5545030075060253, - 0.5391494246126386, - 0.510839208332796, - 0.5109859054626706, - 0.6760790568805043, - 0.5912748968794714, - 0.5148711407901777, - 0.6564261928761785, - 0.627454308540084, - 0.4956242894303058, - 0.6579017560604665, - 0.6583657851851071, - 0.6338594089869016, - 0.454146834444125, - 0.4527944687977861, - 0.5246408778696776, - 0.4622984982906331, - 0.6529188303974952, - 0.4426327189570165, - 0.6339396998360243, - 0.48377729526126556, - 0.46133069550568323, - 0.6331459309534502, - 0.6091853408442324, - 0.609869271724215, - 0.6269556763136219, - 0.5905990320671716, - 0.558037914270326, - 0.6215346942657776, - 0.573176135135519, - 0.5791881306692432, - 0.5274345961135443, - 0.5102259099144196, - 0.4847432177966004, - 0.5003879049695527, - 0.6211846041602989, - 0.5283100949145533, - 0.6586161061082424, - 0.46333943109111164, - 0.5937061168597542, - 0.6583718570319192, - 0.4632948789819427, - 0.4477230927667578, - 0.5270691788319498, - 0.6344605424682579, - 0.5534512277792355, - 0.6692792378437193, - 0.5006911612159592, - 0.5217394788225425, - 0.6379562663311901, - 0.5591850336435836, - 0.6332731970056718, - 0.5811431081632342, - 0.6789775977985137, - 0.6807837241396054, - 0.47045195191731093, - 0.4877410468189467, - 0.6658993060831915, - 0.4796963123214947, - 0.4964105945783305, - 0.5972344509081982, - 0.6434913971579845, - 0.5250845303160325, - 0.5268464777667752, - 0.44562415278450407, - 0.5592981116093527, - 0.5590183146649137, - 0.595741515359447, - 0.5675215763490913, - 0.44881281624161484, - 0.6244887270658785, - 0.48685045064416205, - 0.5624670424514003, - 0.4930045072843514, - 0.6469157771917947, - 0.48791911050447107, - 0.5161145146928123, - 0.49387534507307784, - 0.5998380082259606, - 0.6251823911422553, - 0.5542358103728111, - 0.5177184485322549, - 0.5251355346266126, - 0.44254099040064526, - 0.48920411006675474, - 0.5761743464598077, - 0.47489908206162457, - 0.604250653388749, - 0.47132007461514747, - 0.5179501336023604, - 0.6652045898804734, - 0.5832636992676121, - 0.6491997998928734, - 0.6497746738539082, - 0.5374675894916154, - 0.44383163962631805, - 0.665981496814907, - 0.4764975567942646, - 0.5364752413804432, - 0.6632896115269151, - 0.637787706672216, - 0.5227381983380447, - 0.5645952666899561, - 0.5721385367063817, - 0.5161632384871416, - 0.5607112219635797, - 0.4764820293139854, - 0.6330145209177023, - 0.6381688226718517, - 0.6472291346280188, - 0.6265727599673058, - 0.5628106589390862, - 0.6683379128667091, - 0.6488885973586348, - 0.49912691323537345, - 0.5776611093433675, - 0.44928213450591176, - 0.5261390800607721, - 0.5193348831338441, - 0.46355691278109706, - 0.5020394172787397, - 0.45827488214126916, - 0.6743781048228168, - 0.5199596477084647, - 0.4898061801540138, - 0.6227065651294823, - 0.5394361663699393, - 0.4471347703541837, - 0.4561824750836161, - 0.46297689847901824, - 0.5385868220658017, - 0.4549989583493303, - 0.51203351336516, - 0.6786409936914988, - 0.4567021216577284, - 0.5956890541317068, - 0.6177194304058946, - 0.5058448143059023, - 0.5074662474021415, - 0.5496846364660246, - 0.5010452869472911, - 0.5718820559669844, - 0.6527270113516321, - 0.49155780528864984, - 0.6804700727142128, - 0.6691743934059585, - 0.5264048087587335, - 0.5613438337244918, - 0.6275327553073157, - 0.5493520745131547, - 0.6583200905781511, - 0.44037256236859235, - 0.5032321266001023, - 0.6429431664890837, - 0.4848032343552609, - 0.606234518597266, - 0.5841408478954857, - 0.5575702907198563, - 0.5539314735938924, - 0.4873298189905388, - 0.5968656389731648, - 0.47039241269113813, - 0.5049019976334496, - 0.49856943122935254, - 0.5030513027845037, - 0.6156303733557055, - 0.5056695634725819, - 0.44728393597117383, - 0.583780111078257, - 0.5661316447640253, - 0.5984403563007952, - 0.5436670224546437, - 0.5665601295156334, - 0.44256033169392495, - 0.6328397799208555, - 0.624113735942646, - 0.6756567872981463, - 0.6298316227628284, - 0.47253197250695367, - 0.46472903188243814, - 0.6852291775043369, - 0.587620395747626, - 0.6799767309650568, - 0.5168182489849774, - 0.49825710678322144, - 0.5769776711386276, - 0.5123308372802065, - 0.5496326443366384, - 0.6591227163289497, - 0.6723582249825382, - 0.554462204573682, - 0.49282463914799474, - 0.5668520234624149, - 0.528155551794785, - 0.6414868758329655, - 0.4673049777535435, - 0.5410774329966711, - 0.5672266703629036, - 0.6665050490759274, - 0.47745339141865833, - 0.6266508031536203, - 0.6664043891168614, - 0.5712198009194832, - 0.6525922137096812, - 0.6170592820103513, - 0.5132788746626424, - 0.5505018469901162, - 0.600885236396604, - 0.573820247058425, - 0.5355408127231879, - 0.5471553102081869, - 0.4755819314839998, - 0.6804697794284158, - 0.5992149089705674, - 0.4575282617054079, - 0.6317357482421422, - 0.6065233944419374, - 0.46436209119987704, - 0.5651115428222062, - 0.5970793008011531, - 0.6372143012514113, - 0.4990188354407896, - 0.5483063457116042, - 0.6162048655156155, - 0.6760700653425984, - 0.6030101209731386, - 0.5844812219981701, - 0.5343897716091934, - 0.5881782643545472, - 0.572002486222618, - 0.6283764162994455, - 0.4724436525087782, - 0.594800851822283, - 0.6513293601237691, - 0.6806030559358557, - 0.5851838040419368, - 0.5915952687980398, - 0.5815423873141425, - 0.4454697493692299, - 0.6308242483849074, - 0.6352841901909829, - 0.6131321696541303, - 0.5328005461942372, - 0.6192057091661121, - 0.4708844322869662, - 0.6584278623247364, - 0.6426402222139777, - 0.5366802072687538, - 0.4846597354009292, - 0.5095687433782881, - 0.6103187159526646, - 0.4810463822863416, - 0.45694082567288097, - 0.6697664345578593, - 0.6107588849942163, - 0.5784245939781194, - 0.45245412981200983, - 0.5584556185292503, - 0.6519544253261127, - 0.5567590513459755, - 0.4791067799688062, - 0.6503525696389165, - 0.5620111742560432, - 0.4498956625652682, - 0.45407158490894073, - 0.5683348639865842, - 0.6316804607809832, - 0.582573798087481, - 0.6568235699307039, - 0.5036529282622791, - 0.5839608841035031, - 0.650300033591204, - 0.5152039619034645, - 0.53345888289116, - 0.5912690768925326, - 0.5856932009613326, - 0.6193259837961274, - 0.6721923531085976, - 0.44414369246743496, - 0.6386932716363821, - 0.6674287573934798, - 0.6176745403853527, - 0.590536041466211, - 0.5423645105165135, - 0.6285789652552096, - 0.49910877246099367, - 0.5521824548813984, - 0.5075392451959846, - 0.6449276679604778, - 0.6547004237601628, - 0.5840901661914195, - 0.4712694312383794, - 0.5661794298935394, - 0.48224434686386375, - 0.6467144648576701, - 0.5117098442577237, - 0.6493330192672665, - 0.5803662501941977, - 0.45236536546573447, - 0.46691435512318036, - 0.6351413486251622, - 0.49478208103867777, - 0.6500103936603059, - 0.6155780938053621, - 0.5818931472129969, - 0.5271470038023305, - 0.4419299139873304, - 0.5389758816691002, - 0.44554026751212406, - 0.6316655514052932, - 0.5445908627109942, - 0.573072354522437, - 0.6152850105140067, - 0.4427171459779564, - 0.47079608242410187, - 0.45641485258088976, - 0.557577752250823, - 0.6424962426668197, - 0.4518438041950611, - 0.5825202140911425, - 0.5275454873100476, - 0.44289998018798193, - 0.5068924509679754, - 0.5052183497445488, - 0.5738318045304678, - 0.6323073058821633, - 0.5254683234956344, - 0.6568878555590175, - 0.5120733324555597, - 0.5315243361335894, - 0.48657762278230937, - 0.5998053246565395, - 0.49103391507605304, - 0.6399204303908069, - 0.6157392746261554, - 0.6015964506140795, - 0.6169144276309882, - 0.5831121662048877, - 0.6827813607324338, - 0.5200161806345552, - 0.5395277204799408, - 0.4968989088525742, - 0.647421507107852, - 0.5510794567427066, - 0.525604783320078, - 0.5157716682175186, - 0.5799491300580851, - 0.4563831736517752, - 0.5613811284852219, - 0.47859543983859754, - 0.5806756886120343, - 0.4719643672940389, - 0.4942477192659255, - 0.502663348514532, - 0.6255401820110773, - 0.6742428729551677, - 0.44599717760757385, - 0.6083788873708745, - 0.48898098295673326, - 0.6593011027925471, - 0.5241830519043873, - 0.6463328763863322, - 0.5424419795552649, - 0.6681239105984379, - 0.6736395724887146, - 0.5934491676740155, - 0.44509482184517674, - 0.45500546404620795, - 0.47077140675979295, - 0.6040298806928501, - 0.6198527795708317, - 0.4592524059134645, - 0.5238363346151383, - 0.5777602118096066, - 0.5632679351765472, - 0.5606136932736163, - 0.4557287515848867, - 0.49707559755955594, - 0.5896771809498429, - 0.6547476976488448, - 0.5740832361775645, - 0.6391870839706564, - 0.5613577892375197, - 0.5367689693792417, - 0.515694001431904, - 0.5799921417411714, - 0.4727338345403361, - 0.4894004512762646, - 0.5483448123651282, - 0.5070974821680558, - 0.6489623246752557, - 0.4699243056586576, - 0.5208882557420452, - 0.47687990886093407, - 0.6848174652343276, - 0.48867800476102413, - 0.6744619128891741, - 0.6823546680206038, - 0.4506664243829889, - 0.6283683220279663, - 0.4744085752594246, - 0.5739434521943856, - 0.46064975108995465, - 0.6115263479368258, - 0.5011053949932728, - 0.6740047743924924, - 0.5041962860696187, - 0.4721047816116706, - 0.47618625467553677, - 0.47893001531545565, - 0.4425561115245646, - 0.6414004355375037, - 0.44317068323459585, - 0.6847737080632574, - 0.47236187907095745, - 0.6164394832667128, - 0.4799925401664615, - 0.5780096414899508, - 0.5733785675631108, - 0.643405559888619, - 0.5698311540760643, - 0.6256595845157442, - 0.5792827976227912, - 0.5433782515087038, - 0.5139808658380988, - 0.4469651787491632, - 0.5042079679657623, - 0.5786265122364093, - 0.5832243149332259, - 0.6429145703860153, - 0.5001527079286754, - 0.474181637342013, - 0.5115207442565123, - 0.6641147893060324, - 0.4639822548103484, - 0.6101892226636916, - 0.496429602412059, - 0.44617439704287615, - 0.5129635004509602, - 0.6387771140275907, - 0.5898471686027623, - 0.5594049558408757, - 0.5256413431246031, - 0.638078773444315, - 0.5633920147469048, - 0.4543234554023515, - 0.6577309418486026, - 0.4983154772942743, - 0.6192008653472104, - 0.5068866152797532, - 0.6024906535652911, - 0.6354449432432464, - 0.6517737064874473, - 0.5363004262464077, - 0.4683787262268302, - 0.6140258464276742, - 0.5195927808551966, - 0.6696582866748904, - 0.520754646220703, - 0.4453638554121534, - 0.6539969609247033, - 0.6792072678804201, - 0.5155563568139508, - 0.6527262843843147, - 0.46867550265816593, - 0.662217559874773, - 0.5548484167110739, - 0.6565724261560364, - 0.6081464794753608, - 0.47378341892108977, - 0.6288699162070779, - 0.6284684681927357, - 0.5268003401168635, - 0.5681957208572352, - 0.5529620379244379, - 0.6784855899916294, - 0.5310383510672846, - 0.6493087493034002, - 0.5980312410290349, - 0.6290248975564809, - 0.517338520073014, - 0.5102150118793077, - 0.667404395699329, - 0.6534568346638779, - 0.5199177279571027, - 0.6837672208246217, - 0.47672669197434575, - 0.5078853557421312, - 0.5037641082743557, - 0.6621655355900719, - 0.5704766767165579, - 0.6459813275867098, - 0.6243675129437949, - 0.669048362916095, - 0.6110428631399861, - 0.5342323556350566, - 0.5948920934287629, - 0.46095321946635137, - 0.5112364650846154, - 0.44913559444644446, - 0.533262230523908, - 0.5894130862016707, - 0.5419303088972547, - 0.6000802332827578, - 0.5623425225179336, - 0.5544332018617336, - 0.5430194933475518, - 0.4959870829387866, - 0.591839299910487, - 0.5989042942929192, - 0.6681426812615828, - 0.5227011555335184, - 0.6580442818777898, - 0.5566017899654278, - 0.5905804671756025, - 0.5304407942909122, - 0.6365318841495806, - 0.6537695096892367, - 0.5948614217288843, - 0.6129341626784957, - 0.6455394257076084, - 0.6599127895316607, - 0.6521773804384907, - 0.4874097580000812, - 0.6602896967563836, - 0.6725664504983523, - 0.5945955938541588, - 0.65974074492505, - 0.5203307163084101, - 0.48247893376348333, - 0.6372445804253458, - 0.44157712764396106, - 0.6819944375191354, - 0.5117605149252598, - 0.6565223119919372, - 0.6114366963921763, - 0.5584222880892883, - 0.6635090164565564, - 0.5666882193452736, - 0.6361744870518492, - 0.6657531001967122, - 0.5850936688138977, - 0.6141910079818561, - 0.4931485463879188, - 0.5081444284494371, - 0.5120278101749081, - 0.5985972447162491, - 0.6202372452527389, - 0.5253182616431902, - 0.5361630734657732, - 0.48722237931333157, - 0.5789840367839589, - 0.6242598317292599, - 0.4605226950561711, - 0.5635886080412305, - 0.4964988599661932, - 0.6008955098008699, - 0.6466344963403741, - 0.5882726492622153, - 0.660905508435517, - 0.5000952634421595, - 0.6729841958364575, - 0.5767435883282331, - 0.5034043060585418, - 0.5949031635286604, - 0.45021455363161095, - 0.5640123874497694, - 0.5386556409643695, - 0.667381002999618, - 0.5014455496062313, - 0.47192600850115457, - 0.5087030894643427, - 0.5527411200176524, - 0.49705457227722116, - 0.5602468992196022, - 0.6183927943113103, - 0.5187724453065141, - 0.4725594024425063, - 0.44601349699987664, - 0.4486444834068484, - 0.5086066780477442, - 0.4867001523525552, - 0.5315214175377578, - 0.4734211150094575, - 0.6649105169577649, - 0.6848245690605024, - 0.5167264246189438, - 0.5545106907939776, - 0.49115863183277997, - 0.46335490595905277, - 0.4451755982675752, - 0.6321856470418337, - 0.5607776130946022, - 0.5254140644221645, - 0.5496252918170134, - 0.6507291251946195, - 0.518720881663147, - 0.5737525627399348, - 0.4617835889098078, - 0.5644334491731912, - 0.5369710314525791, - 0.5989626258184141, - 0.600892731929638, - 0.5905810305356091, - 0.6602504979207653, - 0.47294038222156376, - 0.6422723435130282, - 0.5079516371218395, - 0.6630704461062724, - 0.6842537959708559, - 0.6413908105484849, - 0.4507749217586009, - 0.5949528084322161, - 0.5553298220620893, - 0.6231130660745264, - 0.5713446259113117, - 0.5277032707362641, - 0.4651679434126088, - 0.5293808880789291, - 0.4871260291655801, - 0.5760414623049509, - 0.5943807478013469, - 0.5891116592877037, - 0.6771391401691769, - 0.5746659809090255, - 0.5671443296086573, - 0.5473779812388522, - 0.6543383631236517, - 0.6594309743012245, - 0.6146829179863812, - 0.47360809075871957, - 0.5733546114607099, - 0.6737253919167563, - 0.6421763571412047, - 0.6825179337617259, - 0.5888005973510957, - 0.49850109203585574, - 0.4961524384197789, - 0.4909562944668212, - 0.5429442821800009, - 0.5772066723149241, - 0.46267020863709796, - 0.6627721764647986, - 0.5469108057735546, - 0.5042574800344439, - 0.5466182603358225, - 0.4722135280513995, - 0.5928986231469526, - 0.48944474971966184, - 0.4581805144767856, - 0.6084006533534541, - 0.6432287204491525, - 0.5794150299541144, - 0.45192402132710086, - 0.44368774139931905, - 0.46758702558021836, - 0.4808896325979098, - 0.598112778102292, - 0.6399892370125698, - 0.4986635272178834, - 0.640250896146116, - 0.6293123355569178, - 0.6532564204010503, - 0.4960127683580559, - 0.6632156552912274, - 0.4590246623168265, - 0.590403849578483, - 0.6280683319932757, - 0.6695098230895163, - 0.6681218837422851, - 0.4702448273564204, - 0.4596972378131722, - 0.5810279531402553, - 0.6857853746578431, - 0.5608592969942054, - 0.6305471332510403, - 0.4665507045704113, - 0.6356615277197737, - 0.46000828840919006, - 0.5868696460171909, - 0.558008570523817, - 0.5579720441242159, - 0.5569948484903857, - 0.6315648738475632, - 0.5761347895693185, - 0.5602997230468238, - 0.5233610919674557, - 0.6068038309754313, - 0.5900385329022584, - 0.47206131537681406, - 0.6349148660565493, - 0.6591000939600002, - 0.49760704343348416, - 0.6100267830176166, - 0.6348517661628166, - 0.4551513511076921, - 0.5994899256314381, - 0.5620910562168882, - 0.5195519674940732, - 0.6318860550816541, - 0.5413487031816975, - 0.6240238412004904, - 0.6248773999720594, - 0.5628897856226865, - 0.5585792691610748, - 0.6695098868518374, - 0.4936162108901382, - 0.5168917718802043, - 0.6027023692221902, - 0.4550048412895862, - 0.5492291600913987, - 0.5330258234507019, - 0.6854498321770213, - 0.4807954598459829, - 0.5714529225756707, - 0.5312024267802286, - 0.4883573337583427, - 0.5000163320258971, - 0.45757342204186074, - 0.4439152201173108, - 0.49604970089888484, - 0.6743538933017148, - 0.6467670715364408, - 0.5353576252269304, - 0.5164682079377856, - 0.571347376000154, - 0.5421730000548897, - 0.5961201177888613, - 0.5812623974951653, - 0.6262229617522919, - 0.5454317157574944, - 0.6254358475175413, - 0.6464712233073692, - 0.44763199397105613, - 0.47434514139065387, - 0.478853278644226, - 0.5361340616139976, - 0.574918785654438, - 0.6555869850308739, - 0.6709155148383188, - 0.5856768280640228, - 0.6727979974440791, - 0.5742015550355553, - 0.5034925621136086, - 0.669573431915469, - 0.5368069785326419, - 0.6155655290360225, - 0.44198256728160723, - 0.5415564730287799, - 0.6807124494016917, - 0.6779911297302611, - 0.5682116084288031, - 0.6614173791456628, - 0.5381024460207768, - 0.5332103807513887, - 0.6741998687787021, - 0.6180567312024148, - 0.5233725398516671, - 0.488696948904651, - 0.5272373244347627, - 0.6173488423707816, - 0.5931878650162049, - 0.5391117763967771, - 0.5917532426511509, - 0.5542251488473654, - 0.492474769481178, - 0.48389224709683487, - 0.5365739338758905, - 0.46372455181562033, - 0.5346283426243702, - 0.5471672391743301, - 0.5869466838491462, - 0.520100814606337, - 0.46800394950743684, - 0.46723939657347435, - 0.44517536102531957, - 0.5383277272522082, - 0.51190752969153, - 0.5018248038604433, - 0.6781600516730129, - 0.5334331792908766, - 0.5336444758601355, - 0.5224401439114021, - 0.5552749478878877, - 0.5564738022475624, - 0.6478202116246181, - 0.5552724887923639, - 0.5400615558317439, - 0.6839564419629425, - 0.5668438282531949, - 0.6022602748002379, - 0.5724433767324686, - 0.4479485268912028, - 0.6163906695151087, - 0.5292815468146227, - 0.6799604246946969, - 0.5284526022423723, - 0.5641769889167229, - 0.5615252475729601, - 0.5358474079929123, - 0.6653053635832293, - 0.4427269699557605, - 0.5444768546694646, - 0.5645513204947973, - 0.5354695179665607, - 0.6588868357059403, - 0.5813871904174762, - 0.5390757150108434, - 0.6696817691542742, - 0.4498960301094569, - 0.6027664963231459, - 0.6063760475134887, - 0.4904126410468203, - 0.4746900662357298, - 0.6259169079842481, - 0.6605464199099358, - 0.6435993509141602, - 0.5660697904770082, - 0.5045566187239335, - 0.47210556800131476, - 0.451722317383813, - 0.5706226259537057, - 0.6431672009936151, - 0.5668232982247561, - 0.517799570149357, - 0.6750285313215155, - 0.6530994831394874, - 0.6410992317987804, - 0.5656059269908449, - 0.5215741375386627, - 0.5315223299833658, - 0.5508921496720777, - 0.5324105946381678, - 0.46095421918201557, - 0.5521970643352924, - 0.49868218894837024, - 0.48965091331548277, - 0.47551870269625773, - 0.5546652192661589, - 0.5234386534412174, - 0.483640576691406, - 0.6764644476531124, - 0.6798089806094169, - 0.5140348596912535, - 0.5652885783751916, - 0.4619503301585736, - 0.48089974153968384, - 0.5550029315491278, - 0.6168392244552307, - 0.4541967104254731, - 0.5535682456660667, - 0.4788451083570953, - 0.6773111776779763, - 0.5602427531756998, - 0.5641029439153578, - 0.4795129030481348, - 0.45343991268392486, - 0.49901858329140564, - 0.47704247703555946, - 0.46007576740585787, - 0.4704448353529784, - 0.47368937252322585, - 0.5106714362986561, - 0.5774561674629067, - 0.6253077756605778, - 0.5441753149003488, - 0.5298309239893735, - 0.5389417070602776, - 0.6030866021558744, - 0.4497286256703177, - 0.6105262720661497, - 0.4918054848388659, - 0.4723552501339012, - 0.4741784372960602, - 0.5600580898634239, - 0.4517927248745343, - 0.6821258673886806, - 0.48562074017718737, - 0.6365758997432541, - 0.661457151960219, - 0.5800793745779834, - 0.5658655567509546, - 0.6202100797070824, - 0.5177459981473571, - 0.5210579988861291, - 0.5021399760166422, - 0.5634477269809025, - 0.5802421883545756, - 0.6624640255567609, - 0.5550473946977019, - 0.4721873564000713, - 0.5578708521150627, - 0.5089182023131145, - 0.5628437545910903, - 0.6248062170818313, - 0.5817496887808726, - 0.4817077719171631, - 0.545950186469808, - 0.45741805367683963, - 0.6546789978011984, - 0.6472643008882492, - 0.5333859400182972, - 0.5722297746531271, - 0.4587331024736274, - 0.4645848953054591, - 0.47014654569068653, - 0.4689348179585952, - 0.5842489800873916, - 0.5254928377488916, - 0.4433523033992543, - 0.5970672025103327, - 0.6505489035312986, - 0.6748462971318996, - 0.4839491467704821, - 0.6835684017764048, - 0.457253528112578, - 0.46858712847385053, - 0.49664882563820345, - 0.6527981582808984, - 0.5927952690773505, - 0.5538852432180068, - 0.5466136610483628, - 0.46524675270242766, - 0.6371234335248737, - 0.4652804582741862, - 0.6005678951145847, - 0.5287799771431558, - 0.667512575322655, - 0.6209431406309588, - 0.5024460906387075, - 0.5433748081443446, - 0.598498229358589, - 0.4710778578105901, - 0.5368695444108779, - 0.5289464631142222, - 0.6790175830076743, - 0.5919637240027114, - 0.6175503483241808, - 0.5933865652131802, - 0.5602006245546136, - 0.48321021751230475, - 0.5701857487652979, - 0.4766146130265106, - 0.4498431374375972, - 0.5189330596535123, - 0.6795764849133997, - 0.5815846110399387, - 0.5274453650819593, - 0.5202244456287151, - 0.6566074700406396, - 0.5269273777927852, - 0.62820683236998, - 0.6787681174695428, - 0.596321551925663, - 0.6657196961282907, - 0.6213510742630055, - 0.4960462237155066, - 0.536174608941838, - 0.6197651766296904, - 0.5493185801155781, - 0.5680186238268938, - 0.5875285942465918, - 0.45410358002406986, - 0.45402957893538265, - 0.48056987026457765, - 0.512094740790925, - 0.6634467183851825, - 0.612575031773422, - 0.5613205104680705, - 0.5577934966584744, - 0.6436659737619561, - 0.44829717638329075, - 0.6508927596236211, - 0.6191383854044883, - 0.4628234976031428, - 0.54376679956813, - 0.6106298259085499, - 0.5249198623313303, - 0.5437288735566118, - 0.6671303880792671, - 0.5248724318378846, - 0.44540154466546533, - 0.45807125950267813, - 0.625774217311661, - 0.5604195072252581, - 0.5486572552665118, - 0.5730176895562034, - 0.6686789080414116, - 0.6412382161965564, - 0.6349685303216583, - 0.632073805660129, - 0.611432625749623, - 0.5588301176093986, - 0.6781209762823017, - 0.6136463586612724, - 0.4654316310459342, - 0.6669636141012203, - 0.5638893033271705, - 0.6420185503250601, - 0.6221979250974197, - 0.6765839825897186, - 0.546702962422418, - 0.5235469436987832, - 0.5862977527731525, - 0.46477148381639904, - 0.6267452679748471, - 0.552148049659401, - 0.5505830678327976, - 0.4993882748636451, - 0.6570149331496697, - 0.5645293154818987, - 0.6835361369137547, - 0.4714207072971569, - 0.5736234570707648, - 0.6680001009893759, - 0.4544154677776447, - 0.5611835442955326, - 0.5259695497266276, - 0.6383683822664139, - 0.6083606743174331, - 0.5258081542346454, - 0.6561120995256932, - 0.6641533520405256, - 0.44368033474709184, - 0.6663028730563862, - 0.6399477353906304, - 0.46613787907340115, - 0.46247868507476564, - 0.6330079609730914, - 0.57269227900572, - 0.6828962471347089, - 0.454672526166914, - 0.6504805298370373, - 0.6593955730860681, - 0.6035606610738413, - 0.6336737365626478, - 0.592762256337138, - 0.47772029599210564, - 0.5497464347011536, - 0.5792893237837181, - 0.4756549475113364, - 0.46690823136211934, - 0.5233593657774966, - 0.6643099219817927, - 0.5746487522492539, - 0.5944528763209722, - 0.5294477801044197, - 0.45127158006888735, - 0.5406187357617795, - 0.5000397401535825, - 0.599581587710061, - 0.5708161560266791, - 0.6366982261780214, - 0.535231706705086, - 0.4521659871260903, - 0.6414317381838234, - 0.6573948369443499, - 0.5862127952959559, - 0.6323987410757926, - 0.49309155037261865, - 0.5038485291045752, - 0.5008624680726461, - 0.5146122549181881, - 0.684793211196608, - 0.4739979692233952, - 0.6054695637102046, - 0.6475038539853766, - 0.6381112990874157, - 0.6120262264880185, - 0.6585329024368393, - 0.570472633470615, - 0.47076129156754815, - 0.4967949247551656, - 0.4562769518854145, - 0.6052624006803884, - 0.625150870290681, - 0.6443364002729087, - 0.5577336135845075, - 0.6586470139290095, - 0.47995013425974264, - 0.5119262499759213, - 0.5538776591377508, - 0.4981177189530287, - 0.6668415060507464, - 0.6203126445261827, - 0.5075301334534694, - 0.6220358616046164, - 0.6668367996637109, - 0.45364228010422714, - 0.60820066229305, - 0.5869875269532938, - 0.4547070202971324, - 0.66034832295163, - 0.47418148196409954, - 0.644660068165381, - 0.4764940532498069, - 0.46083878880080137, - 0.5673736546765745, - 0.5183819110720027, - 0.5148341837053854, - 0.6855123155052611, - 0.5252128765169186, - 0.520644600092502, - 0.5345372397912245, - 0.6606005534649402, - 0.6573376014549501, - 0.6280988458565366, - 0.4928674580412137, - 0.4848838255400864, - 0.6186992557181691, - 0.6399522240185456, - 0.63931938441491, - 0.44072730595404525, - 0.6619732973775474, - 0.674837092100353, - 0.5683497802738433, - 0.6340024028748197, - 0.515144688545093, - 0.4548359263973176, - 0.65542307423796, - 0.5623644556370097, - 0.5747290855848805, - 0.5097815634413141, - 0.6211070738433878, - 0.6016514912381706, - 0.5191781019242748, - 0.6602245700488147, - 0.48909410152376587, - 0.6038951854938234, - 0.6177920241213369, - 0.5447120193444395, - 0.5285505565859976, - 0.6686518548092786, - 0.6560920220310031, - 0.499443166520624, - 0.47664177554184173, - 0.665641412525719, - 0.6099110495986113, - 0.4866725670628052, - 0.48944494759937435, - 0.49253072505605544, - 0.6528045006756902, - 0.5211808667625308, - 0.4954707224470911, - 0.634731442649873, - 0.6724173612884399, - 0.6436864337891562, - 0.6336982404787685, - 0.670436347065054, - 0.4560976188781654, - 0.5047274311433882, - 0.6055091671705878, - 0.63042301039543, - 0.6372040266961677, - 0.5382697165620723, - 0.47807068365671607, - 0.4517367458973354, - 0.5745479006960355, - 0.6329343757787492, - 0.5846397860786884, - 0.5510276807904427, - 0.6528159449898814, - 0.49774729361318293, - 0.6473025263838529, - 0.4791327100224797, - 0.5894902863350977, - 0.5040010105851592, - 0.4650752508789508, - 0.5644594434606441, - 0.6522413188769198, - 0.44173103575371037, - 0.5843560521041309, - 0.5556046172361794, - 0.5370363623861708, - 0.6801216084931214, - 0.6393721497884123, - 0.6581995544490622, - 0.5563454392851939, - 0.48376202446754607, - 0.550726748494842, - 0.5586788864048308, - 0.5830126164864786, - 0.5550930899215321, - 0.5587592512872869, - 0.6027955980395306, - 0.6638129993135126, - 0.6748420648390607, - 0.6774202239600107, - 0.4954857314957252, - 0.5110540759944552, - 0.6274490847082645, - 0.5339652194514801, - 0.5220506204792952, - 0.5521700249287496, - 0.4876410401859289, - 0.6342495870489663, - 0.6465940145343583, - 0.6361215389837682, - 0.5118765049322922, - 0.47045270356907243, - 0.6562201212498598, - 0.529134466854218, - 0.6824521193036007, - 0.5651753408426796, - 0.5412670120828863, - 0.6570139909783723, - 0.4938393797442794, - 0.49407634481643753, - 0.5232918202324282, - 0.5183293067013653, - 0.6079156299339246, - 0.5014805067980642, - 0.6046767803872438, - 0.47299102272716903, - 0.47092606695864747, - 0.48877872748790946, - 0.4742044150247897, - 0.5789040165832373, - 0.4699666053103068, - 0.5050072691293976, - 0.6496278299458581, - 0.5498002580537354, - 0.6831439658826146, - 0.6522365384172317, - 0.6072228347750961, - 0.5296673695392546, - 0.678689490367895, - 0.5182587234593763, - 0.5260841655448776, - 0.6571815011232439, - 0.6831634514961105, - 0.5128224726345065, - 0.531576325622914, - 0.5223538976041621, - 0.6501180344777551, - 0.5293406100863971, - 0.6407879467224666, - 0.5933370438019813, - 0.5492719179570389, - 0.49059769819298443, - 0.48469981031766446, - 0.4777443879799699, - 0.5692956423965249, - 0.6826593975105594, - 0.4867294614848677, - 0.6416655279783361, - 0.46797840847051136, - 0.6197871815327118, - 0.4883025414273153, - 0.6763416608896169, - 0.6059206831733797, - 0.4995955803614753, - 0.6149242083295869, - 0.6057853980591295, - 0.5214240274762989, - 0.5541184680165373, - 0.4995716310707799, - 0.5494549041817468, - 0.6544995323495598, - 0.45120404272708964, - 0.4711476724992193, - 0.5367311709582273, - 0.5909329208297489, - 0.47737532457402626, - 0.4594480105020925, - 0.6265064655058941, - 0.5902069695068766, - 0.4685438856935339, - 0.6203475233406893, - 0.6465707678419468, - 0.6552706855698835, - 0.44818837837472425, - 0.644880963039913, - 0.45521026310028856, - 0.4460072397735892, - 0.5370729450003058, - 0.4467093559427522, - 0.5553746955779234, - 0.5205809889924102, - 0.602886547771562, - 0.5038347943069957, - 0.5096220168856223, - 0.6128163499277199, - 0.5172314679406635, - 0.6842628265097428, - 0.524171324544091, - 0.5767676921092517, - 0.5436561955515746, - 0.46800854072404235, - 0.6357244024067636, - 0.4538102946491277, - 0.5494340748231604, - 0.5677923927962985, - 0.5331904527666192, - 0.627615408661044, - 0.6445845271795724, - 0.6224246023276773, - 0.5442997369951443, - 0.4986489497231524, - 0.5229271025538298, - 0.6653381982201578, - 0.5637847381336225, - 0.5955117670894015, - 0.48542819195552667, - 0.4584467864473233, - 0.5251846887945487, - 0.5883032723597738, - 0.45253008700142977, - 0.5149796814092447, - 0.5232717371175093, - 0.6133111175799494, - 0.45225236270314056, - 0.5041125600137008, - 0.6042008476846427, - 0.4837355719576277, - 0.5674698540664952, - 0.4902140778650039, - 0.5285612160635096, - 0.6026222233774337, - 0.6254905736927798, - 0.48210840255544757, - 0.5168788423802609, - 0.47662194980930317, - 0.48805497634752565, - 0.559352326557465, - 0.542219914088406, - 0.6118228247243507, - 0.5509484240232974, - 0.5045404884031738, - 0.5349834299050814, - 0.6113708567231433, - 0.48994257788576634, - 0.5554027652775233, - 0.5800453776398001, - 0.5201336882757822, - 0.5335959713785368, - 0.645601149548071, - 0.4799723149928523, - 0.5315300713526945, - 0.5767166402745398, - 0.6694192520823825, - 0.4408912633708767, - 0.4761584527507551, - 0.6287027733406139, - 0.6542466316264333, - 0.542826867462921, - 0.5229693638328993, - 0.526084564183943, - 0.4829708738061655, - 0.4955729615939835, - 0.651417063763857, - 0.48767404187186986, - 0.4879585870802194, - 0.6831590422337287, - 0.6194246053419348, - 0.6222345093812764, - 0.44785824870439866, - 0.5942941327090032, - 0.6119861377829964, - 0.6466510238712782, - 0.570816048141908, - 0.478204647963424, - 0.5114575792040499, - 0.6813381681447991, - 0.5619464964267636, - 0.635313721766641, - 0.6030390130348309, - 0.6553577567179071, - 0.4544106258292319, - 0.45215756700446186, - 0.6766897975051058, - 0.5920413197226186, - 0.6756061064022307, - 0.44264379898209344, - 0.551426781376963, - 0.6726857092536163, - 0.6694121751258557, - 0.5085154751652137, - 0.5245414734694054, - 0.6501756676813785, - 0.6399892999488677, - 0.6655972240365301, - 0.5152259973666686, - 0.4882474709536019, - 0.5390800063091485, - 0.6743511767380761, - 0.5886600764262957, - 0.4715834471116961, - 0.5260452238587159, - 0.6508383257347901, - 0.6189818067799164, - 0.4987178287465214, - 0.4505198549706938, - 0.6852468585158767, - 0.5602467476764629, - 0.617316056692305, - 0.5253675598175246, - 0.5934840957890125, - 0.5077618225641795, - 0.5919170255835421, - 0.6650494232958826, - 0.6406015003620666, - 0.6857646409377405, - 0.4963920151089923, - 0.44701074286461495, - 0.4417266348056806, - 0.5955020908400426, - 0.5705415456382325, - 0.4655658609988797, - 0.4577941417988384, - 0.5690345075274159, - 0.6552727617532549, - 0.47170562247944914, - 0.5666353868898655, - 0.6351264257938992, - 0.6179017421411496, - 0.5113316759312507, - 0.527080559152964, - 0.5274544989256977, - 0.4436813090108846, - 0.47404544553015343, - 0.526606282679318, - 0.5663138836048871, - 0.4970436458675379, - 0.5304860150756745, - 0.5609269424494322, - 0.4652747350376166, - 0.4648763236580914, - 0.6046854727353633, - 0.5732141707878683, - 0.6178811458057719, - 0.5339248062067822, - 0.605939096744302, - 0.5070595164979497, - 0.44443029780205107, - 0.6037900419099844, - 0.5745009772253222, - 0.647297636852217, - 0.5528117375685785, - 0.466739053420056, - 0.5890063431633383, - 0.544115061144074, - 0.49383219263140365, - 0.5450637537500318, - 0.5171187075343255, - 0.5180509315232908, - 0.6410444180082651, - 0.6793772260704173, - 0.5366573925926119, - 0.5067935385922238, - 0.6383313443786299, - 0.6130770599096226, - 0.6613245030092428, - 0.5522810326379, - 0.5471554798747489, - 0.6374074831040584, - 0.5343602999631032, - 0.6358966256081575, - 0.5768651067093961, - 0.6132737340834256, - 0.5450275626251142, - 0.5850649775339334, - 0.61207322093137, - 0.6399946339622813, - 0.5090592500934035, - 0.48590649735160685, - 0.6711427045938428, - 0.5598164942334798, - 0.6282415269377757, - 0.5444645572692706, - 0.5240145357573807, - 0.6434199160530246, - 0.4621085918835168, - 0.6298096844347411, - 0.44212024419302715, - 0.5534262838111063, - 0.49750860057195484, - 0.6141302404639832, - 0.5796938324202855, - 0.5766615198836311, - 0.5001057047432665, - 0.46083264481956765, - 0.6409108022989424, - 0.5537649637276103, - 0.45320073011303974, - 0.50102729178407, - 0.4763338418115967, - 0.6703301303686076, - 0.5330833367861124, - 0.4482098614550655, - 0.5958889125962819, - 0.6237832875794962, - 0.6541682601116032, - 0.6091248773680136, - 0.6413833091297669, - 0.6697402742708163, - 0.5199630740490189, - 0.45699981443206356, - 0.6508079363158598, - 0.6088573749500438, - 0.6794674148309893, - 0.49915172022729887, - 0.46722840888639033, - 0.6464032957944674, - 0.5525505915763667, - 0.6650783881984301, - 0.6269662190340847, - 0.5903085062341392, - 0.6554393731704228, - 0.5549743701118497, - 0.4400347967633047, - 0.6035919663764103, - 0.6671348272583495, - 0.6619599622973751, - 0.6260404809185179, - 0.4722314670618607, - 0.6437852173873456, - 0.45629999985000047, - 0.5629998273618325, - 0.495756236834514, - 0.6229752624658278, - 0.49842720390048234, - 0.5377393394462672, - 0.5481903318919453, - 0.5982760621744545, - 0.6146772076112443, - 0.564098577991494, - 0.6102960045976494, - 0.617108082742306, - 0.45432874572549126, - 0.6684641490312079, - 0.44011307943691386, - 0.5020904131637214, - 0.5120337297797652, - 0.44611686632093916, - 0.4561709165064356, - 0.5357175142226067, - 0.6263428300697226, - 0.6048322521853936, - 0.6141668482457081, - 0.6074602898772411, - 0.6031546167136032, - 0.6133948052903307, - 0.6026541464943224, - 0.5677029481815465, - 0.6160108967535562, - 0.45624565885501256, - 0.6631233476929221, - 0.5527050282866286, - 0.5020925383676533, - 0.5432364421218322, - 0.653292349192339, - 0.515252358250047, - 0.6291312249550632, - 0.6428100029634759, - 0.6432655159427457, - 0.4472658517941974, - 0.5762763986915236, - 0.618540391970108, - 0.5128800791441517, - 0.46528241075640014, - 0.6747512719847313, - 0.6376352979843901, - 0.5556770793507635, - 0.5000603531927442, - 0.5893553604946562, - 0.6795915767998804, - 0.5226680625589077, - 0.5824700510378695, - 0.6037010709237844, - 0.5428292780192554, - 0.4800574149937442, - 0.6817941148261162, - 0.5394062942061245, - 0.6271057720129216, - 0.4659081256550738, - 0.5052942249266389, - 0.4930923456860563, - 0.6081925232144816, - 0.6791804872561729, - 0.6105527786516869, - 0.6008180805743506, - 0.6821623067441862, - 0.4572457326497355, - 0.6204683166764596, - 0.5339810474628955, - 0.5253429822276452, - 0.47106263067143156, - 0.550227336429305, - 0.5173252148717481, - 0.6106301456774432, - 0.6348485353489726, - 0.5833337102400085, - 0.5309917346195049, - 0.6374272447953427, - 0.5477753756632078, - 0.5492466798370743, - 0.552419164486361, - 0.5608960318064634, - 0.5885747979431227, - 0.6519445618397803, - 0.4913280306632312, - 0.45603339363853757, - 0.46231548913791326, - 0.46344875683692943, - 0.4424680073482086, - 0.4425873868633462, - 0.45444088114484243, - 0.4475386200526053, - 0.4542471150264557, - 0.4593183564334706, - 0.46361026942994243, - 0.4570343117849752, - 0.44952863420540945, - 0.4459802594607051, - 0.4520573667656606, - 0.44246018785901675, - 0.45324632180443963, - 0.45570674972820624, - 0.4627121737994615, - 0.4631687418627924, - 0.454619452339615, - 0.4589672395629665, - 0.44203949259743197, - 0.4485877906315598, - 0.4614774235768304, - 0.45284258758116175, - 0.4621062685155843, - 0.44564720959564974, - 0.4496981220821719, - 0.4512557787865811, - 0.44208885561950556, - 0.44675337620228706, - 0.4421901727453063, - 0.44976839514567146, - 0.4589345208226392, - 0.45753099855037227, - 0.4579720951298283, - 0.45686043936038406, - 0.45331293511376447, - 0.46143629259162033, - 0.4574328983531346, - 0.44363649385445314, - 0.44343517875688204, - 0.44036328559251897, - 0.44206453076492247, - 0.44809886079035777, - 0.4491339662501841, - 0.4613261052401351, - 0.45538060021677657, - 0.46293109676261557, - 0.46291973689271154, - 0.44003526405071436, - 0.4576952370546423, - 0.4624658766439772, - 0.4531047553017271, - 0.4513871192436252, - 0.4588905184053309, - 0.4486350265552649, - 0.4576133509077297, - 0.45338271354530374, - 0.46065824057963023, - 0.4621318149647086, - 0.4447102338463974, - 0.45039744522310915, - 0.45575141801489943, - 0.44599581452239373, - 0.46033194501359886, - 0.461084109277259, - 0.4561413574429113, - 0.44397016346893126, - 0.4468792831203738, - 0.4437814125729184, - 0.4625895005069994, - 0.44872181307528236, - 0.45109190530393845, - 0.45102709870055047, - 0.45383289688693557, - 0.4500331441727927, - 0.44133000665439664, - 0.45116337824286623, - 0.4514745422403179, - 0.4471537652892119, - 0.446727987748923, - 0.46260859455273406, - 0.4502438095267574, - 0.4478722464305479, - 0.4588434994813714, - 0.4483320150050167, - 0.4577339308173773, - 0.45699155071356706, - 0.4584132443105738, - 0.44075605703409504, - 0.4576852232902182, - 0.4439696383841615, - 0.4477226230876727, - 0.4412372041105438, - 0.4453599345096742, - 0.4584623963280101, - 0.4496403023522733, - 0.45522349938936657, - 0.44658252486958416, - 0.4617657121947599, - 0.4563426768226051, - 0.44265693439043824, - 0.45951652746314825, - 0.4405107340835382, - 0.4487338212526696, - 0.44716756710383626, - 0.46030424103911494, - 0.462778388577532, - 0.4417321575747928, - 0.44837148873442634, - 0.44496444398644214, - 0.44344897206227224, - 0.44666817905952505, - 0.45334074153366044, - 0.4568851482202455, - 0.440389632870352, - 0.44755323480108533, - 0.45480501897432607, - 0.45000163569816043, - 0.4416082699730659, - 0.4574922901399517, - 0.4621554252306077, - 0.4635835076014503, - 0.448081893664561, - 0.4590936343398673, - 0.44968354725509513, - 0.45662770074777126, - 0.4508831153773791, - 0.4567225070561411, - 0.457085415780591, - 0.4565187150918643, - 0.46353234862084874, - 0.45722514336046904, - 0.4561439070006606, - 0.44859218192326983, - 0.45441284965666084, - 0.4478691992272497, - 0.4625338376484757, - 0.45379852995251757, - 0.4492965072159789, - 0.4597464477509867, - 0.4562641177385836, - 0.4615599658842696, - 0.4563522674409956, - 0.4526982289104713, - 0.45078553089427986, - 0.4569229202591709, - 0.46269092198703454, - 0.4412332984958055, - 0.4508320006283283, - 0.44888337905595277, - 0.4411291856746842, - 0.4549984484247526, - 0.45478480935709875, - 0.4462695761821891, - 0.4521872708000008, - 0.4407796321530118, - 0.4410779123566733, - 0.45899126081526803, - 0.4547271499803354, - 0.45794164462299947, - 0.45173239654358777, - 0.46106439852492526, - 0.44328213476402756, - 0.440084932730712, - 0.44949719730763155, - 0.4468097479450875, - 0.44512355362694, - 0.45195408937884857, - 0.44824738499100025, - 0.4453746322895916, - 0.4478672258453297, - 0.46379346779927605, - 0.44686683173887326, - 0.4613415362364842, - 0.462718053210013, - 0.44030396816280587, - 0.44074121959573304, - 0.4563675464142131, - 0.45311830470237574, - 0.4498946819676726, - 0.4579970282794218, - 0.45911183784270865, - 0.45066868621682626, - 0.4493362919222872, - 0.4559879996977192, - 0.4412097227012472, - 0.4489835518193629, - 0.46078378398801134, - 0.45531878479420573, - 0.4488430841752591, - 0.44823935004713333, - 0.45712282420301437, - 0.4566348345076386, - 0.46357784933589324, - 0.45262928495046795, - 0.4514922905443621, - 0.45823739509823513, - 0.4404313655762367, - 0.4448818733256688, - 0.4514308337378587, - 0.4529015647008634, - 0.4602103168645039, - 0.4522923621779976, - 0.46380864632810104, - 0.4543847100006708, - 0.44873591951006636, - 0.44857868992533567, - 0.45099571058414323, - 0.45657859554961866, - 0.4494377080564312, - 0.4623022080568176, - 0.4630678610249477, - 0.4454116078729532, - 0.44235567824695127, - 0.45421882716755063, - 0.46268424449440476, - 0.45713236646764355, - 0.45459369719516096, - 0.45850334883681654, - 0.4548783306898229, - 0.4613587525369469, - 0.45322123919835017, - 0.4479853087143996, - 0.4569830885669062, - 0.4410009894279965, - 0.4545628936699633, - 0.4516622021870135, - 0.44256005415357275, - 0.4441445735277767, - 0.4540087257064599, - 0.45250159894814673, - 0.4442691840303769, - 0.45013148030361655, - 0.45985888359796556, - 0.4452464196703777, - 0.45108544779653176, - 0.4451907586439555, - 0.4553615015622577, - 0.46338390009722774, - 0.4565082364137164, - 0.4502564195021807, - 0.455327338430175, - 0.440341269440663, - 0.45687419874914476, - 0.4545380449239715, - 0.4419559004005813, - 0.44908808142826884, - 0.4507237456419724, - 0.4480938280641278, - 0.45239886257501116, - 0.4563460107191394, - 0.4575704104615154, - 0.4510733811069653, - 0.4479668595523907, - 0.44690250248486363, - 0.4472863616838509, - 0.4624156919538296, - 0.4634770375886114, - 0.45295658187501653, - 0.44211955351766596, - 0.44285057561114105, - 0.6369362115254968, - 0.6657626954784601, - 0.65004155952808, - 0.6885239787454943, - 0.652644488364838, - 0.6714477061109684, - 0.6533272649692031, - 0.5155158739666248, - 0.4801719298487125, - 0.5720232651234901, - 0.5084351666458858, - 0.6013344826014102, - 0.4756176370966742, - 0.6408845522685611, - 0.452126435884871, - 0.6766435141802936, - 0.5613935142088131, - 0.5803761632017427, - 0.6299088622321387, - 0.48017808030100617, - 0.45650201657005907, - 0.44881107728563946, - 0.45187792959816564, - 0.6015961202226301, - 0.6560699457505255, - 0.5151214116592557, - 0.5747856449347248, - 0.495843150282695, - 0.47535600138692563, - 0.6089994611458828, - 0.551371873210565, - 0.631676073453085, - 0.668226622496779, - 0.5851602441594469, - 0.601691398394382, - 0.6163004788083637, - 0.6851423731675521, - 0.6034410065526026, - 0.6811711640332836, - 0.5981370040814361, - 0.4492274598817192, - 0.5900740386137912, - 0.5029690601697262, - 0.4474809812994321, - 0.5396970678842589, - 0.5736737023773644, - 0.5476590282315098, - 0.45218908779250483, - 0.453032114257786, - 0.5296857405543447, - 0.5485710944255899, - 0.5889428915375325, - 0.4705892086749124, - 0.5171840816898963, - 0.6575487776203599, - 0.6459825693487882, - 0.5437749436461348, - 0.5810087614912853, - 0.4682024343625176, - 0.6412834314722857, - 0.5892192616042851, - 0.6147633837080273, - 0.6190114204110733, - 0.5611328125361542, - 0.6830412120798929, - 0.4872322231748509, - 0.5858798939072049, - 0.6410822381336136, - 0.47609750294154296, - 0.6105908218317112, - 0.5470680049740488, - 0.4445984171308372, - 0.49937382603622743, - 0.45358096383073543, - 0.63012006524824, - 0.46938421796554947, - 0.4703920035082346, - 0.6079783082610777, - 0.6729012911377077, - 0.44698573887548826, - 0.5373145562986157, - 0.6793891718131352, - 0.48346613837913877, - 0.45551142355158303, - 0.4514305140608501, - 0.5325185857918131, - 0.6382287738709005, - 0.6809180643640167, - 0.45801228921183346, - 0.5433783407168473, - 0.5442188210076576, - 0.6418331818923612, - 0.6284311633277687, - 0.548890705035394, - 0.5259886324972022, - 0.5195982012865034, - 0.5894482731520329, - 0.605634649672404, - 0.6763451243316237, - 0.6401554171550663, - 0.6787235552756565, - 0.5800799202615334, - 0.45130991741326454, - 0.6873647780314229, - 0.6396826640603748, - 0.5629644411591019, - 0.6180748646375275, - 0.4790827492116528, - 0.60170444454738, - 0.45619942850593975, - 0.5810444038172977, - 0.6649516691838924, - 0.5881047872157236, - 0.5438655167573996, - 0.5696416600048495, - 0.5819235995977312, - 0.6540021216710257, - 0.44163317537762065, - 0.5078083018451583, - 0.6765166142078323, - 0.6568460878446893, - 0.632615892721744, - 0.494641686538149, - 0.6074488321772631, - 0.5293384902453266, - 0.6024810418168011, - 0.5776516654090348, - 0.5679355442723798, - 0.6391798225735441, - 0.5405547031758847, - 0.6866537728167871, - 0.4704728739478746, - 0.4748383323131176, - 0.6331700467444747, - 0.5753565606604114, - 0.6408211782217603, - 0.4462414620076116, - 0.5297543236444311, - 0.6744842126669743, - 0.6641431874268519, - 0.5722550030360255, - 0.6769390581304078, - 0.5880713229257281, - 0.5828629172099061, - 0.6751143393033757, - 0.4812722314021394, - 0.47301025336963043, - 0.4704941659224975, - 0.4709954955200064, - 0.5519450939044799, - 0.6756682743359452, - 0.5941960334811898, - 0.4424163115432106, - 0.46864932336975773, - 0.5060516265291117, - 0.6875849329770581, - 0.47839130668423024, - 0.5115704393855867, - 0.5004370796470137, - 0.6374423665009311, - 0.47069262875957446, - 0.6861318102251948, - 0.5971010012756507, - 0.5679182635688382, - 0.5728778510630581, - 0.6494060158759665, - 0.5648772341166584, - 0.6517789816563895, - 0.4577096111393605, - 0.5523126601420596, - 0.6296378499995264, - 0.5335796078765914, - 0.5167634179415745, - 0.5034448212738356, - 0.6063184986330697, - 0.610729872785593, - 0.6240974699175937, - 0.6122895951604048, - 0.6629632471375553, - 0.5225371011978163, - 0.6317902441775534, - 0.6143421671745476, - 0.4942333795431436, - 0.6010571679692125, - 0.5114099881447858, - 0.6623031873834789, - 0.5715820068800616, - 0.6808593024683014, - 0.674863821560148, - 0.6437260843267356, - 0.49712426306718605, - 0.556852075401107, - 0.44732858120934393, - 0.4991124307525429, - 0.5166472646028563, - 0.6745034967780279, - 0.4771525949035472, - 0.5750543422577391, - 0.5898124389749206, - 0.5160754301691766, - 0.5457775163732546, - 0.47128909456741863, - 0.6782746051678352, - 0.5466324838871996, - 0.5685381919175053, - 0.6699637446881002, - 0.458104461651296, - 0.5985662462349872, - 0.6253632912440413, - 0.485303507977232, - 0.540208940099221, - 0.4620550342260913, - 0.5414576693208135, - 0.6280222989862156, - 0.5012538186048379, - 0.6740777260259467, - 0.4627768527552769, - 0.6781257113526302, - 0.6792804702100856, - 0.5734389182387724, - 0.4587488358896558, - 0.49018490392482916, - 0.5284762623492507, - 0.45412863534551584, - 0.5707253612433139, - 0.576726729916862, - 0.5287272395656056, - 0.6758802526801815, - 0.5151924555659624, - 0.6060858600460388, - 0.4682910244630679, - 0.48241823440369946, - 0.46521903533992254, - 0.5382794389684822, - 0.6527781886454631, - 0.5150809066220512, - 0.5029313115333338, - 0.6338360974887487, - 0.44766493571131566, - 0.45102300743895446, - 0.6629242606554738, - 0.5198550030652267, - 0.6401131486353613, - 0.5870686568408576, - 0.484099073220651, - 0.4785763692061416, - 0.6080133833426753, - 0.50977982533784, - 0.5631466933247029, - 0.5856184802392537, - 0.570218354894509, - 0.4731294800651183, - 0.4757212430207985, - 0.6871472310404307, - 0.6533500594543888, - 0.46980360160736573, - 0.5245988662672428, - 0.496547136811919, - 0.5728035205791207, - 0.6292496102806646, - 0.553224293231945, - 0.4882743748275563, - 0.6102278256732786, - 0.5692106330033122, - 0.49475769562143257, - 0.4551171833347837, - 0.547234836376278, - 0.6587985759913855, - 0.6562688830825814, - 0.610200454888603, - 0.5060756061561921, - 0.5397622998805203, - 0.45699402777563863, - 0.6268205767786786, - 0.5996562638018881, - 0.6003052438713176, - 0.5656567404338275, - 0.6056221052806523, - 0.47513199725211175, - 0.5264571318460711, - 0.6586198598704833, - 0.632539456522349, - 0.45409510497071676, - 0.4792128991268118, - 0.683955513641842, - 0.46150573254111893, - 0.4838009606717995, - 0.6204448111570201, - 0.6206969846845378, - 0.5161722136698746, - 0.4448141035518563, - 0.5903910025054953, - 0.538867752303656, - 0.5283488891444345, - 0.44975788420065366, - 0.6639355562174305, - 0.5340155814156726, - 0.5291680859585379, - 0.5264054055106373, - 0.6481286619283477, - 0.6470487071421851, - 0.44739826045576536, - 0.4883595971360524, - 0.6272633379956611, - 0.6540963088474501, - 0.5977631576047702, - 0.6737708306241403, - 0.6854841944568096, - 0.6535113167183616, - 0.5504853305095649, - 0.556198197174203, - 0.685116439277216, - 0.4640329356751391, - 0.4507207499773124, - 0.5448278833624931, - 0.5701025018646058, - 0.5271528257722973, - 0.6012655413557375, - 0.47518595149198695, - 0.4581848796754358, - 0.685814207253969, - 0.5623594413965075, - 0.6791991907982582, - 0.4519807536876245, - 0.4777288896626275, - 0.6705124524986276, - 0.672299285058809, - 0.44413992421194654, - 0.6268297994889408, - 0.6414156522043463, - 0.48723329553741007, - 0.5454625814333481, - 0.501842746140446, - 0.539243193273628, - 0.6432525065503343, - 0.5735455511822174, - 0.5575008036596468, - 0.6457306702650685, - 0.5925417545310789, - 0.5058522910128272, - 0.4915999224332679, - 0.46234810941549387, - 0.6725188407813447, - 0.519295450769065, - 0.6783597022985702, - 0.48956654503353275, - 0.5136491431618643, - 0.45136748029284834, - 0.6026381040356569, - 0.6735495968627027, - 0.5310484576738718, - 0.628436783938939, - 0.5761693136753372, - 0.6000707668449841, - 0.4940144075015996, - 0.6014505093171189, - 0.5476328954342664, - 0.5864553611443339, - 0.6095974171273494, - 0.4862843094115489, - 0.45341628387764576, - 0.5970884248581454, - 0.6018939490406963, - 0.46010594034650687, - 0.6374680534148237, - 0.6603967975241855, - 0.5296581654466256, - 0.6675741280853135, - 0.6089588891227324, - 0.46018451119525, - 0.5645889365227186, - 0.5578324652629193, - 0.5059789750837159, - 0.4490273973281317, - 0.5480928595474317, - 0.5995197201561232, - 0.49670666471952585, - 0.6637431453518673, - 0.6169558337526967, - 0.5797415044115011, - 0.658737083365576, - 0.6022005221300426, - 0.5179652625024724, - 0.518346738841812, - 0.4680486660854586, - 0.6741228807369923, - 0.45741138176250995, - 0.504378055830762, - 0.49219302875607973, - 0.6570669206271326, - 0.645093543788625, - 0.547168707704359, - 0.4837591063737455, - 0.5189949453767478, - 0.5227707051938502, - 0.6391622550696902, - 0.5025905250582227, - 0.6573829401338516, - 0.5446023653218486, - 0.5450415666913478, - 0.6607621247241815, - 0.5728657102076687, - 0.5897822824731883, - 0.4694265649146601, - 0.672601696464963, - 0.5875503869338297, - 0.540884431375847, - 0.5407083705537002, - 0.5507228990886381, - 0.44091807743774597, - 0.49047456396741235, - 0.4811800726619049, - 0.46407015630600007, - 0.485344518766317, - 0.4928663605268882, - 0.6736656989981497, - 0.527151151545708, - 0.628996627720017, - 0.6866274542932183, - 0.6865701291306742, - 0.6362434301956474, - 0.5069381849041732, - 0.5360969873874181, - 0.47292450430178234, - 0.46617112985850107, - 0.6531451975919425, - 0.4660662279545214, - 0.6783131905803093, - 0.6245571921090487, - 0.50782971433604, - 0.6018526872594726, - 0.5778127684890756, - 0.5925632027274931, - 0.5511203138241737, - 0.5151743727115723, - 0.4901914701022127, - 0.6264777251823248, - 0.4821460651417126, - 0.46355022801246915, - 0.511478843378451, - 0.449603645975869, - 0.5356240765315585, - 0.5717102114885382, - 0.6224375776801159, - 0.6305345210032292, - 0.6314813585474583, - 0.5185084450333094, - 0.6412142073394849, - 0.466134360711886, - 0.6251088574024869, - 0.6286355946414593, - 0.516194565438314, - 0.533280459699521, - 0.5992753730297348, - 0.6444078766844952, - 0.642220681112383, - 0.46621982493867925, - 0.5182166779525927, - 0.5939896849672338, - 0.5176654201304456, - 0.5530228760234939, - 0.6362112589091157, - 0.6328534250200153, - 0.45251171930227346, - 0.5311040527689186, - 0.5728870913064288, - 0.4987954249443429, - 0.648547798654207, - 0.5793790760579348, - 0.6012386180990188, - 0.5538031986265197, - 0.6402077835934107, - 0.6163656085353111, - 0.48081855414837543, - 0.44822831868297, - 0.4567213767777074, - 0.6554835271753222, - 0.5593931924268337, - 0.5734273190128112, - 0.6622712508077055, - 0.5037226613537923, - 0.6206105698955933, - 0.6177095971609816, - 0.5171324976584566, - 0.5061262693869074, - 0.5340190147295046, - 0.45056359487634084, - 0.44509258772675975, - 0.6097480825261443, - 0.5181607462281105, - 0.4902905428054021, - 0.6381056270535115, - 0.586581782297423, - 0.6818369634587904, - 0.4675707840797423, - 0.6866465457859678, - 0.5159655185089028, - 0.5251344315583976, - 0.4633915915619286, - 0.6449316512680757, - 0.6534448614224101, - 0.5776623163511762, - 0.45503679851858136, - 0.4971769301333007, - 0.5958678946450533, - 0.6029081984272957, - 0.6801384432295283, - 0.4560126446761988, - 0.48601503991654554, - 0.527900595467448, - 0.5254390034696971, - 0.6662095074944387, - 0.6438982831942117, - 0.6734248380684424, - 0.5784006312329191, - 0.6245824979186331, - 0.5587905994457443, - 0.5286624254156153, - 0.5683378989649206, - 0.6582586315149774, - 0.5295622334209601, - 0.45205466102666403, - 0.5098868921969408, - 0.5669520744911716, - 0.45438612217637825, - 0.4924188608206746, - 0.6639376705511488, - 0.6319750910734302, - 0.6491827006983778, - 0.44592320930217605, - 0.5398339696681842, - 0.5725448240925527, - 0.4572775402903683, - 0.5375521958236338, - 0.5336257135206928, - 0.5329868741522443, - 0.5943969808746139, - 0.564852381173135, - 0.6138426568154574, - 0.6348958400802011, - 0.49467958625662384, - 0.5868778243404852, - 0.532858585973484, - 0.6621536675823184, - 0.6454748075498862, - 0.5477947342029882, - 0.445102616291365, - 0.5200762500272992, - 0.575404418787964, - 0.5683303086142542, - 0.4866266214044403, - 0.6813028325691671, - 0.6046206869622177, - 0.6058957976293182, - 0.532920863495986, - 0.5749143782899654, - 0.44703689971371463, - 0.5890637731573295, - 0.5053107922921996, - 0.5681168363059987, - 0.5479804698835966, - 0.5622004081745722, - 0.4512399664103231, - 0.4699137796954954, - 0.6166863918955995, - 0.5420324516470667, - 0.6576626774081862, - 0.6586030623183964, - 0.49660569933891774, - 0.6035409576593864, - 0.5343975581241623, - 0.64430440007148, - 0.45860531976512303, - 0.6768489336689111, - 0.6350195195756974, - 0.5624032956186611, - 0.6261503523666789, - 0.6481342858799197, - 0.6442140405349057, - 0.632272697609428, - 0.6527374272536657, - 0.6142895181404253, - 0.46559405163759826, - 0.5925190996164945, - 0.6860507893664176, - 0.46134735572080837, - 0.5867594016938882, - 0.6385369099599445, - 0.6744524027868217, - 0.6019461902770491, - 0.4730318102663766, - 0.6409973984373456, - 0.4556932209053698, - 0.4786211670532474, - 0.6809598686837894, - 0.6442023020426996, - 0.6696038420038171, - 0.6582168604045777, - 0.5435268344171013, - 0.6775768670723799, - 0.5702621893054642, - 0.6252795637450028, - 0.6103791793755036, - 0.5366787125580281, - 0.6862471484192739, - 0.5540518750576818, - 0.5572916643185485, - 0.4629563446471639, - 0.49844053414189526, - 0.5876980981580158, - 0.5739905945987147, - 0.6067137147997215, - 0.6068687957308775, - 0.4423252380424413, - 0.46591446082562404, - 0.6283434113603457, - 0.5782823386502183, - 0.543498660826423, - 0.6227817408802834, - 0.44975740976039186, - 0.5286009624587882, - 0.6740081389744543, - 0.4497385635290738, - 0.5137227963452833, - 0.6871724247384509, - 0.6395733544287063, - 0.6471493316508915, - 0.6442629242547077, - 0.5184674640229439, - 0.6049926489946339, - 0.682861822602342, - 0.6805085545079493, - 0.4935598291113042, - 0.6220184064601292, - 0.6529945901501883, - 0.6773730973640929, - 0.5242495998402167, - 0.5393053113644963, - 0.5935715529099976, - 0.582109597641311, - 0.6145596284349288, - 0.6227880714410611, - 0.4497034983930753, - 0.5676099036450346, - 0.6228600922151372, - 0.5106893231402011, - 0.5173482660878976, - 0.5127685003262777, - 0.4850042416804243, - 0.4535300839557262, - 0.6433609060696374, - 0.5345685819272452, - 0.6195946228576203, - 0.5787045208896802, - 0.4685385666133252, - 0.5674137899404804, - 0.4811890491477065, - 0.47249121918362386, - 0.592479711895224, - 0.5521684165781697, - 0.6663400972330055, - 0.5068073275981786, - 0.45669525010154954, - 0.4968077371010732, - 0.5457873308928848, - 0.5735291060798939, - 0.6726098102548461, - 0.46030997158105247, - 0.6213885496539016, - 0.4646186113876012, - 0.6493448267549085, - 0.6719727248807239, - 0.5899402071141182, - 0.5470329701862431, - 0.5410550231501745, - 0.488523981531005, - 0.5386116575614581, - 0.4655232613569855, - 0.668242919834355, - 0.5885159552700501, - 0.6045301342970906, - 0.5016057558064743, - 0.5653946896730272, - 0.4798157979806071, - 0.5635248767045811, - 0.44162973353781637, - 0.534049808860496, - 0.47091611767931113, - 0.5977567614149466, - 0.4519654938859319, - 0.4473752038248143, - 0.5894256471098466, - 0.6709339214770064, - 0.5424336049734995, - 0.6150322286012626, - 0.5856639295003374, - 0.45847702611653146, - 0.5964210894220747, - 0.4740592969149767, - 0.5094280621895367, - 0.6870476842228173, - 0.6553030730660241, - 0.605140346988474, - 0.6341044348902318, - 0.5279887300123953, - 0.44142587510397663, - 0.5720378503051181, - 0.4862989853799054, - 0.5174388156603998, - 0.5302273639251173, - 0.6856081383148053, - 0.47685690621554533, - 0.49880222656699863, - 0.625941250473181, - 0.5991673260320003, - 0.660828677209375, - 0.5230816761151418, - 0.5407056267788859, - 0.5377936566314411, - 0.6532862374530489, - 0.49768889820204243, - 0.6788706230613636, - 0.539084200377995, - 0.6082860896803288, - 0.5139335489301503, - 0.4995543451673172, - 0.4447896086239449, - 0.5964512681118402, - 0.614420962786363, - 0.6330417286917511, - 0.5438410934435004, - 0.4496993957188362, - 0.6224138737201956, - 0.6628631584804062, - 0.4914928394541417, - 0.5389221144876825, - 0.5803224543391057, - 0.5060174667897105, - 0.5200917036202763, - 0.4873620593903558, - 0.47001527726219283, - 0.5724126118129278, - 0.5616163641989986, - 0.650658516766696, - 0.6599880939258056, - 0.6753551529856874, - 0.684024370146653, - 0.45906492124468845, - 0.5328555265408187, - 0.46156388107052054, - 0.6472061881390425, - 0.6514075731068962, - 0.6113610338374741, - 0.6012983330541916, - 0.5725603482361835, - 0.6821543428770789, - 0.5831261954174831, - 0.6297716181761721, - 0.48038694207985017, - 0.6425287148810298, - 0.643020643301807, - 0.510101963125371, - 0.6003640121169552, - 0.5128303269807403, - 0.5576825155073148, - 0.5704720999599877, - 0.4940008061285125, - 0.48565012165101185, - 0.5248761022054671, - 0.44483592547162093, - 0.6510503998903293, - 0.5834197864280017, - 0.68062252568805, - 0.6280441194003349, - 0.49070152177219106, - 0.5806548068938004, - 0.5104338516635113, - 0.527255683015098, - 0.6166721773403686, - 0.5749326932081897, - 0.4683058011696998, - 0.5142687981698082, - 0.5288912403782923, - 0.6220501855460354, - 0.6639762781061865, - 0.5724432369611546, - 0.4711253353705647, - 0.5781853792487452, - 0.6475350646445427, - 0.627712032456838, - 0.5358578861760621, - 0.5937763494114576, - 0.5082749597386835, - 0.6610635638069144, - 0.6798361679485165, - 0.474314176289336, - 0.565882813062673, - 0.606551110667628, - 0.4594350779721959, - 0.6326195555010963, - 0.4869173649952052, - 0.5386301986411335, - 0.6464953803135574, - 0.5693920973261934, - 0.6534657265902037, - 0.5539806999382884, - 0.5660653870789142, - 0.5394285057885252, - 0.6745005043965311, - 0.4533244373313024, - 0.581833447452664, - 0.6658402868636892, - 0.5121390862465822, - 0.5055853671770616, - 0.5703185299940601, - 0.5972519119671714, - 0.5873128234456702, - 0.5742221234623685, - 0.6696281535017352, - 0.6843337541040957, - 0.5159493500109102, - 0.526551790407858, - 0.5748025203653823, - 0.5679751946714118, - 0.6823846720789614, - 0.528666947773083, - 0.6388650440154303, - 0.47939263604502835, - 0.6563482230866884, - 0.5795395583034819, - 0.6762149952228803, - 0.4551439443325208, - 0.6034337192149122, - 0.6292034038641641, - 0.5282145556377091, - 0.49162642711087284, - 0.5522000512975365, - 0.5193978091906614, - 0.549414002359202, - 0.4486606095614775, - 0.6884448213025489, - 0.4587363242633381, - 0.5727687041341591, - 0.6781437585660073, - 0.5578877373565767, - 0.4984010290460324, - 0.4913201634815977, - 0.45042123316890004, - 0.6087095077038858, - 0.6260439459368623, - 0.6103030772823523, - 0.4864812816617473, - 0.506473235474217, - 0.45960080261120523, - 0.5703491190829901, - 0.4665622539488563, - 0.6402187131499525, - 0.4808365404740706, - 0.6369500503392939, - 0.549181826748048, - 0.4514398053190846, - 0.6515224773972215, - 0.5924333073892739, - 0.5451330399481916, - 0.4850838837808883, - 0.5517412613359325, - 0.47789852545701916, - 0.6641540405721915, - 0.5556917207565184, - 0.6714098219158262, - 0.5192126286679668, - 0.5922119668439177, - 0.604171364145654, - 0.5605677322301347, - 0.67558673207308, - 0.4670882197886331, - 0.6835362629711512, - 0.624197815143708, - 0.597699143550647, - 0.4624286526657625, - 0.5507482399909547, - 0.4518010282001913, - 0.6767667512198002, - 0.47730211661013955, - 0.6798218658397546, - 0.440966940668895, - 0.46270366060126106, - 0.6673691193685449, - 0.4418689698480737, - 0.5646102356233456, - 0.6117837779258541, - 0.6451685587363637, - 0.6511351927673789, - 0.44704439791046413, - 0.6699734543935687, - 0.668421914639142, - 0.5847771642679304, - 0.5534719903831008, - 0.6055099349661487, - 0.5258177192272996, - 0.59551345154331, - 0.6024956600390182, - 0.5254149466284743, - 0.46433411316742457, - 0.6161570906270832, - 0.654373692009713, - 0.553903085756208, - 0.6362674361730387, - 0.4877838827014525, - 0.5046020203777297, - 0.5813927768174197, - 0.6206589890461898, - 0.6740172179942356, - 0.535148751967006, - 0.4928308796799094, - 0.5632746217801683, - 0.6677415879526287, - 0.5041748997079236, - 0.5242351934617597, - 0.5972872671246127, - 0.6793417882065496, - 0.6573310219171067, - 0.6052898907201882, - 0.45553537264483634, - 0.6841106670247499, - 0.5726472034517118, - 0.5994856169114808, - 0.49506810409392943, - 0.6732375501636794, - 0.6494446567713464, - 0.583154350170261, - 0.579903161450622, - 0.4555058582284606, - 0.6071226016659617, - 0.6328073713885425, - 0.5052069878901968, - 0.5088350994067548, - 0.6411911436158164, - 0.6019391648021166, - 0.6763522020045454, - 0.672747779751589, - 0.5118606272305253, - 0.571559015347009, - 0.5375934231672295, - 0.5030094271818668, - 0.5634965332424701, - 0.5919988149355371, - 0.5034318812604406, - 0.658769925314348, - 0.45784680768568553, - 0.47235947472179307, - 0.585585591032155, - 0.4808862256301218, - 0.6713186902776695, - 0.5689855260525569, - 0.45261360079798946, - 0.4937853001868551, - 0.6686300968198124, - 0.5632109456639839, - 0.4948593529012134, - 0.4627875592202484, - 0.5894351943085903, - 0.47832733697403057, - 0.4487318852301373, - 0.5525155289181365, - 0.6145022209554947, - 0.6295627998748311, - 0.49099856224806865, - 0.5059031083285725, - 0.5431587245571332, - 0.5487151188209569, - 0.5894080770589616, - 0.49420843833931805, - 0.521353687052268, - 0.4831647110384026, - 0.6494431069871757, - 0.6119606505489773, - 0.4854797269535703, - 0.5088993939442861, - 0.6451475432351979, - 0.5562972702330755, - 0.6539509838867933, - 0.5434800732591242, - 0.673904653046993, - 0.5226760516304043, - 0.5409785713563228, - 0.6771176624347548, - 0.4976660577874668, - 0.6382102667730793, - 0.47898108414465945, - 0.44556985105094327, - 0.5510137105369298, - 0.6402165548248198, - 0.615382184465809, - 0.4833592539421878, - 0.677285695889803, - 0.48323848548941256, - 0.6466942012499027, - 0.4595072992318837, - 0.5647028197769733, - 0.47462537186084064, - 0.5654705415483564, - 0.6613208531265329, - 0.5000943340903493, - 0.46086830394176376, - 0.5058181366001157, - 0.6760919098789633, - 0.6478049400046977, - 0.4914230371002378, - 0.5671909854057755, - 0.5632414509063659, - 0.4636730173409638, - 0.6071245111734196, - 0.44354992071227695, - 0.4795313582283294, - 0.5517754631378086, - 0.6318782521906354, - 0.4447024189768246, - 0.46814191014061907, - 0.6484783730929925, - 0.5133782874939943, - 0.667045827105132, - 0.5383693800964141, - 0.5178818600735227, - 0.6876590179038674, - 0.539807394488223, - 0.48997822722023265, - 0.45037730366944445, - 0.6225451595813346, - 0.6744519769176467, - 0.46339619186774444, - 0.515958086194703, - 0.5579432511493341, - 0.6867656056545877, - 0.6729830095034052, - 0.4767156376435558, - 0.5186396012495605, - 0.6745340600101684, - 0.6279765825163709, - 0.4710063356710421, - 0.520872281639728, - 0.5945700610739018, - 0.5382084732901835, - 0.4731657557333987, - 0.4704300006669973, - 0.6534115070877824, - 0.6794651610604481, - 0.6571952909466955, - 0.628842471924761, - 0.6342787791882804, - 0.5639703744383446, - 0.531516391517824, - 0.5884144671805095, - 0.5716044526796114, - 0.5705905004575772, - 0.6055497042139728, - 0.6263599788633746, - 0.47986553533227627, - 0.6244330742556811, - 0.6366315191574223, - 0.5992617832699613, - 0.5701996224721517, - 0.5295704876215911, - 0.5572469470353346, - 0.6849764265079352, - 0.6088501874018333, - 0.6406897040084586, - 0.5232542466100336, - 0.5700589375538009, - 0.44134963490381546, - 0.462949080182871, - 0.5128054396250481, - 0.543502896905484, - 0.5684240258980295, - 0.4827147200203485, - 0.5559174991011248, - 0.6030952710604011, - 0.47596236350698906, - 0.49308213727731043, - 0.5239814470501666, - 0.631740994905952, - 0.55507428265167, - 0.5425357076888905, - 0.48906492567869336, - 0.5070138648685453, - 0.5957283116706116, - 0.5022947576234521, - 0.6310703654754526, - 0.5410480493758002, - 0.5936268816910333, - 0.6152485183605141, - 0.6019153468122858, - 0.5904690171809698, - 0.550580088271778, - 0.5693485263503114, - 0.5259470632141499, - 0.6744679721154335, - 0.5575038611589263, - 0.6120965035611737, - 0.652379135254755, - 0.5743793443261486, - 0.4942946635987465, - 0.6009121042449371, - 0.5864771142106431, - 0.5586810969172193, - 0.5706570650929743, - 0.5311880117998191, - 0.673619463398722, - 0.5799992237628467, - 0.4440587595109389, - 0.5988217095462831, - 0.6736726565785074, - 0.682970587163916, - 0.47377596539907607, - 0.5628540710533246, - 0.568856137851119, - 0.4573138198146103, - 0.4844793674689632, - 0.5966354535090176, - 0.6662356266115059, - 0.679336374906655, - 0.5804199101085432, - 0.5014857071594849, - 0.6837384101029702, - 0.4772420889351513, - 0.5124822760256158, - 0.4697554004714607, - 0.5207728552601107, - 0.6250608259624442, - 0.6058250718183327, - 0.5598443167057839, - 0.5047472585593742, - 0.5795005726378578, - 0.526535406654409, - 0.6533191610378161, - 0.6884668867369557, - 0.5609489142621971, - 0.49942906045687974, - 0.5307469052338573, - 0.5054287358378047, - 0.5941941616079083, - 0.4532136370966078, - 0.5747373117178785, - 0.6737431931287451, - 0.6216675096699658, - 0.5638636411005467, - 0.5465943363581587, - 0.5893287738430781, - 0.5030238679104163, - 0.5607624933907343, - 0.4859961132142636, - 0.4504073679634489, - 0.4910502972258297, - 0.4919874660200801, - 0.6237972874554154, - 0.5637090085254791, - 0.6587226587048596, - 0.462424910529019, - 0.6421592990060998, - 0.5088580151366588, - 0.6335598280064274, - 0.6643392237648633, - 0.4635136064912452, - 0.6799528490873818, - 0.5586589783483433, - 0.5331258048629777, - 0.6264804434363432, - 0.495898020118284, - 0.6001334781918629, - 0.6524807847546381, - 0.5856361649217355, - 0.5157842358792528, - 0.6828717882590492, - 0.6687577835415507, - 0.6051355721279076, - 0.5417271939945546, - 0.6212380592283518, - 0.5876021090262347, - 0.5288217214772142, - 0.44150888608305133, - 0.6423758042481521, - 0.4515262778726809, - 0.5429087531264607, - 0.5139630252799946, - 0.5322465190672218, - 0.5999456939932436, - 0.6393148610488075, - 0.5533290084870663, - 0.6073461500745555, - 0.4472217318759155, - 0.5297273771016748, - 0.6032420899850519, - 0.47324203487530975, - 0.5733692197368009, - 0.538225458102784, - 0.6634826142601109, - 0.6229964919800677, - 0.49830932255631605, - 0.48877935875956896, - 0.6628765600952393, - 0.6846098951631688, - 0.6098390165180592, - 0.47965865720235, - 0.6105401431650024, - 0.5484524110214773, - 0.6052300125461899, - 0.664715968675089, - 0.4571277725972301, - 0.5465010950742598, - 0.6335190121342945, - 0.45375165554634556, - 0.6882429289965395, - 0.6689535094697546, - 0.47236465904260344, - 0.5514912488768843, - 0.5546272593364463, - 0.596275492963826, - 0.5590877628210764, - 0.6522935254789405, - 0.6651508896074293, - 0.569563896676845, - 0.5663084760939225, - 0.6804576772211912, - 0.5480733589866853, - 0.48984776421665555, - 0.45997204203802833, - 0.4797468875293018, - 0.569607683194871, - 0.440319525054345, - 0.6575372905955671, - 0.6268745979859892, - 0.5871975912093363, - 0.584482501848647, - 0.6126097278004335, - 0.4455996977383903, - 0.5769058184648959, - 0.6096197921302567, - 0.5831362319738275, - 0.6148466300766433, - 0.6771635210286384, - 0.6674303452404472, - 0.6204734112404864, - 0.6800249339375942, - 0.6421925030682959, - 0.6619940832208643, - 0.6682183624423778, - 0.5803886019983735, - 0.587184380836295, - 0.5269761195179875, - 0.6353157630933245, - 0.6722161372394239, - 0.6864427852113746, - 0.5243680563430896, - 0.5684673000668305, - 0.5649526488642276, - 0.5582579631800137, - 0.5074871980136139, - 0.513519890612971, - 0.6661161849734771, - 0.5607389010218171, - 0.617389079358936, - 0.660606990957509, - 0.49224220889598097, - 0.4856369449100375, - 0.4898324479646311, - 0.4768212761862734, - 0.5822690410479149, - 0.526205647336572, - 0.5448227385294699, - 0.5795279624843512, - 0.4677931741490968, - 0.4449450975019241, - 0.5428957562172239, - 0.6207364854424864, - 0.5934801714285705, - 0.5661291774064032, - 0.4855331223692906, - 0.575012025475879, - 0.6852398683939924, - 0.6494394026776471, - 0.5901551769110917, - 0.4713116368326482, - 0.5311112237557719, - 0.6764568652376393, - 0.47822932111606714, - 0.5515547246490327, - 0.5577760312469905, - 0.4731645825679273, - 0.5990649967298999, - 0.6529559558833604, - 0.6376555067425265, - 0.5592542401403241, - 0.5018979594813812, - 0.5490417611917213, - 0.4694773679046013, - 0.6183683943599438, - 0.4458115161655807, - 0.6832346067335632, - 0.5074548689476313, - 0.5141048030593822, - 0.6131219789729894, - 0.6002530929390341, - 0.6774350971868326, - 0.6454999780281538, - 0.6523794111887629, - 0.5592160496907175, - 0.5881920390764103, - 0.4607485012808513, - 0.49242120945784096, - 0.6414657924245791, - 0.5953743444762659, - 0.45955504147702136, - 0.5604489928932712, - 0.4927359032033327, - 0.5530144845098364, - 0.5781647113036079, - 0.6590833401699095, - 0.4593828576950503, - 0.4682900002189653, - 0.6396531592484485, - 0.48064429240246753, - 0.5409803202413958, - 0.5862221594553219, - 0.4848427355861327, - 0.4847713861582809, - 0.5821131781566629, - 0.522062755633827, - 0.5419566621021186, - 0.46933172411929547, - 0.5658085210751018, - 0.5855488884995789, - 0.5033111450709978, - 0.47271447853972903, - 0.5129275079747355, - 0.522664917857377, - 0.47985547947833745, - 0.5097504373059597, - 0.45744993780358156, - 0.6439062697886293, - 0.5782088902300881, - 0.5791579055768448, - 0.5994084651724271, - 0.610188203750347, - 0.6744481033419928, - 0.6882453660136088, - 0.5840544360530815, - 0.5005738127257989, - 0.6454375291665775, - 0.5260411868708355, - 0.5843262346891536, - 0.5209426215014427, - 0.46558708254690023, - 0.6632203204436457, - 0.5030588578394819, - 0.6395945005962396, - 0.6479929130224287, - 0.4671125138933459, - 0.6246598759939217, - 0.6445516397937595, - 0.4522131051176452, - 0.5615155151834565, - 0.5646651869427126, - 0.6017660259019426, - 0.6738023818585194, - 0.5538517813871904, - 0.5085196186242703, - 0.4677007397164674, - 0.5386201529333937, - 0.6799901613695266, - 0.4715471981738236, - 0.6297760442780096, - 0.5614366458727992, - 0.46160888136921596, - 0.45604333426597443, - 0.5706865866189975, - 0.5956215926505996, - 0.6314201445725759, - 0.5710033106564107, - 0.524591046863642, - 0.5630824233747346, - 0.6295454579469548, - 0.4750334301813216, - 0.5911539367953582, - 0.5695233559449899, - 0.46683373747522333, - 0.4601299412256765, - 0.5052218278259925, - 0.6847921441939692, - 0.4937548134709694, - 0.5844341090578983, - 0.4501053523748018, - 0.6074450510940983, - 0.6357248200028822, - 0.5568915522776933, - 0.6309466978566545, - 0.5491791918422532, - 0.5613415626395368, - 0.5760798098902326, - 0.5046962116321239, - 0.5474559060943763, - 0.46288788592804536, - 0.555153443389069, - 0.5238102105740232, - 0.6682121494942643, - 0.4615803898478721, - 0.6655492494599473, - 0.6356207598314192, - 0.5342702277343359, - 0.6194446292930498, - 0.6651974625063469, - 0.47335307575267843, - 0.6856786968192703, - 0.558442758852018, - 0.5923753804736971, - 0.6599113931588696, - 0.6283701359603017, - 0.5732304651297288, - 0.5924518537562824, - 0.5845915524515476, - 0.5770768886204636, - 0.583885162196961, - 0.6119723585349833, - 0.4535003506093453, - 0.5490306314002278, - 0.5138167538093632, - 0.4636761018116219, - 0.5055262783558542, - 0.5559516977184931, - 0.47557046331637093, - 0.4988414191470308, - 0.51483666273669, - 0.6658049657494183, - 0.4441848485205156, - 0.6861149576133069, - 0.6050139182855224, - 0.6548117537683371, - 0.5663690696599901, - 0.6031480944619716, - 0.447781358323557, - 0.5147753694335878, - 0.5549520102981134, - 0.5433703966708963, - 0.6414613758577871, - 0.6777315240716393, - 0.6426863463485555, - 0.5707789225303013, - 0.5888199360830484, - 0.5067233033384191, - 0.6097978054695892, - 0.5494691896143861, - 0.5376569550377657, - 0.4697748884039076, - 0.5249966394107826, - 0.6548658436822156, - 0.5912091335557993, - 0.5999224814024458, - 0.605202559022689, - 0.6242628211214815, - 0.5785609613286696, - 0.5066369968198385, - 0.47758002075889155, - 0.5017169426799414, - 0.679188213565856, - 0.6279588267917168, - 0.44491915115675434, - 0.5721915106667167, - 0.4850675746213991, - 0.4913816593767619, - 0.6482738889681978, - 0.5523137354778315, - 0.6103264254568912, - 0.5023870508231965, - 0.6720274377539994, - 0.5565353307834588, - 0.5831328526312224, - 0.5116451886138181, - 0.5607456028886986, - 0.6268716548442526, - 0.5165635524520288, - 0.6551776808343309, - 0.6049296034320039, - 0.6172781770140374, - 0.6655463606696893, - 0.5894756751417425, - 0.5406567759898389, - 0.4674857409722783, - 0.5395750262718032, - 0.5619019356015483, - 0.6234538095166483, - 0.5963235149406535, - 0.6293670640140124, - 0.6595099495045779, - 0.6290337989630927, - 0.5861452035769874, - 0.47386451035818344, - 0.5313745159110076, - 0.6694171958382686, - 0.5205688464646808, - 0.5260892009399377, - 0.45507792494475535, - 0.5449470527389404, - 0.5999267223371406, - 0.6062489589769811, - 0.5094607428158962, - 0.5092933456325072, - 0.6577963986268445, - 0.6069718371359598, - 0.5784362764415685, - 0.4995022480220932, - 0.6036941062147725, - 0.579581904408296, - 0.5243498287176509, - 0.4672049622294723, - 0.5016621058630274, - 0.45041962288375126, - 0.4461026078298861, - 0.5696363255547017, - 0.5246143081562937, - 0.49603322331487965, - 0.6523190011738217, - 0.6818572448252562, - 0.6111725516162931, - 0.6328544560651372, - 0.5677470810898415, - 0.5032669451634091, - 0.6662411879907626, - 0.5226354030782134, - 0.48511468740015384, - 0.6350299395175896, - 0.6864107877017528, - 0.5679410413282147, - 0.44636394469820534, - 0.497663847876471, - 0.4644783820386539, - 0.5103613648295482, - 0.6135140106192226, - 0.6581935680027985, - 0.6860170381429731, - 0.5387052391808496, - 0.47120464140336504, - 0.4957076152022888, - 0.5744586678313455, - 0.5448366783534337, - 0.5058851276297318, - 0.501921804210888, - 0.5183700845893449, - 0.596581085558163, - 0.5463670336731998, - 0.6258130980159107, - 0.5025955913464512, - 0.6807639620788468, - 0.611865997472592, - 0.4925617979824381, - 0.5545956337127486, - 0.5561047826093092, - 0.5527964848580527, - 0.5751753791927515, - 0.5423653257711056, - 0.5270335885875324, - 0.6390571231418682, - 0.648608674308, - 0.5555080799674103, - 0.6543681252678549, - 0.550137418301941, - 0.6340790093685449, - 0.5437784877793186, - 0.515479344831588, - 0.45532859466144715, - 0.6137592377714416, - 0.5739861585773934, - 0.520522283038203, - 0.5351736847104525, - 0.5307231762571503, - 0.6182280501467837, - 0.6076221731822311, - 0.5689253079268367, - 0.49079117042381065, - 0.629343109842914, - 0.5512665332784893, - 0.6439740526779876, - 0.47191634377725517, - 0.5362710160548703, - 0.618757458860187, - 0.6114093554303457, - 0.5659347120056702, - 0.6437400008215439, - 0.5303929724523462, - 0.6305872090130746, - 0.562741426631933, - 0.6506049840311504, - 0.4887064414096123, - 0.6572539334271468, - 0.5542296974431148, - 0.6308765745423339, - 0.619416755264039, - 0.6135115936655473, - 0.506001216369548, - 0.48031571995748096, - 0.4911030591828801, - 0.6130311662037682, - 0.49024133978737067, - 0.50292429609994, - 0.473123734207829, - 0.6592697994997037, - 0.6503578186427281, - 0.4565489637383493, - 0.5791387536501676, - 0.4916108530889437, - 0.6843928792340753, - 0.5171250052343721, - 0.5554849604235743, - 0.5337086589428601, - 0.5787702999169133, - 0.6723497048806999, - 0.5000639015796415, - 0.6248358443411289, - 0.5231913760236423, - 0.6290479575509236, - 0.6810866832686759, - 0.5801640393375911, - 0.5040441115812153, - 0.5739467284436732, - 0.5653145486092961, - 0.480742006616088, - 0.6601519960996363, - 0.6339267529179364, - 0.5082356559453478, - 0.6211937606671758, - 0.5990692658070504, - 0.44760606643715806, - 0.6721155558574352, - 0.5946204686214115, - 0.5763090272302718, - 0.6096023163271538, - 0.6261159859007202, - 0.5460142215311226, - 0.662389636096378, - 0.4662893909256803, - 0.6298769876109889, - 0.4535450424174243, - 0.534811794407085, - 0.6426381784066575, - 0.5715967667773157, - 0.530831243035157, - 0.6671911531339534, - 0.6700675212548037, - 0.6619141783912412, - 0.5385556935745656, - 0.5227690464466558, - 0.4692569575468703, - 0.540922936820996, - 0.5115643832365901, - 0.46065044077275424, - 0.6203548499090934, - 0.653667887660246, - 0.47509319555959817, - 0.6544491700784325, - 0.4551383226134034, - 0.450450640474174, - 0.4866515171278782, - 0.6843853369163141, - 0.5245738446747779, - 0.5185419720481108, - 0.672672816276028, - 0.5713439154961526, - 0.44049241591861354, - 0.44422717383439503, - 0.657259087752813, - 0.6570984544958697, - 0.545126030057857, - 0.5414955183211909, - 0.577663725685497, - 0.6004076397319085, - 0.5884152434164102, - 0.5752531982704425, - 0.54498887061735, - 0.490589303360351, - 0.45728642199909897, - 0.4402916517292048, - 0.6829918263173759, - 0.6696454836429694, - 0.6135141916516095, - 0.6512426038896242, - 0.513862303970084, - 0.545229734659028, - 0.4760384906419035, - 0.6729544140104884, - 0.5671297087415716, - 0.6637863996607283, - 0.5861809241970433, - 0.5354700043916204, - 0.546030442368207, - 0.6864088442139352, - 0.6496560564051592, - 0.5530391838222402, - 0.6695975821999897, - 0.48799068178961874, - 0.6580380734055158, - 0.48712715734853507, - 0.5634709976073352, - 0.49957184673387095, - 0.6229390013949347, - 0.663238940332672, - 0.6065250026429021, - 0.6650631972438145, - 0.5495018506870465, - 0.6140192036344871, - 0.5402461912882306, - 0.46026561278501893, - 0.6776490266947645, - 0.5773326864601489, - 0.48347691059597553, - 0.5289023353508914, - 0.5174758460529506, - 0.5602681227238855, - 0.5127282216832127, - 0.6459329832280793, - 0.5079863527664145, - 0.5298781798470565, - 0.6531526943887489, - 0.4857400002728198, - 0.6879866360477491, - 0.45954871177391726, - 0.5705553866311024, - 0.6329720532325089, - 0.6605197943114838, - 0.44727674785273724, - 0.6696793175480694, - 0.581971085115249, - 0.6107505013345237, - 0.4869699734618382, - 0.5622871449308853, - 0.45266994962646684, - 0.5553878513817837, - 0.6151144638917121, - 0.4789716332624184, - 0.6130113099103204, - 0.5211902732977253, - 0.47846212183150827, - 0.6581615850714346, - 0.6133680266439527, - 0.4857936524161744, - 0.4941078033695345, - 0.5946213222889406, - 0.5498488411607984, - 0.49315604283898706, - 0.5143413768487853, - 0.5922001139203094, - 0.45563172892066617, - 0.44585265370403515, - 0.6745894573647406, - 0.5542243789624269, - 0.5699425346168765, - 0.5504012070121399, - 0.6062918121111669, - 0.4500842985891548, - 0.642201814835665, - 0.49588594763300126, - 0.680381005126089, - 0.473134723175398, - 0.6537092378669349, - 0.4790821169844169, - 0.6680943083042798, - 0.6465661471727064, - 0.6440419539611386, - 0.5782144640826576, - 0.560467958718289, - 0.6433241941226722, - 0.5728914010797155, - 0.6553715573505339, - 0.49976695407147687, - 0.49949624816641663, - 0.5384075626743257, - 0.5994428311735366, - 0.4764095771739246, - 0.6521783484275044, - 0.49813449925754155, - 0.6393939025266782, - 0.6843684512966867, - 0.5171614545247966, - 0.508095612721649, - 0.5732710746849866, - 0.6392066304481554, - 0.6741546450101981, - 0.646064634978614, - 0.4848749618354084, - 0.6055211365092887, - 0.5863892245223865, - 0.5083783414621039, - 0.48019680211591825, - 0.5977966971336852, - 0.6873984040950477, - 0.5999333936179739, - 0.6195628477280042, - 0.5272961467690067, - 0.6544471367399578, - 0.6612034900399816, - 0.5095351315156275, - 0.5621353639145797, - 0.4718611507863758, - 0.5029576359963713, - 0.5453310468673892, - 0.6652138981948806, - 0.5722121159929809, - 0.6323901553623337, - 0.6200811717981181, - 0.49149000052323455, - 0.5997244822455281, - 0.4476689888408407, - 0.6598263895647427, - 0.5680236075771956, - 0.542373081476176, - 0.5846491841839361, - 0.45725925406856005, - 0.5714912354222478, - 0.4811697153312192, - 0.5233098847444714, - 0.5109092095420757, - 0.5345978392960308, - 0.5144049280917351, - 0.6764949780364138, - 0.6546738435157464, - 0.45792617235478394, - 0.6453641500676828, - 0.6176536193409411, - 0.6260690025250117, - 0.6602015670961341, - 0.497282755646826, - 0.6776888884722645, - 0.45835184441268334, - 0.518921430313978, - 0.6103608204213324, - 0.6569406413703034, - 0.5835804732507996, - 0.6225111430597483, - 0.6599402659783347, - 0.44884657932083893, - 0.6758684503357555, - 0.46877207660267434, - 0.6808756522245234, - 0.6687736215170074, - 0.4640203824079174, - 0.6008774651316807, - 0.4687599975686343, - 0.6232946701081785, - 0.5011072763765265, - 0.5073431055365699, - 0.5520293729392027, - 0.6441725320940563, - 0.597072908335481, - 0.5604387624705028, - 0.49495515555062214, - 0.5159808296866706, - 0.6524326119279334, - 0.5744569439519915, - 0.48625529719024757, - 0.6635599582061078, - 0.665097892570035, - 0.5045095571645021, - 0.5881579411883139, - 0.44488350126326187, - 0.5632656230195942, - 0.6821588349704167, - 0.4501680021105125, - 0.6653675806777144, - 0.5163257185184145, - 0.600547781582753, - 0.6671021243853761, - 0.5335672543007625, - 0.6154187253042026, - 0.45771132999193853, - 0.5384498859218089, - 0.5761751284354308, - 0.515218156850023, - 0.5146437975176527, - 0.5469636209176256, - 0.6341686611809934, - 0.5414763686332822, - 0.6487433761857646, - 0.6245315814010884, - 0.627163699450774, - 0.6673125194629701, - 0.5394040862837843, - 0.5021065396943547, - 0.44092340904100225, - 0.46533086764363946, - 0.6174462353960437, - 0.6075520414001586, - 0.5737400728091564, - 0.6786525116017282, - 0.4842062140433758, - 0.4679236329857899, - 0.49054019284841605, - 0.6283925822538305, - 0.4702612696676651, - 0.4443944888578893, - 0.6628723212695697, - 0.5355912063171548, - 0.6589584451288297, - 0.5150325051251106, - 0.6711721099026727, - 0.5123087340892188, - 0.5037447656303302, - 0.6162656488630784, - 0.619599361422996, - 0.6046252456050136, - 0.4611771557210714, - 0.5391061256131465, - 0.6463374421927625, - 0.4549920099045702, - 0.5494132881543735, - 0.5159347762634048, - 0.5100723648538249, - 0.5424409450107159, - 0.506989728083868, - 0.5612124522091089, - 0.6874553251596524, - 0.5196605954154382, - 0.6203694285092928, - 0.5153827779198185, - 0.6537856237700367, - 0.4879797387974937, - 0.5942391448823383, - 0.5855642950482018, - 0.4746266073188346, - 0.6187225257096116, - 0.5467172604313816, - 0.5379061747619794, - 0.6232619676909381, - 0.509029240334056, - 0.5128338598499239, - 0.6250194039251961, - 0.6485758101168704, - 0.46020414216616157, - 0.49674141658991405, - 0.5176551129414938, - 0.5499904674897489, - 0.6705247407331182, - 0.5444397808487854, - 0.5118676623704074, - 0.6615571915443237, - 0.44464795679173563, - 0.46369425288215627, - 0.524008249905481, - 0.5847281000153312, - 0.5469765887319689, - 0.6852591052557582, - 0.6736554595654483, - 0.5233150363733843, - 0.4869156434605909, - 0.513856629182026, - 0.5952310717868572, - 0.6393525653978558, - 0.6232497363222266, - 0.5629802696515539, - 0.5819009530977824, - 0.45758560047915975, - 0.5099644702119424, - 0.5641837995299126, - 0.5342145498791376, - 0.6160662209238967, - 0.4860866014656637, - 0.5599507492979504, - 0.5952803895313301, - 0.6517384339172442, - 0.6553799648232066, - 0.4601971955094367, - 0.46862387393247606, - 0.4695212129603824, - 0.6140022134275014, - 0.6615106199694405, - 0.5403944275630872, - 0.67938576069402, - 0.6694881001609607, - 0.44649382064577253, - 0.5902527370091393, - 0.6462829285041688, - 0.6590313670345166, - 0.5537111795883071, - 0.6581827168078428, - 0.5045641078456505, - 0.6298111481831834, - 0.5556526741945, - 0.5521309512536925, - 0.5519100974305906, - 0.6742460062839654, - 0.5835313380269124, - 0.6354579542433372, - 0.5832763164856503, - 0.5362977343840231, - 0.6382885892062732, - 0.5589611617203923, - 0.45908029512982973, - 0.5863751701987958, - 0.45566233476333506, - 0.4624877904719899, - 0.6522977773120642, - 0.6832071234768, - 0.6212314237018872, - 0.5977833685789412, - 0.6489620582167146, - 0.560985010441036, - 0.46305156637275025, - 0.5841373877593588, - 0.4835769043362254, - 0.6487262449321946, - 0.4470960772257594, - 0.521680732225333, - 0.5790122995173419, - 0.5345892937000382, - 0.45347184388480277, - 0.6103556803078568, - 0.6511223546736093, - 0.5369758246603841, - 0.48686500980805125, - 0.6050601566700138, - 0.5098194440640547, - 0.6246739491899855, - 0.5011178560895705, - 0.5501015774109463, - 0.5501210138398658, - 0.6500846007763914, - 0.6056793303560879, - 0.6398763614362791, - 0.6105717427412304, - 0.5764497961524643, - 0.6839624141099795, - 0.5428538986429721, - 0.6187484955594114, - 0.5059917774378163, - 0.5401284774104076, - 0.685107682818523, - 0.5891996010321244, - 0.520351268886658, - 0.6619901397007939, - 0.5077272087474178, - 0.6763404343094328, - 0.48949724736006095, - 0.6839452827074465, - 0.5829066480090447, - 0.6538994098761723, - 0.5098166346277315, - 0.5092728280591636, - 0.4485858229326921, - 0.5771545209578074, - 0.5415618646150089, - 0.5998598395617666, - 0.48533100070843654, - 0.5590215326774415, - 0.5197456647089524, - 0.6227416071342037, - 0.5535138267166655, - 0.4800869232182128, - 0.6089404578734054, - 0.5246895944880692, - 0.6823623179345192, - 0.6585088908481568, - 0.6013181492718591, - 0.49050570042942854, - 0.4445470880586133, - 0.6629270618786712, - 0.4643000207730223, - 0.5022656426973747, - 0.486524198104312, - 0.6163222432322505, - 0.46655521170895986, - 0.5391947773074942, - 0.5328958077357309, - 0.5447708949024195, - 0.6220701166114179, - 0.5283362861969381, - 0.6350062712082241, - 0.5513670130034928, - 0.5306503095799379, - 0.6022007455024856, - 0.6548036881613569, - 0.5003770897881071, - 0.49274490466680965, - 0.5251076383019274, - 0.4477501542730252, - 0.672770180523826, - 0.6812943892576175, - 0.6223127417787272, - 0.5883740495429566, - 0.4783429685918613, - 0.5826151198401351, - 0.6611524051909117, - 0.6639026308622665, - 0.4582947636906923, - 0.6842924166807584, - 0.6379254904536835, - 0.5932599451212489, - 0.5484417920643749, - 0.4861573131016955, - 0.6122073152581302, - 0.508749192979649, - 0.45785488456832096, - 0.6289875123178692, - 0.6757765768482292, - 0.5821276081257547, - 0.617893719758347, - 0.6877791431914818, - 0.5073305233842073, - 0.6006005609881351, - 0.518383127372612, - 0.608766648314672, - 0.5564339485302031, - 0.6528111877842839, - 0.6066279557013735, - 0.4802560522868241, - 0.5171413427932167, - 0.5237885940493258, - 0.6459823751035322, - 0.452680235702043, - 0.4852279636364282, - 0.4532187183310656, - 0.5445880704433932, - 0.49520839071118994, - 0.5489302628053484, - 0.6796273009558792, - 0.5975627298378718, - 0.5325212355561555, - 0.6484831678023841, - 0.5659538101328176, - 0.5702243381240086, - 0.47564055350239254, - 0.5046998748212571, - 0.5134558366072096, - 0.6759907026161261, - 0.5009483976132615, - 0.6708094636732214, - 0.5491593174425095, - 0.4735973610048871, - 0.5369271663149024, - 0.5700876715650587, - 0.5861671290261231, - 0.6623573118503014, - 0.5157046808824112, - 0.47664120072512495, - 0.5991227211406474, - 0.5394461543812064, - 0.5762088134329347, - 0.6343946532493296, - 0.6026938861028385, - 0.5350226691341093, - 0.6266648519942175, - 0.5689561033568482, - 0.5948700184772966, - 0.5415206628135852, - 0.6273342910676745, - 0.4864915323974527, - 0.49754799597030086, - 0.5935788383819305, - 0.6318770560368379, - 0.6652397483014921, - 0.6461605175020405, - 0.46457911815838304, - 0.4876532741831556, - 0.6721658076466858, - 0.4549948956007423, - 0.6751282080706265, - 0.5066620775200005, - 0.45745976617503664, - 0.5587267223851271, - 0.5235557727610146, - 0.61932291328902, - 0.5614809044542409, - 0.6770320369316594, - 0.5147858571433801, - 0.5317661544529552, - 0.5735270504578415, - 0.5594949485554531, - 0.6688832711859525, - 0.46533991057628943, - 0.6026056319131985, - 0.6609151405209581, - 0.4917086708772584, - 0.467519219744807, - 0.5743176159320686, - 0.5332672707323111, - 0.48644328638593864, - 0.5454858056731176, - 0.5422694152918429, - 0.6710676097438179, - 0.6447224525986643, - 0.6249046065525313, - 0.5374283794673806, - 0.6180449001918733, - 0.4470269895504511, - 0.6293395183234738, - 0.6846117435049421, - 0.5400166562629642, - 0.6201473225570471, - 0.49199742844059347, - 0.5600047217121326, - 0.5916895275965386, - 0.4861792066162054, - 0.46344797169530194, - 0.5397613355613934, - 0.6575160089176786, - 0.57046675585739, - 0.5900976874135411, - 0.6233938761521802, - 0.45071113164655424, - 0.44411648107329854, - 0.4772744765010661, - 0.6736616657476073, - 0.5349378670149125, - 0.6790972645855022, - 0.688418906900533, - 0.580459520259601, - 0.4958253053697415, - 0.5110243107717471, - 0.47286700717024205, - 0.5171702878208336, - 0.6557819086178801, - 0.46080771757343975, - 0.6302871730958612, - 0.6720399334756872, - 0.63785386273174, - 0.6628478902987767, - 0.6073282593468032, - 0.5305884308475555, - 0.6403329440271108, - 0.612523054927751, - 0.5726026402356172, - 0.6810613516975076, - 0.6737477660490385, - 0.5777057241994598, - 0.5949577044130847, - 0.5079663022267633, - 0.6305740542175959, - 0.5633448499306525, - 0.5298784335944121, - 0.47594453613662535, - 0.4543115039076745, - 0.5360348867448483, - 0.5992627594353064, - 0.6488801278232712, - 0.5203982185174928, - 0.570855375940902, - 0.5565990573592149, - 0.5082444282208429, - 0.541224602099551, - 0.6371839384791258, - 0.5545795833672293, - 0.5866941747585929, - 0.6104656599704044, - 0.6793906863769346, - 0.649000814708868, - 0.5050049949772218, - 0.505290544011391, - 0.6512237678819919, - 0.5454985577144491, - 0.6682696157804399, - 0.4492770875216058, - 0.6363166369373892, - 0.5398248689102958, - 0.6261716921225101, - 0.47495802240236795, - 0.6496465277835312, - 0.5397161120499412, - 0.5270946231630333, - 0.6759260597741766, - 0.4782351668691652, - 0.5465102813893006, - 0.5042788113410759, - 0.5873537692287394, - 0.5312122988678314, - 0.5400895295297271, - 0.5333589046223847, - 0.621120411016689, - 0.6300477994833444, - 0.6704153402787473, - 0.6099034258892274, - 0.5993677384840124, - 0.473681057758156, - 0.48638303642087455, - 0.4553856268010249, - 0.5121732987820442, - 0.47117721746006114, - 0.4611157411812807, - 0.58871075183627, - 0.6813294173681466, - 0.5767365639412079, - 0.6209029989790792, - 0.4420247610522552, - 0.5075463771024872, - 0.6381788874854437, - 0.6585090034806038, - 0.44688523232490135, - 0.5603895898682518, - 0.4922976321271781, - 0.6668182212140906, - 0.6480484999936643, - 0.6536068292715083, - 0.6415076399731957, - 0.49392715200004195, - 0.5156014749638985, - 0.6555315820418028, - 0.520880580454417, - 0.452507176545225, - 0.5825923818025156, - 0.5746169579288015, - 0.6197140122301901, - 0.6663206011097872, - 0.6125868442427759, - 0.520759588771704, - 0.5770476199277546, - 0.6317796255273171, - 0.5979350766597775, - 0.6878727008284481, - 0.4953881624202081, - 0.5055835892980932, - 0.6455357929735017, - 0.5828349019426506, - 0.5488844781091924, - 0.510053732508797, - 0.602448534753106, - 0.6578146958330826, - 0.5872752462320134, - 0.6231127425886915, - 0.51411010473866, - 0.5906964428412144, - 0.6235620973479499, - 0.6589348374348173, - 0.5058558413209598, - 0.6133236037798588, - 0.4553568501411271, - 0.5837508568172296, - 0.6847319404181388, - 0.6464966411508045, - 0.5045937750748417, - 0.596801279746143, - 0.4953829381851132, - 0.6221764692744409, - 0.6490762518886326, - 0.5820951650244303, - 0.4637442345513976, - 0.4485009321217292, - 0.6020508641708835, - 0.48910850024806274, - 0.5136491433064744, - 0.5928477295773652, - 0.5187846546028957, - 0.6647687022523642, - 0.5694188900638919, - 0.5100734475184782, - 0.6809891734768069, - 0.4415034885134082, - 0.59806893126845, - 0.6682750161796296, - 0.6170196353356325, - 0.4752526706447212, - 0.6675075238997277, - 0.5365920569840825, - 0.6028632425148858, - 0.5718983159314278, - 0.5161666562288232, - 0.6864591962274613, - 0.6461565819205466, - 0.45195064988748535, - 0.5273758052602588, - 0.5963193520373982, - 0.46842978902967114, - 0.44040568680232894, - 0.663599497955135, - 0.4996286661559152, - 0.5310964915691021, - 0.6064636189832846, - 0.6724956196990224, - 0.5549224678597031, - 0.5343767972804702, - 0.4510618203864506, - 0.6802593070153203, - 0.6713009387206551, - 0.6502589501801443, - 0.48853354585148406, - 0.6533911110567924, - 0.575201878388209, - 0.5382009065520142, - 0.6630102267723061, - 0.5909527846568671, - 0.6822621215663061, - 0.5829930815045646, - 0.5387541042814421, - 0.6818453223862013, - 0.5644236882580194, - 0.47356312941826784, - 0.5737930300367988, - 0.5419617775999377, - 0.679573181143447, - 0.4983700349317091, - 0.6540785516494995, - 0.5543618074213594, - 0.6745591204012894, - 0.47180443245598164, - 0.6353534765310168, - 0.5132174749485202, - 0.47522666737931085, - 0.6477698838565659, - 0.5909291122683032, - 0.49314378107208195, - 0.49413744220732414, - 0.6120921739871817, - 0.6240857735796161, - 0.676741642013726, - 0.4461032605783101, - 0.6680158727367953, - 0.562367691646534, - 0.5493809306312918, - 0.6657891858228522, - 0.647323906744831, - 0.5904704798806705, - 0.5610914237342892, - 0.4574910656540736, - 0.44711246269207483, - 0.4574073263518592, - 0.6584002189540772, - 0.4711861333072987, - 0.6230464684606345, - 0.6664925887494677, - 0.4874991719441998, - 0.48768578450858957, - 0.673253523460956, - 0.6195507059562215, - 0.5712599641859164, - 0.5928846595571706, - 0.5245421608182054, - 0.6674174828607122, - 0.4981343565978367, - 0.6749099538871053, - 0.6285286724812368, - 0.4798466143595557, - 0.6375986834556651, - 0.5379913947900841, - 0.677232257862376, - 0.4770981167624788, - 0.5813039311466119, - 0.4812659491905324, - 0.46565608018250304, - 0.5983020023364553, - 0.6771897882905611, - 0.588365257075346, - 0.5038784331705632, - 0.5870042117685544, - 0.5156012697600094, - 0.6390028571164954, - 0.4465845929897713, - 0.4834287568552667, - 0.6435338381236233, - 0.4719564282450519, - 0.6615399564586779, - 0.5841487758256522, - 0.6768229276706309, - 0.5137289162817298, - 0.47458147431616454, - 0.6410537265373663, - 0.5993423708038758, - 0.6255905748407818, - 0.6418677829657461, - 0.5583520925285561, - 0.49711816857129915, - 0.5743507998488486, - 0.529172300951572, - 0.4646750579205994, - 0.5656955661570603, - 0.600524699402453, - 0.5055794211525587, - 0.4845196374654296, - 0.5928565474083993, - 0.6423532511863816, - 0.61943830863567, - 0.5424779197937997, - 0.49484403080563033, - 0.5204864741736048, - 0.542197583894015, - 0.533406489091549, - 0.5031736898832778, - 0.618420219800552, - 0.523406774156385, - 0.5524990973457703, - 0.6316590412863994, - 0.5146160407087266, - 0.46111895266441977, - 0.5435379718541178, - 0.48461606594411655, - 0.5330754524046176, - 0.5163496312670226, - 0.47241813970064034, - 0.6353998415766445, - 0.6033665305413192, - 0.6216983855397142, - 0.625235601076527, - 0.6453143141545388, - 0.5367146211264028, - 0.5759659480892226, - 0.4586804509029464, - 0.5236516156013363, - 0.46341914300525605, - 0.44373395421149303, - 0.5864011007018778, - 0.6628093107579794, - 0.5501261721994056, - 0.5008962633259116, - 0.6268404303127675, - 0.6337865244364751, - 0.5677150406432929, - 0.5376053499451408, - 0.6256421697007901, - 0.4479520217231885, - 0.6029021741424636, - 0.6533066482311221, - 0.44073948339569874, - 0.6852288159952605, - 0.5033079696934951, - 0.6407004387008444, - 0.5407359893872612, - 0.4858453294113767, - 0.6748294004336531, - 0.6072447821742426, - 0.5507531490612361, - 0.5556638470779973, - 0.5999761261646155, - 0.6002801654766594, - 0.6264377819299418, - 0.4799363148647046, - 0.4409319833084819, - 0.5202886248720847, - 0.5856081454024942, - 0.5266054148541247, - 0.4928972054246613, - 0.6784094076009245, - 0.594144232676878, - 0.4467061885575061, - 0.5242769389679874, - 0.5977239575864146, - 0.5313010458338008, - 0.6663181746181677, - 0.57838628442191, - 0.45548401041143244, - 0.4696854870239617, - 0.5502510520150259, - 0.6191333361019009, - 0.5901087915246737, - 0.6846006025623126, - 0.623072408490327, - 0.4666208883246648, - 0.4407422273830585, - 0.4685041671440134, - 0.44634302320509855, - 0.5538806614175227, - 0.511742756582038, - 0.5848830472229165, - 0.46065678244142994, - 0.6395330833020576, - 0.6631679818499749, - 0.530823576653358, - 0.595964073161044, - 0.5664666762670318, - 0.6105823011400332, - 0.6760483570257254, - 0.6560387257470377, - 0.5380538631885678, - 0.681561023472872, - 0.61044574981332, - 0.5451876947807309, - 0.6534431608833478, - 0.4696830584239785, - 0.6283715659903822, - 0.6091530069198182, - 0.6644667557196912, - 0.49400908875181737, - 0.5145750355429021, - 0.5636409611751932, - 0.5703201999854615, - 0.6561462970099134, - 0.6507188861870264, - 0.6731972642489823, - 0.5641505437065089, - 0.6364305137303803, - 0.5974410397931831, - 0.4661001428892439, - 0.5499410585076306, - 0.4713236989136648, - 0.553335155880864, - 0.6597702556411773, - 0.6157139936270204, - 0.5544573054042432, - 0.49572066570793116, - 0.5618286383063963, - 0.6808228025686677, - 0.5885397523208873, - 0.6313816809845088, - 0.5530649333508254, - 0.5259510497843658, - 0.5944323636566966, - 0.47499729848155475, - 0.533056020923961, - 0.6640611921823883, - 0.6517167488960545 - ], - "y": [ - -0.6668315582497104, - -0.6607717232360909, - -0.6734836085326449, - -0.6648484340627668, - -0.6601144095520328, - -0.6735782744568081, - -0.6741068489839217, - -0.6708113710956819, - -0.6600021148484858, - -0.668209560908767, - -0.6810238564043525, - -0.6747319386960823, - -0.6655083002309671, - -0.6676342688126873, - -0.6709127696259357, - -0.6616939113576187, - -0.6670043758446376, - -0.6794089951474087, - -0.6806595873674365, - -0.6729146476292305, - -0.6801393222295911, - -0.6635532737253048, - -0.6761271632408935, - -0.6781492576694402, - -0.6708015327553323, - -0.6815640661247026, - -0.6786101698233435, - -0.6601226732382303, - -0.6803427840437134, - -0.6684230617207001, - -0.6800345398912112, - -0.6624305937040923, - -0.6686817701917931, - -0.6814082479615897, - -0.6752499599964129, - -0.6759448102887547, - -0.6608604929434724, - -0.6780391263180388, - -0.6784596482206593, - -0.6685874680754338, - -0.6611364528019225, - -0.6616305468791639, - -0.6725095680669281, - -0.6752618577346545, - -0.6684685331479833, - -0.6754861192468661, - -0.6669095255806634, - -0.6719759039655189, - -0.66349545825677, - -0.6624690980716645, - -0.681029124398183, - -0.676027169688359, - -0.6663724132530578, - -0.6790151977333169, - -0.6656955458896762, - -0.670999153115518, - -0.6732636740285202, - -0.6716583646720663, - -0.6623301189181595, - -0.6789748946897183, - -0.6660518943417102, - -0.6804023854773296, - -0.6635999590430296, - -0.6625833488718693, - -0.6686482839808547, - -0.665034923412679, - -0.6651386206256462, - -0.6812021962585506, - -0.6656023595105909, - -0.6743101003938928, - -0.667408855496101, - -0.6638889131156603, - -0.6786386466972024, - -0.6644583037912002, - -0.678241459782015, - -0.6658637406616716, - -0.6713321407718726, - -0.6663589768210818, - -0.6683963424076872, - -0.6649152540724507, - -0.6614391902671382, - -0.6600870545974268, - -0.6638714852310684, - -0.6722783250295027, - -0.6791038037896756, - -0.6616972033603041, - -0.6699963982079004, - -0.6814622752642873, - -0.67037772541873, - -0.6697524898165127, - -0.6624838842108858, - -0.6750077294553942, - -0.6621166120604769, - -0.6794448064972691, - -0.6727153389069879, - -0.6700439335381183, - -0.6653334581972157, - -0.6706500805230011, - -0.6696248859901208, - -0.6736595122836092, - -0.6647474016030142, - -0.6784742833247671, - -0.6682247727373081, - -0.6793404918928848, - -0.6789879552552042, - -0.6665522918001517, - -0.6725687217495101, - -0.6763828889435609, - -0.6633478271918115, - -0.6734779172672405, - -0.6718755825237295, - -0.6634644739458591, - -0.6728388974892653, - -0.665893028598915, - -0.66360927940724, - -0.6668630446581929, - -0.6805694219166992, - -0.6600016685609515, - -0.6767993365018428, - -0.6628784142771201, - -0.668069430459897, - -0.6630094378498275, - -0.6649792741340865, - -0.6736256754221178, - -0.6601854044099229, - -0.6681298835958325, - -0.6675139484154593, - -0.679485271337036, - -0.6630549548190117, - -0.6793751383270976, - -0.6641212305458718, - -0.6747589995581781, - -0.6800306494730497, - -0.6800537857301149, - -0.673189707894642, - -0.6785363773867807, - -0.6806655175984281, - -0.669791406194355, - -0.6709297505587711, - -0.6665925397240791, - -0.6777822316262804, - -0.6657868434021211, - -0.6746257728753862, - -0.676934378120157, - -0.6816606478853694, - -0.6792935384036003, - -0.6620972125197958, - -0.6715282627579485, - -0.6753875599138137, - -0.6711049291320145, - -0.6811630728978785, - -0.6813101183842576, - -0.6730046082188708, - -0.6789471339915577, - -0.665484754660063, - -0.668484303431873, - -0.6790132675532744, - -0.6724087861492395, - -0.6816738098633567, - -0.6708724694540651, - -0.6799395157869776, - -0.6667230311336361, - -0.6613888214394994, - -0.6722024560387154, - -0.6705229606974431, - -0.6732628502299816, - -0.6774032351932198, - -0.6819048051556147, - -0.6687292734290918, - -0.6644799955488142, - -0.6630744810459788, - -0.6669542907348902, - -0.6665104130871184, - -0.6678838495507202, - -0.6760620629373462, - -0.6707632403373756, - -0.6821754864903348, - -0.6775827486676745, - -0.6697086158399632, - -0.6652845109826999, - -0.6675286318015882, - -0.6699829165754368, - -0.664129998508875, - -0.6674554434783793, - -0.677712654442334, - -0.6715523181026741, - -0.6739968027378956, - -0.6674155691879449, - -0.668388401030937, - -0.6751776573390158, - -0.681385694785165, - -0.6788438261114769, - -0.6632623111584615, - -0.6701012429670912, - -0.6658784799883879, - -0.6657982390325247, - -0.6697534288233896, - -0.673410422068826, - -0.6716731203352927, - -0.678414365784445, - -0.6772358935718839, - -0.6704569079089455, - -0.6774115684936481, - -0.6634089080342599, - -0.6654988762997748, - -0.6766630069211315, - -0.6704526114722102, - -0.6638563205904499, - -0.6623522212722996, - -0.6720971565525999, - -0.6618848024544746, - -0.6672966837142845, - -0.6767390334295673, - -0.6635898629605181, - -0.6671732890960824, - -0.6711029287955335, - -0.6743143672926114, - -0.6664002013520213, - -0.677022068617002, - -0.6803103453781107, - -0.6627961287367365, - -0.6731622466425224, - -0.6622332555396757, - -0.6753688675178237, - -0.6688690194134916, - -0.6798733339734938, - -0.6803010995969407, - -0.6709962067337474, - -0.6710277458115799, - -0.6759657168545066, - -0.6623809848059093, - -0.6807805626940766, - -0.671197998465091, - -0.6626505924223711, - -0.681108552956101, - -0.7550480737375442, - -0.7700508042743419, - -0.7782544080505506, - -0.7716517340380081, - -0.7459698860230158, - -0.813258205662125, - -0.6653744576128835, - -0.772372774959879, - -0.7881544620345647, - -0.7385543501162286, - -0.7570717632350344, - -0.7564802024617285, - -0.7443714043123986, - -0.6684741534165765, - -0.8264514242214777, - -0.7382607176484661, - -0.6722380126078511, - -0.6722736714783935, - -0.8247960180349698, - -0.8238968211581758, - -0.7389379574180137, - -0.7197925232855579, - -0.7346160509791788, - -0.7929974608198715, - -0.8222229324433125, - -0.6822929243449354, - -0.7646085699190248, - -0.6783515914506314, - -0.715703320879585, - -0.7039495728807266, - -0.7779935560887778, - -0.6846362563479755, - -0.7507331193740083, - -0.7625099337739474, - -0.8229018467229415, - -0.7141719539403572, - -0.7744426924392408, - -0.8085757987463338, - -0.803262131328913, - -0.8307839794714205, - -0.8115977636024669, - -0.6616305749318847, - -0.6682572064817258, - -0.7265224026351195, - -0.7528886414006531, - -0.7476803467922635, - -0.8062595007602467, - -0.6799270062216481, - -0.7658867536367069, - -0.779675706103769, - -0.7565805315241936, - -0.7019927592301515, - -0.7233288049630601, - -0.8195303470675402, - -0.7103901484647628, - -0.789926476780958, - -0.6751284502208781, - -0.7744874902187052, - -0.7409722201890181, - -0.6738623139557299, - -0.725912780009047, - -0.7088820976523971, - -0.6943214731562302, - -0.8194206874593121, - -0.7105287272107857, - -0.8187459219875597, - -0.7901574789411663, - -0.7237477193293037, - -0.7303245668159615, - -0.7350174367353821, - -0.7737531164683726, - -0.7864612212084223, - -0.834426886674589, - -0.8075993178938186, - -0.8301893159543754, - -0.6822211093225895, - -0.7249852174989648, - -0.7478896072643013, - -0.7058525700990499, - -0.8234900933902415, - -0.673486018855391, - -0.6820582938331424, - -0.6626685224627331, - -0.7678152559593878, - -0.6637675045502154, - -0.8098493871281369, - -0.7761539374046893, - -0.6730984506310912, - -0.8237310635007012, - -0.8034088857432466, - -0.7094067384896414, - -0.673147489554224, - -0.6615175411413035, - -0.7058869052823308, - -0.6801505426516146, - -0.699163005139636, - -0.793145743091007, - -0.7272759780073839, - -0.7455548045425309, - -0.7508776300501376, - -0.6774609452416194, - -0.7063711552609242, - -0.7272619435902099, - -0.7191066762401417, - -0.7281229875288082, - -0.6811349741114315, - -0.7157349784026603, - -0.6646109788614872, - -0.72916632493988, - -0.7032535081282314, - -0.6726745225410686, - -0.7939063601483893, - -0.7846332043571312, - -0.6673516576861149, - -0.833690093725783, - -0.6781974856458242, - -0.786460791705098, - -0.6710350384553365, - -0.8130793980382292, - -0.8161282027834666, - -0.7924785827970315, - -0.707601712295763, - -0.7703341650338985, - -0.7903560701375452, - -0.76894070077479, - -0.8121487718308653, - -0.7778342724029614, - -0.7644168685291115, - -0.8340558384257699, - -0.8099223431097283, - -0.7668808416440193, - -0.6938201226897618, - -0.8163594330642331, - -0.6864247168143086, - -0.726556942246358, - -0.7244998671420729, - -0.8250902157580843, - -0.8154055161595841, - -0.6771907144736422, - -0.665518589521108, - -0.7401015585212822, - -0.675725574620545, - -0.6684483636941078, - -0.70319476751211, - -0.8056608122368586, - -0.78103247853344, - -0.7941383790635234, - -0.6763479786704576, - -0.8230671888626349, - -0.6804016976654421, - -0.734018290962105, - -0.7758108305168734, - -0.810578489574495, - -0.8328521296909948, - -0.7055825457727347, - -0.7271653094124735, - -0.7438833815468646, - -0.7530709813849679, - -0.8340066856453975, - -0.7635882684524131, - -0.7651097620020356, - -0.6810507902582957, - -0.8135457328114536, - -0.7951062543748123, - -0.7731134945082683, - -0.8240208119638317, - -0.7855281286460393, - -0.7435555440835219, - -0.6980094194044031, - -0.7243783499017039, - -0.6782157852678071, - -0.6743299916685357, - -0.6795029957609606, - -0.8169138127958112, - -0.8071792831357405, - -0.6649093174140212, - -0.7107651788426641, - -0.7671627671547131, - -0.8263489534758648, - -0.6888742171614677, - -0.6802714311373391, - -0.7541625412922905, - -0.697543279125809, - -0.7051697939011387, - -0.7563976354261818, - -0.7987879114369322, - -0.778251822752214, - -0.8063394711458748, - -0.7511400220169278, - -0.822130120712597, - -0.7029070066387854, - -0.7667100315918466, - -0.710075193567092, - -0.6856854678644342, - -0.738068310579318, - -0.7534921703739801, - -0.730566801240356, - -0.8008915400753656, - -0.7782593909557118, - -0.6907498347548435, - -0.7434121961664377, - -0.7495233296291057, - -0.7913549498229313, - -0.8247877089659689, - -0.8338639450946366, - -0.7376435930412029, - -0.6602984878796936, - -0.7325481423223247, - -0.7785467405402002, - -0.8229733499431098, - -0.7364987700080374, - -0.8333856528734969, - -0.7224646329880053, - -0.7188285312502795, - -0.744996544658949, - -0.6610901454131257, - -0.6657632512685674, - -0.6865572705948827, - -0.6712657636208094, - -0.82297249928589, - -0.7084903986398872, - -0.6923047165980777, - -0.8350832760221285, - -0.7843329564879894, - -0.7016088072904788, - -0.664595471234724, - -0.7089511475145462, - -0.7943069869850155, - -0.8039659388281586, - -0.786032646584564, - -0.8355581074821987, - -0.7676399950250029, - -0.7325807122922863, - -0.7313089828757705, - -0.7445447025929075, - -0.8126207703888411, - -0.7522482617598435, - -0.6673336736344954, - -0.7841366678125136, - -0.7533505739557564, - -0.7620782889164662, - -0.7973802874162664, - -0.6814494711604994, - -0.8308241210591553, - -0.7823243778473227, - -0.7255866563706734, - -0.667956276819303, - -0.7722823404694855, - -0.6738741949185535, - -0.7075307939421692, - -0.7737450496760783, - -0.7241299116454691, - -0.8056051026073199, - -0.7787698186371698, - -0.793520506547801, - -0.8221576940215211, - -0.6804121469044682, - -0.747936122848166, - -0.7992463745631503, - -0.6745299914069663, - -0.6900487897941718, - -0.7608287034626816, - -0.7614107044100887, - -0.6821101218936483, - -0.6862242856914691, - -0.7882844604303259, - -0.7749655371147081, - -0.6632308063885255, - -0.6886394522228545, - -0.7162415367498481, - -0.8047731402026982, - -0.7824005295844706, - -0.7702952696125301, - -0.7195918179831468, - -0.7238913091640233, - -0.7058713242532055, - -0.7920935722716821, - -0.6799519040032227, - -0.7985243941537684, - -0.7034530292601273, - -0.7942616689733097, - -0.7534608628090214, - -0.8071758874887176, - -0.7072224724718614, - -0.727193809867404, - -0.8355877940318558, - -0.6636482907044227, - -0.6885194167696791, - -0.8354475492910146, - -0.8296952538928686, - -0.7791096848062058, - -0.7935005023416783, - -0.833137344867706, - -0.7316111299640603, - -0.8278965658709779, - -0.7406299474363365, - -0.6708307866022678, - -0.666594281092812, - -0.7201542310819646, - -0.7501050255315991, - -0.6959459346888494, - -0.7665397683466448, - -0.7648761928732528, - -0.8157962444737346, - -0.7246562812234288, - -0.7989153221918939, - -0.6811843173904725, - -0.7118526975068795, - -0.7130582125677072, - -0.7600229605332812, - -0.8132641233383618, - -0.6960006471484601, - -0.6711677578745348, - -0.8092669985751347, - -0.6806271179322796, - -0.8309918968511073, - -0.7015330178711308, - -0.7099908022480316, - -0.8120013626181489, - -0.7690642094681567, - -0.7949442586177609, - -0.8126108547148896, - -0.7975269209209525, - -0.7723684904899175, - -0.7236285003560037, - -0.824875182178552, - -0.6737105831032661, - -0.6746334710088274, - -0.7713829270909439, - -0.7982173079035647, - -0.7146767285383223, - -0.7456110333103381, - -0.7299202112068949, - -0.7361616550135257, - -0.7651962362302359, - -0.6798911816834488, - -0.83453105243257, - -0.7827480013744251, - -0.753314430634882, - -0.712287068354362, - -0.8171208786368336, - -0.6928055708181534, - -0.7034587008303026, - -0.6998306982838088, - -0.7659412983191896, - -0.7626933613702673, - -0.6987831112980343, - -0.7665664945388198, - -0.732514630242331, - -0.835159971395085, - -0.7960555728150671, - -0.6624521158284828, - -0.6650825972842178, - -0.8285385099974382, - -0.6768630818028816, - -0.7502354658669186, - -0.6621892235599265, - -0.8259347929896327, - -0.7666720422135725, - -0.8042976825764987, - -0.6857761871204634, - -0.7075588493116662, - -0.673633584352862, - -0.728091397956582, - -0.7751308091432209, - -0.6610808409837761, - -0.8084960003272387, - -0.7078558951070324, - -0.8033976602390185, - -0.7440054139058898, - -0.7326996170383223, - -0.8217380337655922, - -0.7783837521232595, - -0.8319449741572128, - -0.6886211580497246, - -0.6973604113516507, - -0.796571700829335, - -0.7114886982815574, - -0.6633207047796961, - -0.8255043165648837, - -0.8009799877328936, - -0.6734112140683804, - -0.8280576759126022, - -0.6996544065731518, - -0.7322424703153588, - -0.8304458832137517, - -0.7976890023669266, - -0.7646890258212374, - -0.792286884473739, - -0.822125915635598, - -0.7219766170090036, - -0.6605889253978399, - -0.7086872672082686, - -0.7852445739073513, - -0.7160767119241964, - -0.6633185619406062, - -0.726054234693227, - -0.8293310762188671, - -0.8320401958649182, - -0.8316494912736815, - -0.803854845508691, - -0.7888193969133659, - -0.7960190631085732, - -0.7505276094705273, - -0.6767603275038945, - -0.7049210060063188, - -0.7353275845889917, - -0.8025438841823124, - -0.7201546807622272, - -0.7393459328623858, - -0.6677600989575214, - -0.786978161646176, - -0.7255891408335892, - -0.7828770783003566, - -0.7314847853858286, - -0.805461239606957, - -0.7056861763113156, - -0.7124435416094477, - -0.7531815230053943, - -0.6812520998681151, - -0.75615195508744, - -0.7997099837361972, - -0.6840702574872144, - -0.804761430949785, - -0.7572440414987219, - -0.7266948311677792, - -0.7560997790725758, - -0.7722250094117946, - -0.7478681657272592, - -0.6783133002265753, - -0.7584735172959645, - -0.7990892325650848, - -0.8045439541675973, - -0.7434760750343037, - -0.8274151171301566, - -0.6996466290896213, - -0.7115570412810566, - -0.7500916489844847, - -0.6902268960474726, - -0.8344938979503924, - -0.7297201921129342, - -0.7437123509264861, - -0.8022632346433138, - -0.8330157591233298, - -0.743357994863301, - -0.6813794762397211, - -0.7305855162698736, - -0.8331256784393194, - -0.7290266064077335, - -0.7485449078323348, - -0.7949242791668527, - -0.7109712203661526, - -0.7510818447807749, - -0.7996534976173831, - -0.8321253129231411, - -0.7144568106354885, - -0.8207453465836858, - -0.6783704283170919, - -0.6912559083059868, - -0.7139967925361151, - -0.6666448175472063, - -0.7711233600541455, - -0.7132241347843964, - -0.7390717446711452, - -0.721828050290381, - -0.7119120505561063, - -0.8114976905985238, - -0.7829850909761285, - -0.6841761431622809, - -0.6615905243696381, - -0.6788139471188979, - -0.7728528954634926, - -0.8159593446313599, - -0.6659238273067507, - -0.6951811517705647, - -0.8035158155011675, - -0.7803408644296642, - -0.8287676702173308, - -0.8074423015070183, - -0.7499322844434906, - -0.6737840634886919, - -0.7923996084907751, - -0.8169983280885328, - -0.6648049424514686, - -0.7785648062938746, - -0.7567159784680273, - -0.746932457371329, - -0.802441079404493, - -0.7000652769415209, - -0.835673825787137, - -0.6647551480505209, - -0.7857803673353725, - -0.672913883975, - -0.7816910464585823, - -0.7755546233631542, - -0.7439295233336051, - -0.775440374217991, - -0.7870928972483304, - -0.7992329237875478, - -0.6612956831065583, - -0.7441024931198996, - -0.7215773729977581, - -0.665257318207789, - -0.8047264632541332, - -0.7604221650305723, - -0.8279681265558309, - -0.738676173055996, - -0.7418581703490731, - -0.835709536504665, - -0.7261271417791573, - -0.8078057528105949, - -0.7465157559694033, - -0.7749339271613063, - -0.8263867478926271, - -0.7453028269647722, - -0.6969171792197236, - -0.7549130816265922, - -0.8151184059520992, - -0.7906197103355908, - -0.6630752825549934, - -0.7412698704141925, - -0.785330824419205, - -0.7273784598432189, - -0.7357355439250436, - -0.7469507995939915, - -0.7212474402653175, - -0.7888838470958228, - -0.7564756554530346, - -0.7232900486496534, - -0.6917251813625291, - -0.8067060415609156, - -0.7719156967215148, - -0.7654965587628239, - -0.8164718496625423, - -0.8219605895512176, - -0.8161122505354237, - -0.8161500645755572, - -0.8096866886643492, - -0.6787468886564013, - -0.7706365107823824, - -0.7951521324844868, - -0.8092899159023343, - -0.777332389857948, - -0.7759687100662466, - -0.8352152211834936, - -0.7197199504840377, - -0.7801804992294646, - -0.7308554381272105, - -0.8280623881223121, - -0.7693943536377885, - -0.7371779219692853, - -0.7034101699601231, - -0.7910848173148903, - -0.8349981932379735, - -0.6974372675759715, - -0.7381984925581548, - -0.715535901388076, - -0.6998256184429644, - -0.6979932276366669, - -0.7754708100408968, - -0.6920802609921068, - -0.6886628996121655, - -0.6766018190457601, - -0.7484783102271553, - -0.7560516975358652, - -0.7328270544855708, - -0.678773764967832, - -0.7449644225246008, - -0.7637869652995816, - -0.7255118281905292, - -0.8103129361028525, - -0.7770071804160785, - -0.6706668009689783, - -0.8344878608657206, - -0.7943092680973416, - -0.7824450276842315, - -0.6678327002890945, - -0.7869631612227626, - -0.7822380402712741, - -0.7571226227783765, - -0.7604863120597768, - -0.6842137451717931, - -0.7559195421027028, - -0.7550895581561887, - -0.7136606088209911, - -0.800045847374686, - -0.7009079370916312, - -0.8184933279961524, - -0.8263777656275307, - -0.6621661536276746, - -0.6779654560405483, - -0.8116133611117536, - -0.7457236486032972, - -0.7001659749943312, - -0.8231029416828308, - -0.6650849404656826, - -0.6671684342059201, - -0.8317382737237229, - -0.7139294452796198, - -0.7106955238036106, - -0.730812450457298, - -0.7515542078777542, - -0.8089913665926969, - -0.7281694590586684, - -0.7725550675105991, - -0.7982875376616315, - -0.7819822482206791, - -0.7539298483958087, - -0.8004776317709147, - -0.6783110748045309, - -0.7302089046958276, - -0.6672611518741829, - -0.829087994132587, - -0.7330825955712212, - -0.6839201866267168, - -0.6767094103319478, - -0.83326313253032, - -0.7523868813319714, - -0.6963540270840974, - -0.6903931018659589, - -0.7178522826496758, - -0.7063427532628819, - -0.7112262257384644, - -0.8172146500231713, - -0.7182015300548624, - -0.8014205015639055, - -0.732279688565351, - -0.8086280890351819, - -0.8260936111909047, - -0.7715564747786698, - -0.7284311993361339, - -0.7626640848466565, - -0.8306834924544417, - -0.6744156936064473, - -0.8116898244082678, - -0.8293661271975058, - -0.6655153139915966, - -0.8234774193450263, - -0.746351646398022, - -0.7316559677828094, - -0.752314766086528, - -0.8346448360483761, - -0.7069861935141787, - -0.7315273242568833, - -0.7945086097040398, - -0.7586570372140273, - -0.7695445964658535, - -0.7742175445632238, - -0.6761759489637708, - -0.7248990350225196, - -0.748681360151267, - -0.7057106724260827, - -0.790420953434917, - -0.8348965730830888, - -0.8028652136636467, - -0.7088433535414069, - -0.8155027213726929, - -0.6877195090259133, - -0.7837838653062755, - -0.7070060843110465, - -0.8146410546856672, - -0.6652947606734037, - -0.7895254858707297, - -0.6929497377223192, - -0.772051910427223, - -0.7333356620688575, - -0.6792012054630188, - -0.7783760585342844, - -0.7696835904521142, - -0.7766805461085348, - -0.6844125199228139, - -0.8051397612346801, - -0.689884881862723, - -0.7302611723326736, - -0.8034874249970195, - -0.7511510691018026, - -0.7669609887945885, - -0.7505242944126276, - -0.8162291454006615, - -0.8060288167538795, - -0.8061009501676896, - -0.7885667704241367, - -0.765463722562502, - -0.7765839602677905, - -0.682403970234991, - -0.8090869208282194, - -0.7084390927646979, - -0.6723051008730145, - -0.7780501130713312, - -0.771464405199108, - -0.706998587949819, - -0.7383621084803403, - -0.7115971198065165, - -0.7224740116839953, - -0.7261845473607556, - -0.7328367436124184, - -0.7697121748669982, - -0.8044770647533237, - -0.8051838114206711, - -0.7958976981706649, - -0.734049860433513, - -0.699829620517348, - -0.7353963160207255, - -0.7723421076811362, - -0.6750230122671342, - -0.7346533717368113, - -0.8017417549541268, - -0.805668412722908, - -0.6874572215726654, - -0.7467324511456784, - -0.7822494644316924, - -0.7649293826709853, - -0.6630421681098388, - -0.8035963733056171, - -0.7635645939534003, - -0.8170287350576222, - -0.8060169266774926, - -0.7918707669550552, - -0.8051358621337209, - -0.7741067206211896, - -0.8077212383340002, - -0.6807760859981533, - -0.7187772100857811, - -0.7933457021474601, - -0.6615052893213798, - -0.6741572907543824, - -0.7785994436612443, - -0.8249807938112317, - -0.7402675479582005, - -0.7751471934311521, - -0.776291600870174, - -0.8189482270199596, - -0.7945314391030577, - -0.702718455703975, - -0.8036860635812616, - -0.7150123253670456, - -0.8354460706463761, - -0.7146609132437063, - -0.6928516309249201, - -0.7704349143873858, - -0.6942822104510235, - -0.7504579291559716, - -0.763112830647559, - -0.7205830804577067, - -0.82032726349891, - -0.7475677655424439, - -0.7127978330187558, - -0.7092803207374717, - -0.8018971119821258, - -0.8316813444429473, - -0.682523513255846, - -0.7159776809268822, - -0.6731297407582348, - -0.805910630998889, - -0.8283754342897819, - -0.7042379129449897, - -0.7972233308080927, - -0.7021873060219943, - -0.7434034321690656, - -0.7347559394010152, - -0.7525435181050375, - -0.8065255640823976, - -0.8338430009025073, - -0.8153673822388482, - -0.7970690321916177, - -0.8112296656354614, - -0.8043127025017974, - -0.7535848586865637, - -0.7326354073132793, - -0.7730364703417674, - -0.6675352550399752, - -0.8255603338906623, - -0.6852088449044348, - -0.8274072481300085, - -0.8026447171746541, - -0.747703513042769, - -0.7658503300229599, - -0.7471666112370076, - -0.7580032505495681, - -0.8342322641264293, - -0.7859220400234854, - -0.6872998585749354, - -0.7684483229237675, - -0.8066101631950652, - -0.677770246794372, - -0.723694908025973, - -0.6996691121088756, - -0.8148528797745798, - -0.7227017020013761, - -0.8166476300861195, - -0.7071687273101697, - -0.8141905940277032, - -0.8129619417145891, - -0.7194192198301161, - -0.7122707755840421, - -0.7857517846497359, - -0.7926710110841614, - -0.7070409566039204, - -0.7494900489057295, - -0.6755839612614174, - -0.7381459082320976, - -0.8276393321481019, - -0.6883847050414982, - -0.7217052646367582, - -0.7825551186335278, - -0.6634665469862714, - -0.784291942017626, - -0.7907334963652433, - -0.8065640516749798, - -0.7485717078283011, - -0.7678453711297649, - -0.6776964031086968, - -0.8193504199164221, - -0.7853757449635526, - -0.8169233627294413, - -0.7329427765449498, - -0.754607355927222, - -0.6884872565306829, - -0.8049356812271311, - -0.7748003027592272, - -0.7183090814306557, - -0.8300828749619248, - -0.7726917697935423, - -0.6607448410221008, - -0.8318726598912668, - -0.7882032595404511, - -0.7124974519039113, - -0.691137499715052, - -0.6837527952355513, - -0.7269070751800313, - -0.6783790573243587, - -0.7974739059351071, - -0.661704893877711, - -0.7039593966939751, - -0.7288792659398644, - -0.7502824124093853, - -0.7257299897347189, - -0.6668237377763447, - -0.7685250976886537, - -0.7582545213400018, - -0.8175848547057764, - -0.8086795758561933, - -0.7202160221634921, - -0.7240793229355125, - -0.8041405991828462, - -0.7012423663225209, - -0.8289979776523071, - -0.6953247989489955, - -0.8197763507818808, - -0.7927126541871123, - -0.7745419597179259, - -0.6801143729638446, - -0.8098724958902469, - -0.7348721038117916, - -0.7649306368589943, - -0.7348572211068845, - -0.6823670694372289, - -0.8060209172621804, - -0.8190100614740629, - -0.808553853518254, - -0.7161198019140839, - -0.7395639535860393, - -0.8322813532893987, - -0.8057015329867047, - -0.7791900001795238, - -0.6759807202418799, - -0.7639058925083695, - -0.7992165229540897, - -0.7476245808867266, - -0.685615890970291, - -0.7512287558250097, - -0.6617690247928405, - -0.7241425113138633, - -0.7290470797058661, - -0.821492233718176, - -0.8145018293681907, - -0.7003419851179377, - -0.7324948341553764, - -0.7962927654674683, - -0.6624895778162612, - -0.7266546226682051, - -0.8009930241524401, - -0.700852625615311, - -0.7634817401927231, - -0.7613871781015813, - -0.741091480770212, - -0.7912443457456497, - -0.7717614660336781, - -0.8002760625135981, - -0.7808477616969531, - -0.7496711040529912, - -0.7887606046847084, - -0.8246485434315804, - -0.8007564421932661, - -0.6869591827563879, - -0.6642675384109239, - -0.8036040330109782, - -0.7450933264740762, - -0.6608016171364255, - -0.8329415699109566, - -0.8321364994685067, - -0.7759188771994832, - -0.7755071741930234, - -0.6611745637437869, - -0.7309749261477662, - -0.8195902874572819, - -0.8261760327022998, - -0.8261586953274711, - -0.6827776776475227, - -0.6902231989375408, - -0.708227284957025, - -0.8158871757125837, - -0.7771068785820622, - -0.7737474557102303, - -0.8137618404209013, - -0.7735390739430816, - -0.7389586846898676, - -0.7189207398199595, - -0.7694985166748853, - -0.8298615251018159, - -0.7711944938844584, - -0.734795732758682, - -0.7809437272989682, - -0.7664604022926084, - -0.7887763981056101, - -0.7519157750762033, - -0.819830118528508, - -0.7515263739758558, - -0.7237344391187804, - -0.7860231797675834, - -0.8347552056466568, - -0.7294609681988183, - -0.6985062381167275, - -0.6808715661910868, - -0.8085178954059372, - -0.7244798528453924, - -0.7232160491756314, - -0.800797835775985, - -0.7054689468340118, - -0.720670130107994, - -0.7092463656939829, - -0.671820909535419, - -0.7590494527427148, - -0.807008902527885, - -0.7413864118880518, - -0.7244461997335826, - -0.776193826870054, - -0.7685091383255443, - -0.7652657193928317, - -0.7295497213799542, - -0.6808803482337809, - -0.6671628284013221, - -0.7806204817373563, - -0.8332563176372794, - -0.7145707210949834, - -0.6658795727112901, - -0.7757095774297136, - -0.6791343084594479, - -0.7463593103037941, - -0.6879905471900265, - -0.8269538574941087, - -0.7925331975679658, - -0.8019306055751858, - -0.7978583191546155, - -0.7734415404982076, - -0.7733343612694255, - -0.6916864640815464, - -0.6710886236805942, - -0.7226408201571899, - -0.7859705474192591, - -0.7634724698948168, - -0.6754121736191556, - -0.815645963843626, - -0.7015606044965963, - -0.6766902552265069, - -0.8056857483889694, - -0.7512103607743637, - -0.7242051930540835, - -0.7034927414664988, - -0.7644210325254672, - -0.6985041687876037, - -0.8137719012085264, - -0.7510487557273047, - -0.6860044270890852, - -0.7500411828615946, - -0.7197451424514932, - -0.830638614304874, - -0.7199718731989564, - -0.8314210276356309, - -0.7184036089895018, - -0.8044190368108821, - -0.820957468138641, - -0.7979890372097239, - -0.8042246810532775, - -0.6834695183321303, - -0.7043042887732047, - -0.7442144910315847, - -0.7295397188909724, - -0.7041743229616958, - -0.7381115766596469, - -0.7451473388818608, - -0.7153301474356891, - -0.7851549124557691, - -0.7511779642321408, - -0.7218631007774687, - -0.6668972042094347, - -0.7945609716809614, - -0.6657518109030722, - -0.6661076487711511, - -0.7694383576041753, - -0.7187240255152396, - -0.7555192846222175, - -0.6940101966358655, - -0.777932778304707, - -0.6609640292035812, - -0.7031838221917944, - -0.7335809396037626, - -0.7281572752683747, - -0.82091815341052, - -0.7037962623268386, - -0.7725861280295447, - -0.6694798268529818, - -0.7258854904482572, - -0.6832106474707197, - -0.7905373629952333, - -0.6860189091101749, - -0.7498827646623354, - -0.7638921259094349, - -0.8225116637352682, - -0.7693301370245322, - -0.7017809560298673, - -0.7047341453883474, - -0.7935616053116399, - -0.6861092463462275, - -0.7814985440824099, - -0.7072259255499815, - -0.6922690179865233, - -0.7426461574662276, - -0.6611945475830058, - -0.7231773382144205, - -0.719223964442057, - -0.7415867277832808, - -0.7179975301204921, - -0.7534681434488055, - -0.7860827883247687, - -0.7150949434955256, - -0.7308553493343819, - -0.6849028276418915, - -0.6764321102877389, - -0.6912005550809454, - -0.7432787035275765, - -0.7581180847950434, - -0.7472308484003043, - -0.7339372042938143, - -0.7631376539593494, - -0.8236479719014453, - -0.753062659291688, - -0.7984319156272884, - -0.7591345048835786, - -0.7579324042786085, - -0.7321359378941679, - -0.7785891401863844, - -0.7654892022003195, - -0.7949554251081881, - -0.7220861382522039, - -0.6808029399560391, - -0.7874756762583942, - -0.726929736918245, - -0.7641723617157434, - -0.7870224358159312, - -0.7879327291664412, - -0.7676571732826308, - -0.740431915391115, - -0.7679786383553772, - -0.7205372495369959, - -0.6975937021489694, - -0.7984711500612328, - -0.816469032352262, - -0.6685605630967106, - -0.8158462750467356, - -0.7893214936805573, - -0.7209847205452403, - -0.675417172302675, - -0.7734205002872983, - -0.8163565423758142, - -0.7719428330031695, - -0.7200134944667342, - -0.7588359898622119, - -0.6942996270913391, - -0.6697364849664151, - -0.8196440229927361, - -0.7046144024794697, - -0.828878239171896, - -0.6745797460875506, - -0.7530246774811886, - -0.7042711287884228, - -0.8228147586469786, - -0.7053419147861161, - -0.753361607475682, - -0.7080246516002944, - -0.7066039653153351, - -0.7981780089178778, - -0.7380695130039006, - -0.7791852432128147, - -0.8062438171949244, - -0.691496866387765, - -0.6743026761158973, - -0.6797087247861324, - -0.7327445936998955, - -0.6730243507250218, - -0.7732333123630395, - -0.7536145588731309, - -0.7498907692552839, - -0.7092754783123563, - -0.7495629908781501, - -0.7134289407506087, - -0.7463221327569596, - -0.6661622298962875, - -0.8285140449305086, - -0.7217572085746564, - -0.8220509300373624, - -0.7032915905183276, - -0.7161266250466307, - -0.7497051998319542, - -0.7820504412334047, - -0.7215447463978629, - -0.718045886364628, - -0.6778062283371656, - -0.7045454676515164, - -0.7106286181896644, - -0.7594126538312894, - -0.6949473218762512, - -0.6735034892128875, - -0.7389811509205935, - -0.7966650507067484, - -0.6918493097444389, - -0.751538493058997, - -0.7194805126732625, - -0.826196891002607, - -0.8153632693412347, - -0.8195141186499557, - -0.7827880002190707, - -0.7113166376436426, - -0.7395509236636356, - -0.6845417835262262, - -0.6854195631446274, - -0.7939024567269681, - -0.726074138407989, - -0.700731378024858, - -0.7845095278228229, - -0.7329134112294323, - -0.7520678729193697, - -0.7098857098358355, - -0.6794296404658182, - -0.7954394734514968, - -0.7557763893374474, - -0.6982614671267724, - -0.709142820670944, - -0.7977602729639949, - -0.7304511929860439, - -0.7754903169111419, - -0.6866660702978364, - -0.6997394407979506, - -0.6806519161211915, - -0.7276667918817327, - -0.7037420724277814, - -0.8203494698491011, - -0.7382092927953118, - -0.7714691200082443, - -0.7456051302915591, - -0.7974742599530495, - -0.7795967521275193, - -0.664379911621959, - -0.6615359733048406, - -0.7122503239816743, - -0.8256374463516919, - -0.6722095887993098, - -0.8104573104176716, - -0.7262293761833939, - -0.8092179840389538, - -0.7481136957500293, - -0.6847036210995765, - -0.7478660833733526, - -0.7164314324049454, - -0.6695236789104371, - -0.7810500698125677, - -0.683012686863545, - -0.7746784094328473, - -0.7423412883439156, - -0.8120217343455189, - -0.68248489609433, - -0.7405647162081581, - -0.8223979041826204, - -0.8175848045187644, - -0.7577098286790351, - -0.6794382166682077, - -0.8102449800247057, - -0.6840159323938512, - -0.7115584430121399, - -0.7668303229166046, - -0.7532469961082087, - -0.7990926790016285, - -0.7908255359452269, - -0.7400648413333076, - -0.7806700319235775, - -0.7842981696573146, - -0.762849915750882, - -0.7359400974683139, - -0.7047783025312175, - -0.767068839734436, - -0.8320602314722507, - -0.6670746657543932, - -0.7396351112109698, - -0.7536904608351366, - -0.8122634391595059, - -0.6951727136926101, - -0.7108038100111121, - -0.7844716874369032, - -0.7386993854468169, - -0.7279561013390949, - -0.8141869854023561, - -0.6900177383585533, - -0.7456729952707224, - -0.7407088796393096, - -0.781234383256789, - -0.6824979592225305, - -0.8221075455756078, - -0.7361236420648409, - -0.69308728219416, - -0.7747336245240868, - -0.7285329654781827, - -0.6767785103834496, - -0.8106984851086882, - -0.6888939656418084, - -0.8113533793162885, - -0.7305416945207548, - -0.8118828167612738, - -0.7032115757803034, - -0.7110258813370773, - -0.7591466210619, - -0.8127886372697263, - -0.784543498887396, - -0.8332989355676585, - -0.6710397450917972, - -0.6667437436354945, - -0.8004916446960344, - -0.7740814276897928, - -0.6604128545049874, - -0.7809763698216374, - -0.8038788285614448, - -0.753773136289042, - -0.7967655064171028, - -0.6905375822929567, - -0.7686370140260429, - -0.8140466770851745, - -0.7360340439702867, - -0.676735329088197, - -0.705237244505745, - -0.724647213591253, - -0.708963250059781, - -0.8215858371427736, - -0.8280040066721611, - -0.7349758273530529, - -0.7878369674024881, - -0.7250247983606811, - -0.6775795574345846, - -0.8235549996497469, - -0.6613628171092509, - -0.7567113956537406, - -0.7589707049447523, - -0.8194633981066791, - -0.7434889607823605, - -0.6818577035263504, - -0.7715294389482633, - -0.7167509954601008, - -0.7604048375544813, - -0.7054460241109296, - -0.8308992549764317, - -0.7546339478847073, - -0.750998150561476, - -0.6839588171951025, - -0.7716787007805824, - -0.7752666894887743, - -0.7161152126569863, - -0.7935220510910086, - -0.7580917450527451, - -0.6725822493768121, - -0.7242977605214833, - -0.6965282300964566, - -0.7744894328112399, - -0.7068385456965384, - -0.8212802579924492, - -0.7205256624347034, - -0.7920606815346167, - -0.8192799600774374, - -0.7933332996209679, - -0.7349484572872734, - -0.7961269604063901, - -0.6876281856002915, - -0.7130989669732152, - -0.7643713222313075, - -0.8045448666193349, - -0.8318307283382318, - -0.6853877556516594, - -0.6784130150577691, - -0.7562586877076289, - -0.7753508645815662, - -0.7953627331150457, - -0.7858019954143771, - -0.6785642533327275, - -0.8318395520168014, - -0.6648549293764454, - -0.8325995359906213, - -0.6695559471688548, - -0.6907691391077199, - -0.8135955328727532, - -0.7120416818879115, - -0.8239336001817399, - -0.768269374422795, - -0.7970751856398991, - -0.8178047080490431, - -0.8162270700174056, - -0.7158506400014848, - -0.7709995541003154, - -0.8166335800469126, - -0.751792538455927, - -0.7606186245446659, - -0.7651915370435478, - -0.7781480168942141, - -0.6865471942091674, - -0.7975362119685578, - -0.7969845754535908, - -0.8093153287885395, - -0.771659152074682, - -0.7942510395246813, - -0.8073374400056346, - -0.7333838526717467, - -0.7821639125213337, - -0.7391198924219494, - -0.7978474450590188, - -0.811495374562393, - -0.6983899025422676, - -0.8072353782434892, - -0.8012768544211631, - -0.7094020257005068, - -0.6683326907725906, - -0.6733970537594458, - -0.6676018346252802, - -0.721397211425746, - -0.7186306975915865, - -0.6911298871903371, - -0.8184269336468265, - -0.8281801572713521, - -0.6826344738759813, - -0.7657413349271521, - -0.6648588231667041, - -0.8092975933556769, - -0.7664759600692458, - -0.7457665487106175, - -0.7383053791422212, - -0.7504579523006969, - -0.8252192557045882, - -0.7005449278793203, - -0.737527191472829, - -0.6635705867617753, - -0.6923023467969469, - -0.6759150086327271, - -0.6843045834150845, - -0.7965392001381394, - -0.705653586179075, - -0.8018724936232989, - -0.6758168980456765, - -0.7918443063109248, - -0.8214582722709775, - -0.7314537556130944, - -0.8009709748338796, - -0.6764500967540623, - -0.6915668356311722, - -0.8312898339377107, - -0.7726748841728975, - -0.6965879202278589, - -0.7470851416197308, - -0.8313066538944718, - -0.682748121296475, - -0.7416834329395237, - -0.7611711731989547, - -0.8252507900406041, - -0.813825085329273, - -0.717494227256099, - -0.7691354344162027, - -0.6699336837511043, - -0.6730105935219345, - -0.7876955126942233, - -0.7324726314575846, - -0.7737317664505395, - -0.6645787903049056, - -0.7811352246086984, - -0.799200938283895, - -0.7814403160231742, - -0.7160540390051745, - -0.7655759360988834, - -0.7129478870316048, - -0.7789882061106579, - -0.8268434811997617, - -0.7841068547246258, - -0.7831749553378087, - -0.6839181926719339, - -0.8351825098346952, - -0.7302108879103117, - -0.7636264847784875, - -0.775483545769101, - -0.7425379741428254, - -0.7099585866903056, - -0.7861056575824714, - -0.7830208749374514, - -0.8055514238274318, - -0.660773093972125, - -0.8358841388498345, - -0.7048998746068054, - -0.7401549894372459, - -0.8025733541637019, - -0.7357449293194307, - -0.7611882409207187, - -0.8098859406395319, - -0.7323269402094833, - -0.6909956073469895, - -0.7799368937875159, - -0.7117247053058924, - -0.6613071453271804, - -0.6753700490851033, - -0.7927748551599882, - -0.7994485489772362, - -0.8099137011892654, - -0.7010529901652411, - -0.8087175398356181, - -0.7135163849125548, - -0.7586508233893062, - -0.7062316024858314, - -0.7682167080005123, - -0.7482843856512988, - -0.7229194426807078, - -0.7995152463480076, - -0.7332686140310025, - -0.6869401736803206, - -0.7305076350884497, - -0.674854162064197, - -0.8356358471599818, - -0.6636312898081743, - -0.7764537974617706, - -0.6897455646008337, - -0.6798335406904626, - -0.7676401097370988, - -0.8315478728686988, - -0.7438644913641481, - -0.7876235904628198, - -0.6808924454891211, - -0.7405584847985626, - -0.6676475654898453, - -0.811080802971218, - -0.6792044208397449, - -0.7752790452014913, - -0.7380639420852709, - -0.7258777289821976, - -0.7317734739784144, - -0.744072993238142, - -0.7079495988044497, - -0.7761891360365165, - -0.7288068411436536, - -0.8026480820348187, - -0.7026274756584785, - -0.8323063438201126, - -0.782942974322496, - -0.8200614715197956, - -0.8205305384242583, - -0.7847023448973346, - -0.7846857785850245, - -0.8266765491526725, - -0.7891510508477445, - -0.7764420495822333, - -0.7772478777716779, - -0.7076141650990112, - -0.7588012693255143, - -0.7693398328936056, - -0.6634090217450743, - -0.8006647946541813, - -0.8317276107683453, - -0.8236852362867886, - -0.6613407531277427, - -0.7121511939805926, - -0.7273871854636302, - -0.699483234269611, - -0.7358701702782288, - -0.7008126597263785, - -0.6622539192972634, - -0.7951924292543845, - -0.7739769972461268, - -0.7080672327614783, - -0.786884380831872, - -0.7330646917682212, - -0.8194735988776558, - -0.8314938074204492, - -0.7416361504334708, - -0.7611312826530304, - -0.8271539274088199, - -0.8222010847740376, - -0.7866916083459111, - -0.7320742677705355, - -0.8069729813866909, - -0.7774455674454624, - -0.8352841296521067, - -0.7627695181225148, - -0.8019446882087568, - -0.8239111176647634, - -0.6622858794028101, - -0.7520137423937931, - -0.8080282434918173, - -0.692835282718838, - -0.6649923117005649, - -0.7506252116873774, - -0.6980226682149715, - -0.797719625128018, - -0.7063739527464252, - -0.7678134126339198, - -0.6913914369585744, - -0.7734019326230863, - -0.6830284724455336, - -0.7703138941466035, - -0.7389241728508642, - -0.71302599253426, - -0.674839230117878, - -0.7642710901714822, - -0.782873185849708, - -0.7707423479973685, - -0.7172355062248998, - -0.788802455135331, - -0.804686094305138, - -0.8026827216372704, - -0.7882310113457905, - -0.6864033656607605, - -0.812215882334819, - -0.6721314031202156, - -0.719597389404678, - -0.683164610070369, - -0.8087504339157573, - -0.6798316835323163, - -0.7579677153484684, - -0.7539097608888665, - -0.6674656162174057, - -0.8263989730318662, - -0.6620551644708624, - -0.6910158184319656, - -0.7582883150133537, - -0.7037951066377042, - -0.7024624720683066, - -0.8076264367243802, - -0.8152997458837348, - -0.8288246185679935, - -0.7917911637196536, - -0.6812220919916494, - -0.664308227301323, - -0.7826146428293614, - -0.782447993938662, - -0.6606454107253428, - -0.7440653723467493, - -0.8299504594155356, - -0.693179419681839, - -0.7282963024276686, - -0.6791304445336313, - -0.7998045083155763, - -0.7672253331088373, - -0.6905446539728451, - -0.7337298939700755, - -0.6993413991617704, - -0.825901445842009, - -0.7788415616916489, - -0.7165467405037731, - -0.7180214918234682, - -0.771500630424489, - -0.7151511148912182, - -0.7018722201162026, - -0.6728526456544803, - -0.8326784384637975, - -0.6784828396161667, - -0.7784643666092782, - -0.7329971335286525, - -0.7735020427458172, - -0.6621258984958223, - -0.7232531073359083, - -0.787589283465821, - -0.7746831836660802, - -0.8045323652565645, - -0.7179541553381972, - -0.7694717941383017, - -0.6941056748746596, - -0.7702966736109246, - -0.7448562438386152, - -0.6722283644194363, - -0.828492643746557, - -0.7502034528156023, - -0.7073088306451782, - -0.7214525488729439, - -0.7666351162093875, - -0.7735386204015631, - -0.7238287299268903, - -0.7109473237048167, - -0.8066167033953473, - -0.7741653626719712, - -0.7691878387018904, - -0.7380624023971228, - -0.7665768102733374, - -0.7205576827023933, - -0.8124347642260332, - -0.7197071829810621, - -0.7192450845187403, - -0.6731636430929384, - -0.8121780616775691, - -0.7720623164060517, - -0.7181826866223167, - -0.7270143350231884, - -0.678295400204909, - -0.7526072035117867, - -0.7863855937427195, - -0.7573381701570495, - -0.6882202536986054, - -0.8192288256930537, - -0.748778190013142, - -0.8053069331139274, - -0.7584637259375208, - -0.7016556786469088, - -0.8122889626844647, - -0.8292867322712717, - -0.7057184977229533, - -0.6641891755837882, - -0.7090452090042663, - -0.7105007586209013, - -0.7558335956109399, - -0.7085232052570101, - -0.7311854633743115, - -0.7532222535772631, - -0.7457093713682843, - -0.672582431690807, - -0.7634048008406426, - -0.7680280082123172, - -0.7537963718624925, - -0.786533236910003, - -0.7439839481459515, - -0.8214227767297742, - -0.711798716625998, - -0.665408852804908, - -0.7658158089857918, - -0.6887780454905543, - -0.7843748695002801, - -0.7772619391147395, - -0.7826785510962203, - -0.7613954826928331, - -0.7467529128305681, - -0.685227823149004, - -0.7196163649525104, - -0.6911997810352191, - -0.6670706690880562, - -0.8088188362744609, - -0.6923889892100654, - -0.7815769158095158, - -0.6958973861318207, - -0.7224288247666503, - -0.7506689749411308, - -0.689860399803416, - -0.765986847860089, - -0.7742246572170413, - -0.8210468000696892, - -0.7041249255697257, - -0.7485625893804728, - -0.6644427095846414, - -0.748290709687444, - -0.7882278405209534, - -0.6740529138517121, - -0.8014630288483189, - -0.6704229796755659, - -0.6848065173653581, - -0.7708680734420473, - -0.8016482407298737, - -0.817967500806751, - -0.7051403024166181, - -0.7408157981590975, - -0.7705343841400165, - -0.7295172988887132, - -0.735078108585817, - -0.715820312983704, - -0.7746152737460866, - -0.6917846364962217, - -0.7291654862533974, - -0.6945711639843601, - -0.7165370383697387, - -0.7067749188555518, - -0.8327993355511836, - -0.7243638473046023, - -0.7158980363565967, - -0.7718824586176167, - -0.694699471973532, - -0.7319262419080422, - -0.7443928517813513, - -0.7018085784723157, - -0.7661785607421961, - -0.7857507023380268, - -0.7206882097625404, - -0.7416244079080381, - -0.7209748273585741, - -0.7840999278225913, - -0.7965702931927962, - -0.7802291710251833, - -0.694823611188755, - -0.7641867509758875, - -0.8241221938608613, - -0.7167473981279896, - -0.763651119709172, - -0.694122427996568, - -0.6894281482715325, - -0.7078885220713224, - -0.7884303697899383, - -0.6881841199472305, - -0.7594279089604838, - -0.6784920675657741, - -0.7850915590834834, - -0.7807761325803779, - -0.7089037019819099, - -0.7007404947138404, - -0.7995797395391876, - -0.803981925640787, - -0.775208488962035, - -0.677530813872016, - -0.8211024995683268, - -0.7227762729256462, - -0.6976693165275509, - -0.8309155293807097, - -0.7788814928707753, - -0.7405203049235508, - -0.7026273049436987, - -0.6731907721100703, - -0.719430739827556, - -0.7179181583697698, - -0.7757362596394408, - -0.789118439598744, - -0.8028365569212542, - -0.7648539865479678, - -0.6836672528670076, - -0.6886726955592153, - -0.7269457259231578, - -0.8153430407409478, - -0.7807233200928526, - -0.6840368545168826, - -0.697400802747393, - -0.8157644059781701, - -0.7608199640356522, - -0.7919828748098375, - -0.6988150432915108, - -0.8327952993690166, - -0.7981474243507827, - -0.739206721970271, - -0.7036010983678126, - -0.6960314744742295, - -0.7997925337557086, - -0.702504629083232, - -0.690166061666402, - -0.7185859306465301, - -0.7467330060922527, - -0.8084954955862991, - -0.7184962181010185, - -0.7200877185551794, - -0.6730002218358153, - -0.668590024134411, - -0.7974478627090138, - -0.8262096780551178, - -0.7960746536460206, - -0.7980977603195735, - -0.685406722098223, - -0.8302475794178399, - -0.8269194481029756, - -0.7987335467307324, - -0.6820548242623, - -0.74872761105126, - -0.6641602747067508, - -0.8215352844984787, - -0.7934845537760115, - -0.746192624688613, - -0.794091696661699, - -0.8329832244317164, - -0.6775733989190932, - -0.6718587612412789, - -0.792939693796751, - -0.8155376444522638, - -0.7083779525336069, - -0.7734024516001902, - -0.676433270561092, - -0.7189698374556373, - -0.6674344849910336, - -0.814684113195289, - -0.7071799547967623, - -0.7214992912999105, - -0.8225744936165406, - -0.6756261088503228, - -0.6898576764753916, - -0.7326685849703103, - -0.7609197600499025, - -0.7097936702110901, - -0.662437081194257, - -0.6938572552079012, - -0.8069093034137973, - -0.7655983234714591, - -0.7759488353255686, - -0.780955366346362, - -0.7828087965417894, - -0.8105215680584504, - -0.7920140322587005, - -0.7914157869145495, - -0.7180842480021095, - -0.7454967948235828, - -0.7686163385358816, - -0.7076489420125213, - -0.816395495481654, - -0.6870638530596842, - -0.6914928640250513, - -0.8041700986902829, - -0.7491605748446507, - -0.7834925503826718, - -0.8114888073530143, - -0.8047161594693161, - -0.7123958185965478, - -0.778960197617429, - -0.7732979052158118, - -0.8130616562914552, - -0.8116547688536546, - -0.8334692169772818, - -0.7582310613070489, - -0.7033707474741336, - -0.7866926079641952, - -0.7129154976847731, - -0.8069798406970006, - -0.6746038551367683, - -0.7730132445684097, - -0.7843846947397131, - -0.6606929224367721, - -0.6802528740331801, - -0.6633688917075415, - -0.7458066797315935, - -0.7787348188631554, - -0.7618395455875453, - -0.6968842690209862, - -0.7609474285931052, - -0.7246337963493594, - -0.6827803232899489, - -0.8145717312001683, - -0.7455117719730733, - -0.7000107668985519, - -0.8071824191877426, - -0.776368101855257, - -0.6832860488521583, - -0.7978758577712183, - -0.7198383643880413, - -0.7508349368074587, - -0.6706418148780326, - -0.695114633890763, - -0.688454532739884, - -0.8265799833743859, - -0.8272614777579479, - -0.7295322201330164, - -0.6648828235852047, - -0.8191755055260052, - -0.8057337002799988, - -0.6904467837097326, - -0.7045649001056291, - -0.749475141907838, - -0.7230244001575628, - -0.7146338573902837, - -0.6839120808539183, - -0.8308919717389577, - -0.7586601736105696, - -0.8299302387378442, - -0.7210026576424, - -0.7742242861781652, - -0.6673907615039216, - -0.7353170845792262, - -0.7820382860645443, - -0.6765518587274234, - -0.767019116382483, - -0.7414333524926885, - -0.7199755526767849, - -0.7744612190541185, - -0.720774100803813, - -0.782783164258668, - -0.692012106986209, - -0.6794037175174654, - -0.7856564326809042, - -0.7553298507857753, - -0.7647989078519367, - -0.7904677843484541, - -0.7463035538480616, - -0.6803633507228349, - -0.7554081016862922, - -0.6875744924335155, - -0.6966180631792217, - -0.8116689914357033, - -0.7147447369355158, - -0.7398393753762119, - -0.6870809261893713, - -0.7207029438454544, - -0.7397539347457216, - -0.7164000632063964, - -0.6779391351339177, - -0.6825027060650593, - -0.6903993151626571, - -0.7146843431815442, - -0.6657161780126462, - -0.6606811312809291, - -0.6609523541540016, - -0.7325740322360254, - -0.681654939059207, - -0.680514937988712, - -0.7097694119385616, - -0.686563687370579, - -0.7080793774816584, - -0.6844565567763781, - -0.7022059540537429, - -0.696138512658293, - -0.6785335292241138, - -0.7171061236260258, - -0.7269568799816714, - -0.7244616896460998, - -0.6707530182519136, - -0.6955710416742479, - -0.7301531338974137, - -0.6746099400667356, - -0.7243237448771551, - -0.663324822910843, - -0.6981392840247731, - -0.7358663876753019, - -0.7034572663128762, - -0.6815960602851839, - -0.7205315259082978, - -0.7120079761457381, - -0.7156416109326508, - -0.6977206738671594, - -0.6715492140047975, - -0.6947935791519237, - -0.7408469284476042, - -0.7143018286213157, - -0.7095207110124669, - -0.7232009507741171, - -0.7197457516642011, - -0.7032442407990638, - -0.7186021634579992, - -0.6788478933224878, - -0.7132355277277183, - -0.7166389739845774, - -0.6902332032955866, - -0.7208822531526549, - -0.7237692781633056, - -0.7401748204686424, - -0.7334190821461853, - -0.7395745393750718, - -0.7165105124508767, - -0.663447563729557, - -0.698862988642829, - -0.6770397466215917, - -0.7145252740874397, - -0.6967036332834973, - -0.6899915986580373, - -0.7409650726779877, - -0.6638575657710848, - -0.6951862867222199, - -0.6891006696628466, - -0.725806883668863, - -0.7298767461031218, - -0.7186987780709523, - -0.698687932881345, - -0.6648245226203949, - -0.7143614739254073, - -0.7230428374005452, - -0.7261335439011105, - -0.7218953395880984, - -0.7338525987121869, - -0.7373006126167996, - -0.674932158389489, - -0.7065419075411361, - -0.6912002366558687, - -0.6775495914689761, - -0.7301060687356491, - -0.6741852144020517, - -0.7230832795243839, - -0.7059537718794543, - -0.7235451023806392, - -0.660802138568918, - -0.7087205080551562, - -0.6974739056214395, - -0.7289567195353682, - -0.7146020512123427, - -0.6838944103561445, - -0.6755341756064761, - -0.6853398754917264, - -0.7285350369338494, - -0.6692755251859226, - -0.662247367444439, - -0.6932029040838337, - -0.7024799635490039, - -0.6677692242022112, - -0.6705381858478252, - -0.6817457481218122, - -0.6707402557361372, - -0.7076295541308262, - -0.6981886375445263, - -0.6697688197285583, - -0.72295866773357, - -0.6633243019335462, - -0.6657686896161082, - -0.6793355362903688, - -0.7308106859569066, - -0.738205756370067, - -0.7260137503546421, - -0.6831930788748004, - -0.6696140768867691, - -0.7401516744246344, - -0.717075611471796, - -0.7337629925076069, - -0.6844640726563304, - -0.6798930795659295, - -0.7367174472249257, - -0.6927252287695728, - -0.660942374928809, - -0.7094138464642835, - -0.6601565332594437, - -0.7326214860656747, - -0.6889184698153845, - -0.6751234128702743, - -0.6916408290425458, - -0.7010395190659062, - -0.7176443597421616, - -0.7024823015725765, - -0.6903052994661368, - -0.6867979713398102, - -0.7242638114957901, - -0.7177853078692806, - -0.710847524849726, - -0.7083712967608666, - -0.6784711603502289, - -0.726202609188827, - -0.7411852718918394, - -0.720026805309684, - -0.7345346284069376, - -0.7191729802937926, - -0.6856787520675728, - -0.685849865921384, - -0.7160284957797902, - -0.738249937491938, - -0.6984980981557187, - -0.6984956763950636, - -0.7195036121006874, - -0.7106480590703853, - -0.7024153326339632, - -0.697518013848476, - -0.6927089628524562, - -0.7031970134329562, - -0.6776925715822895, - -0.6819567209211339, - -0.6910441278610485, - -0.7270244400419613, - -0.735099625680584, - -0.6701816191432974, - -0.7095105951844224, - -0.6698197268788407, - -0.7056330623838301, - -0.6672144666661758, - -0.7061795007987517, - -0.6675743998259359, - -0.6918846979869226, - -0.6790174265436282, - -0.7169321588762543, - -0.6670031635987064, - -0.6818069390566122, - -0.7055136037549846, - -0.7254253648096448, - -0.714032013798357, - -0.6624198021239868, - -0.6905723609866838, - -0.6961037186809591, - -0.7125293794701137, - -0.6850950623672554, - -0.6747175655836504, - -0.6900436235702356, - -0.6747107761064648, - -0.6746749696563246, - -0.7258018471096026, - -0.6614578368718831, - -0.6655220892825405, - -0.7129272332357123, - -0.7064475507775732, - -0.727424788555391, - -0.6952556145093735, - -0.6757767156292923, - -0.6966910755997426, - -0.6997914372975103, - -0.6811138757349476, - -0.7246147685366975, - -0.7171350022573629, - -0.6645456162002429, - -0.6930619283331058, - -0.7079248267045035, - -0.7130969782520002, - -0.7293205881471678, - -0.6971774359994671, - -0.725310489026047, - -0.7075702365942077, - -0.6615180072329084, - -0.7027346337127643, - -0.6990095217144919, - -0.7232056382641655, - -0.6798904474396947, - -0.6696893030387503, - -0.6906849493844687, - -0.7391064524400639, - -0.7164595275239851, - -0.6602865766666627, - -0.6715254209444602, - -0.7067369865408321, - -0.6909036965889475, - -0.7287374735384746, - -0.7001443000658325, - -0.6980018555427979, - -0.6809346291280155, - -0.667978651197521, - -0.7374933067017216, - -0.7206379110277688, - -0.6924448726708018, - -0.6881172490370889, - -0.693273677970714, - -0.6782549275449525, - -0.690156360058418, - -0.7246762061182653, - -0.7184540468530201, - -0.7029653564480751, - -0.7359283321466289, - -0.716122806896269, - -0.673244788748572, - -0.7244669609293265, - -0.6660730583394664, - -0.6851815106766264, - -0.7324223801821452, - -0.6763719695470456, - -0.6777237244973755, - -0.7238121618864257, - -0.6862283579442228, - -0.6761106955410897, - -0.7166948990892119, - -0.6740927021320074, - -0.7178519127671621, - -0.6723249124214566, - -0.692015773307457, - -0.7071304277385335, - -0.67929383041275, - -0.6741566620730988, - -0.7029338239649362, - -0.7053435913161673, - -0.6669100697564232, - -0.7257544459558718, - -0.6975186231239142, - -0.7267260077667174, - -0.7406618558112238, - -0.6612624407882999, - -0.7197810913834206, - -0.7612138506525566, - -0.7661733951217942, - -0.7285922264843173, - -0.7840314454225794, - -0.7456981618518047, - -0.6955087048396986, - -0.6989665009319239, - -0.7735564686763708, - -0.6840594773483558, - -0.7432239408864878, - -0.7852723141870912, - -0.7869106001350699, - -0.7327520856498558, - -0.6716326467155871, - -0.7544926881266725, - -0.7275410471425273, - -0.7373619938670902, - -0.683041458621694, - -0.75163069739167, - -0.7174266060439713, - -0.6962006336770347, - -0.730710508840399, - -0.7920084064752426, - -0.7688050672025155, - -0.7858308094952371, - -0.7459134627183248, - -0.7407217221949448, - -0.6750211641696822, - -0.7607624144113626, - -0.6630678723031989, - -0.7004596041251901, - -0.676086908283074, - -0.7043729001809872, - -0.7758876463068454, - -0.736191721515838, - -0.7410300381042004, - -0.7588515894421598, - -0.6752839013670213, - -0.7797315802688349, - -0.6653780694860076, - -0.7826442829713955, - -0.6607490098690394, - -0.6771570801353978, - -0.6781978685783667, - -0.7103506666589694, - -0.7606025808712592, - -0.6929949990640343, - -0.7267621491988147, - -0.7620889900543102, - -0.6875280305036101, - -0.7054604355647951, - -0.7330356564309912, - -0.7871673097583658, - -0.6736558030547137, - -0.66142364499131, - -0.713358177626659, - -0.727529428558536, - -0.6747110064518138, - -0.7749390427898954, - -0.7587773394814645, - -0.6611396089499518, - -0.6844989094991462, - -0.7874460898859705, - -0.6677975575800361, - -0.6918061308167902, - -0.7004104848973456, - -0.689529853619403, - -0.7810160448640193, - -0.7515837587235368, - -0.6688634351797954, - -0.7896187517857214, - -0.7004225907070274, - -0.7551161908180267, - -0.6973708504537516, - -0.695908244755647, - -0.7409467178934142, - -0.6716014385402159, - -0.6824408914285665, - -0.6625143656225634, - -0.728888218526349, - -0.7860064965230621, - -0.6765723463760749, - -0.7826111456791516, - -0.6656127378014417, - -0.7891438078647316, - -0.7110854386587045, - -0.6930106142340435, - -0.735396933037655, - -0.7058134129518078, - -0.7450208076097008, - -0.7881578825202344, - -0.7359506004616192, - -0.7074023568616222, - -0.6780852993491143, - -0.7667166289062719, - -0.7356768405198194, - -0.7720795059424861, - -0.732235051806834, - -0.744684171353979, - -0.7730479664040448, - -0.6751071992115766, - -0.7647983755470047, - -0.7405366466476989, - -0.724420473392408, - -0.6939045655720744, - -0.6701318110034351, - -0.7629074114511736, - -0.6900760737174298, - -0.7164950625321094, - -0.7376481407286327, - -0.706354409584695, - -0.6708720661323611, - -0.7302554974253149, - -0.7530622935339375, - -0.7291521798786549, - -0.6811059005215738, - -0.7326443256299026, - -0.7604169250867502, - -0.6773486989442553, - -0.7891550862705525, - -0.789570566333363, - -0.6948996908824292, - -0.7027298769254285, - -0.7891707957849813, - -0.7079190152779784, - -0.7714214644548549, - -0.6948392535867927, - -0.7474935365575212, - -0.7177729457585799, - -0.7531058774840627, - -0.7319644994822756, - -0.7126296178399365, - -0.762024511038469, - -0.7359779735093454, - -0.746839108341208, - -0.6767496766609241, - -0.6906965143270645, - -0.7267539957483793, - -0.7207461634594403, - -0.7410100123890507, - -0.753204460309697, - -0.7863118243862106, - -0.7367961315323224, - -0.7460639942677231, - -0.7346862263683025, - -0.7230760923814178, - -0.7484876552327336, - -0.7496881973004701, - -0.7153811068540611, - -0.7779821720970412, - -0.6649230329863375, - -0.7865702401492247, - -0.7757984286197038, - -0.6917061246280171, - -0.7114690044318177, - -0.7599952086031081, - -0.742332698150795, - -0.7445024236073778, - -0.7340743082362712, - -0.7226274578202586, - -0.7594813825428787, - -0.7133112353887298, - -0.6834312523599047, - -0.7173523249505507, - -0.7299866501598874, - -0.7004675307592659, - -0.7283729782368354, - -0.7559866417345368, - -0.7309334452850541, - -0.6669891061037252, - -0.7925117773791109, - -0.6918344896471145, - -0.7794519033514012, - -0.6959717663126632, - -0.7738174196177411, - -0.7385989984798228, - -0.7375764980225336, - -0.7583431626164696, - -0.6798087443182518, - -0.7180513773111198, - -0.7732214056084893, - -0.7653030333377212, - -0.7562075817813091, - -0.7853895291620788, - -0.6617690625370399, - -0.6890041666612599, - -0.7532887584140356, - -0.718974333943016, - -0.7243658500163104, - -0.696640991636492, - -0.6692152880494824, - -0.6720878179058757, - -0.7374705139225949, - -0.6889980940753644, - -0.7312493701414138, - -0.7068269183816569, - -0.7048188087048086, - -0.7689974128961663, - -0.6793512637815715, - -0.778627309016016, - -0.7571084618492665, - -0.7660957806903346, - -0.7572553803884642, - -0.7742080077030788, - -0.7733768559138917, - -0.7487472289102298, - -0.7710784359681676, - -0.7534169598754283, - -0.7801210040265782, - -0.7055677571936817, - -0.6982948004391678, - -0.7462399237340004, - -0.7721887317042636, - -0.7674231937459647, - -0.7114688166285209, - -0.7511037279336107, - -0.7029512590018154, - -0.7704895193989291, - -0.7924914123368006, - -0.7057501996606259, - -0.7433383047582434, - -0.7620934092514152, - -0.7754505238097386, - -0.7460441340103401, - -0.6920334562593407, - -0.7029654510308073, - -0.7759797978754606, - -0.6727555402277174, - -0.791774783341456, - -0.7152607724121953, - -0.7579157154666354, - -0.7034336280441295, - -0.7510779488877338, - -0.7859333874129206, - -0.7650503506870979, - -0.778525590845515, - -0.7157922926556416, - -0.687897415179517, - -0.6851908983076673, - -0.7652963449808206, - -0.7638815472917676, - -0.7331682336035708, - -0.7582070100346686, - -0.7755793807148209, - -0.6958848315300302, - -0.718650639073141, - -0.7575408698399525, - -0.7219907751240031, - -0.6993611707024752, - -0.680173387235101, - -0.7473414083301873, - -0.6662963036206836, - -0.7728972482605302, - -0.6832353754757255, - -0.709020309063636, - -0.674136523143112, - -0.6868598169901816, - -0.7601289347036205, - -0.7880262169362123, - -0.7038623719565767, - -0.6867445183494265, - -0.7065694402875635, - -0.6742694661616639, - -0.6902360304066018, - -0.6841411190206336, - -0.775346219434428, - -0.697670555915903, - -0.7626655116750621, - -0.6882328248649251, - -0.7310376706989677, - -0.7512943235987024, - -0.693034745400313, - -0.6814284570685141, - -0.6744525177500612, - -0.709078098218859, - -0.721649812535284, - -0.7880809672185284, - -0.7455894932683041, - -0.7850781063346775, - -0.7553654269662049, - -0.7700060298074459, - -0.7933683425690574, - -0.7024648525883512, - -0.7107815384244155, - -0.7324806874791312, - -0.719916741477775, - -0.7529426824434438, - -0.7828788351944137, - -0.7871866865070808, - -0.7203703314023655, - -0.7003692263830686, - -0.7879156733231205, - -0.750445385471616, - -0.7723798564095782, - -0.7469473385131101, - -0.670340992919906, - -0.7681265195724634, - -0.7262202593994742, - -0.6980275440260677, - -0.7292135627455796, - -0.706347386939748, - -0.7902702178221689, - -0.7636570279142777, - -0.6776746838539539, - -0.6987417849596101, - -0.6711943170165013, - -0.769042423564139, - -0.7661711106915932, - -0.6687697961504657, - -0.773006213288996, - -0.7540527026646469, - -0.7456471413135747, - -0.6627539180668379, - -0.7370825773118554, - -0.699086586126271, - -0.7376102413381547, - -0.7282587980524428, - -0.690936375906557, - -0.7166613171261659, - -0.7753529319801619, - -0.6678904206596771, - -0.6713875821444069, - -0.6977543938448502, - -0.7504649263529412, - -0.6803350732665161, - -0.7275318389145201, - -0.6767094713442174, - -0.7781765748911168, - -0.6753178202534208, - -0.7570100500223466, - -0.7681603656818025, - -0.7513718295545878, - -0.7187181694385911, - -0.6896030589677329, - -0.6701591623329296, - -0.7806567475811977, - -0.7331013494909167, - -0.7858505756302813, - -0.7816151790227348, - -0.7308882518307596, - -0.6659801603339788, - -0.7507991577828824, - -0.742261613506733, - -0.7369185651421225, - -0.7056999858806045, - -0.7772895972916074, - -0.6636707903066184, - -0.7843838055227049, - -0.7698155282610051, - -0.7449372151052839, - -0.7314906536008275, - -0.6795561019759615, - -0.7439353374183223, - -0.6640095904459042, - -0.7052171042894722, - -0.7871088947702292, - -0.7138549246308035, - -0.7852857937788741, - -0.6685857781456416, - -0.6955517047836253, - -0.7131085700539589, - -0.7802496672942439, - -0.6701569262855339, - -0.7902426731936466, - -0.7198371231320125, - -0.7489797738802659, - -0.7604467720392606, - -0.788216451213891, - -0.7626912753889679, - -0.6733982617924311, - -0.7114225442157793, - -0.6973804699083482, - -0.7841768171727856, - -0.6907444912254532, - -0.7750212351609654, - -0.7856144605708917, - -0.7280552414674637, - -0.7474978807268309, - -0.7140833469706015, - -0.7870264211266712, - -0.6718115023299156, - -0.7834331886742747, - -0.7491844098272957, - -0.7282583325191814, - -0.7286240153499892, - -0.7753726536312721, - -0.7386134414347734, - -0.71108793729606, - -0.7155405489659307, - -0.7188805003401277, - -0.7389372802864105, - -0.7645122079182615, - -0.7322899698113203, - -0.7306722514174742, - -0.7612274043093967, - -0.7184155160865133, - -0.7083480702574568, - -0.7029624256064102, - -0.7412726182757933, - -0.7026524403706265, - -0.7082449886701163, - -0.6942582070649178, - -0.7522699740453455, - -0.7618467532919639, - -0.7318491556462896, - -0.7373131647564447, - -0.7502691552797076, - -0.7347051203382331, - -0.7015234790850625, - -0.6631355574445981, - -0.7212602804676328, - -0.7767592464741244, - -0.787122750603658, - -0.7385091302125427, - -0.7214247224682295, - -0.7189580645649163, - -0.7237146710616247, - -0.7244880534744849, - -0.7765147410522945, - -0.7765559194481255, - -0.6610040969989724, - -0.6719433920975159, - -0.7569444031252742, - -0.6606868814976133, - -0.7391419382448261, - -0.7832914593613741, - -0.6799027070606422, - -0.6899924607178303, - -0.6815469939400042, - -0.6961503704777064, - -0.7325660449466309, - -0.7592975745050735, - -0.7884620516518598, - -0.7544158036300531, - -0.7118286775257733, - -0.7422938491274108, - -0.7764796487971463, - -0.6970751170059463, - -0.6710286171790097, - -0.7371640101306157, - -0.6932355772724068, - -0.7055846640484339, - -0.748448953351575, - -0.6649783046691249, - -0.7785272785807449, - -0.7302730409026703, - -0.6964000950214906, - -0.7206647644775508, - -0.7790336308347331, - -0.7718874470001588, - -0.7824951918536095, - -0.6969837554615208, - -0.7606349339479259, - -0.6922007566078444, - -0.6610167688108322, - -0.712688604620632, - -0.6617889433127355, - -0.735556149565699, - -0.7135368593828129, - -0.6785363977360946, - -0.7078612279523694, - -0.7485478202936837, - -0.6909725995279917, - -0.6937927766626932, - -0.6784960959872108, - -0.7894905042340764, - -0.7343288752328955, - -0.7621687370455248, - -0.7321921255315691, - -0.7272316379329258, - -0.7425226445389377, - -0.7243529131144518, - -0.6971871375890558, - -0.7711459007876258, - -0.6772038027927161, - -0.7669239265292161, - -0.667390498377437, - -0.6885357437044174, - -0.7175177042093518, - -0.7613146906377765, - -0.6937600462465386, - -0.7676762154741272, - -0.7007582013287728, - -0.7824642305862878, - -0.718832881583269, - -0.7354183429041896, - -0.7566819965346036, - -0.6974226798334358, - -0.7125742372458581, - -0.7513592165918296, - -0.7774906429427165, - -0.7239705110744864, - -0.7919462332625916, - -0.718892770366961, - -0.6943928230198154, - -0.7759928984251614, - -0.6719705805031065, - -0.7218687969243661, - -0.7205140586455523, - -0.7346626517082309, - -0.714378378650384, - -0.7490828833720498, - -0.7194527891651115, - -0.7414854349040635, - -0.7104003672676488, - -0.770519117833553, - -0.7729040894487895, - -0.7745546389668541, - -0.7537533044659959, - -0.6727248995350683, - -0.7915962075738164, - -0.7215561698185744, - -0.7810519782241139, - -0.6986446522339623, - -0.749410180668191, - -0.6771464926217363, - -0.7083693331531048, - -0.7711727723016868, - -0.6959448737888603, - -0.7574728839818395, - -0.6765751629875204, - -0.6968936569492051, - -0.6623057735122712, - -0.7516696488080818, - -0.7176992920858777, - -0.7354431694514953, - -0.7531595183870752, - -0.7696248380996882, - -0.776818771769105, - -0.7022116687559743, - -0.7773652400722487, - -0.6894820396524055, - -0.6949595040612617, - -0.7649002305638656, - -0.7706009209854914, - -0.6639146984749459, - -0.67110610402689, - -0.6938914552844822, - -0.7041603372134824, - -0.6893406684345499, - -0.7451028736724007, - -0.6706977790894455, - -0.7004014679819066, - -0.7264037739839855, - -0.7486642948769976, - -0.7660310289700486, - -0.6766515330869267, - -0.7915883758787895, - -0.7409115194706907, - -0.772424374353662, - -0.7289969756103009, - -0.7357285431288603, - -0.716638632052911, - -0.7294346543973669, - -0.680398690282496, - -0.7776117809734262, - -0.6784087535918463, - -0.7571695035478389, - -0.7095085198348625, - -0.6988670378565502, - -0.6614569632967826, - -0.6603857812467727, - -0.717410967543275, - -0.7284076713121677, - -0.7568890192391666, - -0.7458288433922525, - -0.7613111301983184, - -0.7234786884687161, - -0.7070609144607971, - -0.6805322946739588, - -0.6874915964801943, - -0.7644242140521154, - -0.7338886233790288, - -0.6819570092017377, - -0.7422066215011061, - -0.7089907161693729, - -0.7449530739222532, - -0.7334885667586183, - -0.779866203364422, - -0.7187896082464702, - -0.6735948090504937, - -0.6939075957160047, - -0.6730661171910668, - -0.7130893060719325, - -0.7032274185499451, - -0.663385595312373, - -0.7760622326982958, - -0.7800186489847659, - -0.7453191696542059, - -0.7129808003726115, - -0.7331331354675925, - -0.6968368144220121, - -0.7281824571856313, - -0.7155359080115724, - -0.7861471564230222, - -0.7123620182584881, - -0.6814319252003004, - -0.6980623503205277, - -0.7530199438176152, - -0.7361872411016046, - -0.6812580407116312, - -0.6754220808703691, - -0.7455777633071126, - -0.7623413149689001, - -0.6614061183974889, - -0.7888063845952593, - -0.760531916177178, - -0.6753596187062375, - -0.6776635851322809, - -0.7159207924192799, - -0.7506103117480108, - -0.780782615441186, - -0.735176837002029, - -0.7553658456433262, - -0.7120342930509832, - -0.7378104571583529, - -0.7012799335899578, - -0.7359827340180846, - -0.7303360323722778, - -0.7441956274888322, - -0.6946801228362115, - -0.7871208164578748, - -0.6719683128015339, - -0.7014677020343695, - -0.6933575963082349, - -0.7723496471117552, - -0.7101446040555477, - -0.7387710295796189, - -0.6758840603880655, - -0.7386083049168739, - -0.7499785330269599, - -0.7470589831650011, - -0.6990074023189606, - -0.7887333902123275, - -0.7322307798136265, - -0.7384564401662702, - -0.700522637426116, - -0.6886919117047233, - -0.7839753103499091, - -0.7542097381043705, - -0.7400359074799371, - -0.7375726966344662, - -0.7324888489346938, - -0.7003696898882238, - -0.7180578023619282, - -0.7408142456591116, - -0.7628205253998336, - -0.704114861643289, - -0.7375412472320888, - -0.711156245601874, - -0.7014820279250682, - -0.7139648204240078, - -0.7007802284554772, - -0.682386424265512, - -0.72144775821592, - -0.7268166199494047, - -0.7811518107139868, - -0.7164933716297855, - -0.7892935046281789, - -0.7796224199048566, - -0.7306670723043452, - -0.7552756108507571, - -0.7136337824571183, - -0.7008479318836591, - -0.771382784383165, - -0.7002949046744327, - -0.6945169251944892, - -0.7898353768996168, - -0.6745775361352506, - -0.7324985201024935, - -0.7245519764663734, - -0.6827099899363893, - -0.6611722271829027, - -0.718717331378071, - -0.6847145471147708, - -0.7381845459906535, - -0.7131084645359611, - -0.7847821317435132, - -0.6779086548319351, - -0.7399204362024042, - -0.785292046568165, - -0.6974169950595005, - -0.7498471178300754, - -0.7795070169928411, - -0.7720325695343926, - -0.7358882166741159, - -0.7125122669183006, - -0.7427896066023377, - -0.6852857106953968, - -0.7476431169891243, - -0.7561029566696603, - -0.7599473383784996, - -0.7493920617188029, - -0.6830079724119967, - -0.6648967384583807, - -0.7235987854800834, - -0.7122119629090848, - -0.7175485145694477, - -0.7423468673618144, - -0.7585914920383742, - -0.7055529225703023, - -0.7406712544896985, - -0.7510531211840812, - -0.7703918720405007, - -0.7476249761768019, - -0.7192352291176866, - -0.7279907933047625, - -0.6772876921756701, - -0.7425253945464907, - -0.7070176419626714, - -0.7109207140057872, - -0.7501143179851694, - -0.7612215717600113, - -0.7165610572474537, - -0.6967213342374272, - -0.719586601770678, - -0.7097946220563094, - -0.742645761022978, - -0.6900662662437234, - -0.6915513521289208, - -0.7272041458718704, - -0.7505032644254582, - -0.7437448610910219, - -0.7357163684389642, - -0.7194221919734131, - -0.6644894884711365, - -0.7445271755330118, - -0.7821706764175587, - -0.6782767671800096, - -0.663979829362119, - -0.7827604510641925, - -0.7138548584257174, - -0.7455351051641859, - -0.7249979966319754, - -0.6870112743623693, - -0.7334263225057285, - -0.6633200143165202, - -0.726617848893464, - -0.772646097959678, - -0.6622334018061904, - -0.7012718762231734, - -0.7156931723284705, - -0.7475985404203866, - -0.7600334043666591, - -0.6853465402341113, - -0.7225921708364553, - -0.7680969609499382, - -0.723356539039939, - -0.7510885631953225, - -0.7082193100355192, - -0.7543028390478671, - -0.6644908924249613, - -0.7057565645262427, - -0.696852780049082, - -0.7667027595019651, - -0.6768488144081708, - -0.7216810613568568, - -0.6778401479029242, - -0.7873026383512134, - -0.7076945950241964, - -0.7657788766597997, - -0.6831293664587573, - -0.7120181427121651, - -0.7292564832055868, - -0.6714724045221444, - -0.6648736868880293, - -0.6887826585397909, - -0.7756268299130102, - -0.6950776159517089, - -0.6880068089787571, - -0.7642571330816161, - -0.7787465016117806, - -0.7245442639243743, - -0.7097743190780296, - -0.7276743820556586, - -0.7882216738610296, - -0.778930469164527, - -0.7182297918798016, - -0.6983933748410984, - -0.7917547917122867, - -0.7172675183098851, - -0.6923782657026956, - -0.7904721878738389, - -0.7629018103987261, - -0.7490945635300295, - -0.6656994980732476, - -0.7681894066443206, - -0.7072506905054413, - -0.7087868166439644, - -0.687957622732382, - -0.7008864235368952, - -0.7032056481815031, - -0.7932006429730489, - -0.7636413452793079, - -0.7177973330803242, - -0.7537314357874256, - -0.7185572443733088, - -0.6619221533300598, - -0.7039353966954981, - -0.6770773738495268, - -0.7164252775025991, - -0.7666817516901692, - -0.7490726649682048, - -0.6783479053887382, - -0.7859419920052321, - -0.7456897713633283, - -0.7831646249539982, - -0.7187298869995818, - -0.7689518034978369, - -0.7612996522910361, - -0.7321882332020007, - -0.6609035121585075, - -0.7605894544145504, - -0.7178114591175957, - -0.6865683174891059, - -0.7363526315219118, - -0.6682403844254243, - -0.7722992351275437, - -0.6732417066101104, - -0.7630613763706896, - -0.6646491699038528, - -0.7123501196119659, - -0.6744932800726066, - -0.7625233898461745, - -0.7399082956187386, - -0.6899116593634511, - -0.7101595604872158, - -0.6777468622548583, - -0.7851517568928947, - -0.7514256227328291, - -0.6938853874732267, - -0.7460439833627616, - -0.7666548402081207, - -0.7372415639749079, - -0.7235098860921906, - -0.7910718483430815, - -0.6814028361154786, - -0.7761420826126831, - -0.6635400044152544, - -0.689189520352806, - -0.7086557427597193, - -0.7067217868769743, - -0.7126251762628519, - -0.7111209038479833, - -0.7251699660914326, - -0.7356967463400869, - -0.7794670430682232, - -0.6755467309930956, - -0.6682188004295472, - -0.6736525724963437, - -0.7687623554041344, - -0.7043086000585794, - -0.6670560534790709, - -0.7600928512924022, - -0.7076274231024007, - -0.7612614173900515, - -0.7305243825208764, - -0.7286711460738095, - -0.6636492389953352, - -0.7357837178680294, - -0.6933641712992697, - -0.6695312444538657, - -0.7784747067129161, - -0.7473069369437862, - -0.7725907544512487, - -0.7091291997548909, - -0.6821048808895842, - -0.6700928383001762, - -0.7389207619819397, - -0.764529739510383, - -0.7249304223215295, - -0.7596580496197499, - -0.690084838633227, - -0.755120041056349, - -0.7002040354966856, - -0.7144785289373099, - -0.7344506911348964, - -0.7799755430277956, - -0.6790632660777638, - -0.7196671494788489, - -0.7393540188766414, - -0.7863977172377669, - -0.6909296639916147, - -0.7604641454007852, - -0.7836069591925151, - -0.7725309658604472, - -0.7472498020488578, - -0.7331763112031566, - -0.7161451659267187, - -0.6675199004936734, - -0.7428413701655773, - -0.6883313533383497, - -0.7245210578212373, - -0.678562497431805, - -0.7318684368357777, - -0.7218305317930199, - -0.7103469523045243, - -0.7302065378107876, - -0.7534304418144844, - -0.7921066473789138, - -0.7465375705457971, - -0.6759056165260031, - -0.6911994062193341, - -0.711387251815371, - -0.6795036314238864, - -0.7933967261633517, - -0.7662905645826003, - -0.7925174962382421, - -0.7812187815384384, - -0.6673055821111058, - -0.7222740005262035, - -0.7578577352578397, - -0.6833285404660824, - -0.7090574449230489, - -0.7250032491869965, - -0.7448797768493397, - -0.7170525589571225, - -0.7124719250052058, - -0.7091560321731076, - -0.6612517746473274, - -0.6998804108530264, - -0.7896268210566775, - -0.6714835057341259, - -0.71750281965762, - -0.7452629023762027, - -0.6880995752950292, - -0.7762601164329297, - -0.7272689653111268, - -0.6794977670828763, - -0.7051404400800919, - -0.6860676548315772, - -0.7423859715954064, - -0.7003342713760553, - -0.6984570051867236, - -0.6746331965872662, - -0.6621179717549506, - -0.7208169170007366, - -0.6930234416643093, - -0.6933664069590534, - -0.7515585524998295, - -0.6600636391653566, - -0.6814469072220009, - -0.737651219078433, - -0.7271210627872399, - -0.6901111236383348, - -0.6881115941837143, - -0.7328935383634642, - -0.713131589360002, - -0.6845265022841737, - -0.7518952788282312, - -0.7579439155082808, - -0.6847662335221548, - -0.685623632471824, - -0.6982941683443602, - -0.7159037548656542, - -0.7644262626664471, - -0.7729870904037156, - -0.7484713835363835, - -0.6925914496991485, - -0.7333567920783703, - -0.7009734467556612, - -0.767244152308779, - -0.697219790542696, - -0.7637882629001681, - -0.6974160983392066, - -0.6659823057995526, - -0.6995063807860913, - -0.7021319595481617, - -0.749937676957209, - -0.7272184597466136, - -0.7757948781195031, - -0.7015104152003863, - -0.789407110796192, - -0.7714740375367937, - -0.7827159728449564, - -0.7560838898005572, - -0.778911666586186, - -0.6926139796447254, - -0.7599012841367562, - -0.7557680503291013, - -0.7913270981411912, - -0.663211373581691, - -0.718694547655036, - -0.7288975590411614, - -0.6742725683024885, - -0.790290405496449, - -0.7121613157124821, - -0.7918323983072586, - -0.7813712490137618, - -0.6621167666627271, - -0.7364936292555273, - -0.7195099379057659, - -0.6703281509735022, - -0.7392284347046109, - -0.7889153198728952, - -0.7053668981427561, - -0.7589106726101614, - -0.6603521786459536, - -0.7201661000032684, - -0.7841219411893563, - -0.7293526321998455, - -0.7622450340703899, - -0.6806764247039293, - -0.6870357321583995, - -0.771328961639428, - -0.7283066100065227, - -0.7617270466796093, - -0.7675343972979007, - -0.6984727675478932, - -0.770592773164756, - -0.7053358868033897, - -0.7840752032590859, - -0.6835338681919414, - -0.6616200324346863, - -0.7446330606245324, - -0.6692474211233692, - -0.750046341864173, - -0.6855907036601477, - -0.7525272987981243, - -0.767177436535108, - -0.764816308394601, - -0.6858722969161504, - -0.7844123547012425, - -0.7903999832022965, - -0.6612480467655476, - -0.6852292593480898, - -0.6890313920942008, - -0.7162536112534885, - -0.775461465551039, - -0.7294288635757344, - -0.6945530588316138, - -0.676367840587077, - -0.6891013617392397, - -0.7411483249304639, - -0.7396753212555683, - -0.7719674505778793, - -0.7283196587168052, - -0.778409966132129, - -0.785630092637226, - -0.7767567376429012, - -0.6626383008603975, - -0.7674646385506597, - -0.7277429583758764, - -0.7722337023953284, - -0.6938273570132761, - -0.7750650783567911, - -0.7382276413719464, - -0.680419725218517, - -0.7246494952253969, - -0.7828180247998998, - -0.726512141415322, - -0.753372263411675, - -0.7023601555439044, - -0.7317265874360831, - -0.679559978834537, - -0.7551149976640553, - -0.6828450432230263, - -0.7222361458999766, - -0.7542832377051735, - -0.7035920009415126, - -0.7781207378094627, - -0.7298771256607937, - -0.707486091635463, - -0.7161247988070026, - -0.7855886422682065, - -0.7573722312596334, - -0.7306982141577723, - -0.6686655148413924, - -0.7499979387468483, - -0.7582107902165943, - -0.6831997010744882, - -0.7127476888382888, - -0.7102745917180444, - -0.6649088512659305, - -0.7816449582003131, - -0.7299194020431747, - -0.7689229261755004, - -0.6690722368354562, - -0.6836869580383604, - -0.664287900600478, - -0.7015444256353833, - -0.6687266097318143, - -0.732817084901176, - -0.6666379473303735, - -0.6948603005381829, - -0.6692785156326262, - -0.6936095116761151, - -0.7249319493024885, - -0.7548623508313451, - -0.7867302149093027, - -0.6609732815109406, - -0.7827842416701224, - -0.6729620390326048, - -0.7624159785594428, - -0.7630226402213771, - -0.7871114680470256, - -0.7064733348312152, - -0.7320281399051937, - -0.7742597271629638, - -0.7294748261616112, - -0.742632868264119, - -0.670406928560177, - -0.7003141765431155, - -0.7255544035156678, - -0.7489557078624991, - -0.7212390625867054, - -0.7143525003995211, - -0.7876572385501235, - -0.680049296474288, - -0.7469208043036081, - -0.7256770930454043, - -0.7800171847714863, - -0.7323990890694072, - -0.7526506799456051, - -0.6753988899632908, - -0.7450924730996256, - -0.7225521500186944, - -0.6950878341704684, - -0.6795708812857147, - -0.6908634535800413, - -0.6923321046340652, - -0.7347333135722512, - -0.7474596056742102, - -0.6885683848689147, - -0.7356779574063216, - -0.7910518567732041, - -0.692166735655898, - -0.7329988219236011, - -0.7381215877395697, - -0.7642318496758315, - -0.7463263098148168, - -0.7459435850996691, - -0.7203824227644879, - -0.6976413729351073, - -0.7880415117762898, - -0.6942007134136632, - -0.7162533668962313, - -0.7004542034814547, - -0.6928994756408541, - -0.7814584927385158, - -0.7264380053169848, - -0.7694789786089202, - -0.7420100278071804, - -0.6817138414572625, - -0.6688890368410095, - -0.6760961200923593, - -0.7695276021735852, - -0.7522771212408812, - -0.7465035847821064, - -0.7038584530846861, - -0.7191244651659228, - -0.6981936482614083, - -0.7149912608038695, - -0.7223628885095584, - -0.6828131130968275, - -0.7057785842542594, - -0.7896880507500487, - -0.720962723688091, - -0.6813708495025074, - -0.6978920534177852, - -0.734490701198463, - -0.7211506281126612, - -0.7690135369389149, - -0.7755731337927465, - -0.7201601359278142, - -0.7144615023453307, - -0.7810681003894031, - -0.6701957049777759, - -0.7267204335822826, - -0.7073242716583552, - -0.7318193770471388, - -0.7169923433713121, - -0.7494229734361703, - -0.7916874337469588, - -0.6630925187318772, - -0.7328883774577559, - -0.7543256116234008, - -0.6949295304644634, - -0.7361314283734178, - -0.7871018500827123, - -0.7163406980350709, - -0.667097915777576, - -0.7744204840846554, - -0.7231401585560325, - -0.702220095179315, - -0.7205700099854013, - -0.6644777620278456, - -0.7822377274934911, - -0.7788499979807948, - -0.6822966386206745, - -0.7342951375005734, - -0.759751470645311, - -0.7545234996468818, - -0.7741964014615784, - -0.7324758310974466, - -0.7778204674597735, - -0.6816374788602063, - -0.7871484302799934, - -0.772601018912985, - -0.6691481024452207, - -0.7488523778500041, - -0.7023497287862753, - -0.7590819193700639, - -0.7174853957343187, - -0.7264699434592471, - -0.7902202415043401, - -0.7096960264565124, - -0.661577666754948, - -0.7104651596583266, - -0.7123529074695261, - -0.7543139357257024, - -0.7613420420817516, - -0.7460876409122583, - -0.7034571904699846, - -0.7059423057741938, - -0.7037137912565451, - -0.7912923665929832, - -0.7506707961518322, - -0.7620596952146439, - -0.7742696043774379, - -0.7127870420256351, - -0.7547278745356172, - -0.7233222704843956, - -0.7927151232577723, - -0.6693025596551619, - -0.7583726612544781, - -0.7602618514551087, - -0.7151526041817621, - -0.6777522635153673, - -0.7483560323850444, - -0.760369981636729, - -0.7067401530046367, - -0.6652205040088, - -0.715958182492279, - -0.7678539879031042, - -0.7308538724572168, - -0.6910077995564279, - -0.7208859986773778, - -0.7360012026430016, - -0.6639821603702639, - -0.6719371838928703, - -0.7146571479892747, - -0.7311527543586047, - -0.7015378513200017, - -0.7765645599768957, - -0.7930890417177898, - -0.6692134214548031, - -0.696232015878327, - -0.7303205435785163, - -0.6620486361039104, - -0.662397322294557, - -0.7303911452212003, - -0.6871626525605917, - -0.7080123959569378, - -0.7688599843764196, - -0.7452278763217794, - -0.6917991896317756, - -0.6749302702494737, - -0.7130505511018963, - -0.7730680157485068, - -0.7905765402576719, - -0.671050822968695, - -0.7818890241583932, - -0.7022887109805807, - -0.7776091359722069, - -0.7771887769990486, - -0.7791992754237934, - -0.6857010904301442, - -0.7788652915854476, - -0.7230929165985507, - -0.7718742777842934, - -0.7575278336779339, - -0.7464339474488734, - -0.7532853573358221, - -0.7728080141052223, - -0.6948564696082803, - -0.7018548322551695, - -0.6711890707109882, - -0.6891518363538857, - -0.7821289902647871, - -0.7436325041546744, - -0.7092183134561679, - -0.7386252119566098, - -0.7505682341351196, - -0.717163486584754, - -0.7206078764173895, - -0.6649067988435393, - -0.6641384078814121, - -0.7910480694977355, - -0.6750597915272001, - -0.7563785822535143, - -0.7247202396080431, - -0.7730272680830468, - -0.7796018048846898, - -0.7479857222133435, - -0.6870822736585784, - -0.702948717574758, - -0.7420155952728003, - -0.7486991364411216, - -0.7807635576559213, - -0.7814530711253239, - -0.7899685617263431, - -0.7381406546315522, - -0.7636681024797602, - -0.7411163764167703, - -0.7817950699173472, - -0.6779355422730092, - -0.7856377859345619, - -0.674905474947248, - -0.6970737234115918, - -0.779000027346798, - -0.7497980049952886, - -0.7554996823410927, - -0.6622106245899566, - -0.7346957383289923, - -0.7171864728148496, - -0.7918375482160105, - -0.7512980040122325, - -0.6986691358197753, - -0.6896326814990436, - -0.6928258611492187, - -0.6753624418606101, - -0.6782604421779665, - -0.6971505248874861, - -0.6906259220792677, - -0.7056360124267653, - -0.772133850616159, - -0.6759423351075996, - -0.7407848204694758, - -0.6883967275042684, - -0.7177918703715743, - -0.6987015666085803, - -0.6692997510187385, - -0.7508146659855066, - -0.7203782441610116, - -0.6850333136548667, - -0.7619527506046803, - -0.7114934827328077, - -0.7088386269195772, - -0.755630809307482, - -0.7060676981555477, - -0.7119805609322541, - -0.7431719674441976, - -0.7704305162690759, - -0.7346603821455496, - -0.7870351288145984, - -0.7696687206771701, - -0.6632532767603426, - -0.6820724300343508, - -0.7023826517638815, - -0.7771570310691284, - -0.7902984902812573, - -0.7636965036121021, - -0.6739381250970167, - -0.7182075199418966, - -0.7340458154980338, - -0.7550194496079781, - -0.786965747343985, - -0.6976639840402192, - -0.7538197196722471, - -0.6983481408984499, - -0.6937686482971375, - -0.6603220096014273, - -0.7834744093619698, - -0.7470661442409952, - -0.7273992695714497, - -0.6742589533581997, - -0.7540128673393652, - -0.7435656370708092, - -0.7404663215236893, - -0.7074274392859147, - -0.7553888367121396, - -0.6730794862346292, - -0.7714777721662033, - -0.6948050422601943, - -0.7818665097138392, - -0.7055297590750482, - -0.6821813917312866, - -0.7734884741919531, - -0.7025317074596461, - -0.7912927418560592, - -0.7379460681657558, - -0.6706372846348289, - -0.6700212239896051, - -0.7823999571330935, - -0.785652571000665, - -0.7346606213756341, - -0.7230062976542728, - -0.7537562122837119, - -0.6988267927272445, - -0.7704289737409166, - -0.6973398792040524, - -0.6664141061387225, - -0.6978493660442376, - -0.7544392390621321, - -0.7231558019099471, - -0.7260357097762377, - -0.7917373712146498, - -0.7132860410262605, - -0.7712060988337933, - -0.731770224034745, - -0.755094376703736, - -0.7310497444421585, - -0.7107092098038278, - -0.7445111365487698, - -0.7754383754443123, - -0.760491792991625, - -0.7202198486372404, - -0.7150534445183394, - -0.7549580084388917, - -0.6672956681506552, - -0.6755238756787076, - -0.752486809639476, - -0.7839279068792895, - -0.7706735713148285, - -0.7918698293762791, - -0.7846493140652192, - -0.7609061652402581, - -0.6725284846864298, - -0.7611684075035129, - -0.7641624947855914, - -0.7858414635150895, - -0.7797194195838989, - -0.7868745340875682, - -0.6747623362335544, - -0.6783127266859142, - -0.7274528080144762, - -0.7853751069420496, - -0.7412248782997507, - -0.7503657975670526, - -0.6944285948900086, - -0.717815860110518, - -0.755941903060007, - -0.6678949299300182, - -0.6693105980605887, - -0.6811630428421567, - -0.721538199055092, - -0.6680966480799839, - -0.7440984672339446, - -0.6674787678367989, - -0.7036971802262826, - -0.7612339730019776, - -0.7908711194671902, - -0.7188091181755581, - -0.6960962889210682, - -0.6751548572090589, - -0.7718019401279401, - -0.713667795759753, - -0.726635131193389, - -0.7776122933778211, - -0.6888434179425396, - -0.744986830891863, - -0.7616798724641265, - -0.7887833131122904, - -0.7728055257673834, - -0.7902815075482784, - -0.7580271183830016, - -0.7304632537285966, - -0.712790449399856, - -0.7561548596490814, - -0.7197612722109851, - -0.733831421814376, - -0.7292890523448541, - -0.6951308145223105, - -0.748559371386328, - -0.6944460848959855, - -0.7590671381134741, - -0.6699749947022103, - -0.7788927127955823, - -0.6856484183620389, - -0.7136472885682795, - -0.7509278046720426, - -0.7616869769746836, - -0.7560297558639837, - -0.7828739588382764, - -0.6785226700448475, - -0.7053281775817425, - -0.7687889290265115, - -0.7268506114407817, - -0.6801314279487539, - -0.7678648691040615, - -0.7860977597678808, - -0.6816295356132908, - -0.7242811994357972, - -0.681350050560529, - -0.7709560186083231, - -0.6633967724435706, - -0.7765017474749051, - -0.7253894317301989, - -0.7254234350549144, - -0.6717628520176074, - -0.7402634784459807, - -0.6860474076649732, - -0.6629786486571058, - -0.6683004880776642, - -0.6704133820456233, - -0.6864758279757663, - -0.7391917428289893, - -0.6604550401260219, - -0.669735638120622, - -0.6914463175861779, - -0.7551326082920379, - -0.7645876648806211, - -0.7626624205989175, - -0.6635096922127244, - -0.6687765545631423, - -0.7413052775587777, - -0.7892620290325564, - -0.7699572142205192, - -0.746204797447436, - -0.7586062764473946, - -0.7871679271990872, - -0.7401913558331906, - -0.6880199156807539, - -0.7225370658122752, - -0.6632643494079297, - -0.7858413339602058, - -0.672989303542084, - -0.6611777248555936, - -0.6623266249931735, - -0.7704626322433398, - -0.7463994801709499, - -0.7291519954167528, - -0.725527144144819, - -0.7495485005603075, - -0.779736368045884, - -0.6983291655607163, - -0.7024522985178538, - -0.7536014627400749, - -0.6662527469183457, - -0.7338601386340575, - -0.6945606281093344, - -0.7268944944046938, - -0.6940049003810123, - -0.7644888699809751, - -0.7131588299675705, - -0.6844288936414613, - -0.6868176448287601, - -0.7585294313598834, - -0.7350230044833801, - -0.7763013015479117, - -0.6781503571645634, - -0.6788108679731846, - -0.7772292060541236, - -0.6726964763975136, - -0.7005244540370841, - -0.7863822526906092, - -0.7152302717782383, - -0.6894375682842567, - -0.7046028901017979, - -0.7564765716691249, - -0.7288997525124036, - -0.7637215282406622, - -0.7158218833417955, - -0.7638709522384095, - -0.6836951976857815, - -0.7467189913922031, - -0.7778638609632018, - -0.7169766424155202, - -0.7136676929632827, - -0.6903045438186217, - -0.6842132712067062, - -0.7613876696710963, - -0.6937186945552845, - -0.7295108027782439, - -0.7719706832067743, - -0.7230158533476622, - -0.7598199735621449, - -0.6949613701436601, - -0.7151914283439664, - -0.7748992742146773, - -0.7624341313052617, - -0.7839442763349191, - -0.72254325796125, - -0.7630893164704505, - -0.7890633058303822, - -0.77211765308414, - -0.7192778847070509, - -0.6601446841372607, - -0.6909881177764496, - -0.7773398426104936, - -0.7465174051345252, - -0.7784780927195951, - -0.7069473681501663, - -0.7910189106650795, - -0.6650502646501248, - -0.7005351322184635, - -0.6707159289020185, - -0.6624653622692075, - -0.7491461073846746, - -0.7548036301395137, - -0.785783537980899, - -0.6880759024991837, - -0.7181825012040994, - -0.7199255542501797, - -0.7497035252856077, - -0.6940242570701558, - -0.773375624987192, - -0.7360363464805371, - -0.7636692435561362, - -0.7451692682969511, - -0.7008309268469483, - -0.7255191622034874, - -0.7209046286330769, - -0.6625364191829546, - -0.7323919915483167, - -0.7828250043437753, - -0.7410531287588848, - -0.6978496743133813, - -0.6800644019857853, - -0.6704767225352686, - -0.7900951474687674, - -0.7529629837189267, - -0.742923519123742, - -0.6909433510933313, - -0.711823561692166, - -0.7559478796538424, - -0.709412090308412, - -0.7451277539751535, - -0.6878748457884354, - -0.7064444948037997, - -0.7009894477076037, - -0.6760768757102205, - -0.7130716737309017, - -0.7895426991094812, - -0.6714767151538535, - -0.7385213476075023, - -0.6867726897417656, - -0.6944868179194859, - -0.7247068639023044, - -0.6693523844630636, - -0.7909334603158485, - -0.6656553184691629, - -0.6645376197948718, - -0.7597848498784839, - -0.6917497526157149, - -0.7637220258278872, - -0.7710814571386858, - -0.6773401356708095, - -0.7435439952688506, - -0.7753284754375361, - -0.6788076105620736, - -0.6975693452098438, - -0.7115025183547994, - -0.7108858886567299, - -0.7452672887148093, - -0.7683730193050065, - -0.6715286171791767, - -0.7746676017099453, - -0.6678232107294997, - -0.786280366749422, - -0.7262038353888026, - -0.7734319357456446, - -0.7062587333574842, - -0.7786229952031362, - -0.709742918134622, - -0.6854084099677382, - -0.7124694555454048, - -0.738867230943208, - -0.7361921234916371, - -0.7859682945445187, - -0.7055982420950695, - -0.7804068783680767, - -0.7050388383797551, - -0.7436637423429131, - -0.7598125915678969, - -0.7075075668468809, - -0.6867286571743074, - -0.6952856472010718, - -0.6907407708953504, - -0.7846802748623034, - -0.6920189590123942, - -0.7924821489173973, - -0.6970148959442258, - -0.7930353966544945, - -0.762116484602487, - -0.7664371535412953, - -0.7581887666495079, - -0.7904247384567066, - -0.7695398849006778, - -0.7880493475391662, - -0.7647810555741671, - -0.7270245781044198, - -0.7820540914325239, - -0.7253133624688781, - -0.7511345573394835, - -0.7229393238678783, - -0.7423811317674963, - -0.7754436052407564, - -0.771080303841912, - -0.6675599684426794, - -0.7230335822212806, - -0.7334874943089574, - -0.7084987741559745, - -0.7533053154282845, - -0.7494802186348591, - -0.7154046078854293, - -0.7292946938874697, - -0.7523475392019519, - -0.7000789341534509, - -0.7185911690261765, - -0.7404547021078034, - -0.6942419539653794, - -0.7534164362416838, - -0.6843716082848986, - -0.7469572351597716, - -0.6639608078554782, - -0.6959954160089091, - -0.7626788383995536, - -0.7251218743593211, - -0.7345856347393458, - -0.7187712668189736, - -0.7291943357220243, - -0.7483613126892849, - -0.731353033907309, - -0.7868077029123867, - -0.6785971478349068, - -0.7784488553962987, - -0.726944139359684, - -0.703390959089319, - -0.7640613930976243, - -0.7609139820420198, - -0.7429015460902133, - -0.6971727520139087, - -0.7919485015930616, - -0.7043617714958562, - -0.7413422286648365, - -0.7427197073781949, - -0.7891877009435699, - -0.7744287634327021, - -0.7054704155199789, - -0.7687781887777771, - -0.7294390995458824, - -0.6837966554540426, - -0.6618852755463258, - -0.695184445839306, - -0.7704180446230362, - -0.7484872278244303, - -0.7637707280252302, - -0.7075711460776406, - -0.7054017414703463, - -0.6652301326594229, - -0.6933763510852915, - -0.7461808429860451, - -0.6900865324694582, - -0.7545392105843066, - -0.7195074604723657, - -0.7150953980262152, - -0.6800921836197303, - -0.7802194794734005, - -0.7863043297607282, - -0.733290351050651, - -0.6673643190447415, - -0.6853734270584366, - -0.7752346434139565, - -0.7639509080787544, - -0.7003296994831948, - -0.7100497156715055, - -0.7187035317866136, - -0.6989801819529475, - -0.7389835345855557, - -0.7175871276838394, - -0.7167980532342788, - -0.7743977585667015, - -0.7288800657002157, - -0.7577815401511155, - -0.7164708112012714, - -0.7658263139353663, - -0.7737871156369406, - -0.7028859854147487, - -0.6616277256678637, - -0.7521779154108171, - -0.7180145132915585, - -0.7801480015348309, - -0.7878673976627354, - -0.6679889272908827, - -0.6625123759643755, - -0.7286966207105525, - -0.7517309033029754, - -0.6777991213459756, - -0.7535431394066081, - -0.6760434335766088, - -0.6851808149927527, - -0.6732482359458625, - -0.7465871323203471, - -0.7069248423913624, - -0.6934463626948157, - -0.7435663340381217, - -0.7511253104312323, - -0.7824442709179216, - -0.6611899479378263, - -0.7262016993864038, - -0.705471673945625, - -0.6630821611173446, - -0.7121535969885896, - -0.7724180775883663, - -0.6713935262383781, - -0.7585898826249708, - -0.7335217107798697, - -0.717388392465319, - -0.6848761490661406, - -0.7626147471655272, - -0.6674826413706805, - -0.7684148090755083, - -0.743661082063406, - -0.6888914891871291, - -0.673854223464377, - -0.7783524987660436, - -0.7144484988135447, - -0.7748266969922148, - -0.7485103972968414, - -0.7157104412652588, - -0.672200711791632, - -0.6754380159505122, - -0.7030542871096414, - -0.7428149697714906, - -0.6846927660947251, - -0.7103322414425761, - -0.763224338353633, - -0.7556365941227752, - -0.6688310291801133, - -0.7574274962470051, - -0.7476093058029121, - -0.7470510023290083, - -0.7377431434139028, - -0.7288633857631914, - -0.7376721078240797, - -0.7913038629186153, - -0.6910455828413339, - -0.7699331808915422, - -0.7124024610292584, - -0.6896487339968659, - -0.6920744368496707, - -0.7266969092471759, - -0.6873596369259426, - -0.7679529341158918, - -0.6857759511735099, - -0.6730903560668454, - -0.6837684132631293, - -0.7911051948048802, - -0.6924835531488621, - -0.7127694114011534, - -0.7522704290755332, - -0.7213697633594578, - -0.7875596273911064, - -0.6952352663322523, - -0.707691642556335, - -0.6870096453468654, - -0.6687646492551442, - -0.6650304812208341, - -0.7450460827433362, - -0.7048291659687478, - -0.7684042833208984, - -0.7694336148571517, - -0.6720656591383259, - -0.6781538614170746, - -0.72917815814226, - -0.6721306738197879, - -0.6649408379018213, - -0.6921053830267813, - -0.7236279855284365, - -0.7455180215297086, - -0.7860487205817391, - -0.7905566197499383, - -0.7471064696300665, - -0.6868951450539528, - -0.6860037283292482, - -0.731973770325746, - -0.7637536732274133, - -0.6918101298412377, - -0.7209989670304072, - -0.6822972693659775, - -0.7542884612103856, - -0.7432630686776326, - -0.7829698941502272, - -0.6761196885075718, - -0.7589941710229658, - -0.753747082539743, - -0.7907022262523654, - -0.6895132064713134, - -0.7682378027544065, - -0.6666362329516161, - -0.7915350951354292, - -0.7206709452493107, - -0.6659476723715682, - -0.6806902862121317, - -0.7070643378282963, - -0.6819117415208183, - -0.6701608916020774, - -0.777593246649664, - -0.7358372602154438, - -0.7841338351230638, - -0.6897339499643366, - -0.7082590664680384, - -0.7558261023947245, - -0.7279878243445491, - -0.6618436419988312, - -0.7063579440291889, - -0.6643844264401749, - -0.6669962815520131, - -0.7071092333082564, - -0.725206709582251, - -0.6923852127238487, - -0.7162021458874348, - -0.740043155702995, - -0.719279124111275, - -0.6993494765407768, - -0.7597599644518738, - -0.67496894260513, - -0.7237602939392201, - -0.7790728639947935, - -0.7226492373705069, - -0.7876248569292139, - -0.6968624343497426, - -0.7931897187674792, - -0.7119857535310316, - -0.7308207401715304, - -0.675857689404193, - -0.6735255032871692, - -0.7876839348816447, - -0.6990946387504042, - -0.662692595786778, - -0.7620424819112448, - -0.6606521928087692, - -0.6628480347015621, - -0.7064871783559199, - -0.6754126551394972, - -0.7358105217428231, - -0.6867021440133754, - -0.688074434017044, - -0.7394702524712188, - -0.7637108639058809, - -0.6819863222227002, - -0.6668604557597405, - -0.7632345670087508, - -0.7216344029364028, - -0.6873446749563398, - -0.6958819505425081, - -0.7674578935430433, - -0.695793871724397, - -0.726764647123481, - -0.6775408296335886, - -0.6671198217208214, - -0.6733494784522838, - -0.7652716696290417, - -0.663304111338288, - -0.6878133316468812, - -0.6810915746627204, - -0.7930189866028612, - -0.72444256202778, - -0.788488148338851, - -0.7237792892380902, - -0.7048494047122364, - -0.7135782037746825, - -0.7377067285028063, - -0.7581833939660177, - -0.7716075024009429, - -0.6684334678899501, - -0.7462937620161627, - -0.6656531872591908, - -0.6609539751431199, - -0.7362199309784278, - -0.6958479488738901, - -0.7369698543950131, - -0.7791866092176915, - -0.7314130670401096, - -0.7018898736291705, - -0.7495612899935772, - -0.6937121885280119, - -0.7029886682837125, - -0.6688240392990175, - -0.7576445399537988, - -0.710671259737002, - -0.6799962707386544, - -0.6769657416995496, - -0.7166791810934692, - -0.7814625252729444, - -0.7675017591180877, - -0.7343835970549903, - -0.7188054046641993, - -0.6825482381785387, - -0.7229244015060438, - -0.7379507410900277, - -0.6743672538241188, - -0.7428814807042009, - -0.7635442715284808, - -0.7547684763228221, - -0.7311507799251454, - -0.7556543482443584, - -0.7703298819460153, - -0.7071071896072145, - -0.7567090361156384, - -0.6660281115710447, - -0.6933172449054777, - -0.7533576638501565, - -0.741908735378679, - -0.7591449630812699, - -0.7606059965442561, - -0.6939043594543728, - -0.7533191708518738, - -0.6747067905845349, - -0.7054718599232497, - -0.7883868056667045, - -0.7052046793426918, - -0.6693413902508569, - -0.7762994347459378, - -0.7232016672432131, - -0.6661876904011359, - -0.7383575367247859, - -0.6950114459089307, - -0.7606321352691345, - -0.7036501196132618, - -0.677468839858865, - -0.718069446707716, - -0.6898977336455796, - -0.6734420753530523, - -0.7345925541420902, - -0.7602578653464531, - -0.7539809283986302, - -0.7323058855001303, - -0.7798761809874117, - -0.7724733832366838, - -0.716002865776737, - -0.6820148189843674, - -0.7605655631440075, - -0.7368348972970623, - -0.7800837709740631, - -0.7594667752070218, - -0.7244951034487207, - -0.6941053640330539, - -0.6991374298172804, - -0.7753353535568313, - -0.7091357180944691, - -0.7815767082996439, - -0.6942868227199206, - -0.6730668987034568, - -0.7200882760396172, - -0.7116556098058708, - -0.7029704631552238, - -0.7204643188284683, - -0.7442228097212165, - -0.6976861845261283, - -0.787359565756124, - -0.7591772665399472, - -0.7418265935939964, - -0.733427553707475, - -0.7753464809751822, - -0.7416787477918138, - -0.7781065958401353, - -0.7903746314588366, - -0.73927634214213, - -0.6621879087751682, - -0.7756854832325084, - -0.7611463735063762, - -0.7167834360526245, - -0.7498116177659507, - -0.7751438093817576, - -0.7462392213276227, - -0.7688351101543801, - -0.7312963602521447, - -0.7619825362728141, - -0.7566681186313153, - -0.6628731331195651, - -0.7249842619980585, - -0.7505577667701125, - -0.695065824489254, - -0.6758785703447011, - -0.7211672397198852, - -0.7311633499120457, - -0.7812366406206993, - -0.6689364351107369, - -0.765332105033398, - -0.7789453930416627, - -0.791407784118351, - -0.758706780955165, - -0.7396451741649833, - -0.7073098338263231, - -0.715864196496372, - -0.6756323066290932, - -0.7498082430938154, - -0.6970725349449698, - -0.755651311717798, - -0.6614046652054397, - -0.6891889029408063, - -0.7080973126715949, - -0.7721442867304991, - -0.699879535851349, - -0.7090367021067178, - -0.7525694854150928, - -0.665531092355097, - -0.7361744273467983, - -0.7886146607222839, - -0.7163592505413342, - -0.6757318884973504, - -0.6642888875288695, - -0.6844782283988963, - -0.7740202446707087, - -0.717771494463103, - -0.748546157533701, - -0.6905827086847619, - -0.6785835094183648, - -0.667196919430401, - -0.718057321437347, - -0.7729184081323612, - -0.7635847377628672, - -0.6889725939293676, - -0.7165010290094409, - -0.6873018325306578, - -0.6926665259571408, - -0.6990694154784209, - -0.790887887128747, - -0.7580035756255878, - -0.7895079177333936, - -0.7860183103804038, - -0.6711411010409052, - -0.6872079191794083, - -0.7017497072319275, - -0.7294361428417222, - -0.7281154444286498, - -0.6749379276237463, - -0.7813221842032481, - -0.7780122209563731, - -0.7124494199481795, - -0.7258491691628722, - -0.6762098316207998, - -0.7656471721596336, - -0.6726753189994771, - -0.748445248431297, - -0.7516925550543561, - -0.7890510715633097, - -0.711279843374019, - -0.7217364348916847, - -0.7358964320540587, - -0.7236449467758588, - -0.7336235264339732, - -0.6799291946441484, - -0.6739077961393475, - -0.77564079295587, - -0.7609616833331138, - -0.7817291483850689, - -0.6959719546857701, - -0.7204358398498263, - -0.7471280384405431, - -0.74919050854115, - -0.75248869265689, - -0.7260604043888979, - -0.7031328568711934, - -0.7724747350365253, - -0.7931812556611203, - -0.6851240406415358, - -0.6744221708885194, - -0.7658066297999608, - -0.7170690106026203, - -0.7099904642107321, - -0.6989879188999713, - -0.6688887661749185, - -0.774691991941232, - -0.7101394180734952, - -0.7496774048985264, - -0.691501079723581, - -0.7170873088934621, - -0.7185293399406893, - -0.7579358128600773, - -0.7882267043826683, - -0.6878104149157473, - -0.6768813239235315, - -0.7781083601580234, - -0.6919092871184092, - -0.728446818906695, - -0.6973154344906932, - -0.716906613868148, - -0.7497172626166083, - -0.7034032205151893, - -0.6765645305323884, - -0.6949024464979333, - -0.6765859783331714, - -0.7909524827640942, - -0.7128254138950942, - -0.7922664773484692, - -0.6846116528682697, - -0.7049144511485318, - -0.7477617464465754, - -0.7371108839511578, - -0.6772207357860527, - -0.7182155694659729, - -0.7863864638358857, - -0.7547031983207688, - -0.6804729602222492, - -0.688186582790938, - -0.6919566097232204, - -0.746040910088004, - -0.68266527242062, - -0.7708041821478111, - -0.7730888443978756, - -0.7131892446608868, - -0.7465663293564164, - -0.7334239925548753, - -0.735351297084726, - -0.7336072223791115, - -0.7441760889127248, - -0.6927771810059792, - -0.7483592304039232, - -0.7270073642213171, - -0.733395720613198, - -0.6987234772116713, - -0.6959043350202588, - -0.7560787799269347, - -0.7393074777517274, - -0.7197030393389049, - -0.7048229681178677, - -0.6979282633504839, - -0.7507957381269407, - -0.6634310216290185, - -0.7279864429616825, - -0.6729122423440207, - -0.7035193264994702, - -0.7546472889047543, - -0.7831463749812322, - -0.7575730770264668, - -0.6789549572770288, - -0.6930204583675318, - -0.7861680798484366, - -0.7796959275958607, - -0.6930268464663852, - -0.778933770931836, - -0.7687473735338285, - -0.6841832725532414, - -0.6989824278087209, - -0.7433411034828237, - -0.675764564226538, - -0.7105518394708837, - -0.7868805219964067, - -0.7595454146660784, - -0.7886563989056484, - -0.7743184226329126, - -0.7081550340225226, - -0.7018660995589481, - -0.7044019153481341, - -0.7644615104346044, - -0.7351996345288233, - -0.768529148816276, - -0.7562563459921665, - -0.6718310662052696, - -0.7536777357230565, - -0.6781005543826713, - -0.7577600881395024, - -0.7266301713799898, - -0.7687349983291951, - -0.7265595821823859, - -0.7218637688992181, - -0.6787050773396897, - -0.6737211770010485, - -0.7314612731308378, - -0.7784167580929866, - -0.7671295787766635, - -0.6666310526941499, - -0.6664326151612712, - -0.7317147430017626, - -0.710685329242566, - -0.6693946357933784, - -0.7750153127860352, - -0.7185073993026052, - -0.778882703221871, - -0.7928515830156879, - -0.6784076184143271, - -0.6775920935225748, - -0.7634482648022406, - -0.7086154760044789, - -0.6913776006456438, - -0.7789423451626581, - -0.7013791485335181, - -0.7221098815947491, - -0.7343592283570665, - -0.730626975006115, - -0.6833591234235066, - -0.6693637737453563, - -0.6898069594584096, - -0.6955981351924282, - -0.7288593246467129, - -0.6870596527911523, - -0.6952955974902765, - -0.7641587441574229, - -0.7555550818318985, - -0.7890061733936796, - -0.7146400828513093, - -0.77551666897533, - -0.6766716176279078, - -0.6801829342352913, - -0.6974104091653897, - -0.7717570033513562, - -0.7794242637833303, - -0.7928213797803041, - -0.6683367678870935, - -0.7459271771431962, - -0.693450370694483, - -0.7891619811541803, - -0.6763196516886315, - -0.6756311608570803, - -0.7468210825286181, - -0.6791145407338013, - -0.6981885615826404, - -0.7846834718251552, - -0.6948847182837116, - -0.6640215062630319, - -0.6775781177402268, - -0.782481795746626, - -0.7391520067747523, - -0.7103030120325926, - -0.6964224177306173, - -0.6881999319008776, - -0.7197416885566338, - -0.7267307923912687, - -0.7615172200027943, - -0.7615117771232797, - -0.6646782478280503, - -0.7155674252298084, - -0.6758944237125408, - -0.6704522475086863, - -0.6896267024379947, - -0.7606845959408144, - -0.74143280597504, - -0.7473859072000016, - -0.7007881551201587, - -0.7636090215408848, - -0.6801183542473633, - -0.6719527403189154, - -0.7073578676801471, - -0.7429066827753162, - -0.7386146060827888, - -0.7931371922196938, - -0.7122514446066788, - -0.7801166739122692, - -0.7287760183153684, - -0.7525674419482771, - -0.7294486372588402, - -0.7934033451566359, - -0.6968947123875086, - -0.7781245370823958, - -0.7371759731170419, - -0.7716980004344216, - -0.6617529068780305, - -0.6993628795486031, - -0.7209259717833413, - -0.6995312174070636, - -0.7554454530864066, - -0.7770879498540828, - -0.7169106622568469, - -0.661820569922148, - -0.7633817091099525, - -0.7771743959353676, - -0.6610780063085435, - -0.6753582868982752, - -0.6762891917963371, - -0.6815282002495577, - -0.6713746581403977, - -0.6959441193453643, - -0.7210514431236255, - -0.6603124643627473, - -0.6778041530117662, - -0.6913399267853132, - -0.7375738021818667, - -0.6824038273013369, - -0.6858631946448925, - -0.7584350891895039, - -0.6800728375080933, - -0.7356356410264668, - -0.7867687562095133, - -0.7185782944578624, - -0.7065212551996503, - -0.7144215175935222, - -0.7427611822761238, - -0.7510751440236052, - -0.6745521187536692, - -0.7843223082759855, - -0.6842246725831492, - -0.6899306270980132, - -0.7113733040539859, - -0.6769670972247075, - -0.7120018651290967, - -0.7018949910346932, - -0.7352318244732772, - -0.7885244514015306, - -0.6828736460727675, - -0.7560945681457497, - -0.6753809828697935, - -0.676411142941336, - -0.7289189605162723, - -0.7908568405301125, - -0.7514153859711836, - -0.6792540747313371, - -0.7302198397009709, - -0.7328722254454337, - -0.7673040684920613, - -0.7880603067976241, - -0.7488294188140664, - -0.7023402794497438, - -0.6820413050280324, - -0.7776684374801729, - -0.7146966657718968, - -0.7177229276596654, - -0.6832511539367492, - -0.6774529846495103, - -0.691646552963121, - -0.7749192215258347, - -0.720921801660826, - -0.6607671260389953, - -0.7495917097999376, - -0.7125755426354798, - -0.6836241983393448, - -0.7404974089006153, - -0.7746470374181003, - -0.7750379485457795, - -0.6695396646344774, - -0.7386927563423793, - -0.7098883176266827, - -0.7368947326962252, - -0.7683326752924893, - -0.6847808849284335, - -0.754580645089243, - -0.7017761397632701, - -0.7715585666368627, - -0.7012951303763169, - -0.7764836060419428, - -0.7132737216098912, - -0.6893601041507389, - -0.7458406145026968, - -0.6942980487282876, - -0.7230070691864268, - -0.7502268749077965, - -0.7419232619714704, - -0.767126625478878, - -0.7053061558506877, - -0.7809902866508712, - -0.7055432454971439, - -0.6984549877143266, - -0.7790135408309519, - -0.6780249449393908, - -0.7384390316376934, - -0.6949559139889685, - -0.7836468959866837, - -0.7008486098790752, - -0.728401003975054, - -0.722988406051982, - -0.7761908437899945, - -0.6835234678202415, - -0.6741861701416721, - -0.7608847773414453, - -0.6612948454460185, - -0.7247857605127922, - -0.6936055215113586, - -0.7374228855611196, - -0.7734250014612665, - -0.6664662847123369, - -0.6908434497948552, - -0.7121652187300602, - -0.6755131627278834, - -0.7313516246009414, - -0.7717323449721964, - -0.7347061182210496, - -0.7515459294569763, - -0.7849684007693336, - -0.7867165431990044, - -0.7843817932129608, - -0.6904315129206301, - -0.7418950213641257, - -0.6692060232136029, - -0.7865156493004938, - -0.7701703889853974, - -0.722622453286989, - -0.7542026176147206, - -0.7515732632573109, - -0.7182752492542437, - -0.7472024490936408, - -0.713882467354427, - -0.7544913643208925, - -0.7807548981393861, - -0.7026236906101335, - -0.7669179466123415, - -0.7177004046737073, - -0.6679310566305136, - -0.7072706840922229, - -0.7621175296713278, - -0.7896290096324168, - -0.7296673845356334, - -0.7816541036552126, - -0.6921577163293655, - -0.7151563616200197, - -0.7928046481411422, - -0.6804613301086488, - -0.7763872550240056, - -0.6624983179389125, - -0.714091720025113, - -0.7321104825366814, - -0.7033914010733908, - -0.7121634955023587, - -0.6639209196656691, - -0.7591881115188981, - -0.6673095737023407, - -0.7610887530855286, - -0.6639781475940939, - -0.7821851736112869, - -0.7732518368763738, - -0.6904498759769209, - -0.6711264146838757, - -0.7785927374952162, - -0.7618368825335108, - -0.7103765598103176, - -0.7220878105638308, - -0.6854404520204773, - -0.6904189076681992, - -0.7766610744684207, - -0.7399529439411933, - -0.7356012791421104, - -0.700810473053583, - -0.7050525158012642, - -0.7032608957802895, - -0.7437790513277412, - -0.6914568961436078, - -0.7217904800986422, - -0.6725771763358225, - -0.7306627164037494, - -0.6812722151346441, - -0.6683545032285325, - -0.7183286286912239, - -0.7481858092118113, - -0.7102691168840504, - -0.7898211929386564, - -0.7635388311568645, - -0.6666718285455763, - -0.7091054285628722, - -0.7792445775024294, - -0.7430320623159582, - -0.6763039361112677, - -0.7344984847379595, - -0.6667710131954943, - -0.6864757237550765, - -0.6924781128037555, - -0.7677284894185472, - -0.7134826389356673, - -0.7214669015800427, - -0.7399963684907018, - -0.6681024619754498, - -0.7215485987791922, - -0.6634583140938237, - -0.7925123148176683, - -0.789652330149457, - -0.7213652877995306, - -0.7881401543789349, - -0.7197684594373567, - -0.7415948195524072, - -0.7573690425298277, - -0.7165573952131383, - -0.769836070166549, - -0.6876207770321183, - -0.737308891543659, - -0.7238513203090735, - -0.7023181359395316, - -0.7535752666435839, - -0.6908823716033664, - -0.7763536628934957, - -0.7721702941821543, - -0.7272649005473804, - -0.7012635736455374, - -0.6983767961999268, - -0.7694031063864708, - -0.7663641575237984, - -0.7351957110641543, - -0.7152792779898305, - -0.7453375803328576, - -0.6745106545678813, - -0.7386472886634508, - -0.7579671195758052, - -0.6891344811389071, - -0.7293323758022418, - -0.7808750500159024, - -0.7641360231517088, - -0.7719513312872205, - -0.7297687697178106, - -0.7546580336285239, - -0.6906714077727704, - -0.7180870566638446, - -0.6769163771733647, - -0.7332759856724878, - -0.782666356152172, - -0.7737716443589477, - -0.6671828070141143, - -0.7363093258641943, - -0.6635087708954657, - -0.6935384730729572, - -0.6764199707771283, - -0.6883038115213298, - -0.6671796988786235, - -0.7299968183222254, - -0.709520192824809, - -0.7290075687311519, - -0.6875380881858829, - -0.6838583960022817, - -0.791916748164993 - ], - "type": "scatter" - }, - { - "mode": "markers", - "name": "Expectation", - "x": [ - 0.5609335742540509 - ], - "y": [ - -0.7307572162679157 - ], - "type": "scatter" - }, - { - "fill": "toself", - "mode": "lines+markers", - "name": "Mode", - "x": [ - 0.44, - 0.4638206958770752, - 0.4638206958770752, - 0.44, - 0.44, - null, - 0.44, - 0.4638206958770752, - 0.4638206958770752, - 0.44, - 0.44, - null - ], - "y": [ - -0.7425735592842102, - -0.7425735592842102, - -0.66, - -0.66, - -0.7425735592842102, - null, - -0.7425735592842102, - -0.7425735592842102, - -0.66, - -0.66, - -0.7425735592842102, - null - ], - "type": "scatter" - } - ], - "layout": { - "title": { - "text": "DeterministicSumUnit" - }, - "xaxis": { - "title": { - "text": "relative_x" - }, - "range": [ - -1, - 1 - ] - }, - "yaxis": { - "title": { - "text": "relative_y" - }, - "range": [ - -1, - 1 - ] - }, - "template": { - "data": { - "histogram2dcontour": [ - { - "type": "histogram2dcontour", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "choropleth": [ - { - "type": "choropleth", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - ], - "histogram2d": [ - { - "type": "histogram2d", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "heatmap": [ - { - "type": "heatmap", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "heatmapgl": [ - { - "type": "heatmapgl", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "contourcarpet": [ - { - "type": "contourcarpet", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - ], - "contour": [ - { - "type": "contour", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "surface": [ - { - "type": "surface", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ] - } - ], - "mesh3d": [ - { - "type": "mesh3d", - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - ], - "scatter": [ - { - "marker": { - "line": { - "color": "#283442" - } - }, - "type": "scatter" - } - ], - "parcoords": [ - { - "type": "parcoords", - "line": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "scatterpolargl": [ - { - "type": "scatterpolargl", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "bar": [ - { - "error_x": { - "color": "#f2f5fa" - }, - "error_y": { - "color": "#f2f5fa" - }, - "marker": { - "line": { - "color": "rgb(17,17,17)", - "width": 0.5 - }, - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "bar" - } - ], - "scattergeo": [ - { - "type": "scattergeo", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "scatterpolar": [ - { - "type": "scatterpolar", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "histogram": [ - { - "marker": { - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "histogram" - } - ], - "scattergl": [ - { - "marker": { - "line": { - "color": "#283442" - } - }, - "type": "scattergl" - } - ], - "scatter3d": [ - { - "type": "scatter3d", - "line": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "scattermapbox": [ - { - "type": "scattermapbox", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "scatterternary": [ - { - "type": "scatterternary", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "scattercarpet": [ - { - "type": "scattercarpet", - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - } - } - ], - "carpet": [ - { - "aaxis": { - "endlinecolor": "#A2B1C6", - "gridcolor": "#506784", - "linecolor": "#506784", - "minorgridcolor": "#506784", - "startlinecolor": "#A2B1C6" - }, - "baxis": { - "endlinecolor": "#A2B1C6", - "gridcolor": "#506784", - "linecolor": "#506784", - "minorgridcolor": "#506784", - "startlinecolor": "#A2B1C6" - }, - "type": "carpet" - } - ], - "table": [ - { - "cells": { - "fill": { - "color": "#506784" - }, - "line": { - "color": "rgb(17,17,17)" - } - }, - "header": { - "fill": { - "color": "#2a3f5f" - }, - "line": { - "color": "rgb(17,17,17)" - } - }, - "type": "table" - } - ], - "barpolar": [ - { - "marker": { - "line": { - "color": "rgb(17,17,17)", - "width": 0.5 - }, - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "barpolar" - } - ], - "pie": [ - { - "automargin": true, - "type": "pie" - } - ] - }, - "layout": { - "autotypenumbers": "strict", - "colorway": [ - "#636efa", - "#EF553B", - "#00cc96", - "#ab63fa", - "#FFA15A", - "#19d3f3", - "#FF6692", - "#B6E880", - "#FF97FF", - "#FECB52" - ], - "font": { - "color": "#f2f5fa" - }, - "hovermode": "closest", - "hoverlabel": { - "align": "left" - }, - "paper_bgcolor": "rgb(17,17,17)", - "plot_bgcolor": "rgb(17,17,17)", - "polar": { - "bgcolor": "rgb(17,17,17)", - "angularaxis": { - "gridcolor": "#506784", - "linecolor": "#506784", - "ticks": "" - }, - "radialaxis": { - "gridcolor": "#506784", - "linecolor": "#506784", - "ticks": "" - } - }, - "ternary": { - "bgcolor": "rgb(17,17,17)", - "aaxis": { - "gridcolor": "#506784", - "linecolor": "#506784", - "ticks": "" - }, - "baxis": { - "gridcolor": "#506784", - "linecolor": "#506784", - "ticks": "" - }, - "caxis": { - "gridcolor": "#506784", - "linecolor": "#506784", - "ticks": "" - } - }, - "coloraxis": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "colorscale": { - "sequential": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ], - "sequentialminus": [ - [ - 0.0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1.0, - "#f0f921" - ] - ], - "diverging": [ - [ - 0, - "#8e0152" - ], - [ - 0.1, - "#c51b7d" - ], - [ - 0.2, - "#de77ae" - ], - [ - 0.3, - "#f1b6da" - ], - [ - 0.4, - "#fde0ef" - ], - [ - 0.5, - "#f7f7f7" - ], - [ - 0.6, - "#e6f5d0" - ], - [ - 0.7, - "#b8e186" - ], - [ - 0.8, - "#7fbc41" - ], - [ - 0.9, - "#4d9221" - ], - [ - 1, - "#276419" - ] - ] - }, - "xaxis": { - "gridcolor": "#283442", - "linecolor": "#506784", - "ticks": "", - "title": { - "standoff": 15 - }, - "zerolinecolor": "#283442", - "automargin": true, - "zerolinewidth": 2 - }, - "yaxis": { - "gridcolor": "#283442", - "linecolor": "#506784", - "ticks": "", - "title": { - "standoff": 15 - }, - "zerolinecolor": "#283442", - "automargin": true, - "zerolinewidth": 2 - }, - "scene": { - "xaxis": { - "backgroundcolor": "rgb(17,17,17)", - "gridcolor": "#506784", - "linecolor": "#506784", - "showbackground": true, - "ticks": "", - "zerolinecolor": "#C8D4E3", - "gridwidth": 2 - }, - "yaxis": { - "backgroundcolor": "rgb(17,17,17)", - "gridcolor": "#506784", - "linecolor": "#506784", - "showbackground": true, - "ticks": "", - "zerolinecolor": "#C8D4E3", - "gridwidth": 2 - }, - "zaxis": { - "backgroundcolor": "rgb(17,17,17)", - "gridcolor": "#506784", - "linecolor": "#506784", - "showbackground": true, - "ticks": "", - "zerolinecolor": "#C8D4E3", - "gridwidth": 2 - } - }, - "shapedefaults": { - "line": { - "color": "#f2f5fa" - } - }, - "annotationdefaults": { - "arrowcolor": "#f2f5fa", - "arrowhead": 0, - "arrowwidth": 1 - }, - "geo": { - "bgcolor": "rgb(17,17,17)", - "landcolor": "rgb(17,17,17)", - "subunitcolor": "#506784", - "showland": true, - "showlakes": true, - "lakecolor": "rgb(17,17,17)" - }, - "title": { - "x": 0.05 - }, - "updatemenudefaults": { - "bgcolor": "#506784", - "borderwidth": 0 - }, - "sliderdefaults": { - "bgcolor": "#C8D4E3", - "borderwidth": 1, - "bordercolor": "rgb(17,17,17)", - "tickwidth": 0 - }, - "mapbox": { - "style": "dark" - } - } - } - }, - "config": { - "plotlyServerURL": "https://plot.ly" - } - }, - "text/html": "
" - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "grounded_model = fpa.ground_model(fpa.policy, fpa.events_from_occupancy_costmap())\n", - "p_xy = grounded_model.marginal([relative_x, relative_y])\n", + "grounded_model = fpa.ground_model()\n", + "p_xy = grounded_model.marginal([relative_x, relative_y]).simplify()\n", "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", - "fig.update_xaxes(range=[-1, 1])\n", - "fig.update_yaxes(range=[-1, 1])\n", + "fig.update_layout(title=\"Marginal View of relative x and y position with respect to the milk\",\n", + " xaxis_range=[-1, 1], yaxis_range=[-1, 1])\n", "fig.show()" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:15:49.278694Z", - "start_time": "2024-03-12T16:15:46.320651Z" + "end_time": "2024-03-13T13:17:36.011305Z", + "start_time": "2024-03-13T13:17:32.910505Z" } }, "id": "a36ee203bb45f8b1", - "execution_count": 12 + "execution_count": 25 }, { - "cell_type": "code", - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n", - "navigate works\n", - "facing works\n", - "\n" - ] - }, - { - "ename": "KeyboardInterrupt", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mServiceException\u001B[0m Traceback (most recent call last)", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mcall_ik\u001B[0;34m(root_link, tip_link, target_pose, robot_object, joints)\u001B[0m\n\u001B[1;32m 95\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 96\u001B[0;31m \u001B[0mresp\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mreq\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 97\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mrospy\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mServiceException\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36m__call__\u001B[0;34m(self, *args, **kwds)\u001B[0m\n\u001B[1;32m 441\u001B[0m \"\"\"\n\u001B[0;32m--> 442\u001B[0;31m \u001B[0;32mreturn\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mcall\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwds\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 443\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36mcall\u001B[0;34m(self, *args, **kwds)\u001B[0m\n\u001B[1;32m 522\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 523\u001B[0;31m \u001B[0mresponses\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mtransport\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mreceive_once\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 524\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mlen\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mresponses\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;34m==\u001B[0m \u001B[0;36m0\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_base.py\u001B[0m in \u001B[0;36mreceive_once\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 741\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mb\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mtell\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;34m>=\u001B[0m \u001B[0;36m4\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 742\u001B[0;31m \u001B[0mp\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mread_messages\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0msock\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 743\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0;32mnot\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36mread_messages\u001B[0;34m(self, b, msg_queue, sock)\u001B[0m\n\u001B[1;32m 359\u001B[0m \"\"\"\n\u001B[0;32m--> 360\u001B[0;31m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_read_ok_byte\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0msock\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 361\u001B[0m \u001B[0mrospy\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mmsg\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdeserialize_messages\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mb\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmsg_queue\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mrecv_data_class\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mqueue_size\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mqueue_size\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mmax_msgs\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mstart\u001B[0m\u001B[0;34m=\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m)\u001B[0m \u001B[0;31m#rospy.msg\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py\u001B[0m in \u001B[0;36m_read_ok_byte\u001B[0;34m(self, b, sock)\u001B[0m\n\u001B[1;32m 342\u001B[0m \u001B[0mb\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mtruncate\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;36m0\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 343\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0mServiceException\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"service [%s] responded with an error: %s\"\u001B[0m\u001B[0;34m%\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mresolved_name\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mstr\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 344\u001B[0m \u001B[0;32melse\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;31mServiceException\u001B[0m: service [/pr2_right_arm_kinematics/get_ik] responded with an error: b''", - "\nDuring handling of the above exception, another exception occurred:\n", - "\u001B[0;31mIKError\u001B[0m Traceback (most recent call last)", - "\u001B[0;32m\u001B[0m in \u001B[0;36m\u001B[0;34m\u001B[0m\n\u001B[1;32m 3\u001B[0m \u001B[0;32mtry\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m----> 4\u001B[0;31m \u001B[0msample\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 5\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mPlanFailure\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/resolver/location/jpt_location.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 298\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"facing works\"\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 299\u001B[0;31m \u001B[0mPickUpActionPerformable\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mobject_designator\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mgrasp\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 300\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m\"pickup works\"\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 256\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstatus\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mTaskStatus\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mFAILED\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 257\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 258\u001B[0m \u001B[0;32mfinally\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 244\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstart_time\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mnow\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 245\u001B[0;31m \u001B[0mresult\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mfun\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwargs\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 246\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/designators/actions/actions.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 296\u001B[0m \u001B[0mBulletWorld\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mcurrent_bullet_world\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0madd_vis_axis\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0madjusted_oTm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 297\u001B[0;31m \u001B[0mMoveTCPMotion\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0madjusted_oTm\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mperform\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 298\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 256\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstatus\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mTaskStatus\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mFAILED\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 257\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 258\u001B[0m \u001B[0;32mfinally\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/task.py\u001B[0m in \u001B[0;36mhandle_tree\u001B[0;34m(*args, **kwargs)\u001B[0m\n\u001B[1;32m 244\u001B[0m \u001B[0mtask_tree\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mstart_time\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mdatetime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mnow\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 245\u001B[0;31m \u001B[0mresult\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mfun\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m*\u001B[0m\u001B[0margs\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0;34m**\u001B[0m\u001B[0mkwargs\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 246\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/designators/motion_designator.py\u001B[0m in \u001B[0;36mperform\u001B[0;34m(self)\u001B[0m\n\u001B[1;32m 142\u001B[0m \u001B[0mpm_manager\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mProcessModuleManager\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mget_manager\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 143\u001B[0;31m \u001B[0;32mreturn\u001B[0m \u001B[0mpm_manager\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mmove_tcp\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mexecute\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mself\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 144\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_module.py\u001B[0m in \u001B[0;36mexecute\u001B[0;34m(self, designator)\u001B[0m\n\u001B[1;32m 59\u001B[0m \u001B[0;32mwith\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_lock\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 60\u001B[0;31m \u001B[0mret\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mself\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0m_execute\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mdesignator\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 61\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mProcessModule\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mexecution_delay\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_modules/pr2_process_modules.py\u001B[0m in \u001B[0;36m_execute\u001B[0;34m(self, desig)\u001B[0m\n\u001B[1;32m 124\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 125\u001B[0;31m \u001B[0m_move_arm_tcp\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mdesig\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0marm\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 126\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/process_modules/pr2_process_modules.py\u001B[0m in \u001B[0;36m_move_arm_tcp\u001B[0;34m(target, robot, arm)\u001B[0m\n\u001B[1;32m 206\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 207\u001B[0;31m \u001B[0minv\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mrequest_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mgripper\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 208\u001B[0m \u001B[0m_apply_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0minv\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mrequest_ik\u001B[0;34m(target_pose, robot, joints, gripper)\u001B[0m\n\u001B[1;32m 132\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m--> 133\u001B[0;31m \u001B[0minv\u001B[0m \u001B[0;34m=\u001B[0m \u001B[0mcall_ik\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mbase_link\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mend_effector\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mtarget_diff\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mrobot\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mjoints\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 134\u001B[0m \u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;32m~/catkin_ws/src/pycram/src/pycram/external_interfaces/ik.py\u001B[0m in \u001B[0;36mcall_ik\u001B[0;34m(root_link, tip_link, target_pose, robot_object, joints)\u001B[0m\n\u001B[1;32m 98\u001B[0m \u001B[0;32mif\u001B[0m \u001B[0mrobot_description\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0mname\u001B[0m \u001B[0;34m==\u001B[0m \u001B[0;34m\"pr2\"\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m---> 99\u001B[0;31m \u001B[0;32mraise\u001B[0m \u001B[0mIKError\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtarget_pose\u001B[0m\u001B[0;34m,\u001B[0m \u001B[0mroot_link\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 100\u001B[0m \u001B[0;32melse\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;31mIKError\u001B[0m: Position header: \n seq: 0\n stamp: \n secs: 1710260163\n nsecs: 817859888\n frame_id: \"pr2_1/torso_lift_link\"\npose: \n position: \n x: 0.7127518608638204\n y: 0.10233092440219571\n z: 0.27932495587642475\n orientation: \n x: -1.5631567650027079e-07\n y: -2.969516120978674e-08\n z: -0.2977579729768291\n w: 0.9546413931569827 in frame 'torso_lift_link' is not reachable for end effector", - "\nDuring handling of the above exception, another exception occurred:\n", - "\u001B[0;31mKeyboardInterrupt\u001B[0m Traceback (most recent call last)", - "\u001B[0;32m\u001B[0m in \u001B[0;36m\u001B[0;34m\u001B[0m\n\u001B[1;32m 5\u001B[0m \u001B[0;32mexcept\u001B[0m \u001B[0mPlanFailure\u001B[0m \u001B[0;32mas\u001B[0m \u001B[0me\u001B[0m\u001B[0;34m:\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[1;32m 6\u001B[0m \u001B[0mprint\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0mtype\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0me\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0;32m----> 7\u001B[0;31m \u001B[0mtime\u001B[0m\u001B[0;34m.\u001B[0m\u001B[0msleep\u001B[0m\u001B[0;34m(\u001B[0m\u001B[0;36m1\u001B[0m\u001B[0;34m)\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[0m\u001B[1;32m 8\u001B[0m \u001B[0;32mcontinue\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n\u001B[1;32m 9\u001B[0m \u001B[0;32mbreak\u001B[0m\u001B[0;34m\u001B[0m\u001B[0;34m\u001B[0m\u001B[0m\n", - "\u001B[0;31mKeyboardInterrupt\u001B[0m: " - ] - } + "cell_type": "markdown", + "source": [ + "Finally, we observe our improved plan in action." ], + "metadata": { + "collapsed": false + }, + "id": "bd4fd2fa3d469c8c" + }, + { + "cell_type": "code", + "outputs": [], "source": [ + "from pycram.designators.actions.actions import ParkArmsActionPerformable\n", + "\n", + "world.reset_bullet_world()\n", + "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", "with simulated_robot:\n", + " \n", + " MoveTorsoActionPerformable(0.3).perform()\n", " for sample in fpa:\n", " try:\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", " sample.perform()\n", " break\n", " except PlanFailure as e:\n", - " print(type(e))\n", - " time.sleep(1)\n", + " time.sleep(0.1)\n", " continue" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-12T16:16:03.995962Z", - "start_time": "2024-03-12T16:15:49.279418Z" + "end_time": "2024-03-13T13:17:56.209834Z", + "start_time": "2024-03-13T13:17:38.934340Z" } }, "id": "ea57ad24b398e28f", - "execution_count": 13 + "execution_count": 26 }, { "cell_type": "code", @@ -84173,10 +63335,14 @@ "# viz_marker_publisher._stop_publishing()" ], "metadata": { - "collapsed": false + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-13T13:15:50.287095Z", + "start_time": "2024-03-13T13:15:50.285792Z" + } }, "id": "62728fa8ed6e55bd", - "execution_count": null + "execution_count": 14 } ], "metadata": { diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 5aee3d24a..09fbc0578 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -1,6 +1,8 @@ # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations +from dataclasses import dataclass + import numpy as np import pybullet as p import rospy @@ -17,6 +19,17 @@ from .pose import Pose +@dataclass +class Rectangle: + """ + A rectangle that is described by a lower and upper x and y value. + """ + x_lower: float + x_upper: float + y_lower: float + y_upper: float + + class Costmap: """ The base class of all Costmaps which implements the visualization of costmaps @@ -213,6 +226,40 @@ def __add__(self, other: Costmap) -> Costmap: else: raise ValueError(f"Can only combine two costmaps other type was {type(other)}") + def partitioning_rectangles(self) -> List[Rectangle]: + """ + Partition the map attached to this costmap into rectangles. The rectangles are axis aligned, exhaustive and + disjoint sets. + + :return: A list containing the partitioning rectangles + """ + ocm_map = np.copy(self.map) + origin = np.array([self.height / 2, self.width / 2]) + rectangles = [] + + # for every index pair (i, j) in the occupancy costmap + for i in range(0, self.map.shape[0]): + for j in range(0, self.map.shape[1]): + + # if this index has not been used yet + if ocm_map[i][j] > 0: + curr_width = self._find_consectuive_line((i, j), ocm_map) + curr_pose = (i, j) + curr_height = self._find_max_box_height((i, j), curr_width, ocm_map) + + # calculate the rectangle in the costmap + x_lower = (curr_pose[0] - origin[0]) * self.resolution + x_upper = (curr_pose[0] + curr_width - origin[0]) * self.resolution + y_lower = (curr_pose[1] - origin[1]) * self.resolution + y_upper = (curr_pose[1] + curr_height - origin[1]) * self.resolution + + # mark the found rectangle as occupied + ocm_map[i:i + curr_height, j:j + curr_width] = 0 + + rectangles.append(Rectangle(x_lower, x_upper, y_lower, y_upper)) + + return rectangles + class OccupancyCostmap(Costmap): """ diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index ff83245c1..e7f109d84 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -1,9 +1,12 @@ import abc import inspect + +import numpy as np +from tf import transformations from typing_extensions import Union, Type from pycram.designator import ActionDesignatorDescription from pycram.designators.motion_designator import * -from pycram.enums import Arms +from pycram.enums import Arms, Grasp from pycram.task import with_tree from dataclasses import dataclass, field from ..location_designator import CostmapLocation @@ -21,7 +24,8 @@ MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, LookAtAction as ORMLookAtAction, DetectAction as ORMDetectAction, TransportAction as ORMTransportAction, OpenAction as ORMOpenAction, - CloseAction as ORMCloseAction, GraspingAction as ORMGraspingAction, Action) + CloseAction as ORMCloseAction, GraspingAction as ORMGraspingAction, Action, + FaceAtAction as ORMFaceAtAction) @dataclass @@ -550,3 +554,68 @@ def perform(self) -> None: MoveTCPMotion(object_pose, self.arm, allow_gripper_collision=True).perform() MoveGripperMotion("close", self.arm, allow_gripper_collision=True).perform() + + +@dataclass +class FaceAtPerformable(ActionAbstract): + """ + Turn the robot chassis such that is faces the ``pose`` and after that perform a look at action. + """ + + pose: Pose + """ + The pose to face + """ + + orm_class = ORMFaceAtAction + + @with_tree + def perform(self) -> None: + # get the robot position + robot_position = BulletWorld.robot.pose + + # calculate orientation for robot to face the object + angle = np.arctan2(robot_position.position.y - self.pose.position.y, + robot_position.position.x - self.pose.position.x) + np.pi + orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) + + # create new robot pose + new_robot_pose = Pose(robot_position.to_list()[0], orientation) + + # turn robot + NavigateActionPerformable(new_robot_pose).perform() + + # look at target + LookAtActionPerformable(self.pose).perform() + + +@dataclass +class MoveAndPickUpPerformable(ActionAbstract): + """ + Navigate to `standing_position`, then turn towards the object and pick it up. + """ + + standing_position: Pose + """ + The pose to stand before trying to pick up the object + """ + + object_designator: ObjectDesignatorDescription.Object + """ + The object to pick up + """ + + arm: Arms + """ + The arm to use + """ + + grasp: Grasp + """ + The grasp to use + """ + + def perform(self): + NavigateActionPerformable(self.standing_position).perform() + FaceAtPerformable(self.object_designator.pose).perform() + PickUpActionPerformable(self.object_designator, self.arm, self.grasp).perform() \ No newline at end of file diff --git a/src/pycram/orm/queries/__init__.py b/src/pycram/orm/queries/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/orm/queries/queries.py b/src/pycram/orm/queries/queries.py new file mode 100644 index 000000000..7854b8c54 --- /dev/null +++ b/src/pycram/orm/queries/queries.py @@ -0,0 +1,51 @@ +import sqlalchemy.orm +from sqlalchemy import Select, alias +from ..task import TaskTreeNode +from ..action_designator import PickUpAction +from ..base import Position, RobotState, Pose +from ..object_designator import Object + + +class Query: + """ + Abstract class for queries + """ + + +class PickUpWithContext(Query): + """ + Query for pickup actions with context. + """ + + robot_position = sqlalchemy.orm.aliased(Position) + """ + 3D Vector of robot position + """ + + robot_pose = sqlalchemy.orm.aliased(Pose) + """ + Complete robot pose + """ + + object_position = sqlalchemy.orm.aliased(Position) + """ + 3D Vector for object position + """ + + relative_x = (robot_position.x - object_position.x).label("relative_x") + """ + Distance on x axis between robot and object + """ + + relative_y = (robot_position.y - object_position.y).label("relative_y") + """ + Distance on y axis between robot and object + """ + + def join_statement(self, query: Select): + return (query.join(TaskTreeNode).join(TaskTreeNode.action.of_type(PickUpAction)) + .join(PickUpAction.robot_state).join(self.robot_pose, RobotState.pose) + .join(self.robot_position, self.robot_pose.position) + .join(Pose.orientation) + .join(PickUpAction.object) + .join(Object.pose).join(self.object_position, Pose.position)) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index a85024e68..38115476c 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -6,18 +6,19 @@ from sqlalchemy import select, Select from typing_extensions import List -import pycram.designators.location_designator -import pycram.task -from pycram.costmaps import OccupancyCostmap -from pycram.orm.action_designator import PickUpAction -from pycram.orm.base import Position, RobotState, Pose as ORMPose, Quaternion -from pycram.orm.object_designator import Object -from pycram.orm.task import TaskTreeNode +from ...costmaps import Rectangle, OccupancyCostmap +from ...designator import LocationDesignatorDescription +from ...designators.location_designator import CostmapLocation +from ...orm.action_designator import PickUpAction +from ...orm.base import RobotState, Quaternion +from ...orm.object_designator import Object +from ...orm.task import TaskTreeNode from ...pose import Pose +from ...orm.queries.queries import PickUpWithContext @dataclass -class Location(pycram.designators.location_designator.LocationDesignatorDescription.Location): +class Location(LocationDesignatorDescription.Location): """ A location that is described by a pose, a reachable arm, a torso height and a grasp. """ @@ -27,76 +28,7 @@ class Location(pycram.designators.location_designator.LocationDesignatorDescript grasp: str -@dataclass -class Rectangle: - """ - A rectangle that is described by a lower and upper x and y value. - """ - x_lower: float - x_upper: float - y_lower: float - y_upper: float - - -class RequiresDatabase: - """ - Mixin class that provides a database session. - """ - - robot_position = sqlalchemy.orm.aliased(Position) - """ - 3D Vector of robot position - """ - - robot_pose = sqlalchemy.orm.aliased(ORMPose) - """ - Complete robot pose - """ - - object_position = sqlalchemy.orm.aliased(Position) - """ - 3D Vector for object position - """ - - relative_x = robot_position.x - object_position.x - """ - Distance on x axis between robot and object - """ - - relative_y = robot_position.y - object_position.y - """ - Distance on y axis between robot and object - """ - - def __init__(self, session: sqlalchemy.orm.Session = None): - """ - Create a new RequiresDatabase instance. - - :param session: The database session - """ - self.session = session - - def create_query(self) -> Select: - """ - Create a query that queries the database for all pick up actions with context. - """ - query = self.join_statement(self.select_statement()) - return query - - def select_statement(self): - return select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, self.relative_x, self.relative_y, - Quaternion.x, Quaternion.y, Quaternion.z, Quaternion.w).distinct() - - def join_statement(self, query: Select): - return (query.join(TaskTreeNode).join(TaskTreeNode.action.of_type(PickUpAction)) - .join(PickUpAction.robot_state).join(self.robot_pose, RobotState.pose) - .join(self.robot_position, self.robot_pose.position) - .join(ORMPose.orientation) - .join(PickUpAction.object) - .join(Object.pose).join(self.object_position, ORMPose.position)) - - -class AbstractCostmapLocation(pycram.designators.location_designator.CostmapLocation): +class AbstractCostmapLocation(CostmapLocation): """ Abstract Class for JPT and Database costmaps. """ @@ -110,41 +42,6 @@ def __init__(self, target, reachable_for=None, reachable_arm=None): """ super().__init__(target, reachable_for, None, reachable_arm, None) - @staticmethod - def create_occupancy_rectangles_from_map(ocm: OccupancyCostmap): - """ - Create a list of rectangles that represent the occupied space of the target object from an OccupancyCostmap. - - :param ocm: The OccupancyCostmap - :return: A list of rectangles that represent the occupied space of the target object. - """ - ocm_map = np.copy(ocm.map) - origin = np.array([ocm.height / 2, ocm.width / 2]) - rectangles = [] - - # for every index pair (i, j) in the occupancy costmap - for i in range(0, ocm.map.shape[0]): - for j in range(0, ocm.map.shape[1]): - - # if this index has not been used yet - if ocm_map[i][j] > 0: - curr_width = ocm._find_consectuive_line((i, j), ocm_map) - curr_pose = (i, j) - curr_height = ocm._find_max_box_height((i, j), curr_width, ocm_map) - - # calculate the rectangle in the costmap - x_lower = (curr_pose[0] - origin[0]) * ocm.resolution - x_upper = (curr_pose[0] + curr_width - origin[0]) * ocm.resolution - y_lower = (curr_pose[1] - origin[1]) * ocm.resolution - y_upper = (curr_pose[1] + curr_height - origin[1]) * ocm.resolution - - # mark the found rectangle as occupied - ocm_map[i:i + curr_height, j:j + curr_width] = 0 - - rectangles.append(Rectangle(x_lower, x_upper, y_lower, y_upper)) - - return rectangles - def create_occupancy_rectangles(self) -> List[Rectangle]: """ :return: A list of rectangles that represent the occupied space of the target object. @@ -152,10 +49,10 @@ def create_occupancy_rectangles(self) -> List[Rectangle]: # create Occupancy costmap for the target object ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, origin=self.target.pose) - return self.create_occupancy_rectangles_from_map(ocm) + return ocm.partitioning_rectangles() -class DatabaseCostmapLocation(AbstractCostmapLocation, RequiresDatabase): +class DatabaseCostmapLocation(AbstractCostmapLocation): """ Class that represents costmap locations from a given Database. The database has to have a schema that is compatible with the pycram.orm package. @@ -172,7 +69,13 @@ def __init__(self, target, session: sqlalchemy.orm.Session = None, reachable_for """ super().__init__(target, reachable_for, reachable_arm) - RequiresDatabase.__init__(self, session) + self.session = session + + @staticmethod + def select_statement(query_context: PickUpWithContext) -> Select: + return query_context.join_statement(select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, + query_context.relative_x, query_context.relative_y, Quaternion.x, + Quaternion.y, Quaternion.z, Quaternion.w).distinct()) def create_query_from_occupancy_costmap(self) -> Select: """ @@ -180,8 +83,10 @@ def create_query_from_occupancy_costmap(self) -> Select: OccupancyCostmap. """ + query_context = PickUpWithContext() + # get query - query = self.create_query() + query = self.select_statement(query_context) # constraint query to correct object type and successful task status query = query.where(Object.type == self.target.type).where(TaskTreeNode.status == "SUCCEEDED") @@ -191,8 +96,10 @@ def create_query_from_occupancy_costmap(self) -> Select: # for every rectangle for rectangle in self.create_occupancy_rectangles(): # add sql filter - filters.append(sqlalchemy.and_(self.relative_x >= rectangle.x_lower, self.relative_x < rectangle.x_upper, - self.relative_y >= rectangle.y_lower, self.relative_y < rectangle.y_upper)) + filters.append(sqlalchemy.and_(query_context.relative_x >= rectangle.x_lower, + query_context.relative_x < rectangle.x_upper, + query_context.relative_y >= rectangle.y_lower, + query_context.relative_y < rectangle.y_upper)) return query.where(sqlalchemy.or_(*filters)) diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py deleted file mode 100644 index 98db73b22..000000000 --- a/src/pycram/resolver/location/jpt_location.py +++ /dev/null @@ -1,415 +0,0 @@ -from dataclasses import dataclass -from typing import Optional, List - -import numpy as np -import pandas as pd -import portion -import pybullet -import sqlalchemy.orm -import tqdm -from probabilistic_model.learning.jpt.jpt import JPT -from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe -from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution -from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit, \ - DecomposableProductUnit -from random_events.events import Event -from random_events.variables import Continuous, Symbolic -from sqlalchemy import select -from tf import transformations - -from .database_location import Location, RequiresDatabase, AbstractCostmapLocation -from ...bullet_world import BulletWorld -from ...costmaps import OccupancyCostmap, plot_grid, VisibilityCostmap -from ...designator import ObjectDesignatorDescription, ActionDesignatorDescription -from ...designators.actions.actions import PickUpActionPerformable, NavigateActionPerformable, ActionAbstract, \ - LookAtActionPerformable -from ...enums import TaskStatus, Grasp, Arms -from ...local_transformer import LocalTransformer -from ...orm.action_designator import PickUpAction as ORMPickUpAction, FaceAtAction as ORMFaceAtAction -from ...orm.base import RobotState, Quaternion -from ...orm.object_designator import Object -from ...orm.task import TaskTreeNode -from ...plan_failures import PlanFailure -from ...pose import Pose -from ...robot_descriptions import robot_description -from ...task import with_tree - - -class GaussianCostmapModel: - """ - Class that generates a Gaussian Costmap around the center of an object. The costmap cuts out a square in the middle - that has side lengths given by ``distance_to_center``. - """ - - distance_to_center: float - """ - The side length of the cut out square. - """ - - variance: float - """ - The variance of the distributions involved - """ - - relative_x = Continuous("relative_x") - relative_y = Continuous("relative_y") - grasp = Symbolic("grasp", ["front", "left", "right"]) - arm = Symbolic("arm", ["left", "right"]) - - def __init__(self, distance_to_center: float = 0., variance: float = 0.5): - self.distance_to_center = distance_to_center - self.variance = variance - - def create_model_with_center(self) -> ProbabilisticCircuit: - """ - Create a fully factorized gaussian at the center of the map. - """ - centered_model = DecomposableProductUnit() - centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., self.variance)) - centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., self.variance)) - return centered_model.probabilistic_circuit - - def create_model(self) -> ProbabilisticCircuit: - """ - Create a gaussian model that assumes mass everywhere besides the center square. - - :return: The probabilistic circuit - """ - centered_model = self.create_model_with_center() - - region_model = DeterministicSumUnit() - - north_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), - self.relative_y: portion.closed(self.distance_to_center, float("inf"))}) - south_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), - self.relative_y: portion.closed(-float("inf"), -self.distance_to_center)}) - east_region = Event({self.relative_x: portion.closed(self.distance_to_center, float("inf")), - self.relative_y: portion.open(-float("inf"), float("inf"))}) - west_region = Event({self.relative_x: portion.closed(-float("inf"), -self.distance_to_center), - self.relative_y: portion.open(-float("inf"), float("inf"))}) - - for region in [north_region, south_region, east_region, west_region]: - conditional, probability = centered_model.conditional(region) - region_model.add_subcircuit(conditional.root, probability) - - result = DecomposableProductUnit() - p_arms = SymbolicDistribution(self.arm, [1 / len(self.arm.domain) for _ in self.arm.domain]) - p_grasp = SymbolicDistribution(self.grasp, [1 / len(self.grasp.domain) for _ in self.grasp.domain]) - result.add_subcircuit(p_arms) - result.add_subcircuit(p_grasp) - result.add_subcircuit(region_model) - - return result.probabilistic_circuit - - -class QueryBuilder(RequiresDatabase): - - def select_statement(self): - return (select(ORMPickUpAction.arm, ORMPickUpAction.grasp, RobotState.torso_height, self.relative_x, - self.relative_y, Quaternion.x, Quaternion.y, Quaternion.z, TaskTreeNode.status)).distinct() - - -class JPTCostmapLocation(AbstractCostmapLocation): - """ - Costmap Locations using Joint Probability Trees (JPTs). - JPT costmaps are trained to model the dependency with a robot position relative to the object, the robots type, - the objects type, the robot torso height, and the grasp parameters. - Solutions to the problem definitions are chosen in such a way that the success probability is highest. - """ - - def __init__(self, target: Object, reachable_for=None, reachable_arm=None, - model: Optional[ProbabilisticCircuit] = None): - """ - Create a JPT Costmap - - :param target: The target object - :param reachable_for: The robot to grab the object with - :param reachable_arm: The arm to use - :param model: The JPT model as a loaded tree in memory, either model or path must be set - """ - super().__init__(target, reachable_for, reachable_arm) - self.model = model - - # initialize member for visualized objects - self.visual_ids: List[int] = [] - - # easy access to models variables - (self.arm, self.grasp, self.relative_x, self.relative_y, self.status, self.torso_height, self.qx, self.qy, - self.qz) = self.model.variables - - @classmethod - def fit_from_database(cls, session: sqlalchemy.orm.session.Session, success_only: bool = False) -> ( - ProbabilisticCircuit): - """ - Fit a JPT to become a location designator using the data from the database that is reachable via the session. - - :param session: - :param success_only: - :return: - """ - query_builder = QueryBuilder(session) - query = query_builder.create_query() - if success_only: - query = query.where(TaskTreeNode.status == TaskStatus.SUCCEEDED) - samples = pd.read_sql(query, session.bind) - samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) - variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) - model = JPT(variables, min_samples_leaf=0.1) - model.fit(samples) - return model.probabilistic_circuit - - def events_from_occupancy_costmap(self) -> List[Event]: - """ - Create a list of boxes that can be used as evidences for a jpt. The list of boxes describe areas where the - robot can stand. - - :return: List of evidences describing the found boxes - """ - events = [] - for rectangle in self.create_occupancy_rectangles(): - # get the occupancy costmap - event = Event({self.relative_x: portion.closedopen(rectangle.x_lower, rectangle.x_upper), - self.relative_y: portion.closedopen(rectangle.y_lower, rectangle.y_upper)}) - events.append(event) - - return events - - def ground_model(self) -> DeterministicSumUnit: - """ - Ground the model to the current evidence. - """ - - locations = self.events_from_occupancy_costmap() - - model = DeterministicSumUnit() - - for location in locations: - conditional, probability = self.model.conditional(location) - if probability > 0: - model.add_subcircuit(conditional.root, probability) - - if len(model.subcircuits) == 0: - raise PlanFailure("No possible locations found") - - model.normalize() - return model - - def sample_to_location(self, sample: np.ndarray) -> Location: - """ - Convert a numpy array sampled from the JPT to a costmap-location - - :param sample: The drawn sample - :return: The usable costmap-location - """ - sample_dict = {variable: value for variable, value in zip(self.model.variables, sample)} - target_x, target_y, target_z = self.target.pose.position_as_list() - pose = [target_x + sample_dict[self.relative_x], target_y + sample_dict[self.relative_y], 0] - orientation = [sample_dict[self.qx], sample_dict[self.qy], sample_dict[self.qz], 1] - torso_height = sample_dict[self.torso_height] - result = Location(Pose(pose, orientation), sample_dict[self.arm], torso_height, sample_dict[self.grasp]) - return result - - def __iter__(self): - model = self.ground_model() - samples = model.sample(20) - for sample in samples: - yield self.sample_to_location(sample) - - def visualize(self): - """ - Plot the possible areas to stand in the BulletWorld. The opacity is the probability of success. - - """ - raise NotImplementedError - - def close_visualization(self) -> None: - """ - Close all plotted objects. - - """ - for id in self.visual_ids: - pybullet.removeBody(id) - self.visual_ids = [] - - -@dataclass -class FaceAtPerformable(ActionAbstract): - """ - Turn the robot chassis such that is faces the ``pose`` and after that perform a look at action. - """ - - pose: Pose - """ - The pose to face - """ - - orm_class = ORMFaceAtAction - - @with_tree - def perform(self) -> None: - # get the robot position - robot_position = BulletWorld.robot.pose - - # calculate orientation for robot to face the object - angle = np.arctan2(robot_position.position.y - self.pose.position.y, - robot_position.position.x - self.pose.position.x) + np.pi - orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) - - # create new robot pose - new_robot_pose = Pose(robot_position.to_list()[0], orientation) - - # turn robot - NavigateActionPerformable(new_robot_pose).perform() - - # look at target - LookAtActionPerformable(self.pose).perform() - - -@dataclass -class FunkyPickUpActionPerformable(ActionAbstract): - """ - Navigate to `standing_position`, then turn towards the object - """ - - standing_position: Pose - """ - The pose to stand before trying to pick up the object - """ - - object_designator: ObjectDesignatorDescription.Object - """ - The object to pick up - """ - - arm: Arms - """ - The arm to use - """ - - grasp: Grasp - """ - The grasp to use - """ - - def perform(self): - NavigateActionPerformable(self.standing_position).perform() - FaceAtPerformable(self.object_designator.pose).perform() - PickUpActionPerformable(self.object_designator, self.arm, self.grasp).perform() - -class FunkyPickUpAction(ActionDesignatorDescription): - """ - Cooler PickUpAction - """ - - sample_amount: int = 20 - - @dataclass - class Variables: - arm: Symbolic - grasp: Symbolic - relative_x: Continuous - relative_y: Continuous - - def __init__(self, object_designator: ObjectDesignatorDescription.Object, arms: List[str], grasps: List[str], - policy: Optional[ProbabilisticCircuit] = None): - super().__init__(None) - - self.object_designator = object_designator - self.arms = arms - self.grasps = grasps - - if policy is None: - policy = self.create_initial_policy() - self.policy = policy - - self.variables = self.Variables(*self.policy.variables) - - @staticmethod - def create_initial_policy() -> ProbabilisticCircuit: - return GaussianCostmapModel(0.3, 0.5).create_model() - - def sample_to_action(self, sample: List) -> FunkyPickUpActionPerformable: - arm, grasp, relative_x, relative_y = sample - position = [relative_x, relative_y, 0.] - pose = Pose(position, frame=self.object_designator.bullet_world_object.tf_frame) - standing_position = LocalTransformer().transform_pose(pose, "map") - standing_position.position.z = 0 - action = FunkyPickUpActionPerformable(standing_position, self.object_designator, arm, grasp) - return action - - def events_from_occupancy_costmap(self) -> List[Event]: - # create Occupancy costmap for the target object - ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, - origin=self.object_designator.pose) - vcm = VisibilityCostmap(min_height=1.27, max_height=1.69, - size=200, resolution=0.02, origin=self.object_designator.pose) - mcm = ocm + vcm - rectangles = AbstractCostmapLocation.create_occupancy_rectangles_from_map(mcm) - - events = [] - - for rectangle in rectangles: - event = Event({self.variables.relative_x: portion.open(rectangle.x_lower, rectangle.x_upper), - self.variables.relative_y: portion.open(rectangle.y_lower, rectangle.y_upper)}) - events.append(event) - return events - - def ground_model(self, model: ProbabilisticCircuit, events: List[Event]) -> ProbabilisticCircuit: - """ - Ground the model to the current evidence. - """ - result = DeterministicSumUnit() - - for event in events: - conditional, probability = model.conditional(event) - if probability > 0: - result.add_subcircuit(conditional.root, probability) - - if len(result.subcircuits) == 0: - raise PlanFailure("No possible locations found") - - result.normalize() - return result.probabilistic_circuit - - def iterate_without_occupancy_costmap(self): - samples = self.policy.sample(self.sample_amount) - for sample in samples: - action = self.sample_to_action(sample) - yield action - - def __iter__(self): - model = self.ground_model(self.policy, self.events_from_occupancy_costmap()) - samples = model.sample(self.sample_amount) - likelihoods = [model.likelihood(sample) for sample in samples] - - # sort samples by likelihood - samples = [x for _, x in sorted(zip(likelihoods, samples), key=lambda pair: pair[0], reverse=True)] - - for sample in samples: - action = self.sample_to_action(sample) - yield action - - @staticmethod - def query_for_database(): - query_builder = RequiresDatabase() - query = select(ORMPickUpAction.arm, ORMPickUpAction.grasp, query_builder.relative_x, - query_builder.relative_y, ).distinct() - query = query_builder.join_statement(query).where(TaskTreeNode.status == TaskStatus.SUCCEEDED) - return query - - def try_out_policy(self): - successful_tries = 0 - total_tries = 0 - - pbar = tqdm.tqdm(self.iterate_without_occupancy_costmap(), total=self.sample_amount) - - for action in pbar: - total_tries += 1 - try: - action.perform() - successful_tries += 1 - except PlanFailure as p: - pass - - pbar.set_postfix({"Success Probability": successful_tries / total_tries}) - BulletWorld.current_bullet_world.reset_bullet_world() diff --git a/src/pycram/resolver/probabilistic/__init__.py b/src/pycram/resolver/probabilistic/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py new file mode 100644 index 000000000..01602391b --- /dev/null +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -0,0 +1,315 @@ +from dataclasses import dataclass +from sqlalchemy import select + +import portion +from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution +from probabilistic_model.probabilistic_circuit.probabilistic_circuit import ProbabilisticCircuit, \ + DecomposableProductUnit, DeterministicSumUnit +from random_events.events import Event +from random_events.variables import Symbolic, Continuous +import tqdm +from typing_extensions import Optional, List, Iterator +from ...bullet_world import BulletWorld +from ...costmaps import OccupancyCostmap, VisibilityCostmap +from ...designator import ActionDesignatorDescription, ObjectDesignatorDescription +from ...designators.actions.actions import MoveAndPickUpPerformable, ActionAbstract +from ...enums import Arms, Grasp, TaskStatus +from ...local_transformer import LocalTransformer +from ...orm.queries.queries import PickUpWithContext +from ...orm.task import TaskTreeNode +from ...orm.action_designator import PickUpAction as ORMPickUpAction +from ...plan_failures import ObjectUnreachable, PlanFailure +from ...pose import Pose + + +class ProbabilisticAction: + """ + Abstract class for probabilistic actions. + """ + + @dataclass + class Variables: + """ + Variables for probabilistic actions. + + This inner class serves the purpose to define the variables that are used in a model and make them easily + accessible for the user. The user can access the variables by using the dot notation, e.g. `self.variables.x`. + + The members of this class have to be ordered the same way as the variables in the policy. + The order of the variables in the policy is most likely alphabetical by name. + """ + ... + + policy: ProbabilisticCircuit + """ + The policy that is used to determine the parameters. + """ + + variables: Variables + """ + The variables of this action. + """ + + def __init__(self, policy: Optional[ProbabilisticCircuit] = None): + if policy is None: + policy = self.default_policy() + self.policy = policy + self.variables = self.Variables(*self.policy.variables) + + def default_policy(self) -> ProbabilisticCircuit: + """ + Create a default policy for the action. + + :return: The default policy for the action + """ + raise NotImplementedError + + def sample_to_action(self, sample: List) -> ActionAbstract: + """ + Convert a sample from the policy to a performable action. + :param sample: The sample + :return: The action + """ + raise NotImplementedError + + +class GaussianCostmapModel: + """ + Class that generates a Gaussian Costmap around the center of an object. The costmap cuts out a square in the middle + that has side lengths given by ``distance_to_center``. + """ + + distance_to_center: float + """ + The side length of the cut out square. + """ + + variance: float + """ + The variance of the distributions involved + """ + + relative_x = Continuous("relative_x") + relative_y = Continuous("relative_y") + grasp = Symbolic("grasp", ["front", "left", "right"]) + arm = Symbolic("arm", ["left", "right"]) + + def __init__(self, distance_to_center: float = 0.2, variance: float = 0.5): + self.distance_to_center = distance_to_center + self.variance = variance + + def create_model_with_center(self) -> ProbabilisticCircuit: + """ + Create a fully factorized gaussian at the center of the map. + """ + centered_model = DecomposableProductUnit() + centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., self.variance)) + centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., self.variance)) + return centered_model.probabilistic_circuit + + def create_model(self) -> ProbabilisticCircuit: + """ + Create a gaussian model that assumes mass everywhere besides the center square. + + :return: The probabilistic circuit + """ + centered_model = self.create_model_with_center() + + region_model = DeterministicSumUnit() + + north_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), + self.relative_y: portion.closed(self.distance_to_center, float("inf"))}) + south_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), + self.relative_y: portion.closed(-float("inf"), -self.distance_to_center)}) + east_region = Event({self.relative_x: portion.closed(self.distance_to_center, float("inf")), + self.relative_y: portion.open(-float("inf"), float("inf"))}) + west_region = Event({self.relative_x: portion.closed(-float("inf"), -self.distance_to_center), + self.relative_y: portion.open(-float("inf"), float("inf"))}) + + for region in [north_region, south_region, east_region, west_region]: + conditional, probability = centered_model.conditional(region) + region_model.add_subcircuit(conditional.root, probability) + + result = DecomposableProductUnit() + p_arms = SymbolicDistribution(self.arm, [1 / len(self.arm.domain) for _ in self.arm.domain]) + p_grasp = SymbolicDistribution(self.grasp, [1 / len(self.grasp.domain) for _ in self.grasp.domain]) + result.add_subcircuit(p_arms) + result.add_subcircuit(p_grasp) + result.add_subcircuit(region_model) + + return result.probabilistic_circuit + + +class MoveAndPickUp(ActionDesignatorDescription, ProbabilisticAction): + + @dataclass + class Variables: + arm: Symbolic = Symbolic("arm", ["left", "right"]) + grasp: Symbolic = Symbolic("grasp", ["front", "left", "right", "top"]) + relative_x: Continuous = Continuous("relative_x") + relative_y: Continuous = Continuous("relative_y") + + variables: Variables # Type hint variables + + sample_amount: int = 20 + """ + The amount of samples that should be drawn from the policy when iterating over it. + """ + + object_designator: ObjectDesignatorDescription.Object + """ + The object designator that should be picked up. + """ + + arms: List[Arms] + """ + The arms that can be used for the pick up. + """ + + grasps: List[Grasp] + """ + The grasps that can be used for the pick up. + """ + + def __init__(self, object_designator: ObjectDesignatorDescription.Object, arms: List[str], grasps: List[str], + policy: Optional[ProbabilisticCircuit] = None): + ActionDesignatorDescription.__init__(self) + ProbabilisticAction.__init__(self, policy) + self.object_designator = object_designator + self.arms = arms + self.grasps = grasps + + def default_policy(self) -> ProbabilisticCircuit: + return GaussianCostmapModel().create_model() + + def sample_to_action(self, sample: List) -> MoveAndPickUpPerformable: + arm, grasp, relative_x, relative_y = sample + position = [relative_x, relative_y, 0.] + pose = Pose(position, frame=self.object_designator.bullet_world_object.tf_frame) + standing_position = LocalTransformer().transform_pose(pose, "map") + standing_position.position.z = 0 + action = MoveAndPickUpPerformable(standing_position, self.object_designator, arm, grasp) + return action + + def events_from_occupancy_and_visibility_costmap(self) -> List[Event]: + """ + Create events from the occupancy and visibility costmap. + + :return: The events that can be used as evidence for the model. + """ + + # create occupancy and visibility costmap for the target object + ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, + origin=self.object_designator.pose) + vcm = VisibilityCostmap(min_height=1.27, max_height=1.69, + size=200, resolution=0.02, origin=self.object_designator.pose) + mcm = ocm + vcm + + # convert rectangles to events + events = [] + for rectangle in mcm.partitioning_rectangles(): + event = Event({self.variables.relative_x: portion.open(rectangle.x_lower, rectangle.x_upper), + self.variables.relative_y: portion.open(rectangle.y_lower, rectangle.y_upper)}) + events.append(event) + return events + + def ground_model(self, model: Optional[ProbabilisticCircuit] = None, + events: Optional[List[Event]] = None) -> ProbabilisticCircuit: + """ + Ground the model to the current evidence. + + :param model: The model that should be grounded. If None, the policy is used. + :param events: The events that should be used as evidence. If None, the occupancy costmap is used. + :return: The grounded model + """ + + if model is None: + model = self.policy + if events is None: + events = self.events_from_occupancy_and_visibility_costmap() + + result = DeterministicSumUnit() + + for event in events: + conditional, probability = model.conditional(event) + if probability > 0: + result.add_subcircuit(conditional.root, probability) + + if len(result.subcircuits) == 0: + raise ObjectUnreachable("No possible locations found") + + result.normalize() + return result.probabilistic_circuit + + def iter_with_mode(self) -> Iterator[MoveAndPickUpPerformable]: + """ + Generate actions by sampling from the mode of the policy conditioned on visibility and occupancy. + """ + model = self.ground_model() + modes, _ = model.mode() + model = self.ground_model(model, modes) + samples = model.sample(self.sample_amount) + + for sample in samples: + action = self.sample_to_action(sample) + yield action + + def __iter__(self) -> Iterator[MoveAndPickUpPerformable]: + """ + Generate actions by sampling from the policy conditioned on visibility and occupancy. + """ + model = self.ground_model(self.policy, self.events_from_occupancy_and_visibility_costmap()) + samples = model.sample(self.sample_amount) + likelihoods = [model.likelihood(sample) for sample in samples] + + # sort samples by likelihood + samples = [x for _, x in sorted(zip(likelihoods, samples), key=lambda pair: pair[0], reverse=True)] + + for sample in samples: + action = self.sample_to_action(sample) + yield action + + def iterate_without_occupancy_costmap(self) -> Iterator[MoveAndPickUpPerformable]: + """ + Generate actions by sampling from the policy without conditioning on visibility and occupancy. + """ + samples = self.policy.sample(self.sample_amount) + for sample in samples: + action = self.sample_to_action(sample) + yield action + + @staticmethod + def query_for_database(): + query_context = PickUpWithContext() + query = select(ORMPickUpAction.arm, ORMPickUpAction.grasp, + query_context.relative_x, query_context.relative_y).distinct() + query = query_context.join_statement(query).where(TaskTreeNode.status == TaskStatus.SUCCEEDED) + return query + + def batch_rollout(self): + """ + Try the policy without conditioning on visibility and occupancy and count the successful tries. + + :amount: The amount of tries + """ + + # initialize statistics + successful_tries = 0 + total_tries = 0 + + # create the progress bar + progress_bar = tqdm.tqdm(iter(self.iterate_without_occupancy_costmap()), total=self.sample_amount) + + for action in progress_bar: + total_tries += 1 + try: + action.perform() + successful_tries += 1 + except PlanFailure as p: + pass + + # update progress bar + progress_bar.set_postfix({"Success Probability": successful_tries / total_tries}) + + # reset world + BulletWorld.current_bullet_world.reset_bullet_world() diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 8687a294a..22ae60fdb 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -1,21 +1,18 @@ import unittest -import numpy as np -import rospkg - import pycram.task -from pycram.bullet_world import BulletWorld, Object, fix_missing_inertial +from pycram.bullet_world import BulletWorld, Object from pycram.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule from pycram.enums import ObjectType -import os -import tf +from pycram.ros.viz_marker_publisher import VizMarkerPublisher class BulletWorldTestCase(unittest.TestCase): world: BulletWorld + viz_marker_publisher: VizMarkerPublisher @classmethod def setUpClass(cls): @@ -25,6 +22,7 @@ def setUpClass(cls): cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95])) ProcessModule.execution_delay = False + cls.viz_marker_publisher = VizMarkerPublisher() def setUp(self): self.world.reset_bullet_world() @@ -39,7 +37,6 @@ def tearDown(self): @classmethod def tearDownClass(cls): + cls.viz_marker_publisher._stop_publishing() cls.world.exit() - - diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 0e1f995dc..da78b44da 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -2,7 +2,8 @@ import unittest from pycram.designators import action_designator, object_designator from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ - NavigateActionPerformable + NavigateActionPerformable, FaceAtPerformable +from pycram.local_transformer import LocalTransformer from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot from pycram.pose import Pose @@ -137,6 +138,12 @@ def test_grasping(self): np.array(self.milk.get_pose().position_as_list())) self.assertTrue(dist < 0.01) + def test_facing(self): + with simulated_robot: + FaceAtPerformable(self.milk.pose).perform() + milk_in_robot_frame = LocalTransformer().transform_to_object_frame(self.milk.pose, self.robot) + self.assertAlmostEqual(milk_in_robot_frame.position.y, 0.) + if __name__ == '__main__': unittest.main() diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 41f9567f0..21801be30 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -22,3 +22,8 @@ def test_attachment_exclusion(self): self.robot.attach(self.milk) self.assertTrue(np.sum(o.map[80:90, 90:110]) != 0) + def test_partition_into_rectangles(self): + ocm = OccupancyCostmap(distance_to_obstacle=0.2, from_ros=False, size=200, resolution=0.02, + origin=Pose([0, 0, 0], [0, 0, 0, 1])) + rectangles = ocm.partitioning_rectangles() + self.assertEqual(len(rectangles), 10) diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py deleted file mode 100644 index 3ebe43d33..000000000 --- a/test/test_jpt_resolver.py +++ /dev/null @@ -1,254 +0,0 @@ -import os -import time -import unittest - -import numpy as np -import pandas as pd -from anytree import RenderTree -from probabilistic_model.probabilistic_circuit.probabilistic_circuit import DeterministicSumUnit, ProbabilisticCircuit -from random_events.variables import Continuous - -import pycram.plan_failures -from pycram.bullet_world import BulletWorld, Object -from pycram.designators import action_designator, object_designator -from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ - NavigateActionPerformable -from pycram.process_module import ProcessModule -from pycram.process_module import simulated_robot -from pycram.robot_descriptions import robot_description -from pycram.pose import Pose, Transform -from pycram.enums import ObjectType, Grasp, Arms -import pycram.orm -import pycram.task -from pycram.task import with_tree -from pycram.designators.object_designator import ObjectDesignatorDescription -from pycram.ros.viz_marker_publisher import VizMarkerPublisher -from pycram.bullet_world_reasoning import visible -from bullet_world_testcase import BulletWorldTestCase - -import plotly.graph_objects as go -import sqlalchemy -import sqlalchemy.orm - -from pycram.local_transformer import LocalTransformer -from pycram.resolver.location.jpt_location import JPTCostmapLocation, GaussianCostmapModel, FaceAtPerformable, \ - FunkyPickUpAction - -# check if jpt is installed -jpt_installed = True -try: - from probabilistic_model.learning.jpt.jpt import JPT - from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe - -except ImportError as e: - print(e) - jpt_installed = False - -pycrorm_uri = os.getenv('PYCRORM_URI') -if pycrorm_uri: - pycrorm_uri = "mysql+pymysql://" + pycrorm_uri - -@unittest.skipIf(not jpt_installed, "probabilistic model is not installed. " - "Install via 'pip install probabilistic_model") -class JPTResolverTestCase(unittest.TestCase): - world: BulletWorld - milk: Object - robot: Object - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - model: JPT - - @classmethod - def setUpClass(cls) -> None: - global pycrorm_uri - cls.world = BulletWorld("DIRECT") - # VizMarkerPublisher(interval=0.1) - cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) - cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") - ProcessModule.execution_delay = False - cls.engine = sqlalchemy.create_engine(pycrorm_uri) - - def setUp(self) -> None: - self.world.reset_bullet_world() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() - self.learn_model() - - def tearDown(self) -> None: - self.world.reset_bullet_world() - pycram.task.reset_tree() - pycram.orm.base.ProcessMetaData.reset() - self.session.rollback() - pycram.orm.base.Base.metadata.drop_all(self.engine) - self.session.close() - - @classmethod - def tearDownClass(cls) -> None: - cls.world.exit() - - @with_tree - def plan(self): - object_description = ObjectDesignatorDescription(types=["milk"]) - description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) - with simulated_robot: - NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() - MoveTorsoActionPerformable(0.3).perform() - PickUpActionPerformable(object_description.resolve(), "left", "front").perform() - description.resolve().perform() - - def learn_model(self): - self.plan() - pycram.orm.base.ProcessMetaData().description = "costmap_no_obstacles_test" - pycram.task.task_tree.root.insert(self.session) - self.model = JPTCostmapLocation.fit_from_database(self.session) - - def test_costmap_no_obstacles(self): - """Check if grasping a milk in the air works.""" - cml = JPTCostmapLocation(self.milk, model=self.model) - sample = next(iter(cml)) - - with simulated_robot: - MoveTorsoActionPerformable(sample.torso_height).perform() - PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, - grasp=sample.grasp).perform() - - def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") - self.world.reset_bullet_world() - - cml = JPTCostmapLocation(self.milk, model=self.model) - sample = next(iter(cml)) - - with simulated_robot: - NavigateActionPerformable(sample.pose).perform() - - MoveTorsoActionPerformable(sample.torso_height).perform() - - try: - PickUpActionPerformable( - ObjectDesignatorDescription(types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() - - except pycram.plan_failures.PlanFailure as p: - kitchen.remove() - raise p - kitchen.remove() - - def test_object_at_different_location(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") - self.world.reset_bullet_world() - - new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) - cml = JPTCostmapLocation(new_milk, model=self.model) - - sample = next(iter(cml)) - with simulated_robot: - NavigateActionPerformable(sample.pose).perform() - MoveTorsoActionPerformable(sample.torso_height).perform() - try: - PickUpActionPerformable( - ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), - arm=sample.reachable_arm, grasp=sample.grasp).perform() - except pycram.plan_failures.PlanFailure as p: - raise p - - -class FacingTestCase(BulletWorldTestCase): - - def test_facing(self): - - with simulated_robot: - FaceAtPerformable(self.robot.pose, self.milk.pose).perform() - milk_in_robot_frame = LocalTransformer().transform_to_object_frame(self.milk.pose, self.robot) - self.assertAlmostEqual(milk_in_robot_frame.position.y, 0.) - - -class TruncatedNormalTestCase(unittest.TestCase): - - def test_normal_costmap(self): - gaussian_model = GaussianCostmapModel(0.1, 0.5) - model = gaussian_model.create_model() - p_xy = model.marginal([gaussian_model.relative_x, gaussian_model.relative_y]) - fig = go.Figure(p_xy.root.plot(),p_xy.root.plotly_layout()) - # fig.show() - - -class FunkyPickUpTestCase(BulletWorldTestCase): - - def test_grounding(self): - fpa = FunkyPickUpAction(ObjectDesignatorDescription(types=[ObjectType.MILK]).ground(), arms=["left", "right"], - grasps=["front", "left", "right", "top"]) - model = fpa.ground_model() - self.assertIsInstance(model, ProbabilisticCircuit) - - -class RLTestCase(unittest.TestCase): - world: BulletWorld - milk: Object - robot: Object - viz_marker_publisher: VizMarkerPublisher - engine: sqlalchemy.engine.Engine - session: sqlalchemy.orm.Session - - @classmethod - def setUpClass(cls): - cls.world = BulletWorld("DIRECT") - cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") - cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) - cls.viz_marker_publisher = VizMarkerPublisher() - ProcessModule.execution_delay = False - cls.engine = sqlalchemy.create_engine(pycrorm_uri) - - def setUp(self): - self.world.reset_bullet_world() - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() - - def tearDown(self): - self.world.reset_bullet_world() - pycram.task.reset_tree() - pycram.orm.base.ProcessMetaData.reset() - self.session.rollback() - pycram.orm.base.Base.metadata.drop_all(self.engine) - self.session.close() - - @classmethod - def tearDownClass(cls): - cls.viz_marker_publisher._stop_publishing() - cls.world.exit() - - def test_funky_pick_up(self): - milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground() - fpa = FunkyPickUpAction(milk_description, - arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], - grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value]) - fpa.sample_amount = 1000 - relative_x = Continuous("relative_x") - relative_y = Continuous("relative_y") - p_xy = fpa.policy.marginal([relative_x, relative_y]) - fig = go.Figure(p_xy.root.plot(), p_xy.root.plotly_layout()) - # fig.show() - with simulated_robot: - fpa.try_out_policy() - - pycram.orm.base.ProcessMetaData().description = "costmap_no_obstacles_test" - - pycram.task.task_tree.root.insert(self.session) - samples = pd.read_sql_query(fpa.query_for_database(), self.engine) - samples = samples.rename(columns={"anon_1": "relative_x", "anon_2": "relative_y"}) - - variables = infer_variables_from_dataframe(samples, scale_continuous_types=False) - model = JPT(variables, min_samples_leaf=0.1) - model.fit(samples) - model = model.probabilistic_circuit - arm, grasp, relative_x, relative_y = model.variables - - p_xy = model.marginal([relative_x, relative_y]) - fig = go.Figure(p_xy.root.plot_2d(5000), p_xy.root.plotly_layout()) - fig.show() - - -if __name__ == '__main__': - unittest.main() diff --git a/test/test_orm/__init__.py b/test/test_orm/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/test/test_orm.py b/test/test_orm/test_orm.py similarity index 99% rename from test/test_orm.py rename to test/test_orm/test_orm.py index 23150b9be..c25257444 100644 --- a/test/test_orm.py +++ b/test/test_orm/test_orm.py @@ -255,7 +255,7 @@ def test_setGripperAction(self): self.assertEqual(result[0].motion, "open") def test_open_and_closeAction(self): - apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") + apartment = Object("apartment", ObjectType.ENVIRONMENT, "../../resources/apartment.urdf") apartment_desig = BelieveObject(names=["apartment"]).resolve() handle_desig = object_designator.ObjectPart(names=["handle_cab10_t"], part_of=apartment_desig).resolve() diff --git a/test/test_probabilistic_actions/__init__.py b/test/test_probabilistic_actions/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/test/test_database_resolver.py b/test/test_probabilistic_actions/test_database_resolver.py similarity index 93% rename from test/test_database_resolver.py rename to test/test_probabilistic_actions/test_database_resolver.py index c6697fa58..20d79de0d 100644 --- a/test/test_database_resolver.py +++ b/test/test_probabilistic_actions/test_database_resolver.py @@ -36,7 +36,7 @@ class DatabaseResolverTestCase(unittest.TestCase,): def setUpClass(cls) -> None: global pycrorm_uri cls.world = BulletWorld("DIRECT") - cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.milk = Object("milk", "milk", "../../resources/milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False cls.engine = sqlalchemy.create_engine(pycrorm_uri) @@ -84,7 +84,7 @@ def test_costmap_no_obstacles(self): grasp=sample.grasp).perform() def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") + kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "costmap_with_obstacles_test" pycram.task.task_tree.root.insert(self.session) @@ -106,14 +106,14 @@ def test_costmap_with_obstacles(self): kitchen.remove() def test_object_at_different_location(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") + kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "object_at_different_location_test" pycram.task.task_tree.root.insert(self.session) self.world.reset_bullet_world() - new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + new_milk = Object("new_milk", "milk", "../../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.95])) cml = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) sample = next(iter(cml)) @@ -134,8 +134,8 @@ def test_object_at_different_location(self): kitchen.remove() def test_multiple_objects(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") - new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.9])) + kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") + new_milk = Object("new_milk", "milk", "../../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.9])) object_description = ObjectDesignatorDescription(names=["milk"]) object_description_new_milk = ObjectDesignatorDescription(names=["new_milk"]) diff --git a/test/test_probabilistic_actions/test_move_and_pick_up.py b/test/test_probabilistic_actions/test_move_and_pick_up.py new file mode 100644 index 000000000..e2bca18a0 --- /dev/null +++ b/test/test_probabilistic_actions/test_move_and_pick_up.py @@ -0,0 +1,49 @@ +import random +import unittest + +import numpy as np + +from pycram.designator import ObjectDesignatorDescription +from pycram.enums import ObjectType +from pycram.plan_failures import PlanFailure +from pycram.process_module import simulated_robot +from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp +from ..bullet_world_testcase import BulletWorldTestCase +import plotly.graph_objects as go + + +class MoveAndPickUpTestCase(BulletWorldTestCase): + + @classmethod + def setUpClass(cls): + super().setUpClass() + np.random.seed(69) + random.seed(69) + + def test_grounding(self): + object_designator = ObjectDesignatorDescription(types=[ObjectType.MILK]).resolve() + move_and_pick = MoveAndPickUp(object_designator, arms=["left", "right"], + grasps=["front", "left", "right", "top"]) + + # p_xy = move_and_pick.policy.marginal([move_and_pick.variables.relative_x, move_and_pick.variables.relative_y]) + # fig = go.Figure(p_xy.plot()) + # fig.show() + model = move_and_pick.ground_model() + self.assertIsNotNone(model) + + def test_move_and_pick_up(self): + object_designator = ObjectDesignatorDescription(types=[ObjectType.MILK]).resolve() + move_and_pick = MoveAndPickUp(object_designator, arms=["left", "right"], + grasps=["front", "left", "right", "top"]) + with simulated_robot: + for action in move_and_pick: + try: + action.perform() + return # Success + except PlanFailure as e: + continue + raise AssertionError("No action performed successfully.") + + +if __name__ == '__main__': + unittest.main() From 894c3490e7d3fd6278079f908060fbac074fd529 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 15:41:35 +0100 Subject: [PATCH 113/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 75 +++++++++++++++++++ .github/workflows/pycram-ci.yml | 88 ----------------------- .github/workflows/update-docker-image.yml | 30 ++++++++ docker/Dockerfile | 23 ++++++ 4 files changed, 128 insertions(+), 88 deletions(-) create mode 100644 .github/workflows/new-pycram-ci.yml delete mode 100644 .github/workflows/pycram-ci.yml create mode 100644 .github/workflows/update-docker-image.yml create mode 100644 docker/Dockerfile diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml new file mode 100644 index 000000000..94f1bf383 --- /dev/null +++ b/.github/workflows/new-pycram-ci.yml @@ -0,0 +1,75 @@ +name: pycram_docker_ci +defaults: + run: + shell: bash -ieo pipefail {0} + +on: + push: + branches: + - dev + - master + pull_request: + branches: + - master + - dev + workflow_dispatch: # For manual debugging + inputs: + debug_enabled: + type: boolean + required: false + default: false + description: "Run tmate session" + +jobs: + build_and_run_tests: + runs-on: ubuntu-20.04 + container: + image: ${{ vars.DOCKER_IMAGE}} #add docker image variable to repo + steps: + - name: Checkout PyCRAM + uses: actions/checkout@v3 + with: + path: "ros/src/pycram" + repository: ${{ github.repository }} + ref: ${{ github.ref }} + submodules: "recursive" + + - name: Update PyCRAM source files + run: | + rm -rf /opt/ros/overlay_ws/src/pycram/* + cd /opt/ros/overlay_ws/src/pycram + rm -rf .git .github .gitignore .gitmodules .readthedocs.yaml + mv /__w/pycram_CI/pycram_CI/ros/src/pycram /opt/ros/overlay_ws/src + + - name: Remake workspace & start roscore + run: | + sudo -s + source /opt/ros/noetic/setup.bash + cd /opt/ros/overlay_ws + catkin_make + source /opt/ros/overlay_ws/devel/setup.bash + roslaunch pycram ik_and_description.launch & + + - name: Install python dependencies + run: | + pip3 install --upgrade pip --root-user-action=ignore + cd /opt/ros/overlay_ws/src/pycram + pip3 install -r requirements.txt + + - name: Install Pytest, pyjpt & mlflow + run: | + pip3 install --ignore-installed pytest pyjpt mlflow + + - name: Run tests + run: | + sudo -s + source /opt/ros/noetic/setup.bash + cd /opt/ros/overlay_ws + source /opt/ros/overlay_ws/devel/setup.bash + roscd pycram + pytest -v test + + # For debugging + - name: Setup tmate session + uses: mxschmitt/action-tmate@v3 + if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} diff --git a/.github/workflows/pycram-ci.yml b/.github/workflows/pycram-ci.yml deleted file mode 100644 index 2c0e299c9..000000000 --- a/.github/workflows/pycram-ci.yml +++ /dev/null @@ -1,88 +0,0 @@ -name: CI standalone -defaults: - run: - shell: bash -ieo pipefail {0} -on: - push: - branches: - - dev - - master - pull_request: - branches: - - master - - dev -jobs: - Build_and_run_Tests: - runs-on: ubuntu-20.04 - steps: - - name: Checkout pycram - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/pycram' - repository: ${{github.repository}} - ref: ${{github.ref}} - submodules: recursive - - - name: Checkout iai_maps - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/iai_maps' - repository: code-iai/iai_maps - ref: master - - name: Checkout iai_robots - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/iai_robots' - repository: code-iai/iai_robots - ref: master - - name: Checkout pr2_common - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/pr2_common' - repository: PR2/pr2_common - ref: master - - name: Checkout kdl_ik_service - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/kdl_ik_service' - repository: cram2/kdl_ik_service - ref: master - - name: Checkout pr2_kinematics - uses: actions/checkout@v3 - with: - path: 'ros_ws/src/pr2_kinematics' - repository: PR2/pr2_kinematics - ref: kinetic-devel - - name: install ros and deps - uses: betwo/github-setup-catkin@master - env: - ACTIONS_ALLOW_UNSECURE_COMMANDS: true - with: - # Version range or exact version of ROS version to use, using SemVer's version range syntax. - ros-version: noetic - build-tool: 'catkin_tools' - # Root directory of the catkin workspace - workspace: $GITHUB_WORKSPACE/ros_ws - - name: build and source workspace - run: | - cd ros_ws - catkin_make - echo 'export ROS_HOSTNAME=localhost' >> ~/.bashrc - echo 'source $GITHUB_WORKSPACE/ros_ws/devel/setup.bash' >> ~/.bashrc - - name: Upgrade pip - run: | - sudo pip3 install --upgrade pip - - name: Install requirements - run: | - cd $GITHUB_WORKSPACE/ros_ws/src/pycram - sudo pip3 install -r requirements.txt - - name: install additional requirements - run: | - sudo pip3 install --ignore-installed pytest pyjpt mlflow - - name: start roscore - run: | - roslaunch pycram ik_and_description.launch & - - name: Run Tests - run: | - roscd pycram - pytest -v test diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml new file mode 100644 index 000000000..88134cbac --- /dev/null +++ b/.github/workflows/update-docker-image.yml @@ -0,0 +1,30 @@ +name: update_docker_image +on: + workflow_run: + workflows: ["pycram_docker_ci"] + types: + - completed + +# Runs if pycram_docker_ci workflow WAS successfuL +jobs: + build_and_push_docker_image: + runs-on: ubuntu-latest + if: ${{ github.event.workflow_run.conclusion == 'success' }} + steps: + - uses: actions/checkout@v4 + - name: Set up Docker Buildx + id: buildx + uses: docker/setup-buildx-action@v3 + + - name: log into Docker Hub #Set repository secrets in github secrets + uses: docker/login-action@v3 + with: + username: ${{ secrets.DOCKERHUB_USERNAME }} + password: ${{ secrets.DOCKERHUB_PASS }} + + - name: Build and push + uses: docker/build-push-action@v5 + with: + context: ./docker + push: true + tags: ${{ secrets.DOCKERHUB_USERNAME}}/testing_ci:latest \ No newline at end of file diff --git a/docker/Dockerfile b/docker/Dockerfile new file mode 100644 index 000000000..eb4d13768 --- /dev/null +++ b/docker/Dockerfile @@ -0,0 +1,23 @@ +ARG FROM_IMAGE=ros:noetic-ros-core +ARG OVERLAY_WS=/opt/ros/overlay_ws + +FROM $FROM_IMAGE as cacher +ARG OVERLAY_WS +WORKDIR $OVERLAY_WS/src + +RUN apt-get update && apt-get install python3-pip python3-vcstool git -y && pip3 install pip --upgrade +RUN pip3 install rosdep && rosdep init + +# Checks PyCRAM repo for latest commit --> will rebuild if there is a new commit +ADD "https://api.github.com/repos/cram2/pycram/commits?per_page=1" latest_commit +RUN vcs import --input https://raw.githubusercontent.com/cram2/pycram/dev/pycram-https.rosinstall --recursive --skip-existing $OVERLAY_WS/src +RUN rosdep update && rosdep install --from-paths $OVERLAY_WS/src --ignore-src -r -y + +RUN . /opt/ros/noetic/setup.sh && cd $OVERLAY_WS && catkin_make +RUN echo "source $OVERLAY_WS/devel/setup.bash" >> ~/.bashrc + +RUN pip3 install --upgrade pip +WORKDIR $OVERLAY_WS/src/pycram +RUN pip3 install -r requirements.txt + +EXPOSE 11311 \ No newline at end of file From 0a83656abbb49a71f9036da0207ba076724ab445 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 15:52:39 +0100 Subject: [PATCH 114/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 94f1bf383..a2e17b461 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -39,7 +39,7 @@ jobs: rm -rf /opt/ros/overlay_ws/src/pycram/* cd /opt/ros/overlay_ws/src/pycram rm -rf .git .github .gitignore .gitmodules .readthedocs.yaml - mv /__w/pycram_CI/pycram_CI/ros/src/pycram /opt/ros/overlay_ws/src + mv ${{github.workspace}}/ros/src/pycram /opt/ros/overlay_ws/src - name: Remake workspace & start roscore run: | From 8cd68fbb72d6e56835b23c87fde0cff40161070b Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 15:55:36 +0100 Subject: [PATCH 115/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index a2e17b461..c56dd5dbb 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -34,6 +34,11 @@ jobs: ref: ${{ github.ref }} submodules: "recursive" + # For debugging + - name: Setup tmate session + uses: mxschmitt/action-tmate@v3 + if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} + - name: Update PyCRAM source files run: | rm -rf /opt/ros/overlay_ws/src/pycram/* @@ -69,7 +74,4 @@ jobs: roscd pycram pytest -v test - # For debugging - - name: Setup tmate session - uses: mxschmitt/action-tmate@v3 - if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} + From e442242d3e03c3a9336671098dfe05a3ee0ddfd5 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 15:58:23 +0100 Subject: [PATCH 116/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index c56dd5dbb..5499e0408 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -44,7 +44,7 @@ jobs: rm -rf /opt/ros/overlay_ws/src/pycram/* cd /opt/ros/overlay_ws/src/pycram rm -rf .git .github .gitignore .gitmodules .readthedocs.yaml - mv ${{github.workspace}}/ros/src/pycram /opt/ros/overlay_ws/src + mv /__w/pycram/pycram/ros/src/pycram /opt/ros/overlay_ws/src - name: Remake workspace & start roscore run: | From 2cb6e7eaab91f67efe39d5d90da7cda557a2f227 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:06:06 +0100 Subject: [PATCH 117/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 5499e0408..7830494f5 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -44,7 +44,7 @@ jobs: rm -rf /opt/ros/overlay_ws/src/pycram/* cd /opt/ros/overlay_ws/src/pycram rm -rf .git .github .gitignore .gitmodules .readthedocs.yaml - mv /__w/pycram/pycram/ros/src/pycram /opt/ros/overlay_ws/src + mv /__w/${{ github.event.repository.name }} /${{ github.event.repository.name }} //ros/src/pycram /opt/ros/overlay_ws/src - name: Remake workspace & start roscore run: | From 3291a15703904f839536fa90c54d52ba23d04e60 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:08:08 +0100 Subject: [PATCH 118/195] [ci] updated ci --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 7830494f5..456445ad2 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -44,7 +44,7 @@ jobs: rm -rf /opt/ros/overlay_ws/src/pycram/* cd /opt/ros/overlay_ws/src/pycram rm -rf .git .github .gitignore .gitmodules .readthedocs.yaml - mv /__w/${{ github.event.repository.name }} /${{ github.event.repository.name }} //ros/src/pycram /opt/ros/overlay_ws/src + mv /__w/${{ github.event.repository.name }}/${{ github.event.repository.name }}/ros/src/pycram /opt/ros/overlay_ws/src - name: Remake workspace & start roscore run: | From 8d44961792b5938d40876c58e3975ef87eb97bbb Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:26:34 +0100 Subject: [PATCH 119/195] [ci] updated ci --- .github/workflows/update-docker-image.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index 88134cbac..dc28d468d 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -27,4 +27,4 @@ jobs: with: context: ./docker push: true - tags: ${{ secrets.DOCKERHUB_USERNAME}}/testing_ci:latest \ No newline at end of file + tags: ${{ secrets.DOCKERHUB_USERNAME }}/testing_ci:latest \ No newline at end of file From c014de1c293b9c5251854ce49074390731cb0fe5 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:27:42 +0100 Subject: [PATCH 120/195] [ci] updated ci --- .github/workflows/update-docker-image.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index dc28d468d..f641e6231 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -27,4 +27,4 @@ jobs: with: context: ./docker push: true - tags: ${{ secrets.DOCKERHUB_USERNAME }}/testing_ci:latest \ No newline at end of file + tags: ${{ vars.DOCKER_IMAGE }} \ No newline at end of file From 2c7c2c82633dc9d4c389a07939ae0b92b78b397f Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:33:02 +0100 Subject: [PATCH 121/195] [ci] updated ci --- .github/workflows/update-docker-image.yml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index f641e6231..fb0ec9d70 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -4,6 +4,12 @@ on: workflows: ["pycram_docker_ci"] types: - completed + workflow_dispatch: # For manual debugging + inputs: + manually_build_and_push_image: + type: boolean + required: false + default: false # Runs if pycram_docker_ci workflow WAS successfuL jobs: From cd13d390ddd336abcbf5bcad64e86a70c6a15ef2 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:35:34 +0100 Subject: [PATCH 122/195] [ci] updated ci --- .github/workflows/update-docker-image.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index fb0ec9d70..37d91c35f 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -15,7 +15,7 @@ on: jobs: build_and_push_docker_image: runs-on: ubuntu-latest - if: ${{ github.event.workflow_run.conclusion == 'success' }} + if: ${{ github.event.workflow_run.conclusion == 'success' || github.event.workflow_dispatch.inputs == 'manually_build_and_push_iamge'}} steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx From 7e1779b781aa4b66ad386f4a0ce94ef24fa790c7 Mon Sep 17 00:00:00 2001 From: leo Date: Wed, 13 Mar 2024 16:36:47 +0100 Subject: [PATCH 123/195] [ci] updated ci --- .github/workflows/update-docker-image.yml | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index 37d91c35f..aef452d4a 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -4,18 +4,13 @@ on: workflows: ["pycram_docker_ci"] types: - completed - workflow_dispatch: # For manual debugging - inputs: - manually_build_and_push_image: - type: boolean - required: false - default: false + workflow_dispatch: # manual run # Runs if pycram_docker_ci workflow WAS successfuL jobs: build_and_push_docker_image: runs-on: ubuntu-latest - if: ${{ github.event.workflow_run.conclusion == 'success' || github.event.workflow_dispatch.inputs == 'manually_build_and_push_iamge'}} + #if: ${{ github.event.workflow_run.conclusion == 'success'}} steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx From faa487e1e120e2f2140cd71f37171548e97e949c Mon Sep 17 00:00:00 2001 From: Leo <114857318+leonyi4@users.noreply.github.com> Date: Thu, 14 Mar 2024 12:09:55 +0100 Subject: [PATCH 124/195] [ci] updating ci --- .github/workflows/update-docker-image.yml | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index aef452d4a..858418f08 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -1,16 +1,22 @@ name: update_docker_image on: - workflow_run: + workflow_run: workflows: ["pycram_docker_ci"] - types: + types: - completed workflow_dispatch: # manual run + inputs: + manual_run: + description: "build and push manually" + type: boolean + default: false + required: false -# Runs if pycram_docker_ci workflow WAS successfuL +# Runs if pycram_docker_ci workflow Wwa successful jobs: - build_and_push_docker_image: + build_and_push_docker_image: runs-on: ubuntu-latest - #if: ${{ github.event.workflow_run.conclusion == 'success'}} + #if: ${{ (github.event.workflow_run.conclusion == 'success') || (github.event.inputs.manual_run)}} steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx @@ -20,12 +26,12 @@ jobs: - name: log into Docker Hub #Set repository secrets in github secrets uses: docker/login-action@v3 with: - username: ${{ secrets.DOCKERHUB_USERNAME }} + username: ${{ secrets.DOCKERHUB_USERNAME }} password: ${{ secrets.DOCKERHUB_PASS }} - name: Build and push uses: docker/build-push-action@v5 - with: + with: context: ./docker push: true - tags: ${{ vars.DOCKER_IMAGE }} \ No newline at end of file + tags: ${{ vars.DOCKER_IMAGE }} From eecc20187831392a777538f9837758b72310ac2a Mon Sep 17 00:00:00 2001 From: Leo <114857318+leonyi4@users.noreply.github.com> Date: Thu, 14 Mar 2024 12:10:09 +0100 Subject: [PATCH 125/195] [ci] updating ci --- .github/workflows/update-docker-image.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index 858418f08..df46c0f98 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -16,7 +16,7 @@ on: jobs: build_and_push_docker_image: runs-on: ubuntu-latest - #if: ${{ (github.event.workflow_run.conclusion == 'success') || (github.event.inputs.manual_run)}} + if: ${{ (github.event.workflow_run.conclusion == 'success') || (github.event.inputs.manual_run)}} steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx From cf89c703a33d2796a1637cc89fefd95d396a88c3 Mon Sep 17 00:00:00 2001 From: Leo <114857318+leonyi4@users.noreply.github.com> Date: Thu, 14 Mar 2024 12:22:15 +0100 Subject: [PATCH 126/195] [ci] updating ci --- .github/workflows/new-pycram-ci.yml | 6 ++---- docker/Dockerfile | 2 -- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 456445ad2..58b2d5624 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -37,7 +37,7 @@ jobs: # For debugging - name: Setup tmate session uses: mxschmitt/action-tmate@v3 - if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} + if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} - name: Update PyCRAM source files run: | @@ -61,7 +61,7 @@ jobs: cd /opt/ros/overlay_ws/src/pycram pip3 install -r requirements.txt - - name: Install Pytest, pyjpt & mlflow + - name: Install pytest, pyjpt & mlflow run: | pip3 install --ignore-installed pytest pyjpt mlflow @@ -73,5 +73,3 @@ jobs: source /opt/ros/overlay_ws/devel/setup.bash roscd pycram pytest -v test - - diff --git a/docker/Dockerfile b/docker/Dockerfile index eb4d13768..e85fb2af8 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -8,8 +8,6 @@ WORKDIR $OVERLAY_WS/src RUN apt-get update && apt-get install python3-pip python3-vcstool git -y && pip3 install pip --upgrade RUN pip3 install rosdep && rosdep init -# Checks PyCRAM repo for latest commit --> will rebuild if there is a new commit -ADD "https://api.github.com/repos/cram2/pycram/commits?per_page=1" latest_commit RUN vcs import --input https://raw.githubusercontent.com/cram2/pycram/dev/pycram-https.rosinstall --recursive --skip-existing $OVERLAY_WS/src RUN rosdep update && rosdep install --from-paths $OVERLAY_WS/src --ignore-src -r -y From 9195a493293e1a7eb50d600f9cd1d6d7784f8c40 Mon Sep 17 00:00:00 2001 From: "Nyi Nyein Aung (Leo)" <114857318+leonyi4@users.noreply.github.com> Date: Fri, 15 Mar 2024 12:48:17 +0100 Subject: [PATCH 127/195] [ci] removed uncessary lines --- .github/workflows/new-pycram-ci.yml | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 58b2d5624..35e1142df 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -66,10 +66,7 @@ jobs: pip3 install --ignore-installed pytest pyjpt mlflow - name: Run tests - run: | - sudo -s - source /opt/ros/noetic/setup.bash - cd /opt/ros/overlay_ws + run: | source /opt/ros/overlay_ws/devel/setup.bash roscd pycram pytest -v test From 21e7759a426f6bb8f9d523977221b5eab07fd36f Mon Sep 17 00:00:00 2001 From: "Nyi Nyein Aung (Leo)" <114857318+leonyi4@users.noreply.github.com> Date: Fri, 15 Mar 2024 15:36:03 +0100 Subject: [PATCH 128/195] [ci] updated workflow condition for building docker image --- .github/workflows/update-docker-image.yml | 20 +++++++------------- 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/.github/workflows/update-docker-image.yml b/.github/workflows/update-docker-image.yml index df46c0f98..8c6686c2c 100644 --- a/.github/workflows/update-docker-image.yml +++ b/.github/workflows/update-docker-image.yml @@ -1,22 +1,16 @@ name: update_docker_image on: - workflow_run: - workflows: ["pycram_docker_ci"] - types: - - completed - workflow_dispatch: # manual run - inputs: - manual_run: - description: "build and push manually" - type: boolean - default: false - required: false + push: + branches: + - master + - dev + paths: + - 'requirements.txt' +# only run when a commit has changes in the requirements.txt file -# Runs if pycram_docker_ci workflow Wwa successful jobs: build_and_push_docker_image: runs-on: ubuntu-latest - if: ${{ (github.event.workflow_run.conclusion == 'success') || (github.event.inputs.manual_run)}} steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx From be6b55b8521e64331e1ecf8d47ff9961c441bfdf Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 18 Mar 2024 14:15:39 +0100 Subject: [PATCH 129/195] [resoures] Added stretch urdf --- resources/stretch.urdf | 952 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 952 insertions(+) create mode 100644 resources/stretch.urdf diff --git a/resources/stretch.urdf b/resources/stretch.urdf new file mode 100644 index 000000000..044ee54e0 --- /dev/null +++ b/resources/stretch.urdf @@ -0,0 +1,952 @@ + + + + + + + + + name="link_gripper"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 1.0 + 1.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From a8942643d621d0f9ffa2c5d968d4c42f76e7d649 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 18 Mar 2024 16:57:56 +0100 Subject: [PATCH 130/195] [pick-up plan] Some quick fixes --- src/pycram/designators/actions/actions.py | 6 +++--- src/pycram/designators/location_designator.py | 2 +- src/pycram/external_interfaces/robokudo.py | 2 +- src/pycram/process_modules/pr2_process_modules.py | 3 ++- src/pycram/robot_descriptions/stretch_description.py | 0 5 files changed, 7 insertions(+), 6 deletions(-) create mode 100644 src/pycram/robot_descriptions/stretch_description.py diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 83ca6c29f..22b4c87c7 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -267,12 +267,12 @@ def perform(self) -> None: # Perform the motion with the prepose and open gripper BulletWorld.current_bullet_world.add_vis_axis(prepose) - MoveTCPMotion(prepose, self.arm).perform() + MoveTCPMotion(prepose, self.arm, allow_gripper_collision=True).perform() MoveGripperMotion(motion="open", gripper=self.arm).perform() # Perform the motion with the adjusted pose -> actual grasp and close gripper BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).perform() + MoveTCPMotion(adjusted_oTm, self.arm, allow_gripper_collision=True).perform() adjusted_oTm.pose.position.z += 0.03 MoveGripperMotion(motion="close", gripper=self.arm).perform() tool_frame = robot_description.get_tool_frame(self.arm) @@ -280,7 +280,7 @@ def perform(self) -> None: # Lift object BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) - MoveTCPMotion(adjusted_oTm, self.arm).perform() + MoveTCPMotion(adjusted_oTm, self.arm, allow_gripper_collision=True).perform() # Remove the vis axis from the world BulletWorld.current_bullet_world.remove_vis_axis() diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 1edb9d17d..100a233f8 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -168,7 +168,7 @@ def __iter__(self): ground_pose = Pose(target_pose.position_as_list()) ground_pose.position.z = 0 - occupancy = OccupancyCostmap(0.4, False, 200, 0.02, ground_pose) + occupancy = OccupancyCostmap(0.32, False, 200, 0.02, ground_pose) final_map = occupancy if self.reachable_for: diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index e332c3e07..5e3f91606 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -39,7 +39,7 @@ def wrapper(*args, **kwargs): rospy.logwarn("RoboKudo is not running, could not initialize RoboKudo interface") return - func(*args, **kwargs) + return func(*args, **kwargs) return wrapper diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 77cc067eb..e49427485 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -291,7 +291,8 @@ def _execute(self, designator: MoveTCPMotion) -> Any: if designator.allow_gripper_collision: giskard.allow_gripper_collision(designator.arm) giskard.achieve_cartesian_goal(pose_in_map, robot_description.get_tool_frame(designator.arm), - robot_description.base_link) + "torso_lift_link") + #robot_description.base_link) class Pr2MoveArmJointsReal(ProcessModule): diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py new file mode 100644 index 000000000..e69de29bb From 44b7d714755f016016cc3e1fe3f949cb8d30ddfe Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Tue, 19 Mar 2024 09:32:52 +0100 Subject: [PATCH 131/195] [AbstractWorld] restructured folders and files. --- demos/pycram_bullet_world_demo/demo.py | 8 +++---- demos/pycram_ur5_demo/demo.py | 2 +- src/neem_interface_python | 2 +- .../{worlds/concepts => }/cache_manager.py | 0 .../concepts => datastructures}/__init__.py | 0 .../datastructures/dataclasses.py | 8 +++---- .../{worlds => }/datastructures/enums.py | 0 .../datastructures/local_transformer.py | 2 +- .../{worlds => }/datastructures/pose.py | 0 src/pycram/description.py | 10 ++++----- src/pycram/designator.py | 8 +++---- src/pycram/designators/action_designator.py | 6 ++--- src/pycram/designators/location_designator.py | 6 ++--- src/pycram/designators/motion_designator.py | 6 ++--- src/pycram/designators/object_designator.py | 4 ++-- src/pycram/external_interfaces/giskard.py | 6 ++--- src/pycram/external_interfaces/ik.py | 6 ++--- src/pycram/external_interfaces/robokudo.py | 6 ++--- src/pycram/helper.py | 4 ++-- src/pycram/language.py | 2 +- src/pycram/object_descriptors/urdf.py | 6 ++--- src/pycram/orm/action_designator.py | 2 +- src/pycram/orm/base.py | 2 +- src/pycram/orm/motion_designator.py | 2 +- src/pycram/orm/object_designator.py | 2 +- src/pycram/orm/task.py | 2 +- src/pycram/pose_generator_and_validator.py | 6 ++--- .../process_modules/boxy_process_modules.py | 2 +- .../default_process_modules.py | 2 +- .../process_modules/donbot_process_modules.py | 2 +- .../process_modules/hsr_process_modules.py | 2 +- .../process_modules/pr2_process_modules.py | 8 +++---- .../resolver/location/database_location.py | 4 ++-- .../resolver/location/giskard_location.py | 2 +- src/pycram/resolver/location/jpt_location.py | 6 ++--- src/pycram/ros/robot_state_updater.py | 2 +- src/pycram/ros/tf_broadcaster.py | 2 +- src/pycram/ros/viz_marker_publisher.py | 4 ++-- src/pycram/task.py | 4 ++-- src/pycram/world.py | 22 +++++++++---------- src/pycram/world_concepts/__init__.py | 1 + .../constraints.py | 4 ++-- .../concepts => world_concepts}/costmaps.py | 8 +++---- .../concepts => world_concepts}/event.py | 0 .../world_object.py | 12 +++++----- src/pycram/world_reasoning.py | 4 ++-- src/pycram/worlds/bullet_world.py | 10 ++++----- src/pycram/worlds/datastructures/__init__.py | 0 test/bullet_world_testcase.py | 6 ++--- test/test_action_designator.py | 4 ++-- test/test_bullet_world.py | 8 +++---- test/test_bullet_world_reasoning.py | 2 +- test/test_cache_manager.py | 4 ++-- test/test_costmaps.py | 4 ++-- test/test_database_merger.py | 4 ++-- test/test_database_resolver.py | 6 ++--- test/test_failure_handling.py | 2 +- test/test_jpt_resolver.py | 6 ++--- test/test_language.py | 4 ++-- test/test_links.py | 2 +- test/test_local_transformer.py | 4 ++-- test/test_location_designator.py | 2 +- test/test_object.py | 8 +++---- test/test_object_designator.py | 2 +- test/test_orm.py | 2 +- test/test_pose.py | 2 +- test/test_task_tree.py | 2 +- 67 files changed, 142 insertions(+), 141 deletions(-) rename src/pycram/{worlds/concepts => }/cache_manager.py (100%) rename src/pycram/{worlds/concepts => datastructures}/__init__.py (100%) rename src/pycram/{worlds => }/datastructures/dataclasses.py (96%) rename src/pycram/{worlds => }/datastructures/enums.py (100%) rename src/pycram/{worlds => }/datastructures/local_transformer.py (98%) rename src/pycram/{worlds => }/datastructures/pose.py (100%) create mode 100644 src/pycram/world_concepts/__init__.py rename src/pycram/{worlds/concepts => world_concepts}/constraints.py (98%) rename src/pycram/{worlds/concepts => world_concepts}/costmaps.py (99%) rename src/pycram/{worlds/concepts => world_concepts}/event.py (100%) rename src/pycram/{worlds/concepts => world_concepts}/world_object.py (98%) delete mode 100644 src/pycram/worlds/datastructures/__init__.py diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index 188eb1baa..c44ca362c 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -2,12 +2,12 @@ from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.designators.object_designator import * -from pycram.worlds.datastructures.enums import ObjectType -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.enums import ObjectType +from pycram.datastructures.pose import Pose from pycram.process_module import simulated_robot, with_simulated_robot from pycram.object_descriptors.urdf import ObjectDescription -from pycram.worlds.concepts.world_object import Object -from pycram.worlds.datastructures.dataclasses import Color +from pycram.world_concepts.world_object import Object +from pycram.datastructures.dataclasses import Color extension = ObjectDescription.get_file_extension() diff --git a/demos/pycram_ur5_demo/demo.py b/demos/pycram_ur5_demo/demo.py index b0cc4358e..a9839ea4d 100644 --- a/demos/pycram_ur5_demo/demo.py +++ b/demos/pycram_ur5_demo/demo.py @@ -6,7 +6,7 @@ from pycram.worlds.bullet_world import BulletWorld from pycram.world import Object -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.ros.force_torque_sensor import ForceTorqueSensor from pycram.ros.joint_state_publisher import JointStatePublisher from pycram.ros.tf_broadcaster import TFBroadcaster diff --git a/src/neem_interface_python b/src/neem_interface_python index 285033958..899d74eca 160000 --- a/src/neem_interface_python +++ b/src/neem_interface_python @@ -1 +1 @@ -Subproject commit 28503395862f676fc2ad19877559673bd988fd07 +Subproject commit 899d74eca6c34d8bb53202d41677fdae9ee9d0a6 diff --git a/src/pycram/worlds/concepts/cache_manager.py b/src/pycram/cache_manager.py similarity index 100% rename from src/pycram/worlds/concepts/cache_manager.py rename to src/pycram/cache_manager.py diff --git a/src/pycram/worlds/concepts/__init__.py b/src/pycram/datastructures/__init__.py similarity index 100% rename from src/pycram/worlds/concepts/__init__.py rename to src/pycram/datastructures/__init__.py diff --git a/src/pycram/worlds/datastructures/dataclasses.py b/src/pycram/datastructures/dataclasses.py similarity index 96% rename from src/pycram/worlds/datastructures/dataclasses.py rename to src/pycram/datastructures/dataclasses.py index c41a41b50..b67833fbc 100644 --- a/src/pycram/worlds/datastructures/dataclasses.py +++ b/src/pycram/datastructures/dataclasses.py @@ -2,14 +2,14 @@ from dataclasses import dataclass from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING -from pycram.worlds.datastructures.enums import JointType, Shape -from pycram.worlds.datastructures.pose import Pose, Point +from pycram.datastructures.enums import JointType, Shape +from pycram.datastructures.pose import Pose, Point from abc import ABC, abstractmethod if TYPE_CHECKING: from pycram.description import Link - from pycram.worlds.concepts.world_object import Object - from pycram.worlds.concepts.constraints import Attachment + from pycram.world_concepts.world_object import Object + from pycram.world_concepts.constraints import Attachment def get_point_as_list(point: Point) -> List[float]: diff --git a/src/pycram/worlds/datastructures/enums.py b/src/pycram/datastructures/enums.py similarity index 100% rename from src/pycram/worlds/datastructures/enums.py rename to src/pycram/datastructures/enums.py diff --git a/src/pycram/worlds/datastructures/local_transformer.py b/src/pycram/datastructures/local_transformer.py similarity index 98% rename from src/pycram/worlds/datastructures/local_transformer.py rename to src/pycram/datastructures/local_transformer.py index 635a6fa38..59a9f594d 100644 --- a/src/pycram/worlds/datastructures/local_transformer.py +++ b/src/pycram/datastructures/local_transformer.py @@ -9,7 +9,7 @@ from rospy import Duration from geometry_msgs.msg import TransformStamped -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.pose import Pose, Transform from typing_extensions import List, Optional, Union, Iterable diff --git a/src/pycram/worlds/datastructures/pose.py b/src/pycram/datastructures/pose.py similarity index 100% rename from src/pycram/worlds/datastructures/pose.py rename to src/pycram/datastructures/pose.py diff --git a/src/pycram/description.py b/src/pycram/description.py index dc11387ea..f10a8efd0 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -8,14 +8,14 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING -from pycram.worlds.datastructures.enums import JointType -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.enums import JointType +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose, Transform from pycram.world import WorldEntity -from pycram.worlds.datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape +from pycram.datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape if TYPE_CHECKING: - from pycram.worlds.concepts.world_object import Object + from pycram.world_concepts.world_object import Object class EntityDescription(ABC): diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 6b1743d64..eec2b4e87 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -9,17 +9,17 @@ import rospy from pycram.world import World -from pycram.worlds.concepts.world_object import Object as WorldObject +from pycram.world_concepts.world_object import Object as WorldObject from .helper import GeneratorList, bcolors from threading import Lock from time import time from typing_extensions import List, Dict, Any, Optional, Union, get_type_hints, Callable, Iterable -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from .language import Language -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from .robot_descriptions import robot_description -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType import logging diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index 987a787a2..8cff34ed4 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -6,7 +6,7 @@ from .location_designator import CostmapLocation from .motion_designator import * from .object_designator import ObjectDesignatorDescription, BelieveObject, ObjectPart -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from ..orm.action_designator import (ParkArmsAction as ORMParkArmsAction, NavigateAction as ORMNavigateAction, PickUpAction as ORMPickUpAction, PlaceAction as ORMPlaceAction, MoveTorsoAction as ORMMoveTorsoAction, SetGripperAction as ORMSetGripperAction, @@ -19,10 +19,10 @@ from ..plan_failures import ObjectUnfetchable, ReachabilityFailure from ..robot_descriptions import robot_description from ..task import with_tree -from pycram.worlds.datastructures.enums import Arms +from pycram.datastructures.enums import Arms from ..designator import ActionDesignatorDescription from pycram.world import World -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from ..helper import multiply_quaternions diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index cc78cedc5..810c94d0f 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -5,14 +5,14 @@ from pycram.world import World, UseProspectionWorld from pycram.world_reasoning import link_pose_for_joint_config from ..designator import DesignatorError, LocationDesignatorDescription -from pycram.worlds.concepts.costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap +from pycram.world_concepts.costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap from ..robot_descriptions import robot_description -from pycram.worlds.datastructures.enums import JointType +from pycram.datastructures.enums import JointType from ..helper import transform from pycram.pose_generator_and_validator import pose_generator, visibility_validator, reachability_validator, \ generate_orientation from ..robot_description import ManipulatorDescription -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose class Location(LocationDesignatorDescription): diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index f24cb0f05..6b439996f 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -3,7 +3,7 @@ from sqlalchemy.orm import Session from .object_designator import ObjectDesignatorDescription, ObjectPart, RealObject from pycram.world import World -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from ..designator import DesignatorError from ..plan_failures import PerceptionObjectNotFound from ..process_module import ProcessModuleManager @@ -13,10 +13,10 @@ MoveTCPMotion as ORMMoveTCPMotion, LookingMotion as ORMLookingMotion, MoveGripperMotion as ORMMoveGripperMotion, DetectingMotion as ORMDetectingMotion, OpeningMotion as ORMOpeningMotion, ClosingMotion as ORMClosingMotion) -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType from typing_extensions import List, Dict, Callable, Optional -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from ..task import with_tree diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 6826eef00..6fcb5c40e 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -2,11 +2,11 @@ from typing_extensions import List, Optional, Callable import sqlalchemy.orm from pycram.world import World -from pycram.worlds.concepts.world_object import Object as WorldObject +from pycram.world_concepts.world_object import Object as WorldObject from ..designator import ObjectDesignatorDescription from ..orm.base import ProcessMetaData from ..orm.object_designator import (BelieveObject as ORMBelieveObject, ObjectPart as ORMObjectPart) -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from ..external_interfaces.robokudo import query diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index ce1afabec..bd88af990 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -5,11 +5,11 @@ import sys import rosnode -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from ..robot_descriptions import robot_description from pycram.world import World -from pycram.worlds.datastructures.dataclasses import MeshVisualShape -from pycram.worlds.concepts.world_object import Object +from pycram.datastructures.dataclasses import MeshVisualShape +from pycram.world_concepts.world_object import Object from ..robot_description import ManipulatorDescription from typing_extensions import List, Dict, Callable, Optional diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index c70a6469c..1d98a30a1 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -6,10 +6,10 @@ from moveit_msgs.srv import GetPositionIK from sensor_msgs.msg import JointState -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from ..helper import calculate_wrist_tool_offset, _apply_ik -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose from ..robot_descriptions import robot_description from ..plan_failures import IKError diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index 531c0eb6f..23c571cbc 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -6,10 +6,10 @@ import rosnode from ..designator import ObjectDesignatorDescription -from pycram.worlds.datastructures.pose import Pose -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose +from pycram.datastructures.local_transformer import LocalTransformer from pycram.world import World -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType try: from robokudo_msgs.msg import ObjectDesignator as robokudo_ObjetDesignator diff --git a/src/pycram/helper.py b/src/pycram/helper.py index 0da52632a..672d9951f 100644 --- a/src/pycram/helper.py +++ b/src/pycram/helper.py @@ -13,8 +13,8 @@ from pytransform3d.rotations import quaternion_wxyz_from_xyzw, quaternion_xyzw_from_wxyz from pytransform3d.transformations import transform_from_pq, transform_from, pq_from_transform -from pycram.worlds.concepts.world_object import Object as WorldObject -from pycram.worlds.datastructures.pose import Transform, Pose +from pycram.world_concepts.world_object import Object as WorldObject +from pycram.datastructures.pose import Transform, Pose import math diff --git a/src/pycram/language.py b/src/pycram/language.py index 310f8ce1b..8786f9309 100644 --- a/src/pycram/language.py +++ b/src/pycram/language.py @@ -5,7 +5,7 @@ from typing_extensions import Iterable, Optional, Callable, Dict, Any, List, Union from anytree import NodeMixin, Node, PreOrderIter -from pycram.worlds.datastructures.enums import State +from pycram.datastructures.enums import State import threading from .fluent import Fluent diff --git a/src/pycram/object_descriptors/urdf.py b/src/pycram/object_descriptors/urdf.py index b2905e170..4db166b3b 100644 --- a/src/pycram/object_descriptors/urdf.py +++ b/src/pycram/object_descriptors/urdf.py @@ -10,11 +10,11 @@ from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, Sphere as URDF_Sphere, Mesh as URDF_Mesh) -from pycram.worlds.datastructures.enums import JointType, Shape -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.enums import JointType, Shape +from pycram.datastructures.pose import Pose from pycram.description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription -from pycram.worlds.datastructures.dataclasses import Color +from pycram.datastructures.dataclasses import Color class LinkDescription(AbstractLinkDescription): diff --git a/src/pycram/orm/action_designator.py b/src/pycram/orm/action_designator.py index 7bbaa0525..527fade81 100644 --- a/src/pycram/orm/action_designator.py +++ b/src/pycram/orm/action_designator.py @@ -2,7 +2,7 @@ from .base import RobotState, Designator, MapperArgsMixin, PoseMixin from .object_designator import ObjectMixin -from pycram.worlds.datastructures.enums import Arms +from pycram.datastructures.enums import Arms from sqlalchemy.orm import Mapped, mapped_column, relationship from sqlalchemy import ForeignKey diff --git a/src/pycram/orm/base.py b/src/pycram/orm/base.py index 61a6ab39a..e076fc929 100644 --- a/src/pycram/orm/base.py +++ b/src/pycram/orm/base.py @@ -10,7 +10,7 @@ from sqlalchemy.orm import DeclarativeBase, Mapped, MappedAsDataclass, mapped_column, Session, relationship, \ declared_attr -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType def get_pycram_version_from_git() -> Optional[str]: diff --git a/src/pycram/orm/motion_designator.py b/src/pycram/orm/motion_designator.py index af67aeb9e..bada973b4 100644 --- a/src/pycram/orm/motion_designator.py +++ b/src/pycram/orm/motion_designator.py @@ -12,7 +12,7 @@ from sqlalchemy.orm import Mapped, mapped_column, relationship from sqlalchemy import ForeignKey -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType class Motion(MapperArgsMixin, Designator): diff --git a/src/pycram/orm/object_designator.py b/src/pycram/orm/object_designator.py index 776ab59ce..ff7fd0665 100644 --- a/src/pycram/orm/object_designator.py +++ b/src/pycram/orm/object_designator.py @@ -2,7 +2,7 @@ from pycram.orm.base import Base, MapperArgsMixin, PoseMixin from sqlalchemy.orm import Mapped, mapped_column, declared_attr, relationship from sqlalchemy import ForeignKey -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType class ObjectMixin: """ diff --git a/src/pycram/orm/task.py b/src/pycram/orm/task.py index d821a2a5d..427fee0a2 100644 --- a/src/pycram/orm/task.py +++ b/src/pycram/orm/task.py @@ -3,7 +3,7 @@ from sqlalchemy import ForeignKey from sqlalchemy.orm import Mapped, mapped_column, relationship from .base import Base, Designator -from pycram.worlds.datastructures.enums import TaskStatus +from pycram.datastructures.enums import TaskStatus import datetime diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 96f1bf26f..fc2e0fff1 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -2,10 +2,10 @@ import numpy as np from pycram.world import World -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram.world_reasoning import contact -from pycram.worlds.concepts.costmaps import Costmap -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.world_concepts.costmaps import Costmap +from pycram.datastructures.pose import Pose, Transform from pycram.robot_descriptions import robot_description from pycram.external_interfaces.ik import request_ik from pycram.plan_failures import IKError diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index f0aecef08..366cac9dd 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -4,7 +4,7 @@ from pycram.world import World from ..designators.motion_designator import PlaceMotion -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description from ..process_modules.pr2_process_modules import (_park_arms, Pr2Navigation as BoxyNavigation, diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 8993b10d2..9ee40414d 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -9,7 +9,7 @@ Pr2MoveTCP as DefaultMoveTCP from ..robot_descriptions import robot_description from pycram.world import World -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from ..designators.motion_designator import LookingMotion, MoveArmJointsMotion, MoveJointsMotion diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 41a8704b9..7371a8876 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -5,7 +5,7 @@ from pycram.worlds.bullet_world import World from ..designators.motion_designator import MoveArmJointsMotion, WorldStateDetectingMotion -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description from ..process_modules.pr2_process_modules import Pr2PickUp, Pr2Detecting as DonbotDetecting, _move_arm_tcp diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 75cb82e72..871c4b808 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -4,7 +4,7 @@ from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager from pycram.world import World -from pycram.worlds.datastructures.pose import Pose, Point +from pycram.datastructures.pose import Pose, Point from ..helper import _apply_ik from ..external_interfaces.ik import request_ik from .. import world_reasoning as btr diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 204b3d1b8..784f18385 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -12,16 +12,16 @@ from ..process_module import ProcessModule, ProcessModuleManager from ..external_interfaces.ik import request_ik from ..helper import _apply_ik -from pycram.worlds.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from ..designators.object_designator import ObjectDesignatorDescription from ..designators.motion_designator import MoveMotion, PickUpMotion, PlaceMotion, LookingMotion, \ DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ MoveGripperMotion, OpeningMotion, ClosingMotion, MotionDesignatorDescription from ..robot_descriptions import robot_description from pycram.world import World -from pycram.worlds.concepts.world_object import Object -from pycram.worlds.datastructures.pose import Pose -from pycram.worlds.datastructures.enums import JointType, ObjectType +from pycram.world_concepts.world_object import Object +from pycram.datastructures.pose import Pose +from pycram.datastructures.enums import JointType, ObjectType from ..external_interfaces import giskard from ..external_interfaces.robokudo import query diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 4c205bbbb..3c9beb519 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -4,14 +4,14 @@ from tf import transformations import pycram.designators.location_designator import pycram.task -from pycram.worlds.concepts.costmaps import OccupancyCostmap +from pycram.world_concepts.costmaps import OccupancyCostmap from pycram.orm.action_designator import PickUpAction from pycram.orm.object_designator import Object from pycram.orm.base import Position, RobotState from pycram.orm.task import TaskTreeNode, Code from .jpt_location import JPTCostmapLocation from ... import orm -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose class DatabaseCostmapLocation(pycram.designators.location_designator.CostmapLocation): diff --git a/src/pycram/resolver/location/giskard_location.py b/src/pycram/resolver/location/giskard_location.py index 506e3503c..3d8ee79ec 100644 --- a/src/pycram/resolver/location/giskard_location.py +++ b/src/pycram/resolver/location/giskard_location.py @@ -1,7 +1,7 @@ from ...external_interfaces.giskard import achieve_cartesian_goal from ...designators.location_designator import CostmapLocation from pycram.world import UseProspectionWorld, World -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from ...robot_descriptions import robot_description from pycram.pose_generator_and_validator import reachability_validator from typing_extensions import Tuple, Dict diff --git a/src/pycram/resolver/location/jpt_location.py b/src/pycram/resolver/location/jpt_location.py index 73aa3a6f7..bd71413ae 100644 --- a/src/pycram/resolver/location/jpt_location.py +++ b/src/pycram/resolver/location/jpt_location.py @@ -6,10 +6,10 @@ import tf from ...designators import location_designator -from pycram.worlds.concepts.costmaps import OccupancyCostmap -from pycram.worlds.datastructures.pose import Pose +from pycram.world_concepts.costmaps import OccupancyCostmap +from pycram.datastructures.pose import Pose from pycram.world import Object, World -from pycram.worlds.datastructures.dataclasses import BoxVisualShape, Color +from pycram.datastructures.dataclasses import BoxVisualShape, Color class JPTCostmapLocation(location_designator.CostmapLocation): diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index e1400fb5b..8c8a8e43b 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -7,7 +7,7 @@ from sensor_msgs.msg import JointState from pycram.world import World from ..robot_descriptions import robot_description -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose class RobotStateUpdater: diff --git a/src/pycram/ros/tf_broadcaster.py b/src/pycram/ros/tf_broadcaster.py index c698f9b8b..ab14c1297 100644 --- a/src/pycram/ros/tf_broadcaster.py +++ b/src/pycram/ros/tf_broadcaster.py @@ -3,7 +3,7 @@ import threading import atexit -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.world import World from tf2_msgs.msg import TFMessage diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 317af4724..1b98da46c 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -9,8 +9,8 @@ from visualization_msgs.msg import MarkerArray, Marker import rospy -from pycram.worlds.datastructures.pose import Transform -from pycram.worlds.datastructures.dataclasses import MeshVisualShape, CylinderVisualShape, BoxVisualShape, SphereVisualShape +from pycram.datastructures.pose import Transform +from pycram.datastructures.dataclasses import MeshVisualShape, CylinderVisualShape, BoxVisualShape, SphereVisualShape class VizMarkerPublisher: diff --git a/src/pycram/task.py b/src/pycram/task.py index de870493f..415d7d68c 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -18,8 +18,8 @@ from .orm.base import ProcessMetaData from .plan_failures import PlanFailure from .language import Code -from pycram.worlds.datastructures.enums import TaskStatus -from pycram.worlds.datastructures.dataclasses import Color +from pycram.datastructures.enums import TaskStatus +from pycram.datastructures.dataclasses import Color class TaskCode(Code): diff --git a/src/pycram/world.py b/src/pycram/world.py index 3df891777..97e4361f7 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -14,19 +14,19 @@ from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING from typing_extensions import Union -from pycram.worlds.concepts.cache_manager import CacheManager -from pycram.worlds.datastructures.enums import JointType, ObjectType, WorldMode -from pycram.worlds.concepts.event import Event -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose, Transform -from pycram.worlds.concepts.constraints import Constraint -from pycram.worlds.datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, - MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, - CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, - ObjectState, State, WorldState) +from pycram.cache_manager import CacheManager +from pycram.datastructures.enums import JointType, ObjectType, WorldMode +from pycram.world_concepts.event import Event +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose, Transform +from pycram.world_concepts.constraints import Constraint +from pycram.datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, + MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, + CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, + ObjectState, State, WorldState) if TYPE_CHECKING: - from pycram.worlds.concepts.world_object import Object + from pycram.world_concepts.world_object import Object from pycram.description import Link, Joint diff --git a/src/pycram/world_concepts/__init__.py b/src/pycram/world_concepts/__init__.py new file mode 100644 index 000000000..8b1378917 --- /dev/null +++ b/src/pycram/world_concepts/__init__.py @@ -0,0 +1 @@ + diff --git a/src/pycram/worlds/concepts/constraints.py b/src/pycram/world_concepts/constraints.py similarity index 98% rename from src/pycram/worlds/concepts/constraints.py rename to src/pycram/world_concepts/constraints.py index c36b733a2..540155ff5 100644 --- a/src/pycram/worlds/concepts/constraints.py +++ b/src/pycram/world_concepts/constraints.py @@ -3,8 +3,8 @@ from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional, TYPE_CHECKING -from pycram.worlds.datastructures.enums import JointType -from pycram.worlds.datastructures.pose import Transform, Pose +from pycram.datastructures.enums import JointType +from pycram.datastructures.pose import Transform, Pose if TYPE_CHECKING: from pycram.description import Link diff --git a/src/pycram/worlds/concepts/costmaps.py b/src/pycram/world_concepts/costmaps.py similarity index 99% rename from src/pycram/worlds/concepts/costmaps.py rename to src/pycram/world_concepts/costmaps.py index 8411e5fa0..7f714afa8 100644 --- a/src/pycram/worlds/concepts/costmaps.py +++ b/src/pycram/world_concepts/costmaps.py @@ -11,12 +11,12 @@ from nav_msgs.msg import OccupancyGrid, MapMetaData from pycram.world import UseProspectionWorld -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram.description import Link -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose, Transform from pycram.world import World -from pycram.worlds.datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color +from pycram.datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color class Costmap: diff --git a/src/pycram/worlds/concepts/event.py b/src/pycram/world_concepts/event.py similarity index 100% rename from src/pycram/worlds/concepts/event.py rename to src/pycram/world_concepts/event.py diff --git a/src/pycram/worlds/concepts/world_object.py b/src/pycram/world_concepts/world_object.py similarity index 98% rename from src/pycram/worlds/concepts/world_object.py rename to src/pycram/world_concepts/world_object.py index 71b05579c..3f9757b1a 100644 --- a/src/pycram/worlds/concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -12,12 +12,12 @@ from pycram.object_descriptors.urdf import ObjectDescription as URDFObject from pycram.robot_descriptions import robot_description from pycram.world import WorldEntity, World -from pycram.worlds.concepts.constraints import Attachment -from pycram.worlds.datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, - AxisAlignedBoundingBox, VisualShape) -from pycram.worlds.datastructures.enums import ObjectType, JointType -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.world_concepts.constraints import Attachment +from pycram.datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, + AxisAlignedBoundingBox, VisualShape) +from pycram.datastructures.enums import ObjectType, JointType +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose, Transform Link = ObjectDescription.Link diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 27111daa7..7e7d89712 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -4,9 +4,9 @@ import numpy as np from pycram.external_interfaces.ik import try_to_reach, try_to_reach_with_grasp -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.pose import Pose, Transform from pycram.robot_descriptions import robot_description -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram.world import World, UseProspectionWorld diff --git a/src/pycram/worlds/bullet_world.py b/src/pycram/worlds/bullet_world.py index addb57190..0013a52d5 100755 --- a/src/pycram/worlds/bullet_world.py +++ b/src/pycram/worlds/bullet_world.py @@ -11,13 +11,13 @@ from geometry_msgs.msg import Point from typing_extensions import List, Optional, Dict -from pycram.worlds.datastructures.enums import ObjectType, WorldMode, JointType -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.enums import ObjectType, WorldMode, JointType +from pycram.datastructures.pose import Pose from pycram.object_descriptors.urdf import ObjectDescription from pycram.world import World -from pycram.worlds.concepts.constraints import Constraint -from pycram.worlds.datastructures.dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.constraints import Constraint +from pycram.datastructures.dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape +from pycram.world_concepts.world_object import Object Link = ObjectDescription.Link RootLink = ObjectDescription.RootLink diff --git a/src/pycram/worlds/datastructures/__init__.py b/src/pycram/worlds/datastructures/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 46144af36..3b8ae3ea7 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -2,11 +2,11 @@ import unittest from pycram.worlds.bullet_world import BulletWorld -from pycram.worlds.concepts.world_object import Object -from pycram.worlds.datastructures.pose import Pose +from pycram.world_concepts.world_object import Object +from pycram.datastructures.pose import Pose from pycram.robot_descriptions import robot_description from pycram.process_module import ProcessModule -from pycram.worlds.datastructures.enums import ObjectType, WorldMode +from pycram.datastructures.enums import ObjectType, WorldMode from pycram.object_descriptors.urdf import ObjectDescription diff --git a/test/test_action_designator.py b/test/test_action_designator.py index 656df74b8..363ae8602 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -2,8 +2,8 @@ from pycram.designators import action_designator, object_designator from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot -from pycram.worlds.datastructures.pose import Pose -from pycram.worlds.datastructures.enums import ObjectType, Arms +from pycram.datastructures.pose import Pose +from pycram.datastructures.enums import ObjectType, Arms from bullet_world_testcase import BulletWorldTestCase import numpy as np diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index 058adb0c4..bf0c5d75e 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -5,12 +5,12 @@ import rospkg from bullet_world_testcase import BulletWorldTestCase, BulletWorldGUITestCase -from pycram.worlds.datastructures.enums import ObjectType, WorldMode -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.enums import ObjectType, WorldMode +from pycram.datastructures.pose import Pose from pycram.robot_descriptions import robot_description from pycram.object_descriptors.urdf import ObjectDescription -from pycram.worlds.datastructures.dataclasses import Color -from pycram.worlds.concepts.world_object import Object +from pycram.datastructures.dataclasses import Color +from pycram.world_concepts.world_object import Object fix_missing_inertial = ObjectDescription.fix_missing_inertial diff --git a/test/test_bullet_world_reasoning.py b/test/test_bullet_world_reasoning.py index 4438d37ce..660c9682b 100644 --- a/test/test_bullet_world_reasoning.py +++ b/test/test_bullet_world_reasoning.py @@ -2,7 +2,7 @@ import pycram.world_reasoning as btr from bullet_world_testcase import BulletWorldTestCase -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.robot_descriptions import robot_description use_new = True diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py index ef126f2eb..0a4ac8524 100644 --- a/test/test_cache_manager.py +++ b/test/test_cache_manager.py @@ -1,8 +1,8 @@ from pathlib import Path from bullet_world_testcase import BulletWorldTestCase -from pycram.worlds.datastructures.enums import ObjectType -from pycram.worlds.concepts.world_object import Object +from pycram.datastructures.enums import ObjectType +from pycram.world_concepts.world_object import Object class TestCacheManager(BulletWorldTestCase): diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 1bffb32c2..429021dec 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -1,8 +1,8 @@ import numpy as np from bullet_world_testcase import BulletWorldTestCase -from pycram.worlds.concepts.costmaps import OccupancyCostmap -from pycram.worlds.datastructures.pose import Pose +from pycram.world_concepts.costmaps import OccupancyCostmap +from pycram.datastructures.pose import Pose class TestCostmapsCase(BulletWorldTestCase): diff --git a/test/test_database_merger.py b/test/test_database_merger.py index fbe396431..c0d3018f5 100644 --- a/test/test_database_merger.py +++ b/test/test_database_merger.py @@ -8,11 +8,11 @@ from pycram.designators.action_designator import * from pycram.designators.location_designator import * from pycram.process_module import simulated_robot -from pycram.worlds.datastructures.enums import Arms, ObjectType, WorldMode +from pycram.datastructures.enums import Arms, ObjectType, WorldMode from pycram.task import with_tree import pycram.task from pycram.worlds.bullet_world import BulletWorld -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram.designators.object_designator import * from dataclasses import dataclass, field diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 2809396d2..ce458b127 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -3,17 +3,17 @@ import sqlalchemy import sqlalchemy.orm import pycram.plan_failures -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram import task from pycram.world import World from pycram.designators import action_designator, object_designator from pycram.orm.base import Base from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.robot_descriptions import robot_description from pycram.task import with_tree -from pycram.worlds.datastructures.enums import ObjectType, WorldMode +from pycram.datastructures.enums import ObjectType, WorldMode # check if jpt is installed jpt_installed = True diff --git a/test/test_failure_handling.py b/test/test_failure_handling.py index bd7f36258..9008431e6 100644 --- a/test/test_failure_handling.py +++ b/test/test_failure_handling.py @@ -5,7 +5,7 @@ from pycram.worlds.bullet_world import BulletWorld, Object from pycram.designator import ActionDesignatorDescription from pycram.designators.action_designator import ParkArmsAction -from pycram.worlds.datastructures.enums import ObjectType, Arms, WorldMode +from pycram.datastructures.enums import ObjectType, Arms, WorldMode from pycram.failure_handling import Retry from pycram.plan_failures import PlanFailure from pycram.process_module import ProcessModule, simulated_robot diff --git a/test/test_jpt_resolver.py b/test/test_jpt_resolver.py index 534d6e4e3..b20cb64f1 100644 --- a/test/test_jpt_resolver.py +++ b/test/test_jpt_resolver.py @@ -6,13 +6,13 @@ import pycram.plan_failures from pycram.worlds.bullet_world import BulletWorld -from pycram.worlds.concepts.world_object import Object +from pycram.world_concepts.world_object import Object from pycram.designators import action_designator, object_designator from pycram.process_module import ProcessModule from pycram.process_module import simulated_robot from pycram.robot_descriptions import robot_description -from pycram.worlds.datastructures.pose import Pose -from pycram.worlds.datastructures.enums import WorldMode +from pycram.datastructures.pose import Pose +from pycram.datastructures.enums import WorldMode # check if jpt is installed jpt_installed = True diff --git a/test/test_language.py b/test/test_language.py index 458fbe0ac..4dcfa6d3e 100644 --- a/test/test_language.py +++ b/test/test_language.py @@ -2,10 +2,10 @@ import time import unittest from pycram.designators.action_designator import * -from pycram.worlds.datastructures.enums import ObjectType, State +from pycram.datastructures.enums import ObjectType, State from pycram.fluent import Fluent from pycram.plan_failures import PlanFailure -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.language import Sequential, Language, Parallel, TryAll, TryInOrder, Monitor, Code from pycram.process_module import simulated_robot from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_links.py b/test/test_links.py index f737a55ce..695e670c1 100644 --- a/test/test_links.py +++ b/test/test_links.py @@ -1,5 +1,5 @@ from bullet_world_testcase import BulletWorldTestCase -from pycram.worlds.datastructures.dataclasses import Color +from pycram.datastructures.dataclasses import Color class TestLinks(BulletWorldTestCase): diff --git a/test/test_local_transformer.py b/test/test_local_transformer.py index afaac7a71..e64682d0d 100644 --- a/test/test_local_transformer.py +++ b/test/test_local_transformer.py @@ -1,8 +1,8 @@ import rospy -from pycram.worlds.datastructures.local_transformer import LocalTransformer -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.local_transformer import LocalTransformer +from pycram.datastructures.pose import Pose, Transform from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_location_designator.py b/test/test_location_designator.py index 54860a746..714f8ad54 100644 --- a/test/test_location_designator.py +++ b/test/test_location_designator.py @@ -1,6 +1,6 @@ from pycram.designators.location_designator import * from pycram.robot_descriptions import robot_description -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from bullet_world_testcase import BulletWorldTestCase diff --git a/test/test_object.py b/test/test_object.py index d0c0ee12b..5c71fc347 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -2,10 +2,10 @@ from bullet_world_testcase import BulletWorldTestCase -from pycram.worlds.datastructures.enums import JointType, ObjectType -from pycram.worlds.datastructures.pose import Pose -from pycram.worlds.datastructures.dataclasses import Color -from pycram.worlds.concepts.world_object import Object +from pycram.datastructures.enums import JointType, ObjectType +from pycram.datastructures.pose import Pose +from pycram.datastructures.dataclasses import Color +from pycram.world_concepts.world_object import Object from geometry_msgs.msg import Point, Quaternion diff --git a/test/test_object_designator.py b/test/test_object_designator.py index 695fc6b84..f85b036f4 100644 --- a/test/test_object_designator.py +++ b/test/test_object_designator.py @@ -1,7 +1,7 @@ import unittest from bullet_world_testcase import BulletWorldTestCase from pycram.designators.object_designator import * -from pycram.worlds.datastructures.enums import ObjectType +from pycram.datastructures.enums import ObjectType class TestObjectDesignator(BulletWorldTestCase): diff --git a/test/test_orm.py b/test/test_orm.py index f8697b78e..c2bd6d544 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -13,7 +13,7 @@ from bullet_world_testcase import BulletWorldTestCase import test_task_tree from pycram.designators import action_designator, object_designator -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.process_module import simulated_robot from pycram.task import with_tree diff --git a/test/test_pose.py b/test/test_pose.py index c6ce5a63e..5cee8c022 100644 --- a/test/test_pose.py +++ b/test/test_pose.py @@ -1,6 +1,6 @@ import unittest -from pycram.worlds.datastructures.pose import Pose, Transform +from pycram.datastructures.pose import Pose, Transform class TestPose(unittest.TestCase): diff --git a/test/test_task_tree.py b/test/test_task_tree.py index ee06fd717..9a0a6bd45 100644 --- a/test/test_task_tree.py +++ b/test/test_task_tree.py @@ -1,4 +1,4 @@ -from pycram.worlds.datastructures.pose import Pose +from pycram.datastructures.pose import Pose from pycram.process_module import simulated_robot import pycram.task from pycram.task import with_tree From db2d5a92c5675f6df394f0b01bf91f8b714c2237 Mon Sep 17 00:00:00 2001 From: "Nyi Nyein Aung (Leo)" <114857318+leonyi4@users.noreply.github.com> Date: Wed, 20 Mar 2024 09:30:35 +0100 Subject: [PATCH 132/195] [ci] update ci pipeline hardcode docker image into workflow --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 35e1142df..07678b99d 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -24,7 +24,7 @@ jobs: build_and_run_tests: runs-on: ubuntu-20.04 container: - image: ${{ vars.DOCKER_IMAGE}} #add docker image variable to repo + image: "pycram/pycram:dev" steps: - name: Checkout PyCRAM uses: actions/checkout@v3 From 4155d6af9feabf1681ab39c16b2b25510bae8939 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 21 Mar 2024 09:52:28 +0100 Subject: [PATCH 133/195] [AbstractWorld] Fixed viz_marker_publisher.py to use VisualShape for geometry. --- src/pycram/datastructures/enums.py | 4 +-- src/pycram/datastructures/pose.py | 4 +-- src/pycram/description.py | 2 +- src/pycram/object_descriptors/urdf.py | 41 ++++++++++++++++------- src/pycram/ros/viz_marker_publisher.py | 4 +-- src/pycram/world_concepts/world_object.py | 2 +- 6 files changed, 36 insertions(+), 21 deletions(-) diff --git a/src/pycram/datastructures/enums.py b/src/pycram/datastructures/enums.py index 2f03e422b..a6867246f 100644 --- a/src/pycram/datastructures/enums.py +++ b/src/pycram/datastructures/enums.py @@ -19,6 +19,7 @@ class TaskStatus(Enum): SUCCEEDED = 2 FAILED = 3 + class JointType(Enum): """ Enum for readable joint types. @@ -32,9 +33,6 @@ class JointType(Enum): CONTINUOUS = 6 FLOATING = 7 - # override enum method to return an int - - class Grasp(Enum): """ diff --git a/src/pycram/datastructures/pose.py b/src/pycram/datastructures/pose.py index 79eadaeef..7927ea277 100644 --- a/src/pycram/datastructures/pose.py +++ b/src/pycram/datastructures/pose.py @@ -58,10 +58,10 @@ def __init__(self, position: Optional[List[float]] = None, orientation: Optional :param time: The time at which this Pose is valid, as ROS time """ super().__init__() - if position: + if position is not None: self.position = position - if orientation: + if orientation is not None: self.orientation = orientation else: self.pose.orientation.w = 1.0 diff --git a/src/pycram/description.py b/src/pycram/description.py index f10a8efd0..0bd412e54 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -51,7 +51,7 @@ def __init__(self, parsed_link_description: Any): @property @abstractmethod - def geometry(self) -> VisualShape: + def geometry(self) -> Union[VisualShape, None]: """ Returns the geometry type of the collision element of this link. """ diff --git a/src/pycram/object_descriptors/urdf.py b/src/pycram/object_descriptors/urdf.py index 4db166b3b..47b76931a 100644 --- a/src/pycram/object_descriptors/urdf.py +++ b/src/pycram/object_descriptors/urdf.py @@ -10,38 +10,55 @@ from urdf_parser_py.urdf import (URDF, Collision, Box as URDF_Box, Cylinder as URDF_Cylinder, Sphere as URDF_Sphere, Mesh as URDF_Mesh) -from pycram.datastructures.enums import JointType, Shape +from pycram.datastructures.enums import JointType from pycram.datastructures.pose import Pose from pycram.description import JointDescription as AbstractJointDescription, \ LinkDescription as AbstractLinkDescription, ObjectDescription as AbstractObjectDescription -from pycram.datastructures.dataclasses import Color +from pycram.datastructures.dataclasses import Color, VisualShape, BoxVisualShape, CylinderVisualShape, \ + SphereVisualShape, MeshVisualShape class LinkDescription(AbstractLinkDescription): """ A class that represents a link description of an object. """ - urdf_shape_map = { - URDF_Box: Shape.BOX, - URDF_Cylinder: Shape.CYLINDER, - URDF_Sphere: Shape.SPHERE, - URDF_Mesh: Shape.MESH - } def __init__(self, urdf_description: urdf.Link): super().__init__(urdf_description) @property - def geometry(self) -> Union[Shape, None]: + def geometry(self) -> Union[VisualShape, None]: """ Returns the geometry type of the URDF collision element of this link. """ - return self.urdf_shape_map[type(self.collision.geometry)] + if self.collision is None: + return None + urdf_geometry = self.collision.geometry + return self._get_visual_shape(urdf_geometry) + + @staticmethod + def _get_visual_shape(urdf_geometry) -> Union[VisualShape, None]: + """ + Returns the VisualShape of the given URDF geometry. + """ + if isinstance(urdf_geometry, URDF_Box): + return BoxVisualShape(Color(), [0, 0, 0], urdf_geometry.size) + if isinstance(urdf_geometry, URDF_Cylinder): + return CylinderVisualShape(Color(), [0, 0, 0], urdf_geometry.radius, urdf_geometry.length) + if isinstance(urdf_geometry, URDF_Sphere): + return SphereVisualShape(Color(), [0, 0, 0], urdf_geometry.radius) + if isinstance(urdf_geometry, URDF_Mesh): + return MeshVisualShape(Color(), [0, 0, 0], urdf_geometry.scale, urdf_geometry.filename) + return None @property - def origin(self) -> Pose: + def origin(self) -> Union[Pose, None]: + if self.collision is None: + return None + if self.collision.origin is None: + return None return Pose(self.collision.origin.xyz, - quaternion_from_euler(*self.collision.origin.rpy)) + quaternion_from_euler(*self.collision.origin.rpy).tolist()) @property def name(self) -> str: diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 1b98da46c..5b2189189 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -70,14 +70,14 @@ def _make_marker_array(self) -> MarkerArray: msg.type = Marker.MESH_RESOURCE msg.action = Marker.ADD link_pose = obj.get_link_transform(link) - if obj.get_link_origin(link): + if obj.get_link_origin(link) is not None: link_origin = obj.get_link_origin_transform(link) else: link_origin = Transform() link_pose_with_origin = link_pose * link_origin msg.pose = link_pose_with_origin.to_pose().pose - color = [1, 1, 1, 1] if obj.link_name_to_id[link] == -1 else obj.get_color() + color = [1, 1, 1, 1] if obj.link_name_to_id[link] == -1 else obj.get_link_color(link).get_rgba() msg.color = ColorRGBA(*color) msg.lifetime = rospy.Duration(1) diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index 3f9757b1a..54a80f8ae 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -286,7 +286,7 @@ def set_link_color(self, link_name: str, color: List[float]) -> None: """ self.links[link_name].color = Color.from_list(color) - def get_link_geometry(self, link_name: str) -> VisualShape: + def get_link_geometry(self, link_name: str) -> Union[VisualShape, None]: """ Returns the geometry of the link with the given name. :param link_name: The name of the link. From 5290dda3626aeea2ee4041ee4abb2004291d8023 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 21 Mar 2024 14:15:44 +0100 Subject: [PATCH 134/195] [process modules] Added stretch PMS --- src/pycram/process_modules/__init__.py | 2 + .../stretch_process_modules.py | 111 ++++++++++++++++++ 2 files changed, 113 insertions(+) create mode 100644 src/pycram/process_modules/stretch_process_modules.py diff --git a/src/pycram/process_modules/__init__.py b/src/pycram/process_modules/__init__.py index 8349b3ec5..30f5906a3 100644 --- a/src/pycram/process_modules/__init__.py +++ b/src/pycram/process_modules/__init__.py @@ -3,9 +3,11 @@ from .donbot_process_modules import DonbotManager from .hsr_process_modules import HSRBManager from .default_process_modules import DefaultManager +from .stretch_process_modules import StretchManager Pr2Manager() BoxyManager() DonbotManager() HSRBManager() DefaultManager() +StretchManager() diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py new file mode 100644 index 000000000..106373601 --- /dev/null +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -0,0 +1,111 @@ +from threading import Lock +from typing import Any + +from ..external_interfaces.ik import request_ik +from ..helper import _apply_ik +from ..pose import Pose +from ..process_module import ProcessModule, ProcessModuleManager +from ..robot_descriptions import robot_description +from ..bullet_world import BulletWorld, Object +from ..bullet_world_reasoning import visible + + +class StretchNavigate(ProcessModule): + def _execute(self, designator) -> Any: + BulletWorld.robot.set_pose(designator.target) + + +class StretchMoveHead(ProcessModule): + def _execute(self, designator) -> Any: + pass + + +class StretchMoveGripper(ProcessModule): + def _execute(self, designator) -> Any: + robot = BulletWorld.robot + gripper = designator.gripper + motion = designator.motion + for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): + robot.set_joint_state(joint, state) + + +class StretchDetect(ProcessModule): + def _execute(self, designator) -> Any: + robot = BulletWorld.robot + object_type = designator.object_type + # Should be "wide_stereo_optical_frame" + cam_frame_name = robot_description.get_camera_frame() + # should be [0, 0, 1] + front_facing_axis = robot_description.front_facing_axis + + objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + for obj in objects: + if visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): + return obj + + +class StretchMoveTCP(ProcessModule): + def _execute(self, designator) -> Any: + target = designator.target + robot = BulletWorld.robot + + _move_arm_tcp(target, robot, designator.arm) + + +class StretchMoveArmJoints(ProcessModule): + def _execute(self, designator) -> Any: + robot = BulletWorld.robot + if designator.right_arm_poses: + robot.set_joint_states(designator.right_arm_poses) + if designator.left_arm_poses: + robot.set_joint_states(designator.left_arm_poses) + + +class StretchMoveJoints(ProcessModule): + def _execute(self, designator) -> Any: + robot = BulletWorld.robot + robot.set_joint_states(dict(zip(designator.names, designator.positions))) + + +class StretchWorldStateDetecting(ProcessModule): + def _execute(self, designator) -> Any: + obj_type = designator.object_type + return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + + +class StretchOpen(ProcessModule): + def _execute(self, designator) -> Any: + pass + + +class StretchClose(ProcessModule): + def _execute(self, designator) -> Any: + pass + + +def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: + gripper = robot_description.get_tool_frame(arm) + + joints = robot_description.chains[arm].joints + + inv = request_ik(target, robot, joints, gripper) + _apply_ik(robot, inv, joints) + + +class StretchManager(ProcessModuleManager): + def __init__(self): + super().__init__("stretch") + self._navigate_lock = Lock() + self._looking_lock = Lock() + self._detecting_lock = Lock() + self._move_tcp_lock = Lock() + self._move_arm_joints_lock = Lock() + self._world_state_detecting_lock = Lock() + self._move_joints_lock = Lock() + self._move_gripper_lock = Lock() + self._open_lock = Lock() + self._close_lock = Lock() + + def navigate(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchNavigate() From 044b540bdf808a6d8d5e81fc8a258100229b3387 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 21 Mar 2024 14:16:13 +0100 Subject: [PATCH 135/195] [robot-descriptions] Added stretch description --- src/pycram/robot_descriptions/__init__.py | 3 + .../robot_descriptions/stretch_description.py | 61 +++++++++++++++++++ 2 files changed, 64 insertions(+) diff --git a/src/pycram/robot_descriptions/__init__.py b/src/pycram/robot_descriptions/__init__.py index 897e86d4d..d32c9d37f 100644 --- a/src/pycram/robot_descriptions/__init__.py +++ b/src/pycram/robot_descriptions/__init__.py @@ -9,6 +9,7 @@ from .pr2_description import PR2Description from .ur5_description import UR5Description from .tiago_description import TiagoDescription +from .stretch_description import StretchDescription from .. import utils from ..robot_description import RobotDescription @@ -61,6 +62,8 @@ def update_robot_description(robot_name=None, from_ros=None): description = UR5Description elif "tiago_dual" in robot: description = TiagoDescription + elif "stretch" in robot: + description = StretchDescription else: logger.error("(robot-description) The given robot name %s has no description class.", robot_name) return None diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index e69de29bb..fedbbd55b 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -0,0 +1,61 @@ +from ..robot_description import * + + +class StretchDescription(RobotDescription): + + def __init__(self): + super().__init__("stretch", "base_link", "base_link", "link_lift", "joint_lift") + + realsense_color = CameraDescription('camera_color_optical_frame', horizontal_angle=1.047, vertical_angle=0.785, + minimal_height=1.322, maximal_height=1.322) + + realsense_depth = CameraDescription('camera_depth_optical_frame', horizontal_angle=1.047, vertical_angle=0.785, + minimal_height=1.307, maximal_height=1.307) + + realsense_infra1 = CameraDescription('camera_infra1_optical_frame', horizontal_angle=1.047, + vertical_angle=0.785, + minimal_height=1.307, maximal_height=1.307) + realsense_infra2 = CameraDescription('camera_infra2_optical_frame', horizontal_angle=1.047, + vertical_angle=0.785, + minimal_height=1.257, maximal_height=1.257) + self.add_cameras( + {'color': realsense_color, 'depth': realsense_depth, 'infra1': realsense_infra1, + 'infra2': realsense_infra2}) + + self.front_facing_axis = [0, 0, 1] + + neck = ChainDescription("neck", ["joint_head_pan", "joint_head_tilt"], + ["link_head_pan", "link_head_tilt"]) + self.add_chain("neck", neck) + + arm_joints = ['joint_arm_l4', 'joint_arm_l3', 'joint_arm_l2', 'joint_arm_l1', 'joint_arm_l0'] + arm_links = ['link_arm_l4', 'link_arm_l3', 'link_arm_l2', 'link_arm_l1', 'link_arm_l0'] + + arm_chain_desc = ChainDescription("arm", arm_joints, arm_links) + arm_inter_desc = InteractionDescription(arm_chain_desc, "link_wrist_yaw") + + gripper_links = ['link_gripper_finger_left', 'link_gripper_fingertip_left', + 'link_gripper_finger_right', 'link_gripper_fingertip_right', 'link_grasp_center'] + gripper_joints = ['joint_gripper_finger_left', 'joint_gripper_fingertip_left', + 'joint_gripper_finger_right', 'joint_gripper_fingertip_right', 'joint_grasp_center'] + arm_gripper_desc = GripperDescription("gripper", gripper_links, gripper_joints, + gripper_meter_to_jnt_multiplier=5.0, + gripper_minimal_position=0.013, + gripper_convergence_delta=0.005) + + arm_desc = ManipulatorDescription(arm_inter_desc, tool_frame="link_grasp_center", gripper_description=arm_gripper_desc) + self.add_chain("arm", arm_desc) + + arm_park = [0.0, 0.0, 0.0, 0.0, 0.0] + self.add_static_joint_chain("arm", "park", arm_park) + + gripper_confs = {"open": [0.59, 0.59], "close": [0.0, 0.0]} + self.add_static_gripper_chains("arm", gripper_confs) + + self.grasps = GraspingDescription({"front": [0, 0, 0, 1], + "left": [0, 0, -1, 1], + "right": [0, 0, 1, 1], + "top": [0, 1, 0, 1]}) + + def get_camera_frame(self, name="color"): + return super().get_camera_frame(name) From e7bf734ed2da946992fe93a6dfe5e567dae87a22 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 21 Mar 2024 14:16:49 +0100 Subject: [PATCH 136/195] [process-module] Deactivated delay for real_robot --- src/pycram/process_module.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/pycram/process_module.py b/src/pycram/process_module.py index 6fa95efcf..1341852f7 100644 --- a/src/pycram/process_module.py +++ b/src/pycram/process_module.py @@ -74,6 +74,7 @@ class RealRobot: """ def __init__(self): self.pre: str = "" + self.pre_delay: bool = False def __enter__(self): """ @@ -82,6 +83,8 @@ def __enter__(self): """ self.pre = ProcessModuleManager.execution_type ProcessModuleManager.execution_type = "real" + self.pre_delay = ProcessModule.execution_delay + ProcessModule.execution_delay = False def __exit__(self, type, value, traceback): """ @@ -89,6 +92,7 @@ def __exit__(self, type, value, traceback): used one. """ ProcessModuleManager.execution_type = self.pre + ProcessModule.execution_delay = self.pre_delay def __call__(self): return self From 6a93943e673f88e53947aff9f6bd82105462823a Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 21 Mar 2024 14:17:24 +0100 Subject: [PATCH 137/195] [launch] Added stretch to launch file --- launch/ik_and_description.launch | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/launch/ik_and_description.launch b/launch/ik_and_description.launch index b4fc410ac..efe640395 100644 --- a/launch/ik_and_description.launch +++ b/launch/ik_and_description.launch @@ -1,5 +1,5 @@ - + @@ -38,6 +38,13 @@ textfile="$(find pycram)/resources/hsrb.urdf"/> + + + + + + From 4791a36632596dbea9820b776335bed58ec4c37f Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Thu, 21 Mar 2024 14:53:25 +0100 Subject: [PATCH 138/195] [Resolver] Integrated resolvers with new versions --- doc/source/index.rst | 2 +- examples/improving_actions.ipynb | 141381 +++++++++------ requirements-resolver.txt | 8 + src/pycram/costmaps.py | 30 +- .../probabilistic/probabilistic_action.py | 76 +- test/__init__.py | 0 test/test_costmaps.py | 29 +- .../test_database_resolver.py | 1 + .../test_move_and_pick_up.py | 23 +- 9 files changed, 81227 insertions(+), 60323 deletions(-) create mode 100644 requirements-resolver.txt create mode 100644 test/__init__.py diff --git a/doc/source/index.rst b/doc/source/index.rst index fb1161d2d..65293c4a4 100644 --- a/doc/source/index.rst +++ b/doc/source/index.rst @@ -1,4 +1,4 @@ -================================== + ================================== Welcome to pycram's documentation! ================================== diff --git a/examples/improving_actions.ipynb b/examples/improving_actions.ipynb index 802648b9e..7bbfc41ef 100644 --- a/examples/improving_actions.ipynb +++ b/examples/improving_actions.ipynb @@ -37,11 +37,13 @@ "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", - "[WARN] [1710335617.063405]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" + "[WARN] [1711028821.218958]: Could not import RoboKudo messages, RoboKudo interface could not be initialized\n" ] } ], "source": [ + "import json\n", + "\n", "import numpy as np\n", "import os\n", "import random\n", @@ -53,9 +55,11 @@ "\n", "import plotly\n", "import plotly.graph_objects as go\n", + "import tqdm\n", "\n", "from probabilistic_model.learning.jpt.jpt import JPT\n", "from probabilistic_model.learning.jpt.variables import infer_variables_from_dataframe\n", + "from probabilistic_model.probabilistic_circuit.probabilistic_circuit import ProbabilisticCircuit\n", "from random_events.events import Event\n", "\n", "import pycram.orm.base\n", @@ -69,7 +73,7 @@ "from pycram.ros.viz_marker_publisher import VizMarkerPublisher\n", "from pycram.process_module import ProcessModule, simulated_robot\n", "from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp\n", - "from pycram.task import task_tree\n", + "from pycram.task import task_tree, reset_tree\n", "\n", "ProcessModule.execution_delay = False\n", "np.random.seed(69)\n", @@ -78,8 +82,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:13:37.164656Z", - "start_time": "2024-03-13T13:13:35.538099Z" + "end_time": "2024-03-21T13:47:01.262567Z", + "start_time": "2024-03-21T13:46:59.567924Z" } }, "id": "690c193e24875d2b", @@ -102,8 +106,8 @@ "metadata": { "collapsed": true, "ExecuteTime": { - "end_time": "2024-03-13T13:13:37.183725Z", - "start_time": "2024-03-13T13:13:37.165474Z" + "end_time": "2024-03-21T13:47:01.280456Z", + "start_time": "2024-03-21T13:47:01.263722Z" } }, "outputs": [], @@ -135,8 +139,8 @@ "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown tag \"material\" in /robot[@name='plane']/link[@name='planeLink']/collision[1]\n", - "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='base_laser_link']\n", + "Unknown tag \"contact\" in /robot[@name='plane']/link[@name='planeLink']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']\n", "Unknown attribute \"type\" in /robot[@name='pr2']/link[@name='laser_tilt_link']\n", @@ -157,8 +161,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:13:37.608057Z", - "start_time": "2024-03-13T13:13:37.184410Z" + "end_time": "2024-03-21T13:47:01.710037Z", + "start_time": "2024-03-21T13:47:01.281829Z" } }, "id": "a66e49b86c6c92f1", @@ -177,9 +181,16 @@ { "cell_type": "code", "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "ProbabilisticCircuit with 15 nodes and 14 edges\n" + ] + }, { "data": { - "text/html": " \n " + "text/html": " \n " }, "metadata": {}, "output_type": "display_data" @@ -190,20016 +201,20016 @@ "data": [ { "hovertext": [ - "Likelihood: 0.2960051973772738", - "Likelihood: 0.2635974014418118", - "Likelihood: 0.2961502809293496", - "Likelihood: 0.24383418113789573", - "Likelihood: 0.2887295183970094", - "Likelihood: 0.2823943705198645", - "Likelihood: 0.24956378310538715", - "Likelihood: 0.23778477851861288", - "Likelihood: 0.11806185366215745", - "Likelihood: 0.12159224815973602", - "Likelihood: 0.269110410078513", - "Likelihood: 0.23580291943781614", - "Likelihood: 0.25495344657955277", - "Likelihood: 0.2955781723092807", - "Likelihood: 0.25706766173056445", - "Likelihood: 0.279590899879218", - "Likelihood: 0.25699796816183523", - "Likelihood: 0.2728375195554467", - "Likelihood: 0.23699914088567298", - "Likelihood: 0.14061059152779215", - "Likelihood: 0.21478260994432644", - "Likelihood: 0.25252470776916447", - "Likelihood: 0.13509486034575932", - "Likelihood: 0.3031291604210207", - "Likelihood: 0.2737190862395978", - "Likelihood: 0.30073770544000517", - "Likelihood: 0.16135949442440256", - "Likelihood: 0.3032056718654632", - "Likelihood: 0.2295320379629453", - "Likelihood: 0.18872972584135736", - "Likelihood: 0.20728403866794487", - "Likelihood: 0.2500392660016838", - "Likelihood: 0.023533580852094754", - "Likelihood: 0.09261195612351694", - "Likelihood: 0.30006312639562666", - "Likelihood: 0.20617832857778134", - "Likelihood: 0.21653222664654434", - "Likelihood: 0.29017550122237257", - "Likelihood: 0.2008344229030325", - "Likelihood: 0.2050160750713673", - "Likelihood: 0.23855719076563903", - "Likelihood: 0.2172944008429403", - "Likelihood: 0.24186450995555772", - "Likelihood: 0.21864772293135398", - "Likelihood: 0.1914478484038575", - "Likelihood: 0.29523801449642434", - "Likelihood: 0.2196511929285684", - "Likelihood: 0.11500227281147939", - "Likelihood: 0.2126862664209067", - "Likelihood: 0.2933150694807476", - "Likelihood: 0.23644121451450262", - "Likelihood: 0.25484688787665516", - "Likelihood: 0.2644166531625321", - "Likelihood: 0.27841369296775537", - "Likelihood: 0.09561406271963308", - "Likelihood: 0.2102453045420369", - "Likelihood: 0.2462282409310526", - "Likelihood: 0.1541942903125031", - "Likelihood: 0.201939214136583", - "Likelihood: 0.2641975335636654", - "Likelihood: 0.08588999534905599", - "Likelihood: 0.21116177994038246", - "Likelihood: 0.06273406982854238", - "Likelihood: 0.14700378345905793", - "Likelihood: 0.21640576636738587", - "Likelihood: 0.22422828857945917", - "Likelihood: 0.17788545212620985", - "Likelihood: 0.29875229912760504", - "Likelihood: 0.1404796862847426", - "Likelihood: 0.2878687736767476", - "Likelihood: 0.016572648158587375", - "Likelihood: 0.27956650804865996", - "Likelihood: 0.23870828512075742", - "Likelihood: 0.28191599408486673", - "Likelihood: 0.26991156495393315", - "Likelihood: 0.2948064620205842", - "Likelihood: 0.2848691505858482", - "Likelihood: 0.22559801225618986", - "Likelihood: 0.11786267204079678", - "Likelihood: 0.28275955596874147", - "Likelihood: 0.1240316390426622", - "Likelihood: 0.14887828449355353", - "Likelihood: 0.3036030368325772", - "Likelihood: 0.23461744957449832", - "Likelihood: 0.2866056729976452", - "Likelihood: 0.282943100950079", - "Likelihood: 0.30341190952991226", - "Likelihood: 0.2343782115368479", - "Likelihood: 0.29240527744838485", - "Likelihood: 0.2828923153310132", - "Likelihood: 0.26662493100299484", - "Likelihood: 0.17521317645743623", - "Likelihood: 0.27073650053728393", - "Likelihood: 0.3034869089853294", - "Likelihood: 0.22806442448016107", - "Likelihood: 0.11931498113377373", - "Likelihood: 0.24720157937725343", - "Likelihood: 0.21268378630671353", - "Likelihood: 0.21842626162369613", - "Likelihood: 0.24003893092304415", - "Likelihood: 0.26097437156246006", - "Likelihood: 0.27985342972548405", - "Likelihood: 0.20448022608716185", - "Likelihood: 0.19862611141714973", - "Likelihood: 0.24187716104248108", - "Likelihood: 0.17488866682925794", - "Likelihood: 0.051600309189276224", - "Likelihood: 0.21477078493864352", - "Likelihood: 0.19381747268488905", - "Likelihood: 0.24260226747748018", - "Likelihood: 0.10953479829572849", - "Likelihood: 0.15713840452397737", - "Likelihood: 0.19082573305131662", - "Likelihood: 0.19765394513896142", - "Likelihood: 0.22984265934658477", - "Likelihood: 0.2693754927929895", - "Likelihood: 0.269568075417542", - "Likelihood: 0.29247702351381794", - "Likelihood: 0.21447092243173788", - "Likelihood: 0.298859439189825", - "Likelihood: 0.2728075399918466", - "Likelihood: 0.26963148316015534", - "Likelihood: 0.2762321459241093", - "Likelihood: 0.28131313590992174", - "Likelihood: 0.2787452837045864", - "Likelihood: 0.25536635605892644", - "Likelihood: 0.2815559357316336", - "Likelihood: 0.1919491181113979", - "Likelihood: 0.23607796037118237", - "Likelihood: 0.28030584631567274", - "Likelihood: 0.2500602309691388", - "Likelihood: 0.3010739482401385", - "Likelihood: 0.22115037280240216", - "Likelihood: 0.27183876055464706", - "Likelihood: 0.2488751059911652", - "Likelihood: 0.12463843918990865", - "Likelihood: 0.2357268007478759", - "Likelihood: 0.2900776768499681", - "Likelihood: 0.13214949706642173", - "Likelihood: 0.29843196087254714", - "Likelihood: 0.30285653974328686", - "Likelihood: 0.1423846744985272", - "Likelihood: 0.14718018422719079", - "Likelihood: 0.26940425833174597", - "Likelihood: 0.21047736490379368", - "Likelihood: 0.1252790983357328", - "Likelihood: 0.2285340077106262", - "Likelihood: 0.2850958040747654", - "Likelihood: 0.2820481837911448", - "Likelihood: 0.2981120133218698", - "Likelihood: 0.29546719052366505", - "Likelihood: 0.3043507116533075", - "Likelihood: 0.2706056940509797", - "Likelihood: 0.2582807934861423", - "Likelihood: 0.2925235538364052", - "Likelihood: 0.25343266918580276", - "Likelihood: 0.20862314918912864", - "Likelihood: 0.19796399998090686", - "Likelihood: 0.15963105596419339", - "Likelihood: 0.21448392317988269", - "Likelihood: 0.2819898547377224", - "Likelihood: 0.2402898023905061", - "Likelihood: 0.23622951157002076", - "Likelihood: 0.294375855751143", - "Likelihood: 0.2391104597132889", - "Likelihood: 0.3010519388747714", - "Likelihood: 0.24121868743067995", - "Likelihood: 0.1570366680774678", - "Likelihood: 0.3015257205333031", - "Likelihood: 0.3020541070676427", - "Likelihood: 0.22415445416953475", - "Likelihood: 0.29489793133683234", - "Likelihood: 0.15753958690932446", - "Likelihood: 0.07596739337500384", - "Likelihood: 0.2401260157791593", - "Likelihood: 0.1318246469636361", - "Likelihood: 0.14929914340749842", - "Likelihood: 0.2951410226538208", - "Likelihood: 0.290941653830903", - "Likelihood: 0.27391194445694267", - "Likelihood: 0.28488210798316", - "Likelihood: 0.16356617545055813", - "Likelihood: 0.11232152841379293", - "Likelihood: 0.13957894500520096", - "Likelihood: 0.29117644592457365", - "Likelihood: 0.26120698877807175", - "Likelihood: 0.2551055117508274", - "Likelihood: 0.2867431020787879", - "Likelihood: 0.16539837091027249", - "Likelihood: 0.29641892027276384", - "Likelihood: 0.2714350940769336", - "Likelihood: 0.19780662184254197", - "Likelihood: 0.18495414708441799", - "Likelihood: 0.30274710254966986", - "Likelihood: 0.24034748874458303", - "Likelihood: 0.3000310172551274", - "Likelihood: 0.19425865019350205", - "Likelihood: 0.26273783275965923", - "Likelihood: 0.21118823847587156", - "Likelihood: 0.2602340986082089", - "Likelihood: 0.29729767255614253", - "Likelihood: 0.29854536000005666", - "Likelihood: 0.2885567107679648", - "Likelihood: 0.2691490061288963", - "Likelihood: 0.18699638524772863", - "Likelihood: 0.19182427917388253", - "Likelihood: 0.2933185316431407", - "Likelihood: 0.2868418222926477", - "Likelihood: 0.033619150000750664", - "Likelihood: 0.26268050571100243", - "Likelihood: 0.27663531699682736", - "Likelihood: 0.27680583385067326", - "Likelihood: 0.29988300981301885", - "Likelihood: 0.2054330200726069", - "Likelihood: 0.19223541250400958", - "Likelihood: 0.30069670945008664", - "Likelihood: 0.28659745793161084", - "Likelihood: 0.2494113505786499", - "Likelihood: 0.25809006968601694", - "Likelihood: 0.27317155672121035", - "Likelihood: 0.2957846314816964", - "Likelihood: 0.28855169232006944", - "Likelihood: 0.2795777366696988", - "Likelihood: 0.30324336898895476", - "Likelihood: 0.1952679089071436", - "Likelihood: 0.22387250693778155", - "Likelihood: 0.2464313735160234", - "Likelihood: 0.28603038851303", - "Likelihood: 0.23928561778995147", - "Likelihood: 0.29357414655254627", - "Likelihood: 0.2531573567016042", - "Likelihood: 0.18296110638230265", - "Likelihood: 0.24632753510408792", - "Likelihood: 0.06206716413073452", - "Likelihood: 0.15050936332446027", - "Likelihood: 0.28185048456665573", - "Likelihood: 0.29726634004960717", - "Likelihood: 0.18269858065774947", - "Likelihood: 0.28699831858752134", - "Likelihood: 0.2369143171469688", - "Likelihood: 0.16686748540115076", - "Likelihood: 0.09402625017779871", - "Likelihood: 0.2559396416807935", - "Likelihood: 0.2543250841096261", - "Likelihood: 0.29413510065485843", - "Likelihood: 0.2805151728974315", - "Likelihood: 0.25166432045200343", - "Likelihood: 0.19944777379639697", - "Likelihood: 0.26501236776712556", - "Likelihood: 0.2996644891328505", - "Likelihood: 0.20507621582101818", - "Likelihood: 0.29089065199916625", - "Likelihood: 0.1503981653611301", - "Likelihood: 0.2535178231525427", - "Likelihood: 0.27934801097316325", - "Likelihood: 0.29989509021498983", - "Likelihood: 0.09913148604284053", - "Likelihood: 0.269375945126131", - "Likelihood: 0.20878280944929853", - "Likelihood: 0.11956242216596763", - "Likelihood: 0.08495485673586783", - "Likelihood: 0.2578293367552083", - "Likelihood: 0.29540727286405744", - "Likelihood: 0.29114184484101624", - "Likelihood: 0.16753691044145685", - "Likelihood: 0.2559573439917049", - "Likelihood: 0.26666091109473616", - "Likelihood: 0.2113889480080851", - "Likelihood: 0.21229555840653777", - "Likelihood: 0.042258911565124554", - "Likelihood: 0.26769757448624126", - "Likelihood: 0.21480688546414203", - "Likelihood: 0.15954375119396205", - "Likelihood: 0.20580264207238935", - "Likelihood: 0.250542412701729", - "Likelihood: 0.22503459508191392", - "Likelihood: 0.27435715715220504", - "Likelihood: 0.18256813697016305", - "Likelihood: 0.18399375552229", - "Likelihood: 0.1700961672398993", - "Likelihood: 0.29289179614961997", - "Likelihood: 0.22889766051874785", - "Likelihood: 0.27798312794703506", - "Likelihood: 0.20777740162764327", - "Likelihood: 0.2980762758724712", - "Likelihood: 0.28171847345072587", - "Likelihood: 0.23658176511988172", - "Likelihood: 0.1961872927637657", - "Likelihood: 0.26287558198485234", - "Likelihood: 0.25687416766385207", - "Likelihood: 0.2803921737575837", - "Likelihood: 0.28543475768889615", - "Likelihood: 0.2630058576977688", - "Likelihood: 0.27445905585827735", - "Likelihood: 0.17553467663791578", - "Likelihood: 0.28076381200526324", - "Likelihood: 0.15649559773411326", - "Likelihood: 0.15120828637054146", - "Likelihood: 0.1829355880729986", - "Likelihood: 0.24875899297934692", - "Likelihood: 0.17713490630581288", - "Likelihood: 0.28518504620759366", - "Likelihood: 0.2774514297061875", - "Likelihood: 0.28567041664473286", - "Likelihood: 0.2884389538829595", - "Likelihood: 0.16342400942122282", - "Likelihood: 0.22698192109957482", - "Likelihood: 0.28034335738368893", - "Likelihood: 0.2857971262656073", - "Likelihood: 0.21979741258361554", - "Likelihood: 0.3032634563831829", - "Likelihood: 0.1736977151154615", - "Likelihood: 0.29705963236617533", - "Likelihood: 0.14901602166217792", - "Likelihood: 0.21328703922340767", - "Likelihood: 0.2077622949442935", - "Likelihood: 0.288320054797426", - "Likelihood: 0.2612900199768941", - "Likelihood: 0.15613994503788314", - "Likelihood: 0.09749403425229707", - "Likelihood: 0.22086328235952432", - "Likelihood: 0.06923180729720761", - "Likelihood: 0.13664206136594761", - "Likelihood: 0.2454731671039702", - "Likelihood: 0.18383474856941837", - "Likelihood: 0.2395363874193355", - "Likelihood: 0.28897699708888536", - "Likelihood: 0.26190649375255415", - "Likelihood: 0.1549726301080116", - "Likelihood: 0.2511281389647274", - "Likelihood: 0.25399139484198585", - "Likelihood: 0.2289946078253289", - "Likelihood: 0.1293788837627745", - "Likelihood: 0.24656754108997064", - "Likelihood: 0.24705555621553885", - "Likelihood: 0.1339630268037889", - "Likelihood: 0.3018188443557378", - "Likelihood: 0.150485252107519", - "Likelihood: 0.2671266646418594", - "Likelihood: 0.28630402150370116", - "Likelihood: 0.047172271555570064", - "Likelihood: 0.2947868466668038", - "Likelihood: 0.28146396173119326", - "Likelihood: 0.17928679312555287", - "Likelihood: 0.2146196760276306", - "Likelihood: 0.15481419590593812", - "Likelihood: 0.1704173538142748", - "Likelihood: 0.24956133339181935", - "Likelihood: 0.26323389355750526", - "Likelihood: 0.295455150670845", - "Likelihood: 0.21530802323005058", - "Likelihood: 0.23072387517705775", - "Likelihood: 0.11014779550449762", - "Likelihood: 0.23357694871315618", - "Likelihood: 0.19650192876377684", - "Likelihood: 0.23333120904386093", - "Likelihood: 0.16244585019110547", - "Likelihood: 0.2711572891685677", - "Likelihood: 0.10835505039967633", - "Likelihood: 0.2913373181275813", - "Likelihood: 0.1557298836982097", - "Likelihood: 0.267211801174563", - "Likelihood: 0.09062695899434588", - "Likelihood: 0.2680990038842886", - "Likelihood: 0.29905399908110414", - "Likelihood: 0.131164930458136", - "Likelihood: 0.28737874810491076", - "Likelihood: 0.20663824558240343", - "Likelihood: 0.29507577509108596", - "Likelihood: 0.2531292304036051", - "Likelihood: 0.28066534327524134", - "Likelihood: 0.2760795892440463", - "Likelihood: 0.13367256685216306", - "Likelihood: 0.28597607056191554", - "Likelihood: 0.28628707348088456", - "Likelihood: 0.14939960112489276", - "Likelihood: 0.23749142627335434", - "Likelihood: 0.28935597880495917", - "Likelihood: 0.1692207985361009", - "Likelihood: 0.1744408349102826", - "Likelihood: 0.14620102323697529", - "Likelihood: 0.14706340664834355", - "Likelihood: 0.17928800573560227", - "Likelihood: 0.1458541590588936", - "Likelihood: 0.21418727862031053", - "Likelihood: 0.1431509472683106", - "Likelihood: 0.22496139747819588", - "Likelihood: 0.2831400505738617", - "Likelihood: 0.29305026200752177", - "Likelihood: 0.22586075837396352", - "Likelihood: 0.09183719601538261", - "Likelihood: 0.13794166472225533", - "Likelihood: 0.300227269125567", - "Likelihood: 0.2846146653863931", - "Likelihood: 0.2970135215877043", - "Likelihood: 0.18851785566576634", - "Likelihood: 0.28160258368036767", - "Likelihood: 0.28477977262469745", - "Likelihood: 0.2941229395217518", - "Likelihood: 0.2897108013809919", - "Likelihood: 0.29726729265597224", - "Likelihood: 0.03772006554782948", - "Likelihood: 0.247277408531523", - "Likelihood: 0.26235220978850177", - "Likelihood: 0.2792854701680436", - "Likelihood: 0.1818892670824121", - "Likelihood: 0.27289583300719183", - "Likelihood: 0.2954246579457717", - "Likelihood: 0.21873066316863174", - "Likelihood: 0.20072534114558643", - "Likelihood: 0.22083152282690374", - "Likelihood: 0.25929286924678385", - "Likelihood: 0.19616136309545495", - "Likelihood: 0.2814167625250302", - "Likelihood: 0.23667697183665776", - "Likelihood: 0.2744986207883696", - "Likelihood: 0.10860370787369225", - "Likelihood: 0.10304327489535654", - "Likelihood: 0.2726971756426144", - "Likelihood: 0.22282829618314334", - "Likelihood: 0.10889764326899565", - "Likelihood: 0.26315640035768056", - "Likelihood: 0.005811409751917357", - "Likelihood: 0.23641955986992347", - "Likelihood: 0.29974598433915306", - "Likelihood: 0.2916408861890767", - "Likelihood: 0.2553976212524727", - "Likelihood: 0.2996671195686481", - "Likelihood: 0.25773869682697337", - "Likelihood: 0.11729379192146351", - "Likelihood: 0.24980373327350183", - "Likelihood: 0.2860328721089231", - "Likelihood: 0.09714522725471347", - "Likelihood: 0.09547776887418687", - "Likelihood: 0.2283136524422173", - "Likelihood: 0.25095578479709213", - "Likelihood: 0.23668489903472756", - "Likelihood: 0.2512086658093602", - "Likelihood: 0.2335240986050694", - "Likelihood: 0.2935530986986391", - "Likelihood: 0.24861629937736782", - "Likelihood: 0.3024477408866091", - "Likelihood: 0.2649748378880566", - "Likelihood: 0.22573939752516053", - "Likelihood: 0.26301003051194577", - "Likelihood: 0.30163494521566186", - "Likelihood: 0.10608788228471784", - "Likelihood: 0.06946110871793945", - "Likelihood: 0.2550933155545067", - "Likelihood: 0.2980678356662104", - "Likelihood: 0.28860578137641507", - "Likelihood: 0.2869645782508876", - "Likelihood: 0.30237995766479775", - "Likelihood: 0.08316293227235626", - "Likelihood: 0.19013455025694992", - "Likelihood: 0.2639911638218235", - "Likelihood: 0.2395091932849628", - "Likelihood: 0.19492400891186903", - "Likelihood: 0.22723101439876792", - "Likelihood: 0.24992922175726545", - "Likelihood: 0.24964983897769025", - "Likelihood: 0.21439469004295728", - "Likelihood: 0.25466091957814807", - "Likelihood: 0.29213803633628405", - "Likelihood: 0.301119692762104", - "Likelihood: 0.28188540064141154", - "Likelihood: 0.05946076363123784", - "Likelihood: 0.16575893181495532", - "Likelihood: 0.13995533532316515", - "Likelihood: 0.2918660554134687", - "Likelihood: 0.25854008637126213", - "Likelihood: 0.22159740584042975", - "Likelihood: 0.26244743006135113", - "Likelihood: 0.29079986882078", - "Likelihood: 0.26602051522310277", - "Likelihood: 0.25519826236180726", - "Likelihood: 0.28029064459555125", - "Likelihood: 0.2755810488047902", - "Likelihood: 0.23888827356283057", - "Likelihood: 0.21143129566308114", - "Likelihood: 0.21247540202700543", - "Likelihood: 0.2869521671920473", - "Likelihood: 0.17573151783780158", - "Likelihood: 0.21855920371738338", - "Likelihood: 0.24989152944083828", - "Likelihood: 0.28812025950683784", - "Likelihood: 0.28651243452083436", - "Likelihood: 0.22162449023698402", - "Likelihood: 0.2336540910856105", - "Likelihood: 0.13621008336782467", - "Likelihood: 0.2632381757171688", - "Likelihood: 0.29474563278110477", - "Likelihood: 0.2881186472452377", - "Likelihood: 0.2981543445425233", - "Likelihood: 0.27451434867283087", - "Likelihood: 0.25556051496380916", - "Likelihood: 0.14372829112485894", - "Likelihood: 0.2859010322352819", - "Likelihood: 0.2952965439335267", - "Likelihood: 0.24493164320491168", - "Likelihood: 0.2048724286145789", - "Likelihood: 0.2540039348838295", - "Likelihood: 0.08573297919891314", - "Likelihood: 0.22649400991302482", - "Likelihood: 0.2524756855252271", - "Likelihood: 0.20364271093077335", - "Likelihood: 0.19719023960774618", - "Likelihood: 0.17094615168902588", - "Likelihood: 0.2860387238025606", - "Likelihood: 0.2742753391793435", - "Likelihood: 0.2926617126535415", - "Likelihood: 0.24284913904232633", - "Likelihood: 0.30051281695678805", - "Likelihood: 0.20483575827766629", - "Likelihood: 0.23925147130243382", - "Likelihood: 0.2705541805358004", - "Likelihood: 0.27943346845577705", - "Likelihood: 0.11300587730449582", - "Likelihood: 0.24110266914038844", - "Likelihood: 0.2698825386432986", - "Likelihood: 0.2624566710219319", - "Likelihood: 0.18759824118893967", - "Likelihood: 0.280346873320084", - "Likelihood: 0.27892422804490663", - "Likelihood: 0.2855696214529743", - "Likelihood: 0.2927388388373448", - "Likelihood: 0.12416714120439445", - "Likelihood: 0.2984952348606522", - "Likelihood: 0.23415933045935716", - "Likelihood: 0.240880377553291", - "Likelihood: 0.2825604370797697", - "Likelihood: 0.22503620290107557", - "Likelihood: 0.1407237388416774", - "Likelihood: 0.23291670009224588", - "Likelihood: 0.3007689864197902", - "Likelihood: 0.240867189082956", - "Likelihood: 0.28410245720353494", - "Likelihood: 0.2954757182774075", - "Likelihood: 0.29830168475327395", - "Likelihood: 0.22907011167503366", - "Likelihood: 0.27925115680994794", - "Likelihood: 0.2858492537781597", - "Likelihood: 0.29451570030647606", - "Likelihood: 0.2826854221791677", - "Likelihood: 0.1508939485138827", - "Likelihood: 0.1044205851214603", - "Likelihood: 0.11513908379113098", - "Likelihood: 0.29212138289822714", - "Likelihood: 0.28345807034610065", - "Likelihood: 0.30076325660272796", - "Likelihood: 0.30030969537406976", - "Likelihood: 0.25106597304918193", - "Likelihood: 0.2750469504755384", - "Likelihood: 0.24920135399387305", - "Likelihood: 0.273666486838556", - "Likelihood: 0.10481582045158627", - "Likelihood: 0.2069498218242434", - "Likelihood: 0.2707236427714333", - "Likelihood: 0.09151421954592576", - "Likelihood: 0.19821840041388383", - "Likelihood: 0.2865009758610928", - "Likelihood: 0.28935188545938034", - "Likelihood: 0.18571169478629335", - "Likelihood: 0.2981723969010715", - "Likelihood: 0.19401389921293116", - "Likelihood: 0.10425687916856417", - "Likelihood: 0.2805703095135145", - "Likelihood: 0.11125495918962044", - "Likelihood: 0.26457106534861086", - "Likelihood: 0.20098444757096248", - "Likelihood: 0.24533592107446478", - "Likelihood: 0.29754145560147793", - "Likelihood: 0.27378839691518325", - "Likelihood: 0.29025227882677423", - "Likelihood: 0.29367202421226074", - "Likelihood: 0.249823336329853", - "Likelihood: 0.19654753180627674", - "Likelihood: 0.2886076915481312", - "Likelihood: 0.21961349511190964", - "Likelihood: 0.1371109959123549", - "Likelihood: 0.27404402761586255", - "Likelihood: 0.2410679836956021", - "Likelihood: 0.27678469422380086", - "Likelihood: 0.2352327621695618", - "Likelihood: 0.2996070015975585", - "Likelihood: 0.20295615251765392", - "Likelihood: 0.1396819613351756", - "Likelihood: 0.06480404419372822", - "Likelihood: 0.2975729083154207", - "Likelihood: 0.28723910147710574", - "Likelihood: 0.280846052519463", - "Likelihood: 0.2897202693993566", - "Likelihood: 0.12391792234812905", - "Likelihood: 0.20009958406985623", - "Likelihood: 0.09843973854141926", - "Likelihood: 0.299093722924223", - "Likelihood: 0.16920133519092354", - "Likelihood: 0.1953896181061389", - "Likelihood: 0.2886704391173958", - "Likelihood: 0.22149032512813305", - "Likelihood: 0.058286627629738255", - "Likelihood: 0.30018593992244685", - "Likelihood: 0.0690606029032214", - "Likelihood: 0.1373701646047654", - "Likelihood: 0.1233276600969845", - "Likelihood: 0.28979036827627974", - "Likelihood: 0.29067092837852376", - "Likelihood: 0.16267730267971028", - "Likelihood: 0.14135494500520301", - "Likelihood: 0.159587481205658", - "Likelihood: 0.20816907827086786", - "Likelihood: 0.2133423741521511", - "Likelihood: 0.2536191564954792", - "Likelihood: 0.2603318130895654", - "Likelihood: 0.28092669071409526", - "Likelihood: 0.2846868401646544", - "Likelihood: 0.2306443779049465", - "Likelihood: 0.2104888907003376", - "Likelihood: 0.2938190130005592", - "Likelihood: 0.16244029142544128", - "Likelihood: 0.25307860619930006", - "Likelihood: 0.20455602399940623", - "Likelihood: 0.18924791271893288", - "Likelihood: 0.28993788471440807", - "Likelihood: 0.18613821192267666", - "Likelihood: 0.28970297853725674", - "Likelihood: 0.21848015635407048", - "Likelihood: 0.21589703651133924", - "Likelihood: 0.27667468338393036", - "Likelihood: 0.21312416659879677", - "Likelihood: 0.2822247454800003", - "Likelihood: 0.2671569689816849", - "Likelihood: 0.24284653504577403", - "Likelihood: 0.28853751591782717", - "Likelihood: 0.14308564768597873", - "Likelihood: 0.17604813147430756", - "Likelihood: 0.2506493746853913", - "Likelihood: 0.23020317817643926", - "Likelihood: 0.17925017386434905", - "Likelihood: 0.18846231586262333", - "Likelihood: 0.24504385421784022", - "Likelihood: 0.30234915687834113", - "Likelihood: 0.2622108318419333", - "Likelihood: 0.17706826438900308", - "Likelihood: 0.2880273968082686", - "Likelihood: 0.22917265870070969", - "Likelihood: 0.22398236158118429", - "Likelihood: 0.23094511587642252", - "Likelihood: 0.29629704999004897", - "Likelihood: 0.29643932069931833", - "Likelihood: 0.12249737903763225", - "Likelihood: 0.27683516456554846", - "Likelihood: 0.06182481392856916", - "Likelihood: 0.221100307091509", - "Likelihood: 0.15513028797200218", - "Likelihood: 0.2140711618680663", - "Likelihood: 0.14278902280901576", - "Likelihood: 0.26971335975853167", - "Likelihood: 0.22373341510582695", - "Likelihood: 0.23619108936451383", - "Likelihood: 0.21053993777901508", - "Likelihood: 0.23286241933459365", - "Likelihood: 0.2836279020353891", - "Likelihood: 0.1955157518975518", - "Likelihood: 0.2938052728580348", - "Likelihood: 0.2597852249799945", - "Likelihood: 0.24501593073352157", - "Likelihood: 0.28519739765407204", - "Likelihood: 0.2798654553322318", - "Likelihood: 0.2641044458939613", - "Likelihood: 0.2079486058458403", - "Likelihood: 0.17330439916894094", - "Likelihood: 0.051725875718593176", - "Likelihood: 0.22562881752417185", - "Likelihood: 0.15157078443477903", - "Likelihood: 0.1574620196260669", - "Likelihood: 0.2997717369516266", - "Likelihood: 0.16126438299351473", - "Likelihood: 0.19746560557021337", - "Likelihood: 0.1772593037776395", - "Likelihood: 0.2936577701737042", - "Likelihood: 0.27335642216071104", - "Likelihood: 0.10591241124959835", - "Likelihood: 0.20860278604563912", - "Likelihood: 0.30302131473309973", - "Likelihood: 0.18040822925342806", - "Likelihood: 0.2292569959252749", - "Likelihood: 0.26472057562820733", - "Likelihood: 0.146778609344068", - "Likelihood: 0.276007509500781", - "Likelihood: 0.2281970473717115", - "Likelihood: 0.24875276334988788", - "Likelihood: 0.2601286098784966", - "Likelihood: 0.22052809230154702", - "Likelihood: 0.19104635241698537", - "Likelihood: 0.260407880027994", - "Likelihood: 0.28342501643192736", - "Likelihood: 0.29494440772780284", - "Likelihood: 0.2356655454193884", - "Likelihood: 0.29292542156189794", - "Likelihood: 0.28398585220820444", - "Likelihood: 0.28636341326030795", - "Likelihood: 0.28906732668100443", - "Likelihood: 0.26407154528234644", - "Likelihood: 0.23257884346475738", - "Likelihood: 0.13837984616678894", - "Likelihood: 0.209710834621091", - "Likelihood: 0.2730226296859091", - "Likelihood: 0.2644616494950432", - "Likelihood: 0.2574058137730611", - "Likelihood: 0.27216762915461823", - "Likelihood: 0.23307390892732327", - "Likelihood: 0.3038890617230413", - "Likelihood: 0.293369418406101", - "Likelihood: 0.26158812302866735", - "Likelihood: 0.20404951646710479", - "Likelihood: 0.2528272687924256", - "Likelihood: 0.3036312155425935", - "Likelihood: 0.2987198492378236", - "Likelihood: 0.24201129660463402", - "Likelihood: 0.17393343783613932", - "Likelihood: 0.23174131690380861", - "Likelihood: 0.23123199635198233", - "Likelihood: 0.2823350772067628", - "Likelihood: 0.2572129910077664", - "Likelihood: 0.1523839391547686", - "Likelihood: 0.13134746881560938", - "Likelihood: 0.14674347409173694", - "Likelihood: 0.15339654765367866", - "Likelihood: 0.13223545479374127", - "Likelihood: 0.21663348756744463", - "Likelihood: 0.29809385695345153", - "Likelihood: 0.15233553520164483", - "Likelihood: 0.27992974063694104", - "Likelihood: 0.1761302011577866", - "Likelihood: 0.2547442005909253", - "Likelihood: 0.20295232763726434", - "Likelihood: 0.26909359208806666", - "Likelihood: 0.10553104313690846", - "Likelihood: 0.2613702439580583", - "Likelihood: 0.2967124131528324", - "Likelihood: 0.3003498871302205", - "Likelihood: 0.2779558907931639", - "Likelihood: 0.29313928192188454", - "Likelihood: 0.18369850777614968", - "Likelihood: 0.24466729735108408", - "Likelihood: 0.25420217003814505", - "Likelihood: 0.30272877337837245", - "Likelihood: 0.0544167605014875", - "Likelihood: 0.2552494256901108", - "Likelihood: 0.24750089645939932", - "Likelihood: 0.13272822681088337", - "Likelihood: 0.21500218810716706", - "Likelihood: 0.15201673634575372", - "Likelihood: 0.1555220327859978", - "Likelihood: 0.29928352251560464", - "Likelihood: 0.14438181687203414", - "Likelihood: 0.27113104188134646", - "Likelihood: 0.15624765552140624", - "Likelihood: 0.25389519017216994", - "Likelihood: 0.2880129793797895", - "Likelihood: 0.15046015612192765", - "Likelihood: 0.3004127064029729", - "Likelihood: 0.2768350794769215", - "Likelihood: 0.2833116116789994", - "Likelihood: 0.22491325722874192", - "Likelihood: 0.2750220862994127", - "Likelihood: 0.295802940875195", - "Likelihood: 0.24960430082974816", - "Likelihood: 0.1638475661394475", - "Likelihood: 0.257858626485779", - "Likelihood: 0.1951568094377378", - "Likelihood: 0.2559311628028245", - "Likelihood: 0.217532960883545", - "Likelihood: 0.25304020124484644", - "Likelihood: 0.11782028084365925", - "Likelihood: 0.2687097694439468", - "Likelihood: 0.2487857279814359", - "Likelihood: 0.14892713187593662", - "Likelihood: 0.03575144749134307", - "Likelihood: 0.19037754313741392", - "Likelihood: 0.16501584884640416", - "Likelihood: 0.22089282577486544", - "Likelihood: 0.20342999685942534", - "Likelihood: 0.301714608947704", - "Likelihood: 0.26453613607544724", - "Likelihood: 0.27832555704745204", - "Likelihood: 0.20983643032488328", - "Likelihood: 0.27532725656462376", - "Likelihood: 0.2083189183932531", - "Likelihood: 0.18412092644965009", - "Likelihood: 0.2698676832819896", - "Likelihood: 0.19203365555625262", - "Likelihood: 0.12385533073533418", - "Likelihood: 0.2695124111978697", - "Likelihood: 0.27406763059957484", - "Likelihood: 0.12190207544181239", - "Likelihood: 0.24032463637989573", - "Likelihood: 0.2763190238258697", - "Likelihood: 0.26430919279724785", - "Likelihood: 0.1663111454701358", - "Likelihood: 0.26507983326883405", - "Likelihood: 0.2328587719308773", - "Likelihood: 0.28817007079087836", - "Likelihood: 0.06133743514886796", - "Likelihood: 0.2537942619672616", - "Likelihood: 0.2722521980595358", - "Likelihood: 0.17792995688733942", - "Likelihood: 0.2992757717408057", - "Likelihood: 0.18935214000449732", - "Likelihood: 0.1897292465091863", - "Likelihood: 0.2597723884892549", - "Likelihood: 0.2911544865044354", - "Likelihood: 0.05846318649964085", - "Likelihood: 0.13151189113837516", - "Likelihood: 0.15828007988974346", - "Likelihood: 0.10458833659850031", - "Likelihood: 0.290130800260699", - "Likelihood: 0.29240229142375945", - "Likelihood: 0.2856322080309242", - "Likelihood: 0.29135422418932305", - "Likelihood: 0.3015275190856002", - "Likelihood: 0.17501261922484238", - "Likelihood: 0.2741878989780075", - "Likelihood: 0.22860107029916732", - "Likelihood: 0.2960928141877308", - "Likelihood: 0.21596785939264562", - "Likelihood: 0.21200176722273675", - "Likelihood: 0.12269638840988077", - "Likelihood: 0.2876969544570238", - "Likelihood: 0.27491570733732856", - "Likelihood: 0.03225299599294464", - "Likelihood: 0.2877856523684416", - "Likelihood: 0.27168171580460243", - "Likelihood: 0.28810077169370457", - "Likelihood: 0.13319659681129373", - "Likelihood: 0.2735834484726898", - "Likelihood: 0.2702312870593459", - "Likelihood: 0.15778983151913162", - "Likelihood: 0.15793326169039754", - "Likelihood: 0.2553495166851402", - "Likelihood: 0.15399971667587017", - "Likelihood: 0.2280508218986353", - "Likelihood: 0.300710640311969", - "Likelihood: 0.2830964880347255", - "Likelihood: 0.30411835362678374", - "Likelihood: 0.22630745032387928", - "Likelihood: 0.0932491169463781", - "Likelihood: 0.21047693192081263", - "Likelihood: 0.2576755305394904", - "Likelihood: 0.18773988526410124", - "Likelihood: 0.20598484485255422", - "Likelihood: 0.29792603965254244", - "Likelihood: 0.2980974908790451", - "Likelihood: 0.19658148226768368", - "Likelihood: 0.16009696542544563", - "Likelihood: 0.0900757221269017", - "Likelihood: 0.2438917553815996", - "Likelihood: 0.24629968595958454", - "Likelihood: 0.2541965439363413", - "Likelihood: 0.16327400068702705", - "Likelihood: 0.07114627983598008", - "Likelihood: 0.2606534315825352", - "Likelihood: 0.30336945035716434", - "Likelihood: 0.11081911894416206", - "Likelihood: 0.2803812638365542", - "Likelihood: 0.28842264462794737", - "Likelihood: 0.2547490611077962", - "Likelihood: 0.2814323946342493", - "Likelihood: 0.14919316745760333", - "Likelihood: 0.2888090861108627", - "Likelihood: 0.1859619116336988", - "Likelihood: 0.17418014348354396", - "Likelihood: 0.2815443327757822", - "Likelihood: 0.1584962060848333", - "Likelihood: 0.3048931818783448", - "Likelihood: 0.2829442688279079", - "Likelihood: 0.3019100720944198", - "Likelihood: 0.2853839282799968", - "Likelihood: 0.25202558554090304", - "Likelihood: 0.1568230531106573", - "Likelihood: 0.19722524157378987", - "Likelihood: 0.2238011040455", - "Likelihood: 0.285654117109514", - "Likelihood: 0.1667981712523717", - "Likelihood: 0.2924155073408582", - "Likelihood: 0.21414331977070664", - "Likelihood: 0.29970005734430544", - "Likelihood: 0.24683519262041248", - "Likelihood: 0.2752451276903912", - "Likelihood: 0.26890183067351964", - "Likelihood: 0.17377242856529243", - "Likelihood: 0.26744042867633144", - "Likelihood: 0.167933679026306", - "Likelihood: 0.1680183676244491", - "Likelihood: 0.2705836328226614", - "Likelihood: 0.16734136646958825", - "Likelihood: 0.2761543661943008", - "Likelihood: 0.19478254190558084", - "Likelihood: 0.2545639457043728", - "Likelihood: 0.26175208627231505", - "Likelihood: 0.1949888808809122", - "Likelihood: 0.28262529889707627", - "Likelihood: 0.25433508124308335", - "Likelihood: 0.20165770793854207", - "Likelihood: 0.29549212921166057", - "Likelihood: 0.2899277293283511", - "Likelihood: 0.2898905487061178", - "Likelihood: 0.30193834750418874", - "Likelihood: 0.1986963571272873", - "Likelihood: 0.18470119673193378", - "Likelihood: 0.24926983948812753", - "Likelihood: 0.27448326702804055", - "Likelihood: 0.2382160538158945", - "Likelihood: 0.033291413377066564", - "Likelihood: 0.19109127940072648", - "Likelihood: 0.03345251525228836", - "Likelihood: 0.08218096693717389", - "Likelihood: 0.29088936855120323", - "Likelihood: 0.08800595997622683", - "Likelihood: 0.305112279911373", - "Likelihood: 0.22324323758328068", - "Likelihood: 0.10782903045214584", - "Likelihood: 0.23913902825742286", - "Likelihood: 0.24097702939748453", - "Likelihood: 0.21231915379760893", - "Likelihood: 0.19519405164509906", - "Likelihood: 0.16996306628495964", - "Likelihood: 0.04726056429674222", - "Likelihood: 0.2321323024860711", - "Likelihood: 0.1316126167777104", - "Likelihood: 0.1733670061131893", - "Likelihood: 0.18619223648747812", - "Likelihood: 0.1104175140629014", - "Likelihood: 0.1774772236376992", - "Likelihood: 0.007531087583359291", - "Likelihood: 0.29107968000970436", - "Likelihood: 0.17657489851223168", - "Likelihood: 0.21181426367278472", - "Likelihood: 0.19584166581705464", - "Likelihood: 0.23775209343983283", - "Likelihood: 0.0754816080970455", - "Likelihood: 0.24442495315792445", - "Likelihood: 0.11838482174831942", - "Likelihood: 0.15944193134235216", - "Likelihood: 0.1765011234658163", - "Likelihood: 0.2908190331206214", - "Likelihood: 0.16879697277193773", - "Likelihood: 0.21606567897054227", - "Likelihood: 0.04361357997798882", - "Likelihood: 0.10712233099111194", - "Likelihood: 0.26116537022999103", - "Likelihood: 0.20932905397616433", - "Likelihood: 0.039624939315852356", - "Likelihood: 0.12107064591675334", - "Likelihood: 0.1467760886858863", - "Likelihood: 0.25540950654128025", - "Likelihood: 0.13787942821757213", - "Likelihood: 0.09555263094087621", - "Likelihood: 0.2738721190367032", - "Likelihood: 0.1616753043804631", - "Likelihood: 0.23463831340557556", - "Likelihood: 0.1620781799664746", - "Likelihood: 0.20989844698483356", - "Likelihood: 0.19923758407274303", - "Likelihood: 0.18727456503952697", - "Likelihood: 0.27149681547128984", - "Likelihood: 0.256933203690812", - "Likelihood: 0.11402460088966629", - "Likelihood: 0.3050900178291943", - "Likelihood: 0.1608277080907704", - "Likelihood: 0.21771443814148173", - "Likelihood: 0.195296872516779", - "Likelihood: 0.06138427769297077", - "Likelihood: 0.043364134707698496", - "Likelihood: 0.25617527972376614", - "Likelihood: 0.19539465019125743", - "Likelihood: 0.18703806904227072", - "Likelihood: 0.207730644085514", - "Likelihood: 0.13716321668545653", - "Likelihood: 0.27504528266827205", - "Likelihood: 0.24391657737237835", - "Likelihood: 0.21573255646726072", - "Likelihood: 0.24666501162975807", - "Likelihood: 0.26732237934939607", - "Likelihood: 0.1828286033883923", - "Likelihood: 0.06415781798389382", - "Likelihood: 0.058916879117314705", - "Likelihood: 0.2345042423640075", - "Likelihood: 0.2670130732045123", - "Likelihood: 0.23887987176121203", - "Likelihood: 0.20690284099183956", - "Likelihood: 0.18411236735400327", - "Likelihood: 0.29259091643876456", - "Likelihood: 0.15028267395487685", - "Likelihood: 0.09925371196132009", - "Likelihood: 0.23654540873301297", - "Likelihood: 0.2146876858417141", - "Likelihood: 0.28128311538971235", - "Likelihood: 0.18408145212690966", - "Likelihood: 0.1365653750378884", - "Likelihood: 0.21343007668649547", - "Likelihood: 0.16372259263347044", - "Likelihood: 0.24847030346685178", - "Likelihood: 0.10876821894464692", - "Likelihood: 0.2630988555042597", - "Likelihood: 0.30319279324490594", - "Likelihood: 0.19502684222616695", - "Likelihood: 0.0841639732883481", - "Likelihood: 0.279544712136446", - "Likelihood: 0.16892660660363493", - "Likelihood: 0.24451851638412636", - "Likelihood: 0.24013712395957815", - "Likelihood: 0.15811183716059185", - "Likelihood: 0.30472917863553745", - "Likelihood: 0.11388174890355485", - "Likelihood: 0.13592438420473546", - "Likelihood: 0.18558902670217647", - "Likelihood: 0.22913220497002879", - "Likelihood: 0.2838724492313794", - "Likelihood: 0.2096407954150203", - "Likelihood: 0.08606467906599463", - "Likelihood: 0.16545814934165898", - "Likelihood: 0.18866347236791892", - "Likelihood: 0.138257964792312", - "Likelihood: 0.24306474661246", - "Likelihood: 0.18074579208418723", - "Likelihood: 0.2575402772763422", - "Likelihood: 0.22979778505138193", - "Likelihood: 0.054147778014123085", - "Likelihood: 0.11075099532323447", - "Likelihood: 0.11926493948654013", - "Likelihood: 0.21730573923016056", - "Likelihood: 0.21492725864656098", - "Likelihood: 0.1932982736312301", - "Likelihood: 0.1932066204251951", - "Likelihood: 0.17409988122618902", - "Likelihood: 0.1690718342510549", - "Likelihood: 0.17271499332392995", - "Likelihood: 0.20029135531521214", - "Likelihood: 0.1550297236503454", - "Likelihood: 0.19325923934414568", - "Likelihood: 0.24669801626793558", - "Likelihood: 0.2403458305881896", - "Likelihood: 0.13570134917147056", - "Likelihood: 0.0318593236775221", - "Likelihood: 0.18061523406811247", - "Likelihood: 0.3014479396845426", - "Likelihood: 0.24545523227583327", - "Likelihood: 0.24755001795951942", - "Likelihood: 0.09577480704131587", - "Likelihood: 0.1157648588439342", - "Likelihood: 0.2614712726074537", - "Likelihood: 0.24923310095689089", - "Likelihood: 0.20073312224856915", - "Likelihood: 0.29391218214985826", - "Likelihood: 0.19151339680034024", - "Likelihood: 0.19268538714965308", - "Likelihood: 0.28464229589541934", - "Likelihood: 0.2591575892650212", - "Likelihood: 0.2236049239589166", - "Likelihood: 0.29912548299382713", - "Likelihood: 0.23823268733684894", - "Likelihood: 0.12799694524378102", - "Likelihood: 0.16928945184174965", - "Likelihood: 0.07836467659729589", - "Likelihood: 0.30009811474534576", - "Likelihood: 0.23394158965002837", - "Likelihood: 0.2333289168618451", - "Likelihood: 0.21386710459470398", - "Likelihood: 0.2386472258976251", - "Likelihood: 0.26203606333826274", - "Likelihood: 0.28135526669981537", - "Likelihood: 0.13648417589249348", - "Likelihood: 0.07616722748895324", - "Likelihood: 0.27456101647512704", - "Likelihood: 0.2700319261998122", - "Likelihood: 0.16997798046685547", - "Likelihood: 0.054191243156702706", - "Likelihood: 0.04155744740848175", - "Likelihood: 0.18131214402092857", - "Likelihood: 0.09949202873809292", - "Likelihood: 0.190161777107382", - "Likelihood: 0.28043455978279064", - "Likelihood: 0.11691319736880243", - "Likelihood: 0.19307908810123345", - "Likelihood: 0.08234154531304508", - "Likelihood: 0.1317114044230014", - "Likelihood: 0.18807562032547828", - "Likelihood: 0.11896850437630734", - "Likelihood: 0.18797215252353855", - "Likelihood: 0.21204153318102736", - "Likelihood: 0.14040540619320088", - "Likelihood: 0.19955064355664445", - "Likelihood: 0.2933790459943371", - "Likelihood: 0.12953111609954598", - "Likelihood: 0.10425575996040035", - "Likelihood: 0.10763332218648487", - "Likelihood: 0.16965410488804517", - "Likelihood: 0.25365233585716607", - "Likelihood: 0.20243050807879817", - "Likelihood: 0.21560580870482413", - "Likelihood: 0.2441030229577517", - "Likelihood: 0.12231758467873355", - "Likelihood: 0.29460288781208316", - "Likelihood: 0.0726616640091915", - "Likelihood: 0.25566156241555454", - "Likelihood: 0.2389122042686293", - "Likelihood: 0.11098251615101051", - "Likelihood: 0.03961067351572849", - "Likelihood: 0.2715840614190186", - "Likelihood: 0.23081817640299132", - "Likelihood: 0.20013625526384282", - "Likelihood: 0.07175816397325756", - "Likelihood: 0.24549591859746464", - "Likelihood: 0.1454283622038863", - "Likelihood: 0.20883484207423725", - "Likelihood: 0.06347293045725452", - "Likelihood: 0.2873348139002063", - "Likelihood: 0.27776623883543744", - "Likelihood: 0.08003069236295654", - "Likelihood: 0.16594229420860113", - "Likelihood: 0.18620453586760413", - "Likelihood: 0.09618332112351188", - "Likelihood: 0.24275386498528173", - "Likelihood: 0.24894586389026538", - "Likelihood: 0.24976836704007033", - "Likelihood: 0.022736343340402494", - "Likelihood: 0.2580979238879956", - "Likelihood: 0.1397184014423235", - "Likelihood: 0.15522843679176326", - "Likelihood: 0.19053951374965514", - "Likelihood: 0.09959938598216131", - "Likelihood: 0.22751280877772498", - "Likelihood: 0.06829242368045933", - "Likelihood: 0.12616590851644086", - "Likelihood: 0.16810976609089218", - "Likelihood: 0.22221584552067994", - "Likelihood: 0.2155269432939214", - "Likelihood: 0.28394375253496706", - "Likelihood: 0.19819469423527136", - "Likelihood: 0.23293063012207937", - "Likelihood: 0.05190446776745225", - "Likelihood: 0.2721137310153136", - "Likelihood: 0.17636289125411822", - "Likelihood: 0.21957885700814944", - "Likelihood: 0.20195825359904723", - "Likelihood: 0.2667371569399727", - "Likelihood: 0.2746626380507134", - "Likelihood: 0.12827898707636468", - "Likelihood: 0.2274288479843043", - "Likelihood: 0.029551136079996022", - "Likelihood: 0.20143908426805418", - "Likelihood: 0.2804435674185338", - "Likelihood: 0.15833905371240015", - "Likelihood: 0.2826493968288475", - "Likelihood: 0.17444400453442196", - "Likelihood: 0.25527549985248726", - "Likelihood: 0.11438616396047241", - "Likelihood: 0.15506816984591681", - "Likelihood: 0.1335032269586358", - "Likelihood: 0.08530391623030241", - "Likelihood: 0.24437080002730707", - "Likelihood: 0.24659884080992148", - "Likelihood: 0.18898140893737075", - "Likelihood: 0.29847954774576957", - "Likelihood: 0.1508832573841655", - "Likelihood: 0.09047094060415316", - "Likelihood: 0.1999786098665686", - "Likelihood: 0.15662486336888237", - "Likelihood: 0.21971453532446542", - "Likelihood: 0.20896141359818296", - "Likelihood: 0.0656020731412141", - "Likelihood: 0.10599085354900807", - "Likelihood: 0.3009505280227678", - "Likelihood: 0.18138588185202598", - "Likelihood: 0.21621852981759493", - "Likelihood: 0.10506762385760439", - "Likelihood: 0.25102284571810035", - "Likelihood: 0.14096359033479994", - "Likelihood: 0.06389310410880107", - "Likelihood: 0.11038200805893185", - "Likelihood: 0.19196385569533003", - "Likelihood: 0.23387772958221462", - "Likelihood: 0.23706500094036204", - "Likelihood: 0.038724657005628216", - "Likelihood: 0.15758794490185216", - "Likelihood: 0.2987098972750515", - "Likelihood: 0.22944504438493568", - "Likelihood: 0.2826589865231378", - "Likelihood: 0.2827792760369573", - "Likelihood: 0.2779108658050437", - "Likelihood: 0.22747616329813497", - "Likelihood: 0.1639217612067807", - "Likelihood: 0.2707977832830238", - "Likelihood: 0.29411651696722574", - "Likelihood: 0.13516644232448807", - "Likelihood: 0.17284230040718598", - "Likelihood: 0.2627153760298775", - "Likelihood: 0.19570462031062477", - "Likelihood: 0.26839359811284386", - "Likelihood: 0.04673840898478119", - "Likelihood: 0.15302650500610326", - "Likelihood: 0.053670676566372005", - "Likelihood: 0.292336498942764", - "Likelihood: 0.08294677045318995", - "Likelihood: 0.25170316318255376", - "Likelihood: 0.23639570021731013", - "Likelihood: 0.21235682956537139", - "Likelihood: 0.18341563589512513", - "Likelihood: 0.1347244763396118", - "Likelihood: 0.275108271484215", - "Likelihood: 0.23459028514762587", - "Likelihood: 0.2300772099373741", - "Likelihood: 0.1426324450444451", - "Likelihood: 0.18327551116842136", - "Likelihood: 0.1942884866403007", - "Likelihood: 0.2162143487717809", - "Likelihood: 0.1928474081041427", - "Likelihood: 0.11013511341226828", - "Likelihood: 0.15762776776787749", - "Likelihood: 0.25245661304467276", - "Likelihood: 0.15551666061892672", - "Likelihood: 0.1627706767276717", - "Likelihood: 0.10549436759915497", - "Likelihood: 0.2266285188603278", - "Likelihood: 0.28460281053015124", - "Likelihood: 0.13479478292196273", - "Likelihood: 0.16405495968202", - "Likelihood: 0.11013976885376327", - "Likelihood: 0.27587911769765183", - "Likelihood: 0.1848037713782701", - "Likelihood: 0.08771032306142855", - "Likelihood: 0.12492483985320008", - "Likelihood: 0.24006760826985696", - "Likelihood: 0.2536119656601371", - "Likelihood: 0.22249403292802572", - "Likelihood: 0.17686487663544354", - "Likelihood: 0.17657412452756605", - "Likelihood: 0.2643654816874487", - "Likelihood: 0.2845130459986827", - "Likelihood: 0.15781354953196247", - "Likelihood: 0.11189564710058467", - "Likelihood: 0.26327188923591865", - "Likelihood: 0.09869711632911359", - "Likelihood: 0.29114120489527495", - "Likelihood: 0.23668974638153334", - "Likelihood: 0.26594692252509833", - "Likelihood: 0.252406022031699", - "Likelihood: 0.021630441835911587", - "Likelihood: 0.11369840478659449", - "Likelihood: 0.2860895968152142", - "Likelihood: 0.2345150581026916", - "Likelihood: 0.24773006054048657", - "Likelihood: 0.23259987483107877", - "Likelihood: 0.18454260916465984", - "Likelihood: 0.17230027066408843", - "Likelihood: 0.23402913381102233", - "Likelihood: 0.1709614806055704", - "Likelihood: 0.12236273724588753", - "Likelihood: 0.03966598989753502", - "Likelihood: 0.16551917527808302", - "Likelihood: 0.17272702602081264", - "Likelihood: 0.24937358642302268", - "Likelihood: 0.20035595866248768", - "Likelihood: 0.3009183708290256", - "Likelihood: 0.12500109371742782", - "Likelihood: 0.07190773920281028", - "Likelihood: 0.24732212381291116", - "Likelihood: 0.09175051360663655", - "Likelihood: 0.1814298593129246", - "Likelihood: 0.13666359386067545", - "Likelihood: 0.21593466756858956", - "Likelihood: 0.09212524765849356", - "Likelihood: 0.1498202113885425", - "Likelihood: 0.29742245813305457", - "Likelihood: 0.26931993731908727", - "Likelihood: 0.11285257274849662", - "Likelihood: 0.14045104479357173", - "Likelihood: 0.05439386084608382", - "Likelihood: 0.07237007555711757", - "Likelihood: 0.13044353800044475", - "Likelihood: 0.15272018669954035", - "Likelihood: 0.27355688772605846", - "Likelihood: 0.27377502586912666", - "Likelihood: 0.29617811520206916", - "Likelihood: 0.23443904662482234", - "Likelihood: 0.17128889892286858", - "Likelihood: 0.11227439694982111", - "Likelihood: 0.20839321907085334", - "Likelihood: 0.2278534835808811", - "Likelihood: 0.2759106477405964", - "Likelihood: 0.20023115313160775", - "Likelihood: 0.15703429766987767", - "Likelihood: 0.13911313578857082", - "Likelihood: 0.04953695410839012", - "Likelihood: 0.10560487236810226", - "Likelihood: 0.19506236019989326", - "Likelihood: 0.2605174358733478", - "Likelihood: 0.10395254623898395", - "Likelihood: 0.13356477117349208", - "Likelihood: 0.27106696476232695", - "Likelihood: 0.13565701148804496", - "Likelihood: 0.12595700205011542", - "Likelihood: 0.09950318378907434", - "Likelihood: 0.24457722935066914", - "Likelihood: 0.2729274077297739", - "Likelihood: 0.17749482607577957", - "Likelihood: 0.1403406033995485", - "Likelihood: 0.05171886089554751", - "Likelihood: 0.24404413911503406", - "Likelihood: 0.1719760155935362", - "Likelihood: 0.220174993426906", - "Likelihood: 0.24482076034804615", - "Likelihood: 0.20154792379629274", - "Likelihood: 0.13987964510829295", - "Likelihood: 0.247237539553854", - "Likelihood: 0.2471637634782163", - "Likelihood: 0.1696925810778644", - "Likelihood: 0.16684430659044902", - "Likelihood: 0.29257766412492087", - "Likelihood: 0.25374895421834687", - "Likelihood: 0.2707803875530861", - "Likelihood: 0.19211813609659179", - "Likelihood: 0.16065888470937287", - "Likelihood: 0.29399442664347974", - "Likelihood: 0.2440764120083932", - "Likelihood: 0.22049000617390163", - "Likelihood: 0.22061614421974438", - "Likelihood: 0.24008714660537492", - "Likelihood: 0.1397817966386081", - "Likelihood: 0.23757981725140517", - "Likelihood: 0.2089148514542091", - "Likelihood: 0.17653084785596762", - "Likelihood: 0.16597545847039238", - "Likelihood: 0.13290570175431962", - "Likelihood: 0.2650634356714364", - "Likelihood: 0.25657302726307857", - "Likelihood: 0.06505218450613923", - "Likelihood: 0.19339362523869166", - "Likelihood: 0.2660616286758842", - "Likelihood: 0.2560016263174407", - "Likelihood: 0.2563634416273239", - "Likelihood: 0.054043865795941705", - "Likelihood: 0.12676334655082103", - "Likelihood: 0.21026977753554893", - "Likelihood: 0.18175894361003925", - "Likelihood: 0.18788135378632237", - "Likelihood: 0.20295114934503752", - "Likelihood: 0.24109265840499308", - "Likelihood: 0.27237130329427117", - "Likelihood: 0.23722140113605944", - "Likelihood: 0.12412266941887566", - "Likelihood: 0.16004256070343736", - "Likelihood: 0.29918085407080486", - "Likelihood: 0.21676567222973533", - "Likelihood: 0.16777053627657368", - "Likelihood: 0.17091356328166604", - "Likelihood: 0.2810530999178123", - "Likelihood: 0.08833707723884085", - "Likelihood: 0.15997602237287123", - "Likelihood: 0.22593158876522595", - "Likelihood: 0.20751386816749634", - "Likelihood: 0.12645631312908628", - "Likelihood: 0.2992297039502094", - "Likelihood: 0.05917621031563381", - "Likelihood: 0.20535018385881149", - "Likelihood: 0.23144884592209586", - "Likelihood: 0.1133054465978782", - "Likelihood: 0.22549518128901241", - "Likelihood: 0.2952487634610577", - "Likelihood: 0.14690860023804772", - "Likelihood: 0.2395392627808987", - "Likelihood: 0.21272572236863987", - "Likelihood: 0.2738375788477263", - "Likelihood: 0.19735475078019551", - "Likelihood: 0.21054055260952004", - "Likelihood: 0.2229613090264543", - "Likelihood: 0.15615895512228742", - "Likelihood: 0.14845564476563836", - "Likelihood: 0.16893390668078617", - "Likelihood: 0.26558558815796146", - "Likelihood: 0.07238624651755536", - "Likelihood: 0.24928837530270814", - "Likelihood: 0.21422583763207834", - "Likelihood: 0.19906966627119377", - "Likelihood: 0.2650468434787773", - "Likelihood: 0.14953251786359906", - "Likelihood: 0.05172219716641924", - "Likelihood: 0.2849790790502597", - "Likelihood: 0.27048545274768543", - "Likelihood: 0.27295019424400513", - "Likelihood: 0.22179780569802493", - "Likelihood: 0.21617755752906861", - "Likelihood: 0.20132395424962485", - "Likelihood: 0.2797219238982994", - "Likelihood: 0.2309923514485878", - "Likelihood: 0.2144310004144844", - "Likelihood: 0.10161320303258811", - "Likelihood: 0.16485082916776606", - "Likelihood: 0.22211710782715194", - "Likelihood: 0.06632074904412566", - "Likelihood: 0.13823505300454517", - "Likelihood: 0.19881951247108368", - "Likelihood: 0.16585898272982444", - "Likelihood: 0.07732007121659197", - "Likelihood: 0.09873943341013029", - "Likelihood: 0.14718136908386342", - "Likelihood: 0.19974401716092657", - "Likelihood: 0.24776195531348746", - "Likelihood: 0.2297780184496713", - "Likelihood: 0.21119526929350044", - "Likelihood: 0.09933150530604527", - "Likelihood: 0.12266108297393072", - "Likelihood: 0.20131582786153193", - "Likelihood: 0.21551018683950215", - "Likelihood: 0.272886417847633", - "Likelihood: 0.22800772197272742", - "Likelihood: 0.24677091865965092", - "Likelihood: 0.13747133979707005", - "Likelihood: 0.17731835001953072", - "Likelihood: 0.2316495524992777", - "Likelihood: 0.12685367398134362", - "Likelihood: 0.1833551041763661", - "Likelihood: 0.2980093050230984", - "Likelihood: 0.21728555093183335", - "Likelihood: 0.12803342034496992", - "Likelihood: 0.1951556108136913", - "Likelihood: 0.06640706202073056", - "Likelihood: 0.1285029906529403", - "Likelihood: 0.2695608338231991", - "Likelihood: 0.17403856509080398", - "Likelihood: 0.28595448507509136", - "Likelihood: 0.20517214103237527", - "Likelihood: 0.2454379633261945", - "Likelihood: 0.06259913469070623", - "Likelihood: 0.2429889841219692", - "Likelihood: 0.178351538499323", - "Likelihood: 0.12339657691609691", - "Likelihood: 0.20907126554996033", - "Likelihood: 0.19753664573905588", - "Likelihood: 0.20086420961015425", - "Likelihood: 0.2227015695394197", - "Likelihood: 0.28221011543567825", - "Likelihood: 0.2838598617436372", - "Likelihood: 0.09796056263922075", - "Likelihood: 0.2159207005919831", - "Likelihood: 0.29640183278645604", - "Likelihood: 0.278142746951829", - "Likelihood: 0.29413353142365306", - "Likelihood: 0.18501933798641534", - "Likelihood: 0.250317361904399", - "Likelihood: 0.22287488549694418", - "Likelihood: 0.2733775292371595", - "Likelihood: 0.07085372700977158", - "Likelihood: 0.23195064161343323", - "Likelihood: 0.2595060710643127", - "Likelihood: 0.16610404362681228", - "Likelihood: 0.1721020382504013", - "Likelihood: 0.1343477399513794", - "Likelihood: 0.2181345853666833", - "Likelihood: 0.17597329559277397", - "Likelihood: 0.10528660006064616", - "Likelihood: 0.2349865581553251", - "Likelihood: 0.23342676304045173", - "Likelihood: 0.2748387512118633", - "Likelihood: 0.04090749019163001", - "Likelihood: 0.18008237955353884", - "Likelihood: 0.09863592250734422", - "Likelihood: 0.14034745230524653", - "Likelihood: 0.24189164044058178", - "Likelihood: 0.17655783240820402", - "Likelihood: 0.18617154577156578", - "Likelihood: 0.2655019421978888", - "Likelihood: 0.22360827179225895", - "Likelihood: 0.22794161739538432", - "Likelihood: 0.18088888586328272", - "Likelihood: 0.12465645785608827", - "Likelihood: 0.2682454320354297", - "Likelihood: 0.28595546484900297", - "Likelihood: 0.17056099303856465", - "Likelihood: 0.09921174603923628", - "Likelihood: 0.21726539489497826", - "Likelihood: 0.19788421395509398", - "Likelihood: 0.0671602365766904", - "Likelihood: 0.26185846025021814", - "Likelihood: 0.13528143912411358", - "Likelihood: 0.2913180932660853", - "Likelihood: 0.16320735258286906", - "Likelihood: 0.14194226174902222", - "Likelihood: 0.20150639696345485", - "Likelihood: 0.19119460205245467", - "Likelihood: 0.26808330289816107", - "Likelihood: 0.16195608050816593", - "Likelihood: 0.10700020249712115", - "Likelihood: 0.14602363907383856", - "Likelihood: 0.2677690510306172", - "Likelihood: 0.21773751356034513", - "Likelihood: 0.10518249707810175", - "Likelihood: 0.18018266932165203", - "Likelihood: 0.28705321719231003", - "Likelihood: 0.2667040284277176", - "Likelihood: 0.22451323714085375", - "Likelihood: 0.16692484740466929", - "Likelihood: 0.18368321217042874", - "Likelihood: 0.183340421416651", - "Likelihood: 0.24908306455430196", - "Likelihood: 0.28483923769670894", - "Likelihood: 0.28472285563198774", - "Likelihood: 0.24583726751879884", - "Likelihood: 0.23387516970520755", - "Likelihood: 0.2449044535925918", - "Likelihood: 0.15778445199344718", - "Likelihood: 0.09696574901877066", - "Likelihood: 0.09076576352410706", - "Likelihood: 0.28793793417618974", - "Likelihood: 0.2431074999438459", - "Likelihood: 0.18821972345677973", - "Likelihood: 0.14793617506921214", - "Likelihood: 0.26261331059337295", - "Likelihood: 0.26555083083429265", - "Likelihood: 0.2792652058628759", - "Likelihood: 0.16586563763391515", - "Likelihood: 0.2128180817511142", - "Likelihood: 0.2526551853509839", - "Likelihood: 0.19346385964355417", - "Likelihood: 0.2320766275982338", - "Likelihood: 0.10298480481624447", - "Likelihood: 0.0448363267520611", - "Likelihood: 0.22950962291666577", - "Likelihood: 0.14500595682182005", - "Likelihood: 0.24050178794313426", - "Likelihood: 0.23522834975612586", - "Likelihood: 0.10748281317298992", - "Likelihood: 0.15452172951386353", - "Likelihood: 0.22592776474664242", - "Likelihood: 0.1778483411085408", - "Likelihood: 0.17231226993573626", - "Likelihood: 0.27590309290084886", - "Likelihood: 0.18733427198876879", - "Likelihood: 0.19687114484618484", - "Likelihood: 0.20797262281914328", - "Likelihood: 0.1286539259941555", - "Likelihood: 0.16386543364018694", - "Likelihood: 0.2189382677283932", - "Likelihood: 0.20407195089544672", - "Likelihood: 0.2317663592578784", - "Likelihood: 0.1577008524317086", - "Likelihood: 0.23509455673267526", - "Likelihood: 0.096366092552183", - "Likelihood: 0.17282845702336522", - "Likelihood: 0.1883491493764855", - "Likelihood: 0.1836472525238907", - "Likelihood: 0.21838256016593893", - "Likelihood: 0.23100532635895812", - "Likelihood: 0.2122399627514725", - "Likelihood: 0.14514130314081009", - "Likelihood: 0.2152749579247468", - "Likelihood: 0.20893550827171864", - "Likelihood: 0.09868415854130534", - "Likelihood: 0.21709985156750897", - "Likelihood: 0.20220912890181483", - "Likelihood: 0.2121011149457165", - "Likelihood: 0.16993181508491575", - "Likelihood: 0.10528575280340344", - "Likelihood: 0.202720699960693", - "Likelihood: 0.018898118680344286", - "Likelihood: 0.15212198893521187", - "Likelihood: 0.15430680881639752", - "Likelihood: 0.11869276627198795", - "Likelihood: 0.2407146460280921", - "Likelihood: 0.12277132657047167", - "Likelihood: 0.2081377422867851", - "Likelihood: 0.0644720686542784", - "Likelihood: 0.0891675341808055", - "Likelihood: 0.1036885455751936", - "Likelihood: 0.29741627799545683", - "Likelihood: 0.24400851646598026", - "Likelihood: 0.26998867097590573", - "Likelihood: 0.19909021441211966", - "Likelihood: 0.20999285809362928", - "Likelihood: 0.28462464671909854", - "Likelihood: 0.26724257793357675", - "Likelihood: 0.2249953141678716", - "Likelihood: 0.23256548915356498", - "Likelihood: 0.17507649228052968", - "Likelihood: 0.25870518142425947", - "Likelihood: 0.2326969219548261", - "Likelihood: 0.11538118037763345", - "Likelihood: 0.29762355814458374", - "Likelihood: 0.18797180824939042", - "Likelihood: 0.19723426631346339", - "Likelihood: 0.13669155750871662", - "Likelihood: 0.19785111730408741", - "Likelihood: 0.21140412000066414", - "Likelihood: 0.2542854643459774", - "Likelihood: 0.21635537202769417", - "Likelihood: 0.24651066198786292", - "Likelihood: 0.2038272659053591", - "Likelihood: 0.2911271686556825", - "Likelihood: 0.29129413234546075", - "Likelihood: 0.06304673832188881", - "Likelihood: 0.17047173437359414", - "Likelihood: 0.12408236712851713", - "Likelihood: 0.10483241736119195", - "Likelihood: 0.26735645089872434", - "Likelihood: 0.14247891532441798", - "Likelihood: 0.2246983245826498", - "Likelihood: 0.2847962696382853", - "Likelihood: 0.19019543906750686", - "Likelihood: 0.18249727040048952", - "Likelihood: 0.15326195730718517", - "Likelihood: 0.06228611334669175", - "Likelihood: 0.08392431226574858", - "Likelihood: 0.1618731012489437", - "Likelihood: 0.12210293143454827", - "Likelihood: 0.08973973483840945", - "Likelihood: 0.13178516373971627", - "Likelihood: 0.25512766294819317", - "Likelihood: 0.2061843907712517", - "Likelihood: 0.11117719465830016", - "Likelihood: 0.16884960839599666", - "Likelihood: 0.21340646028301213", - "Likelihood: 0.19341629058426787", - "Likelihood: 0.22465262258740806", - "Likelihood: 0.12073405791316368", - "Likelihood: 0.27748425533627347", - "Likelihood: 0.28567790232222245", - "Likelihood: 0.18899697461378337", - "Likelihood: 0.21636693100382504", - "Likelihood: 0.1595420450941716", - "Likelihood: 0.27224999239659126", - "Likelihood: 0.27270283606732115", - "Likelihood: 0.09219479986358699", - "Likelihood: 0.0889822574728296", - "Likelihood: 0.272214433818482", - "Likelihood: 0.2357738820512381", - "Likelihood: 0.1603877555431732", - "Likelihood: 0.13147712807128994", - "Likelihood: 0.12996587937675566", - "Likelihood: 0.1319164862984217", - "Likelihood: 0.21967668820263864", - "Likelihood: 0.2417863912833152", - "Likelihood: 0.07820982220782471", - "Likelihood: 0.25227324698472586", - "Likelihood: 0.0571075940344746", - "Likelihood: 0.282911621111673", - "Likelihood: 0.17712655333065833", - "Likelihood: 0.055134508335885894", - "Likelihood: 0.2997998403951188", - "Likelihood: 0.15124872178961482", - "Likelihood: 0.2662702741681715", - "Likelihood: 0.27352201238064683", - "Likelihood: 0.2253654727743762", - "Likelihood: 0.11926321702624548", - "Likelihood: 0.29728268854959256", - "Likelihood: 0.25896263823525884", - "Likelihood: 0.20534529758616857", - "Likelihood: 0.27021356550946163", - "Likelihood: 0.12876329323602248", - "Likelihood: 0.08732450367967608", - "Likelihood: 0.07300935699299847", - "Likelihood: 0.23517321815613546", - "Likelihood: 0.22969502108899734", - "Likelihood: 0.13514672743720701", - "Likelihood: 0.2739496254957244", - "Likelihood: 0.2655035524753501", - "Likelihood: 0.24027202327079447", - "Likelihood: 0.299617222283339", - "Likelihood: 0.2658901511087618", - "Likelihood: 0.1164650888660763", - "Likelihood: 0.2581299698594998", - "Likelihood: 0.17248031230877212", - "Likelihood: 0.2726969074901538", - "Likelihood: 0.16975718276550777", - "Likelihood: 0.1553770093302075", - "Likelihood: 0.22026592929408212", - "Likelihood: 0.2408679285683447", - "Likelihood: 0.2279524194556734", - "Likelihood: 0.10133452235374703", - "Likelihood: 0.20949354473169898", - "Likelihood: 0.1265279559644034", - "Likelihood: 0.14247329494282412", - "Likelihood: 0.22792557862156235", - "Likelihood: 0.17978391696100954", - "Likelihood: 0.2518933600078773", - "Likelihood: 0.2622859420777334", - "Likelihood: 0.1512852067419167", - "Likelihood: 0.11459013011860342", - "Likelihood: 0.015130586503977033", - "Likelihood: 0.22889688625169366", - "Likelihood: 0.2235924136561524", - "Likelihood: 0.19920333904635154", - "Likelihood: 0.24045615413674046", - "Likelihood: 0.21261823316262732", - "Likelihood: 0.06411953087256102", - "Likelihood: 0.1608264010960205", - "Likelihood: 0.08718615645496135", - "Likelihood: 0.2946128170233322", - "Likelihood: 0.022312549426751555", - "Likelihood: 0.29906845498128776", - "Likelihood: 0.2522675469740475", - "Likelihood: 0.18686659736987588", - "Likelihood: 0.169974316229605", - "Likelihood: 0.21091165940631607", - "Likelihood: 0.24714376930603", - "Likelihood: 0.23502993126174065", - "Likelihood: 0.22201518347545976", - "Likelihood: 0.25878716083058817", - "Likelihood: 0.15915207592522435", - "Likelihood: 0.14345597592497095", - "Likelihood: 0.20626797449069403", - "Likelihood: 0.018009340072310923", - "Likelihood: 0.20963605982173103", - "Likelihood: 0.22021718029151982", - "Likelihood: 0.08511308533115616", - "Likelihood: 0.28529264101944785", - "Likelihood: 0.1330465098885672", - "Likelihood: 0.25786543033274417", - "Likelihood: 0.15966427092214447", - "Likelihood: 0.15527915763763186", - "Likelihood: 0.192523339909868", - "Likelihood: 0.28881039720438684", - "Likelihood: 0.061330184021588977", - "Likelihood: 0.1348130786089015", - "Likelihood: 0.16838010237254564", - "Likelihood: 0.29053808583857044", - "Likelihood: 0.04275741936098256", - "Likelihood: 0.20625268024858445", - "Likelihood: 0.17504794516740538", - "Likelihood: 0.17668948809198048", - "Likelihood: 0.0788110977275982", - "Likelihood: 0.029401726552997054", - "Likelihood: 0.08291262296054666", - "Likelihood: 0.2808888658484632", - "Likelihood: 0.12513405187560844", - "Likelihood: 0.22843983514055033", - "Likelihood: 0.24234619434270824", - "Likelihood: 0.16300931667187477", - "Likelihood: 0.21696698526310765", - "Likelihood: 0.16281375764842454", - "Likelihood: 0.18331647478337876", - "Likelihood: 0.19306379556186082", - "Likelihood: 0.14899745969954592", - "Likelihood: 0.24252135739699882", - "Likelihood: 0.10135218648622535", - "Likelihood: 0.2905973762988807", - "Likelihood: 0.0626629433005062", - "Likelihood: 0.2669591032645717", - "Likelihood: 0.26286866753241106", - "Likelihood: 0.23598634470601948", - "Likelihood: 0.02192537654854545", - "Likelihood: 0.11288601367012491", - "Likelihood: 0.23150065267638165", - "Likelihood: 0.18153679909511147", - "Likelihood: 0.1848875724560143", - "Likelihood: 0.25767928757177594", - "Likelihood: 0.13226696840769148", - "Likelihood: 0.08679016259352969", - "Likelihood: 0.22781996373901875", - "Likelihood: 0.1735768877234029", - "Likelihood: 0.2645593206150752", - "Likelihood: 0.17669133334672485", - "Likelihood: 0.2360802676739949", - "Likelihood: 0.28503118312480125", - "Likelihood: 0.22057992393363343", - "Likelihood: 0.08331019278014953", - "Likelihood: 0.1735209834664876", - "Likelihood: 0.30276550720632817", - "Likelihood: 0.24426074717538374", - "Likelihood: 0.15352811117531984", - "Likelihood: 0.14849558911549865", - "Likelihood: 0.0603418843424588", - "Likelihood: 0.278767940105198", - "Likelihood: 0.2808143366678585", - "Likelihood: 0.20539717396249182", - "Likelihood: 0.18363857178223134", - "Likelihood: 0.2674946595103876", - "Likelihood: 0.21609610226230477", - "Likelihood: 0.14240912475269182", - "Likelihood: 0.22141860864159052", - "Likelihood: 0.18769416161371835", - "Likelihood: 0.18202362623988252", - "Likelihood: 0.21980090883892106", - "Likelihood: 0.11247774811556134", - "Likelihood: 0.267929494834779", - "Likelihood: 0.10594398636942184", - "Likelihood: 0.26721083276485535", - "Likelihood: 0.13158943741495877", - "Likelihood: 0.11799096180700692", - "Likelihood: 0.15969495138385606", - "Likelihood: 0.19894769793575126", - "Likelihood: 0.24745249204732472", - "Likelihood: 0.14405330791868992", - "Likelihood: 0.08556565053325058", - "Likelihood: 0.26164113324636556", - "Likelihood: 0.2851429021308463", - "Likelihood: 0.07946749748624364", - "Likelihood: 0.12491628260986594", - "Likelihood: 0.17518613604188224", - "Likelihood: 0.27786626358856803", - "Likelihood: 0.2548116921433457", - "Likelihood: 0.2045121053137181", - "Likelihood: 0.21936621343189244", - "Likelihood: 0.2141764348363892", - "Likelihood: 0.13821919520111084", - "Likelihood: 0.19826211359345547", - "Likelihood: 0.3031817690745593", - "Likelihood: 0.22022365803405014", - "Likelihood: 0.13558559383306587", - "Likelihood: 0.2226994939808481", - "Likelihood: 0.23602253763199738", - "Likelihood: 0.1324597021271762", - "Likelihood: 0.29580872497893446", - "Likelihood: 0.19521694198747022", - "Likelihood: 0.14286965708226862", - "Likelihood: 0.25803896211864946", - "Likelihood: 0.2700993826272165", - "Likelihood: 0.14954922679450527", - "Likelihood: 0.1891874277533951", - "Likelihood: 0.16654285196400184", - "Likelihood: 0.19915378274157491", - "Likelihood: 0.28051148506879753", - "Likelihood: 0.22062470833949466", - "Likelihood: 0.2928553408421224", - "Likelihood: 0.19968696951412204", - "Likelihood: 0.2475104316649361", - "Likelihood: 0.25126577420321006", - "Likelihood: 0.2830483831344267", - "Likelihood: 0.15193356273288425", - "Likelihood: 0.14012947618572164", - "Likelihood: 0.30339129136486515", - "Likelihood: 0.07752719763168196", - "Likelihood: 0.157776211878984", - "Likelihood: 0.2876581589389093", - "Likelihood: 0.26277784132679816", - "Likelihood: 0.17378218056628345", - "Likelihood: 0.13837069245486175", - "Likelihood: 0.2464132408520835", - "Likelihood: 0.09211993785829226", - "Likelihood: 0.2568432396431044", - "Likelihood: 0.1326718911341", - "Likelihood: 0.20426084099648328", - "Likelihood: 0.20618701418981364", - "Likelihood: 0.16639557806880467", - "Likelihood: 0.2564947192705591", - "Likelihood: 0.2590054536296896", - "Likelihood: 0.19692107077702092", - "Likelihood: 0.29016191987489437", - "Likelihood: 0.11072737499552697", - "Likelihood: 0.11502719397793108", - "Likelihood: 0.042473376573612234", - "Likelihood: 0.15594683320548025", - "Likelihood: 0.02152919750260241", - "Likelihood: 0.2492749524952565", - "Likelihood: 0.23021031474342307", - "Likelihood: 0.2835082969849027", - "Likelihood: 0.2567751619518954", - "Likelihood: 0.227474764990129", - "Likelihood: 0.09958096945389873", - "Likelihood: 0.14337312351811696", - "Likelihood: 0.1921286034103214", - "Likelihood: 0.18311891139098477", - "Likelihood: 0.2708376212168452", - "Likelihood: 0.2164431307972528", - "Likelihood: 0.27057337853301433", - "Likelihood: 0.09019881536950383", - "Likelihood: 0.2539998861700445", - "Likelihood: 0.2227640332526775", - "Likelihood: 0.20227848300005194", - "Likelihood: 0.2550448131664871", - "Likelihood: 0.11676706467916576", - "Likelihood: 0.08737720287525745", - "Likelihood: 0.2823517821332575", - "Likelihood: 0.20307246227536244", - "Likelihood: 0.2281356004404157", - "Likelihood: 0.2242437214267084", - "Likelihood: 0.0593126864918483", - "Likelihood: 0.18260515526907625", - "Likelihood: 0.09932288149204936", - "Likelihood: 0.221378411192434", - "Likelihood: 0.2878690272413046", - "Likelihood: 0.10586430998895108", - "Likelihood: 0.04914968548446518", - "Likelihood: 0.16317221868056955", - "Likelihood: 0.13767371896867817", - "Likelihood: 0.12943129359996294", - "Likelihood: 0.282107800648092", - "Likelihood: 0.22789640365697172", - "Likelihood: 0.1525515383420608", - "Likelihood: 0.2525864749925585", - "Likelihood: 0.2667262511206517", - "Likelihood: 0.23483780000744992", - "Likelihood: 0.2908478611941437", - "Likelihood: 0.21095921104873244", - "Likelihood: 0.23195859819824527", - "Likelihood: 0.11438491406429792", - "Likelihood: 0.2312315180734451", - "Likelihood: 0.006541113636750487", - "Likelihood: 0.17506971051919756", - "Likelihood: 0.274107091283225", - "Likelihood: 0.2755938207949834", - "Likelihood: 0.2921773878803099", - "Likelihood: 0.19495093655087542", - "Likelihood: 0.2846052073857303", - "Likelihood: 0.22297516330953546", - "Likelihood: 0.24633836747778615", - "Likelihood: 0.18620761468120098", - "Likelihood: 0.13740152754620258", - "Likelihood: 0.24370721709938614", - "Likelihood: 0.16605949071503223", - "Likelihood: 0.22485620834876266", - "Likelihood: 0.16291678348072905", - "Likelihood: 0.08316568441832774", - "Likelihood: 0.12170657499398434", - "Likelihood: 0.22984943233921384", - "Likelihood: 0.17897865040039634", - "Likelihood: 0.27352075195668113", - "Likelihood: 0.2258027783551675", - "Likelihood: 0.23569810438414693", - "Likelihood: 0.19662019242760057", - "Likelihood: 0.15602890988473564", - "Likelihood: 0.13193994629769787", - "Likelihood: 0.17955372211981446", - "Likelihood: 0.0915777236524987", - "Likelihood: 0.0662790049165268", - "Likelihood: 0.29382241262053227", - "Likelihood: 0.08247675876910794", - "Likelihood: 0.09079194946567659", - "Likelihood: 0.30100472876755596", - "Likelihood: 0.266203693226217", - "Likelihood: 0.14337888311347963", - "Likelihood: 0.21650982718319306", - "Likelihood: 0.27281387939104845", - "Likelihood: 0.17278060768932785", - "Likelihood: 0.055376795515479305", - "Likelihood: 0.26382766375159433", - "Likelihood: 0.23155414285638382", - "Likelihood: 0.23162772095225495", - "Likelihood: 0.1476692565775839", - "Likelihood: 0.24300453799892116", - "Likelihood: 0.2750345239865073", - "Likelihood: 0.12800947830133574", - "Likelihood: 0.21988497404808674", - "Likelihood: 0.20067033458353886", - "Likelihood: 0.18213926132505756", - "Likelihood: 0.0348809068396792", - "Likelihood: 0.17098213181368896", - "Likelihood: 0.09297658748824598", - "Likelihood: 0.20083992585949026", - "Likelihood: 0.14860453377146896", - "Likelihood: 0.24416946449476276", - "Likelihood: 0.2675224834385586", - "Likelihood: 0.2602844683511139", - "Likelihood: 0.19980031960290054", - "Likelihood: 0.20603766521574943", - "Likelihood: 0.2413454205083339", - "Likelihood: 0.10720789757882077", - "Likelihood: 0.25722945847147605", - "Likelihood: 0.1371543358414774", - "Likelihood: 0.17141991213797245", - "Likelihood: 0.16363664035865294", - "Likelihood: 0.17195549750124645", - "Likelihood: 0.14901824103100114", - "Likelihood: 0.26617608089273626", - "Likelihood: 0.170200889240268", - "Likelihood: 0.11043689890224498", - "Likelihood: 0.23546599877738644", - "Likelihood: 0.2748836338853741", - "Likelihood: 0.3039486234356906", - "Likelihood: 0.13373090113987451", - "Likelihood: 0.1802411958077837", - "Likelihood: 0.19622603225000418", - "Likelihood: 0.13668882868900262", - "Likelihood: 0.2755762591603915", - "Likelihood: 0.1488657003263755", - "Likelihood: 0.2536525320694672", - "Likelihood: 0.11018193916364533", - "Likelihood: 0.25558809352948475", - "Likelihood: 0.22463941744508997", - "Likelihood: 0.1084838582946466", - "Likelihood: 0.1668763329809771", - "Likelihood: 0.2304690274147457", - "Likelihood: 0.27769932014195814", - "Likelihood: 0.24738165028805548", - "Likelihood: 0.1984547634917522", - "Likelihood: 0.22581053382101096", - "Likelihood: 0.19869192754501946", - "Likelihood: 0.16594936710936908", - "Likelihood: 0.2719367485560884", - "Likelihood: 0.25271148440035984", - "Likelihood: 0.15013073590825543", - "Likelihood: 0.15577025625694116", - "Likelihood: 0.2830482238979884", - "Likelihood: 0.1413981627825187", - "Likelihood: 0.09526478023288378", - "Likelihood: 0.1637264136109912", - "Likelihood: 0.21562650379812529", - "Likelihood: 0.1358326018751923", - "Likelihood: 0.2915152923493532", - "Likelihood: 0.24173779905272133", - "Likelihood: 0.26034449301435997", - "Likelihood: 0.07287305014139461", - "Likelihood: 0.12026033202719683", - "Likelihood: 0.1989684622200308", - "Likelihood: 0.11805570303456628", - "Likelihood: 0.268933495921877", - "Likelihood: 0.26043471806279267", - "Likelihood: 0.2964309624201217", - "Likelihood: 0.2858779556986227", - "Likelihood: 0.17985749223899375", - "Likelihood: 0.09189067363158626", - "Likelihood: 0.053799240077419826", - "Likelihood: 0.1932260257276969", - "Likelihood: 0.0934364794323832", - "Likelihood: 0.26824139361154453", - "Likelihood: 0.1710346050845573", - "Likelihood: 0.2455804042419595", - "Likelihood: 0.19969276083892798", - "Likelihood: 0.27136439367254983", - "Likelihood: 0.273214711477825", - "Likelihood: 0.1982764834617303", - "Likelihood: 0.10370283775319286", - "Likelihood: 0.26670706870917205", - "Likelihood: 0.02254576439763968", - "Likelihood: 0.2274242860728687", - "Likelihood: 0.15389654331268185", - "Likelihood: 0.2955174850756024", - "Likelihood: 0.17542834589196904", - "Likelihood: 0.13687331998784477", - "Likelihood: 0.24593402372169734", - "Likelihood: 0.12479004907533689", - "Likelihood: 0.07261256471166361", - "Likelihood: 0.15325447876197343", - "Likelihood: 0.05712526829238628", - "Likelihood: 0.19877178254228778", - "Likelihood: 0.20917425984953703", - "Likelihood: 0.22690902891860595", - "Likelihood: 0.16960488510831187", - "Likelihood: 0.1390426168933149", - "Likelihood: 0.18249195821498915", - "Likelihood: 0.1733197966069247", - "Likelihood: 0.12946403845745155", - "Likelihood: 0.2356297722298361", - "Likelihood: 0.23775873823984836", - "Likelihood: 0.24530125859001645", - "Likelihood: 0.17972185141827032", - "Likelihood: 0.11783978125023345", - "Likelihood: 0.1892724644135291", - "Likelihood: 0.1014692244413603", - "Likelihood: 0.22568844914062566", - "Likelihood: 0.20289736746764384", - "Likelihood: 0.23932200184071103", - "Likelihood: 0.28135000392499754", - "Likelihood: 0.27141422268602955", - "Likelihood: 0.21531957100704505", - "Likelihood: 0.16611866977063547", - "Likelihood: 0.1287181381955705", - "Likelihood: 0.2523287699806822", - "Likelihood: 0.20501642642227144", - "Likelihood: 0.13582956398265547", - "Likelihood: 0.2083981995592043", - "Likelihood: 0.24430039697244005", - "Likelihood: 0.2617746797064583", - "Likelihood: 0.24361405290204305", - "Likelihood: 0.11109348078463738", - "Likelihood: 0.08051013026758229", - "Likelihood: 0.2812187021547169", - "Likelihood: 0.28313966171857724", - "Likelihood: 0.25479505276068937", - "Likelihood: 0.15286960407214517", - "Likelihood: 0.26464521939868085", - "Likelihood: 0.2661617925739468", - "Likelihood: 0.28021724606020704", - "Likelihood: 0.06396913856667824", - "Likelihood: 0.11406600556862026", - "Likelihood: 0.18801260316993132", - "Likelihood: 0.12021742601269492", - "Likelihood: 0.16017272567158244", - "Likelihood: 0.22637125836798924", - "Likelihood: 0.25818049032398604", - "Likelihood: 0.06455552440303162", - "Likelihood: 0.09607225974803303", - "Likelihood: 0.24907646063074362", - "Likelihood: 0.2100667062905943", - "Likelihood: 0.011474110040463713", - "Likelihood: 0.1972430960031025", - "Likelihood: 0.24312770854916071", - "Likelihood: 0.28978956694396435", - "Likelihood: 0.1560479264688962", - "Likelihood: 0.1355604601961092", - "Likelihood: 0.2359502658759168", - "Likelihood: 0.13710867209403216", - "Likelihood: 0.29815042865567454", - "Likelihood: 0.17725967854705818", - "Likelihood: 0.11675333852170483", - "Likelihood: 0.1763234091868755", - "Likelihood: 0.26769494617123096", - "Likelihood: 0.14917732894766395", - "Likelihood: 0.1981906097270498", - "Likelihood: 0.24613996232765553", - "Likelihood: 0.26815443801740235", - "Likelihood: 0.13556771197668982", - "Likelihood: 0.13759964245234485", - "Likelihood: 0.1972805038923744", - "Likelihood: 0.2280202307858229", - "Likelihood: 0.19311761342971442", - "Likelihood: 0.2897613125576324", - "Likelihood: 0.19126592468158746", - "Likelihood: 0.1341675737972313", - "Likelihood: 0.1670687394361393", - "Likelihood: 0.14084338904316526", - "Likelihood: 0.12221827018068394", - "Likelihood: 0.1271066310304912", - "Likelihood: 0.2003638428643911", - "Likelihood: 0.1824822011151203", - "Likelihood: 0.055009352806502584", - "Likelihood: 0.15364439660261875", - "Likelihood: 0.19020885395819723", - "Likelihood: 0.10820333613880877", - "Likelihood: 0.20398637057208627", - "Likelihood: 0.19949575818715934", - "Likelihood: 0.1813460616699816", - "Likelihood: 0.24610124722617338", - "Likelihood: 0.037158807723262195", - "Likelihood: 0.11349784440712356", - "Likelihood: 0.23291955279367588", - "Likelihood: 0.3033183705059726", - "Likelihood: 0.17977502345309318", - "Likelihood: 0.1703277632732763", - "Likelihood: 0.16496902012423093", - "Likelihood: 0.0753328168469319", - "Likelihood: 0.27529502943457207", - "Likelihood: 0.248369221952312", - "Likelihood: 0.23666125128303495", - "Likelihood: 0.03683672397943074", - "Likelihood: 0.1451574744073546", - "Likelihood: 0.2935851692811669", - "Likelihood: 0.15038949962163084", - "Likelihood: 0.1880901037674344", - "Likelihood: 0.19521903893355502", - "Likelihood: 0.2551825940727606", - "Likelihood: 0.22345968998330729", - "Likelihood: 0.2628738489040089", - "Likelihood: 0.12405253465680044", - "Likelihood: 0.23221398347933886", - "Likelihood: 0.2089378934207066", - "Likelihood: 0.2819024334090949", - "Likelihood: 0.20498558846955947", - "Likelihood: 0.12139586717793052", - "Likelihood: 0.19443474277566858", - "Likelihood: 0.22385682101268334", - "Likelihood: 0.23672831100352673", - "Likelihood: 0.1792062491859811", - "Likelihood: 0.2756623497449613", - "Likelihood: 0.16487082411528", - "Likelihood: 0.18284203309091204", - "Likelihood: 0.22615294004616554", - "Likelihood: 0.16421046638512002", - "Likelihood: 0.22838903683592807", - "Likelihood: 0.30254073938521536", - "Likelihood: 0.29884889786467006", - "Likelihood: 0.22177611957259716", - "Likelihood: 0.15469093475496382", - "Likelihood: 0.18895975088416084", - "Likelihood: 0.25226022237362117", - "Likelihood: 0.2108550175228998", - "Likelihood: 0.2554830530759696", - "Likelihood: 0.2029167718067003", - "Likelihood: 0.28274831440359116", - "Likelihood: 0.24867783066804672", - "Likelihood: 0.2667772895432627", - "Likelihood: 0.27187101112208845", - "Likelihood: 0.21343697283120278", - "Likelihood: 0.1761940465667346", - "Likelihood: 0.2959442062198631", - "Likelihood: 0.17545921568653358", - "Likelihood: 0.2700515329559339", - "Likelihood: 0.18508765556785886", - "Likelihood: 0.06370885775515209", - "Likelihood: 0.28486643402206324", - "Likelihood: 0.25297494296827155", - "Likelihood: 0.264836328797687", - "Likelihood: 0.2502108268353748", - "Likelihood: 0.23876056811409435", - "Likelihood: 0.26107351649076177", - "Likelihood: 0.24366651329933506", - "Likelihood: 0.26535572957444087", - "Likelihood: 0.11176412598226478", - "Likelihood: 0.2703523972159863", - "Likelihood: 0.30117619095393516", - "Likelihood: 0.1410150118040422", - "Likelihood: 0.25368650795000697", - "Likelihood: 0.20473935489875983", - "Likelihood: 0.1398159180876657", - "Likelihood: 0.2717310443797253", - "Likelihood: 0.15725370503252764", - "Likelihood: 0.17023952147003443", - "Likelihood: 0.27927799756272353", - "Likelihood: 0.2683206889196256", - "Likelihood: 0.22485163257708232", - "Likelihood: 0.30009345386583913", - "Likelihood: 0.27786847867462616", - "Likelihood: 0.2459501740308977", - "Likelihood: 0.2751804304579441", - "Likelihood: 0.2319142364590869", - "Likelihood: 0.16567653904006807", - "Likelihood: 0.0817651844571923", - "Likelihood: 0.13885796133246614", - "Likelihood: 0.2567296563356995", - "Likelihood: 0.16040426456194334", - "Likelihood: 0.155985434144907", - "Likelihood: 0.179988783535012", - "Likelihood: 0.22514606020028083", - "Likelihood: 0.02708919341992422", - "Likelihood: 0.09199633239676148", - "Likelihood: 0.11263651153944436", - "Likelihood: 0.07579885053466141", - "Likelihood: 0.13868886167667094", - "Likelihood: 0.19776984171332093", - "Likelihood: 0.1121495220139872", - "Likelihood: 0.16924183225446698", - "Likelihood: 0.04611883092395974", - "Likelihood: 0.15553229205469263", - "Likelihood: 0.26995147185172885", - "Likelihood: 0.2717852352208117", - "Likelihood: 0.15597780510004944", - "Likelihood: 0.12972050655564826", - "Likelihood: 0.20258409329894214", - "Likelihood: 0.2937874613348116", - "Likelihood: 0.20827652524501378", - "Likelihood: 0.10864025597069005", - "Likelihood: 0.07980015777784119", - "Likelihood: 0.15914104637811108", - "Likelihood: 0.2888280269086792", - "Likelihood: 0.16145039605353534", - "Likelihood: 0.159453018595154", - "Likelihood: 0.298373928222213", - "Likelihood: 0.14404158114835172", - "Likelihood: 0.1643672207780662", - "Likelihood: 0.19394580287990817", - "Likelihood: 0.061553671452141516", - "Likelihood: 0.2110585102421283", - "Likelihood: 0.2363082627588958", - "Likelihood: 0.29932567012131145", - "Likelihood: 0.27050128705943416", - "Likelihood: 0.20282868286188613", - "Likelihood: 0.20956346755814018", - "Likelihood: 0.29430048150863586", - "Likelihood: 0.11065833019440728", - "Likelihood: 0.2626894540524518", - "Likelihood: 0.17092689793892352", - "Likelihood: 0.1765661420093829", - "Likelihood: 0.14199724348001783", - "Likelihood: 0.22630488331589899", - "Likelihood: 0.10733490335821669", - "Likelihood: 0.06024848199871234", - "Likelihood: 0.16187835346536097", - "Likelihood: 0.09854779822858734", - "Likelihood: 0.16356609846822365", - "Likelihood: 0.22696919251087724", - "Likelihood: 0.2999430034145131", - "Likelihood: 0.27237784805513243", - "Likelihood: 0.09881733624837548", - "Likelihood: 0.19275755981625423", - "Likelihood: 0.16246933039100042", - "Likelihood: 0.28665331463887056", - "Likelihood: 0.22214946715628725", - "Likelihood: 0.06655288384705803", - "Likelihood: 0.29635424002132754", - "Likelihood: 0.1784326720678221", - "Likelihood: 0.11221932553448981", - "Likelihood: 0.2960050767854066", - "Likelihood: 0.21475726309867088", - "Likelihood: 0.06775353723708231", - "Likelihood: 0.28723845633015016", - "Likelihood: 0.25311744139924774", - "Likelihood: 0.14793069134849454", - "Likelihood: 0.20564185449516645", - "Likelihood: 0.2675754665826771", - "Likelihood: 0.14963004706909813", - "Likelihood: 0.1203445537423593", - "Likelihood: 0.2567099344847782", - "Likelihood: 0.14942228853943462", - "Likelihood: 0.1662201855435933", - "Likelihood: 0.19764437831469103", - "Likelihood: 0.25370120505128596", - "Likelihood: 0.26749049728629487", - "Likelihood: 0.2532045933819046", - "Likelihood: 0.28238045819369983", - "Likelihood: 0.18615081796292707", - "Likelihood: 0.1975274607751929", - "Likelihood: 0.2530931171303836", - "Likelihood: 0.2603557782477547", - "Likelihood: 0.08873924389130562", - "Likelihood: 0.1888739624334823", - "Likelihood: 0.04255682941242666", - "Likelihood: 0.2644356537223953", - "Likelihood: 0.18382901278727307", - "Likelihood: 0.26839185222498174", - "Likelihood: 0.10867937804247745", - "Likelihood: 0.27739521001875383", - "Likelihood: 0.29875741732395866", - "Likelihood: 0.1399563274421952", - "Likelihood: 0.2127447212969073", - "Likelihood: 0.29307761633698853", - "Likelihood: 0.23755673335102606", - "Likelihood: 0.1302686368665886", - "Likelihood: 0.15352279282627243", - "Likelihood: 0.15722445380776834", - "Likelihood: 0.25493357693154506", - "Likelihood: 0.11608097234719846", - "Likelihood: 0.24347160346449487", - "Likelihood: 0.29474812541640766", - "Likelihood: 0.14727617852144873", - "Likelihood: 0.2967837068676958", - "Likelihood: 0.13215380081272587", - "Likelihood: 0.204484726282082", - "Likelihood: 0.17102335320341974", - "Likelihood: 0.03701017197075056", - "Likelihood: 0.14210075345485484", - "Likelihood: 0.19172928861697128", - "Likelihood: 0.0549699897525326", - "Likelihood: 0.249266148290262", - "Likelihood: 0.20492894375129114", - "Likelihood: 0.22102451117091618", - "Likelihood: 0.09995331348853695", - "Likelihood: 0.1363108822412598", - "Likelihood: 0.1160740197353326", - "Likelihood: 0.15829418309590876", - "Likelihood: 0.13052778161185788", - "Likelihood: 0.2223599898517518", - "Likelihood: 0.21793049232160067", - "Likelihood: 0.2872601808781622", - "Likelihood: 0.06831793229062412", - "Likelihood: 0.18921505317563986", - "Likelihood: 0.02671950987479404", - "Likelihood: 0.1970305419955053", - "Likelihood: 0.015815917264079143", - "Likelihood: 0.20988583051453785", - "Likelihood: 0.297732554193972", - "Likelihood: 0.18830791174695025", - "Likelihood: 0.14394477271161069", - "Likelihood: 0.08116613936939579", - "Likelihood: 0.2280646633295464", - "Likelihood: 0.06658839522465713", - "Likelihood: 0.2245108097393159", - "Likelihood: 0.0667054617318554", - "Likelihood: 0.29922761488236627", - "Likelihood: 0.2241874350836583", - "Likelihood: 0.09107708881799213", - "Likelihood: 0.17842766276752872", - "Likelihood: 0.24052564055925246", - "Likelihood: 0.10134843756461397", - "Likelihood: 0.276123779979496", - "Likelihood: 0.22367926228497145", - "Likelihood: 0.23563049283137139", - "Likelihood: 0.3007040521631009", - "Likelihood: 0.11514668292680415", - "Likelihood: 0.18309554067477726", - "Likelihood: 0.18469801778159434", - "Likelihood: 0.2200397555859477", - "Likelihood: 0.2676190860893067", - "Likelihood: 0.20096215532155196", - "Likelihood: 0.27841471878278945", - "Likelihood: 0.03749038405211817", - "Likelihood: 0.23746769483007055", - "Likelihood: 0.23005750282462606", - "Likelihood: 0.2859982330546782", - "Likelihood: 0.0964714180192584", - "Likelihood: 0.28758710237073", - "Likelihood: 0.17381875896765256", - "Likelihood: 0.03631522486614094", - "Likelihood: 0.29963768947294245", - "Likelihood: 0.25773429701024936", - "Likelihood: 0.2870153091128544", - "Likelihood: 0.16477516293375613", - "Likelihood: 0.21152411135664245", - "Likelihood: 0.28972495114219227", - "Likelihood: 0.23030099882493021", - "Likelihood: 0.14246424894803916", - "Likelihood: 0.2013017930058462", - "Likelihood: 0.20416090992763739", - "Likelihood: 0.15638993179545874", - "Likelihood: 0.14877223228780895", - "Likelihood: 0.2897154705905388", - "Likelihood: 0.16218696478264658", - "Likelihood: 0.17938980208830635", - "Likelihood: 0.22830846226528095", - "Likelihood: 0.27206059087814916", - "Likelihood: 0.2053640237114913", - "Likelihood: 0.10611873418501504", - "Likelihood: 0.20289132529307613", - "Likelihood: 0.2421543367238845", - "Likelihood: 0.27683372357405883", - "Likelihood: 0.22820895983009362", - "Likelihood: 0.17199807074127832", - "Likelihood: 0.21759350772253655", - "Likelihood: 0.14212900445055607", - "Likelihood: 0.2633391663071907", - "Likelihood: 0.2282843654376956", - "Likelihood: 0.20237064009123668", - "Likelihood: 0.18372002350765726", - "Likelihood: 0.21077414029853622", - "Likelihood: 0.0560216019136292", - "Likelihood: 0.26331331722754153", - "Likelihood: 0.2777357315732394", - "Likelihood: 0.09994985146829272", - "Likelihood: 0.1590520773607099", - "Likelihood: 0.06402396505258556", - "Likelihood: 0.21707908396698933", - "Likelihood: 0.13873765591288828", - "Likelihood: 0.04572038700534716", - "Likelihood: 0.0559988624844678", - "Likelihood: 0.21287202408659553", - "Likelihood: 0.22741207028737065", - "Likelihood: 0.1101922931701992", - "Likelihood: 0.08775136853419827", - "Likelihood: 0.06390712127809361", - "Likelihood: 0.20622458421623885", - "Likelihood: 0.25872812921458177", - "Likelihood: 0.21275491331339608", - "Likelihood: 0.2747493725710653", - "Likelihood: 0.25362859249303943", - "Likelihood: 0.13551902220528964", - "Likelihood: 0.10907993339057354", - "Likelihood: 0.22509653332401103", - "Likelihood: 0.16289988679811687", - "Likelihood: 0.2714036075870722", - "Likelihood: 0.1187088373326918", - "Likelihood: 0.11733647274555419", - "Likelihood: 0.15063588850693863", - "Likelihood: 0.18835962006100515", - "Likelihood: 0.11618624461161679", - "Likelihood: 0.10536778852882547", - "Likelihood: 0.14784315692857422", - "Likelihood: 0.2615363522358122", - "Likelihood: 0.14381714492012307", - "Likelihood: 0.12560318512890892", - "Likelihood: 0.20646690457008499", - "Likelihood: 0.1637150760815312", - "Likelihood: 0.2750000919014876", - "Likelihood: 0.18943310844313865", - "Likelihood: 0.20639923537075874", - "Likelihood: 0.20641958607839261", - "Likelihood: 0.2935793432232652", - "Likelihood: 0.18340445613910952", - "Likelihood: 0.24607549563239126", - "Likelihood: 0.25193910283384996", - "Likelihood: 0.2713123824611651", - "Likelihood: 0.2959565784306845", - "Likelihood: 0.2826076187168084", - "Likelihood: 0.26869942244548145", - "Likelihood: 0.10006689949398219", - "Likelihood: 0.26203026124148177", - "Likelihood: 0.269603373782773", - "Likelihood: 0.19128050575990274", - "Likelihood: 0.10808402146447015", - "Likelihood: 0.24595554928938476", - "Likelihood: 0.273581771095687", - "Likelihood: 0.243666702091334", - "Likelihood: 0.15112727180290494", - "Likelihood: 0.24635893006120443", - "Likelihood: 0.25538239054589845", - "Likelihood: 0.16148033221748603", - "Likelihood: 0.1589438668094897", - "Likelihood: 0.23735545309300735", - "Likelihood: 0.2617130731936932", - "Likelihood: 0.22261762242838645", - "Likelihood: 0.04891509728989826", - "Likelihood: 0.1740874071607521", - "Likelihood: 0.29723840926292194", - "Likelihood: 0.18840834958151617", - "Likelihood: 0.2665843202334963", - "Likelihood: 0.2134988304868592", - "Likelihood: 0.2376083360140564", - "Likelihood: 0.24088589181653675", - "Likelihood: 0.25810581821148726", - "Likelihood: 0.14294645167578832", - "Likelihood: 0.06747735307418017", - "Likelihood: 0.11759629220472773", - "Likelihood: 0.2725244289669497", - "Likelihood: 0.21974816942566064", - "Likelihood: 0.09212079286821101", - "Likelihood: 0.061708384565392176", - "Likelihood: 0.11035773644393686", - "Likelihood: 0.1271295577489391", - "Likelihood: 0.14208215813262523", - "Likelihood: 0.18571984767345623", - "Likelihood: 0.137598261555489", - "Likelihood: 0.08475270372713074", - "Likelihood: 0.15725905358452327", - "Likelihood: 0.22863999185932127", - "Likelihood: 0.24925307483167253", - "Likelihood: 0.13565706290462745", - "Likelihood: 0.21728219473392194", - "Likelihood: 0.17822892351283454", - "Likelihood: 0.16491820337059934", - "Likelihood: 0.027501131916890718", - "Likelihood: 0.18433752417659707", - "Likelihood: 0.28083173422254454", - "Likelihood: 0.2714879450844847", - "Likelihood: 0.12863588856719813", - "Likelihood: 0.08602100877412228", - "Likelihood: 0.24793315992692552", - "Likelihood: 0.24365565078677723", - "Likelihood: 0.20280769900924", - "Likelihood: 0.19516814015564923", - "Likelihood: 0.1869002631157674", - "Likelihood: 0.11584312772614504", - "Likelihood: 0.23728072059608302", - "Likelihood: 0.08984010793614708", - "Likelihood: 0.2288479699816595", - "Likelihood: 0.1053164820465474", - "Likelihood: 0.26365462169940374", - "Likelihood: 0.21796004936498375", - "Likelihood: 0.29283561187055895", - "Likelihood: 0.23770342256730104", - "Likelihood: 0.17438873040924777", - "Likelihood: 0.21125712936539542", - "Likelihood: 0.148668518842153", - "Likelihood: 0.23297957842260153", - "Likelihood: 0.2983781875850028", - "Likelihood: 0.27452690127861346", - "Likelihood: 0.17277893520072823", - "Likelihood: 0.18885520464144853", - "Likelihood: 0.10771635708779746", - "Likelihood: 0.21011099313942258", - "Likelihood: 0.2628866930299805", - "Likelihood: 0.2249171719353691", - "Likelihood: 0.25614724624447216", - "Likelihood: 0.15566423696182052", - "Likelihood: 0.18047116900909704", - "Likelihood: 0.0947649014078679", - "Likelihood: 0.28993472712961305", - "Likelihood: 0.1549377168432127", - "Likelihood: 0.18769159931133383", - "Likelihood: 0.05916492251941881", - "Likelihood: 0.092667643802336", - "Likelihood: 0.2439120850016802", - "Likelihood: 0.18685368551341677", - "Likelihood: 0.0803152614577204", - "Likelihood: 0.2949247731266329", - "Likelihood: 0.17792124242858726", - "Likelihood: 0.03200483500897826", - "Likelihood: 0.15295902620696594", - "Likelihood: 0.04861844415835719", - "Likelihood: 0.21367215807699763", - "Likelihood: 0.06189951780483009", - "Likelihood: 0.21283045949345542", - "Likelihood: 0.22628398355560864", - "Likelihood: 0.1535386978699327", - "Likelihood: 0.296353375730741", - "Likelihood: 0.11904515468591961", - "Likelihood: 0.290766736145766", - "Likelihood: 0.09206695445536967", - "Likelihood: 0.137413503824892", - "Likelihood: 0.1908353697376777", - "Likelihood: 0.1382992641293992", - "Likelihood: 0.11578285018807616", - "Likelihood: 0.28597670063243386", - "Likelihood: 0.27770152016956573", - "Likelihood: 0.16169859145745386", - "Likelihood: 0.06803375430150493", - "Likelihood: 0.2673574847273275", - "Likelihood: 0.13331132034184218", - "Likelihood: 0.23233672116939155", - "Likelihood: 0.27445843942277437", - "Likelihood: 0.2688025876443324", - "Likelihood: 0.23066564994429098", - "Likelihood: 0.2925087264070046", - "Likelihood: 0.247746720126777", - "Likelihood: 0.257544359787317", - "Likelihood: 0.24277750725141312", - "Likelihood: 0.2776865983530913", - "Likelihood: 0.20928164091575321", - "Likelihood: 0.19582929457336792", - "Likelihood: 0.24532950927369576", - "Likelihood: 0.292728134938128", - "Likelihood: 0.2649595454551072", - "Likelihood: 0.17634615733225362", - "Likelihood: 0.06938982025955495", - "Likelihood: 0.1524835251120407", - "Likelihood: 0.18965997966718756", - "Likelihood: 0.16872087495855193", - "Likelihood: 0.2544562618612752", - "Likelihood: 0.2774185064772214", - "Likelihood: 0.25132971342466714", - "Likelihood: 0.18966955477006733", - "Likelihood: 0.16421247518457865", - "Likelihood: 0.15857527524300002", - "Likelihood: 0.2722674331892163", - "Likelihood: 0.18096701234532925", - "Likelihood: 0.19042858857363898", - "Likelihood: 0.1612766650523468", - "Likelihood: 0.17144563156543047", - "Likelihood: 0.18463000078303773", - "Likelihood: 0.04623743885595052", - "Likelihood: 0.20142550495880748", - "Likelihood: 0.21270137631303643", - "Likelihood: 0.28217657382811634", - "Likelihood: 0.19342029759513008", - "Likelihood: 0.1983022476865043", - "Likelihood: 0.30213766794842734", - "Likelihood: 0.2769664378782489", - "Likelihood: 0.254301186158647", - "Likelihood: 0.1813904200037245", - "Likelihood: 0.1128367660957337", - "Likelihood: 0.1503021289059715", - "Likelihood: 0.16506982614461996", - "Likelihood: 0.11455433635731176", - "Likelihood: 0.25519947771235596", - "Likelihood: 0.20529142851148532", - "Likelihood: 0.2149216016664524", - "Likelihood: 0.19915115685368961", - "Likelihood: 0.24460845052828065", - "Likelihood: 0.20743334726315776", - "Likelihood: 0.050552009238711615", - "Likelihood: 0.12451102453282047", - "Likelihood: 0.08698955747438293", - "Likelihood: 0.254378064172261", - "Likelihood: 0.17314821383671097", - "Likelihood: 0.1320164455863662", - "Likelihood: 0.19599437974282946", - "Likelihood: 0.09440245737056707", - "Likelihood: 0.20318299823109848", - "Likelihood: 0.2614509075482488", - "Likelihood: 0.22982274099233813", - "Likelihood: 0.09517064080969725", - "Likelihood: 0.10392989878749377", - "Likelihood: 0.10475076379279889", - "Likelihood: 0.12947136200128204", - "Likelihood: 0.2753369310269679", - "Likelihood: 0.2651825810220236", - "Likelihood: 0.19698802481118685", - "Likelihood: 0.1429297957070095", - "Likelihood: 0.1926719159808625", - "Likelihood: 0.1964288800730238", - "Likelihood: 0.21139276550255848", - "Likelihood: 0.19891403434558064", - "Likelihood: 0.24336426022731328", - "Likelihood: 0.2659475835869698", - "Likelihood: 0.0654084921687753", - "Likelihood: 0.060893613584598494", - "Likelihood: 0.2579361251721984", - "Likelihood: 0.24090799038706925", - "Likelihood: 0.14517828263701982", - "Likelihood: 0.16548503167472897", - "Likelihood: 0.07137047834222764", - "Likelihood: 0.2119192050720958", - "Likelihood: 0.1915301447779727", - "Likelihood: 0.2765599168347364", - "Likelihood: 0.2266379530228758", - "Likelihood: 0.1502239265683238", - "Likelihood: 0.2947726339887255", - "Likelihood: 0.25095234511136044", - "Likelihood: 0.03113889844584782", - "Likelihood: 0.23988316142091676", - "Likelihood: 0.20037508374084304", - "Likelihood: 0.2914210203671921", - "Likelihood: 0.13947980498844367", - "Likelihood: 0.2656530270318265", - "Likelihood: 0.28207690984769007", - "Likelihood: 0.035994584209260105", - "Likelihood: 0.17116015640956436", - "Likelihood: 0.13531855517691826", - "Likelihood: 0.2767613720166875", - "Likelihood: 0.21442716841909018", - "Likelihood: 0.2684881008723987", - "Likelihood: 0.049935694185642275", - "Likelihood: 0.2809148378175228", - "Likelihood: 0.183439435654441", - "Likelihood: 0.15770572318574158", - "Likelihood: 0.13145990214534806", - "Likelihood: 0.18247141298633326", - "Likelihood: 0.1739048668846208", - "Likelihood: 0.2941504109898054", - "Likelihood: 0.25112025052837467", - "Likelihood: 0.2212817341875433", - "Likelihood: 0.24656871409059739", - "Likelihood: 0.1709043498862508", - "Likelihood: 0.15195143471184439", - "Likelihood: 0.20126608668046134", - "Likelihood: 0.2273936364123934", - "Likelihood: 0.2463313580197324", - "Likelihood: 0.20404943926141061", - "Likelihood: 0.1589887770997928", - "Likelihood: 0.1215932560296765", - "Likelihood: 0.10812058584085463", - "Likelihood: 0.13356701230119467", - "Likelihood: 0.09281927539429474", - "Likelihood: 0.23070066524858018", - "Likelihood: 0.16556557961600968", - "Likelihood: 0.2572018106470413", - "Likelihood: 0.24857406306801544", - "Likelihood: 0.21232756251677345", - "Likelihood: 0.2788644417128806", - "Likelihood: 0.11284326873365941", - "Likelihood: 0.2388825729662311", - "Likelihood: 0.1574146302919062", - "Likelihood: 0.25572328934343946", - "Likelihood: 0.1711271995760733", - "Likelihood: 0.16917929822325234", - "Likelihood: 0.0718777435908894", - "Likelihood: 0.21308640026325154", - "Likelihood: 0.24856874791860958", - "Likelihood: 0.17594189193034257", - "Likelihood: 0.17387433995627213", - "Likelihood: 0.24893908577778956", - "Likelihood: 0.1330632451279741", - "Likelihood: 0.24758442741231157", - "Likelihood: 0.0596992190044114", - "Likelihood: 0.09953743006288746", - "Likelihood: 0.27433752686587537", - "Likelihood: 0.28802567239433835", - "Likelihood: 0.05935415728341932", - "Likelihood: 0.2787696789330513", - "Likelihood: 0.11925993936887552", - "Likelihood: 0.26740680404376416", - "Likelihood: 0.23416676562112745", - "Likelihood: 0.1568901580186192", - "Likelihood: 0.26128695337966", - "Likelihood: 0.16151897419032873", - "Likelihood: 0.19728780206009916", - "Likelihood: 0.23550902374170435", - "Likelihood: 0.301174501036681", - "Likelihood: 0.2533485336504923", - "Likelihood: 0.046684284700389364", - "Likelihood: 0.13268475060136736", - "Likelihood: 0.16455126480846052", - "Likelihood: 0.13990518792881765", - "Likelihood: 0.295870918617254", - "Likelihood: 0.14509019685959787", - "Likelihood: 0.042492544868262205", - "Likelihood: 0.14999079836026608", - "Likelihood: 0.2618813631741553", - "Likelihood: 0.21542799811749866", - "Likelihood: 0.11250535020428067", - "Likelihood: 0.07895640318849899", - "Likelihood: 0.2725146701732617", - "Likelihood: 0.10279140111879613", - "Likelihood: 0.22138451733765102", - "Likelihood: 0.11396381022502372", - "Likelihood: 0.2771696692871002", - "Likelihood: 0.13605878515128694", - "Likelihood: 0.1170648230269685", - "Likelihood: 0.17788613787086205", - "Likelihood: 0.05925384462417591", - "Likelihood: 0.27536242597138166", - "Likelihood: 0.14860902193248218", - "Likelihood: 0.12728754189194977", - "Likelihood: 0.26852059027127634", - "Likelihood: 0.06681374124282956", - "Likelihood: 0.09850185545219756", - "Likelihood: 0.26494181554944657", - "Likelihood: 0.20976806138840084", - "Likelihood: 0.1748322939415486", - "Likelihood: 0.26912877174337557", - "Likelihood: 0.0863410491904152", - "Likelihood: 0.08637832403214933", - "Likelihood: 0.14877441326817967", - "Likelihood: 0.13669740470569533", - "Likelihood: 0.2148172930380695", - "Likelihood: 0.2612583901246702", - "Likelihood: 0.23678715546356766", - "Likelihood: 0.04947350617511751", - "Likelihood: 0.26752952482827785", - "Likelihood: 0.22428614961160068", - "Likelihood: 0.29872684132073685", - "Likelihood: 0.2008960408915122", - "Likelihood: 0.05595729724642963", - "Likelihood: 0.18788888423145567", - "Likelihood: 0.23696443702751574", - "Likelihood: 0.09813402074567709", - "Likelihood: 0.11429043009383302", - "Likelihood: 0.2112152648488134", - "Likelihood: 0.21715458042031024", - "Likelihood: 0.11677692899723566", - "Likelihood: 0.29836694377338585", - "Likelihood: 0.10501675271852595", - "Likelihood: 0.06100965639976344", - "Likelihood: 0.294710091103422", - "Likelihood: 0.18307106333335083", - "Likelihood: 0.256647067623878", - "Likelihood: 0.2711666469704115", - "Likelihood: 0.2439739914299956", - "Likelihood: 0.2917562605577263", - "Likelihood: 0.2932346372242866", - "Likelihood: 0.11243099248069878", - "Likelihood: 0.2750534665255552", - "Likelihood: 0.21682215957347756", - "Likelihood: 0.2403426683183695", - "Likelihood: 0.3049574556622532", - "Likelihood: 0.08932449744023185", - "Likelihood: 0.13141357738789164", - "Likelihood: 0.2944149419285522", - "Likelihood: 0.1386882592925695", - "Likelihood: 0.2946499219743973", - "Likelihood: 0.05037087436836904", - "Likelihood: 0.04848539550149805", - "Likelihood: 0.2987892864219753", - "Likelihood: 0.19545115291745843", - "Likelihood: 0.11803834258696366", - "Likelihood: 0.1527328659790965", - "Likelihood: 0.2697455351402424", - "Likelihood: 0.2330725132351514", - "Likelihood: 0.2685649841420422", - "Likelihood: 0.25670850534585243", - "Likelihood: 0.2583924754918913", - "Likelihood: 0.2612095800205337", - "Likelihood: 0.13960105758466076", - "Likelihood: 0.1893827762782471", - "Likelihood: 0.062431601509258694", - "Likelihood: 0.2077628663209051", - "Likelihood: 0.24526523102399125", - "Likelihood: 0.08942849944835024", - "Likelihood: 0.07602544341197182", - "Likelihood: 0.17401253756978383", - "Likelihood: 0.07269655980676717", - "Likelihood: 0.11966693021670884", - "Likelihood: 0.13895033348013416", - "Likelihood: 0.2235648783233332", - "Likelihood: 0.23154443642133143", - "Likelihood: 0.24093758157002293", - "Likelihood: 0.14113668351751452", - "Likelihood: 0.23607058952941373", - "Likelihood: 0.23353734008684576", - "Likelihood: 0.1780280952143999", - "Likelihood: 0.277571698644259", - "Likelihood: 0.19603874778457192", - "Likelihood: 0.2723364206423367", - "Likelihood: 0.18315587040921208", - "Likelihood: 0.2144534184044388", - "Likelihood: 0.1322228748094203", - "Likelihood: 0.2763471224157263", - "Likelihood: 0.15866730560059025", - "Likelihood: 0.25132532639040567", - "Likelihood: 0.23020385746448568", - "Likelihood: 0.10374972921828333", - "Likelihood: 0.195497301900063", - "Likelihood: 0.2092215454539467", - "Likelihood: 0.2596776019538848", - "Likelihood: 0.22336220189857758", - "Likelihood: 0.24208856132692058", - "Likelihood: 0.15858843154447966", - "Likelihood: 0.20983925235186235", - "Likelihood: 0.24317983078583996", - "Likelihood: 0.2597270539754326", - "Likelihood: 0.200063594941608", - "Likelihood: 0.17584710252521457", - "Likelihood: 0.2950159424094801", - "Likelihood: 0.06330414887324332", - "Likelihood: 0.14428354269730093", - "Likelihood: 0.21933052116384058", - "Likelihood: 0.2859190608199167", - "Likelihood: 0.05329986083652049", - "Likelihood: 0.28431290483868943", - "Likelihood: 0.13348107986245983", - "Likelihood: 0.26841258670524376", - "Likelihood: 0.26945685105487865", - "Likelihood: 0.1866798098172761", - "Likelihood: 0.18929038683130028", - "Likelihood: 0.25048601236425916", - "Likelihood: 0.26453251424262525", - "Likelihood: 0.1791676157126125", - "Likelihood: 0.07663716553439982", - "Likelihood: 0.07976340734345949", - "Likelihood: 0.10470632502333875", - "Likelihood: 0.0631859210763834", - "Likelihood: 0.26094793289614293", - "Likelihood: 0.1270059330574097", - "Likelihood: 0.1798510048319772", - "Likelihood: 0.11766578785931397", - "Likelihood: 0.09835708117490324", - "Likelihood: 0.24758935700554535", - "Likelihood: 0.21431955381901482", - "Likelihood: 0.2738377267194303", - "Likelihood: 0.2524451120194225", - "Likelihood: 0.18407732878157348", - "Likelihood: 0.2220264981451593", - "Likelihood: 0.29377519096574495", - "Likelihood: 0.2030492813286229", - "Likelihood: 0.2253448398840221", - "Likelihood: 0.2757545987936251", - "Likelihood: 0.10881102277705022", - "Likelihood: 0.23890105071477624", - "Likelihood: 0.22355673583191865", - "Likelihood: 0.06862411824155626", - "Likelihood: 0.19058656848198213", - "Likelihood: 0.12797879694933673", - "Likelihood: 0.16643040052140934", - "Likelihood: 0.19508305696052386", - "Likelihood: 0.2775276567954545", - "Likelihood: 0.09844236691039271", - "Likelihood: 0.2903495515414531", - "Likelihood: 0.2577099140153874", - "Likelihood: 0.1359709145258848", - "Likelihood: 0.12611998125174537", - "Likelihood: 0.2578718123856432", - "Likelihood: 0.16260711546558065", - "Likelihood: 0.1558029719899216", - "Likelihood: 0.21860497756437688", - "Likelihood: 0.059648091402771275", - "Likelihood: 0.13258077195545426", - "Likelihood: 0.13254206195931797", - "Likelihood: 0.023880905138725282", - "Likelihood: 0.07653399337770829", - "Likelihood: 0.23134023365054807", - "Likelihood: 0.19387234851620314", - "Likelihood: 0.18656961773862768", - "Likelihood: 0.12935413820579403", - "Likelihood: 0.21224313880077364", - "Likelihood: 0.200003253759934", - "Likelihood: 0.1490793181261236", - "Likelihood: 0.19070244154691068", - "Likelihood: 0.03178836718208688", - "Likelihood: 0.2689986730158917", - "Likelihood: 0.27289187100463425", - "Likelihood: 0.24743829471058862", - "Likelihood: 0.2423608388593911", - "Likelihood: 0.24105162973731778", - "Likelihood: 0.10413112764227919", - "Likelihood: 0.19406368267108617", - "Likelihood: 0.037029907965581144", - "Likelihood: 0.23229694151963698", - "Likelihood: 0.2545490150705274", - "Likelihood: 0.06714103830487904", - "Likelihood: 0.01621075636644242", - "Likelihood: 0.17916429212349758", - "Likelihood: 0.17114457121814147", - "Likelihood: 0.12976032071275834", - "Likelihood: 0.294451149712326", - "Likelihood: 0.22084318496120867", - "Likelihood: 0.19520444619551233", - "Likelihood: 0.10589559337293186", - "Likelihood: 0.23676314406960347", - "Likelihood: 0.17865790178502633", - "Likelihood: 0.2884388218304051", - "Likelihood: 0.16327702831640167", - "Likelihood: 0.193260322330855", - "Likelihood: 0.14878558994894775", - "Likelihood: 0.28705750283429154", - "Likelihood: 0.20221098182351635", - "Likelihood: 0.2068344223117404", - "Likelihood: 0.20422864373623634", - "Likelihood: 0.0867883963663297", - "Likelihood: 0.25732290390823886", - "Likelihood: 0.15459040029118504", - "Likelihood: 0.13082549172034094", - "Likelihood: 0.17127744055917224", - "Likelihood: 0.21248688039806118", - "Likelihood: 0.28129990209680783", - "Likelihood: 0.09562540307234636", - "Likelihood: 0.14181390906613653", - "Likelihood: 0.13153745350542426", - "Likelihood: 0.1511967129367401", - "Likelihood: 0.21344153137430666", - "Likelihood: 0.21913051344793147", - "Likelihood: 0.20664639104874158", - "Likelihood: 0.17760206738191905", - "Likelihood: 0.19549078515384322", - "Likelihood: 0.22992298461852279", - "Likelihood: 0.2942144386459369", - "Likelihood: 0.2882343808996561", - "Likelihood: 0.22631132145513314", - "Likelihood: 0.17157737389885389", - "Likelihood: 0.16746187574291418", - "Likelihood: 0.20653912763412477", - "Likelihood: 0.26617874023380383", - "Likelihood: 0.23135575530736502", - "Likelihood: 0.17590267395907785", - "Likelihood: 0.2458048108734482", - "Likelihood: 0.2994726982319261", - "Likelihood: 0.2742487148886411", - "Likelihood: 0.1913447569433716", - "Likelihood: 0.2049942166875808", - "Likelihood: 0.2086765127353059", - "Likelihood: 0.2670105630566214", - "Likelihood: 0.14176579794318298", - "Likelihood: 0.17820507739834776", - "Likelihood: 0.17708446964670999", - "Likelihood: 0.2264021161819211", - "Likelihood: 0.22193116613440655", - "Likelihood: 0.2556241005918659", - "Likelihood: 0.16662357124814292", - "Likelihood: 0.16248972962983527", - "Likelihood: 0.10507074440363405", - "Likelihood: 0.2967333663213511", - "Likelihood: 0.2721635098082887", - "Likelihood: 0.0647910240460424", - "Likelihood: 0.26910987653285007", - "Likelihood: 0.2506555402418606", - "Likelihood: 0.27498511458937763", - "Likelihood: 0.1590363707624451", - "Likelihood: 0.24939013546697603", - "Likelihood: 0.3033518367833507", - "Likelihood: 0.10704379569346616", - "Likelihood: 0.15216783061399414", - "Likelihood: 0.21661633876770653", - "Likelihood: 0.21924236597204957", - "Likelihood: 0.28375055997989634", - "Likelihood: 0.2552027673864118", - "Likelihood: 0.1437194551927165", - "Likelihood: 0.282447493395739", - "Likelihood: 0.18197123753808264", - "Likelihood: 0.09185175356594194", - "Likelihood: 0.2171683338128877", - "Likelihood: 0.1827730872878532", - "Likelihood: 0.07017219368185806", - "Likelihood: 0.2437202730343982", - "Likelihood: 0.24080168629418852", - "Likelihood: 0.2603295636481468", - "Likelihood: 0.08525392525346295", - "Likelihood: 0.08730934800954751", - "Likelihood: 0.14750872288854097", - "Likelihood: 0.1897436027517512", - "Likelihood: 0.18586954293063346", - "Likelihood: 0.2142616881801557", - "Likelihood: 0.10418888455453847", - "Likelihood: 0.27347364663225554", - "Likelihood: 0.23949715489254603", - "Likelihood: 0.17235834168944403", - "Likelihood: 0.08890675743215926", - "Likelihood: 0.20793826226808873", - "Likelihood: 0.19169732141201432", - "Likelihood: 0.11885031560762488", - "Likelihood: 0.23471175742510494", - "Likelihood: 0.27732688408450373", - "Likelihood: 0.15139333147656397", - "Likelihood: 0.23187950699885662", - "Likelihood: 0.25989650895741384", - "Likelihood: 0.2533076255587839", - "Likelihood: 0.16611580922359212", - "Likelihood: 0.08392455997103646", - "Likelihood: 0.28098407467840936", - "Likelihood: 0.14711675073649438", - "Likelihood: 0.25728183643761005", - "Likelihood: 0.17465811471978165", - "Likelihood: 0.2646684968201291", - "Likelihood: 0.2738021788229068", - "Likelihood: 0.11436563926853924", - "Likelihood: 0.09163524980402678", - "Likelihood: 0.12157300963024494", - "Likelihood: 0.1538548229549228", - "Likelihood: 0.1457846901626721", - "Likelihood: 0.24260725660387042", - "Likelihood: 0.21829110614213873", - "Likelihood: 0.2798070380848523", - "Likelihood: 0.22064796698320147", - "Likelihood: 0.28059701211064914", - "Likelihood: 0.29013735117258405", - "Likelihood: 0.23680390162865844", - "Likelihood: 0.17052573423566558", - "Likelihood: 0.08244057994597583", - "Likelihood: 0.23960939933483688", - "Likelihood: 0.2055608565416956", - "Likelihood: 0.207092896280663", - "Likelihood: 0.26596278163295584", - "Likelihood: 0.2667975423194512", - "Likelihood: 0.26486999684606455", - "Likelihood: 0.08889072535634454", - "Likelihood: 0.08137266645577122", - "Likelihood: 0.30119976139202637", - "Likelihood: 0.0876377916790137", - "Likelihood: 0.07497609852549218", - "Likelihood: 0.24587645291119586", - "Likelihood: 0.19453060387412557", - "Likelihood: 0.2109145656297156", - "Likelihood: 0.23381146935442612", - "Likelihood: 0.1542414567600134", - "Likelihood: 0.1985466291560352", - "Likelihood: 0.2849202193555577", - "Likelihood: 0.26593912895385063", - "Likelihood: 0.2727459923233786", - "Likelihood: 0.2311185100018597", - "Likelihood: 0.2014989062799403", - "Likelihood: 0.22353352695965553", - "Likelihood: 0.27529442422462574", - "Likelihood: 0.1900596311928918", - "Likelihood: 0.109992132685431", - "Likelihood: 0.29349357738297044", - "Likelihood: 0.24459798929059767", - "Likelihood: 0.037401239517852236", - "Likelihood: 0.11422338025062678", - "Likelihood: 0.16499645454259704", - "Likelihood: 0.24067402429431953", - "Likelihood: 0.23875961197547224", - "Likelihood: 0.25048637313555616", - "Likelihood: 0.20442692736581494", - "Likelihood: 0.24710141099488261", - "Likelihood: 0.06284542806785955", - "Likelihood: 0.1828771123190389", - "Likelihood: 0.1755125830829071", - "Likelihood: 0.28308844260027854", - "Likelihood: 0.27590064271412545", - "Likelihood: 0.13849828870751665", - "Likelihood: 0.2517273624552892", - "Likelihood: 0.2472371867548735", - "Likelihood: 0.140894298165114", - "Likelihood: 0.3003944825219128", - "Likelihood: 0.24923249385613458", - "Likelihood: 0.24525215793079355", - "Likelihood: 0.24526101172965317", - "Likelihood: 0.20857651674867705", - "Likelihood: 0.24237142290011668", - "Likelihood: 0.07213647247025529", - "Likelihood: 0.1763367016930232", - "Likelihood: 0.11795564570360091", - "Likelihood: 0.12486102141122865", - "Likelihood: 0.20508254779824306", - "Likelihood: 0.18524772752775226", - "Likelihood: 0.190894034230388", - "Likelihood: 0.1062031428286803", - "Likelihood: 0.21970495405654614", - "Likelihood: 0.2846491557757646", - "Likelihood: 0.2803152240418822", - "Likelihood: 0.2335469747716439", - "Likelihood: 0.15463096264536494", - "Likelihood: 0.07634668896636192", - "Likelihood: 0.18974330509762719", - "Likelihood: 0.08726953527670324", - "Likelihood: 0.24934471998801258", - "Likelihood: 0.1730625067484582", - "Likelihood: 0.08737024614240646", - "Likelihood: 0.16248359877542382", - "Likelihood: 0.28998484118023277", - "Likelihood: 0.19113177842758503", - "Likelihood: 0.23106438768595072", - "Likelihood: 0.1148252050032318", - "Likelihood: 0.11652711007722986", - "Likelihood: 0.20812650881007194", - "Likelihood: 0.10597058141393893", - "Likelihood: 0.3006459822534042", - "Likelihood: 0.20433238141015067", - "Likelihood: 0.19593410366820035", - "Likelihood: 0.28964939733661477", - "Likelihood: 0.0868526655458777", - "Likelihood: 0.23908171403402279", - "Likelihood: 0.195920828282564", - "Likelihood: 0.20109726970707906", - "Likelihood: 0.20061517026922598", - "Likelihood: 0.1448864234403762", - "Likelihood: 0.22458339634923152", - "Likelihood: 0.25428471431931887", - "Likelihood: 0.27793251901031296", - "Likelihood: 0.26905353931675646", - "Likelihood: 0.28948057841037134", - "Likelihood: 0.18098932440162213", - "Likelihood: 0.06802525937894337", - "Likelihood: 0.17730294717169048", - "Likelihood: 0.20094750135774983", - "Likelihood: 0.1821123914180863", - "Likelihood: 0.21009221259200947", - "Likelihood: 0.23176802571554186", - "Likelihood: 0.26660798267837194", - "Likelihood: 0.14206669730941535", - "Likelihood: 0.2642749864975025", - "Likelihood: 0.24473161320184791", - "Likelihood: 0.14295103976660298", - "Likelihood: 0.29664028021976113", - "Likelihood: 0.1334296569926491", - "Likelihood: 0.24495685434496983", - "Likelihood: 0.2674554757978272", - "Likelihood: 0.1455413571492778", - "Likelihood: 0.15189242219120538", - "Likelihood: 0.22624082397404982", - "Likelihood: 0.2500747026708758", - "Likelihood: 0.05560220979854107", - "Likelihood: 0.19169353116524668", - "Likelihood: 0.16193279990943604", - "Likelihood: 0.1665633605180817", - "Likelihood: 0.17111009068773445", - "Likelihood: 0.2352965879516126", - "Likelihood: 0.12925845567485975", - "Likelihood: 0.2138841646557797", - "Likelihood: 0.2438999473840945", - "Likelihood: 0.2553038710163622", - "Likelihood: 0.13728929425549155", - "Likelihood: 0.29082665448344497", - "Likelihood: 0.17069368751838102", - "Likelihood: 0.19320096245616528", - "Likelihood: 0.24586630869504517", - "Likelihood: 0.1864919771760076", - "Likelihood: 0.2618803473908039", - "Likelihood: 0.20323621223669294", - "Likelihood: 0.08466164256941368", - "Likelihood: 0.27585772081489934", - "Likelihood: 0.2908075848627869", - "Likelihood: 0.23898975043780687", - "Likelihood: 0.14726764926684696", - "Likelihood: 0.0926740829962329", - "Likelihood: 0.18103181073004387", - "Likelihood: 0.1561010891870346", - "Likelihood: 0.1038284806057399", - "Likelihood: 0.2816949626128598", - "Likelihood: 0.25839881146571275", - "Likelihood: 0.10375090051304217", - "Likelihood: 0.19645828345503452", - "Likelihood: 0.19922873064572877", - "Likelihood: 0.2940588301181771", - "Likelihood: 0.2479189324399589", - "Likelihood: 0.12299270056160906", - "Likelihood: 0.1701540037737213", - "Likelihood: 0.08925209801660774", - "Likelihood: 0.2049452060811266", - "Likelihood: 0.23900667148393606", - "Likelihood: 0.2213713212795473", - "Likelihood: 0.21535861476987248", - "Likelihood: 0.24155808457986172", - "Likelihood: 0.2969891225424423", - "Likelihood: 0.2774677573441467", - "Likelihood: 0.24012528493942895", - "Likelihood: 0.259808230665337", - "Likelihood: 0.13795915585931767", - "Likelihood: 0.17176463370981337", - "Likelihood: 0.26637529704786983", - "Likelihood: 0.048745851653155016", - "Likelihood: 0.23474852192782777", - "Likelihood: 0.11399694116536523", - "Likelihood: 0.20641334779132034", - "Likelihood: 0.27099042875756063", - "Likelihood: 0.1827735346449752", - "Likelihood: 0.18999263989217466", - "Likelihood: 0.10061072118063943", - "Likelihood: 0.2251205950675202", - "Likelihood: 0.2712791971192526", - "Likelihood: 0.1850114211726369", - "Likelihood: 0.13214613242645493", - "Likelihood: 0.1386439758186536", - "Likelihood: 0.2909488472766573", - "Likelihood: 0.040597764613397445", - "Likelihood: 0.2380366457529427", - "Likelihood: 0.28508268044419643", - "Likelihood: 0.22341760010058295", - "Likelihood: 0.1013245704313373", - "Likelihood: 0.1967088431271883", - "Likelihood: 0.2508562325857625", - "Likelihood: 0.2163661773986633", - "Likelihood: 0.29816793747499354", - "Likelihood: 0.09998548505517049", - "Likelihood: 0.1292937329337788", - "Likelihood: 0.08458663648388148", - "Likelihood: 0.11311871119808095", - "Likelihood: 0.14711873596277852", - "Likelihood: 0.042578014104016335", - "Likelihood: 0.022494255060539255", - "Likelihood: 0.260808530496998", - "Likelihood: 0.21848679773250673", - "Likelihood: 0.1594657520636895", - "Likelihood: 0.13206367646844525", - "Likelihood: 0.2459618294153849", - "Likelihood: 0.05983306091051088", - "Likelihood: 0.23467252391927731", - "Likelihood: 0.29037215505044445", - "Likelihood: 0.21028058383215725", - "Likelihood: 0.16272973987333256", - "Likelihood: 0.2162327189883201", - "Likelihood: 0.2519322816413202", - "Likelihood: 0.2296566939121587", - "Likelihood: 0.13991087054865034", - "Likelihood: 0.21992542337738372", - "Likelihood: 0.11786490125784768", - "Likelihood: 0.1919429894806307", - "Likelihood: 0.2901198869141247", - "Likelihood: 0.18272401369406038", - "Likelihood: 0.23166468900873688", - "Likelihood: 0.1582874044623564", - "Likelihood: 0.02862692236181499", - "Likelihood: 0.07510730240764908", - "Likelihood: 0.20492736714043985", - "Likelihood: 0.2797334941834408", - "Likelihood: 0.06550419022416579", - "Likelihood: 0.1940805336281592", - "Likelihood: 0.2533052426290743", - "Likelihood: 0.3046880051108923", - "Likelihood: 0.06094571220029496", - "Likelihood: 0.24846438203288898", - "Likelihood: 0.1854681800172875", - "Likelihood: 0.10281325921319458", - "Likelihood: 0.23628244606888155", - "Likelihood: 0.21284220812138396", - "Likelihood: 0.1652716035666159", - "Likelihood: 0.21813534852123004", - "Likelihood: 0.12521108039187076", - "Likelihood: 0.1394688244526908", - "Likelihood: 0.07548853060447387", - "Likelihood: 0.15825301952124274", - "Likelihood: 0.16429190801242918", - "Likelihood: 0.20251106416621703", - "Likelihood: 0.2760886939396213", - "Likelihood: 0.13817025493221735", - "Likelihood: 0.23967660812544297", - "Likelihood: 0.26616697972725145", - "Likelihood: 0.13728479774863275", - "Likelihood: 0.26007857857113625", - "Likelihood: 0.14847529883543542", - "Likelihood: 0.30178255203701637", - "Likelihood: 0.2889545687413967", - "Likelihood: 0.13206265336543882", - "Likelihood: 0.2645184772765739", - "Likelihood: 0.12300619001149607", - "Likelihood: 0.24044920973049566", - "Likelihood: 0.14252185316535662", - "Likelihood: 0.256311263705815", - "Likelihood: 0.16250330449612407", - "Likelihood: 0.18304060511949732", - "Likelihood: 0.03295663468594081", - "Likelihood: 0.2832816130405111", - "Likelihood: 0.08651216877767635", - "Likelihood: 0.1361541415159924", - "Likelihood: 0.24888503465163847", - "Likelihood: 0.2133130117622247", - "Likelihood: 0.2673250716671947", - "Likelihood: 0.08386981838355191", - "Likelihood: 0.13912332472787384", - "Likelihood: 0.11718325890029498", - "Likelihood: 0.2779241603780239", - "Likelihood: 0.2600404707708506", - "Likelihood: 0.23429817483410484", - "Likelihood: 0.1948963714920783", - "Likelihood: 0.2396703760361919", - "Likelihood: 0.2947730228346357", - "Likelihood: 0.18345483247505853", - "Likelihood: 0.1916685104356544", - "Likelihood: 0.12687633597232864", - "Likelihood: 0.239001978871302", - "Likelihood: 0.06883075131578055", - "Likelihood: 0.22471016752938378", - "Likelihood: 0.2770861688101639", - "Likelihood: 0.2523506168517875", - "Likelihood: 0.1941426866779897", - "Likelihood: 0.24560861421365088", - "Likelihood: 0.22994028955297433", - "Likelihood: 0.18511972793458006", - "Likelihood: 0.11398236492261211", - "Likelihood: 0.1840888121185323", - "Likelihood: 0.14219981812272883", - "Likelihood: 0.2564659449714686", - "Likelihood: 0.23470947915565182", - "Likelihood: 0.10884010184962925", - "Likelihood: 0.1512680155899017", - "Likelihood: 0.30078350284249", - "Likelihood: 0.25016264900574303", - "Likelihood: 0.24755091282209535", - "Likelihood: 0.1501624711087172", - "Likelihood: 0.21442840728839102", - "Likelihood: 0.21648323539746828", - "Likelihood: 0.049473733416550175", - "Likelihood: 0.26877841873060043", - "Likelihood: 0.05026438423654999", - "Likelihood: 0.2158414688951642", - "Likelihood: 0.20475191683030847", - "Likelihood: 0.18070049104158048", - "Likelihood: 0.1661822481082412", - "Likelihood: 0.18609036899678788", - "Likelihood: 0.26341826396555756", - "Likelihood: 0.046932662149153655", - "Likelihood: 0.1139918096511208", - "Likelihood: 0.13483429958943316", - "Likelihood: 0.23093093108138896", - "Likelihood: 0.24146456515631096", - "Likelihood: 0.22578190858856065", - "Likelihood: 0.15147224630921405", - "Likelihood: 0.23623287106038243", - "Likelihood: 0.24295067190488298", - "Likelihood: 0.07899526855862417", - "Likelihood: 0.11678148677818391", - "Likelihood: 0.1404915821099031", - "Likelihood: 0.23453234906433845", - "Likelihood: 0.07464930853728394", - "Likelihood: 0.10507371965812154", - "Likelihood: 0.21692510990580025", - "Likelihood: 0.17033587612155493", - "Likelihood: 0.2741787521294755", - "Likelihood: 0.25599908995335025", - "Likelihood: 0.1845217982777907", - "Likelihood: 0.18266602974576354", - "Likelihood: 0.1288942691251415", - "Likelihood: 0.22227189854541465", - "Likelihood: 0.2405721064800439", - "Likelihood: 0.17714852283172575", - "Likelihood: 0.29176413896878717", - "Likelihood: 0.22241421462010488", - "Likelihood: 0.1695562291715777", - "Likelihood: 0.28469385717779705", - "Likelihood: 0.2128086727568179", - "Likelihood: 0.2259905410037472", - "Likelihood: 0.19799297242552183", - "Likelihood: 0.07290152056348623", - "Likelihood: 0.11303507312534554", - "Likelihood: 0.26549415746993216", - "Likelihood: 0.25325013269569024", - "Likelihood: 0.23772681687170671", - "Likelihood: 0.23688008820393322", - "Likelihood: 0.19149798200457466", - "Likelihood: 0.19723975517533116", - "Likelihood: 0.21006864729171199", - "Likelihood: 0.206811358837785", - "Likelihood: 0.28691816819774185", - "Likelihood: 0.2568641463437059", - "Likelihood: 0.0761888110265176", - "Likelihood: 0.12813168697893576", - "Likelihood: 0.2575065981513198", - "Likelihood: 0.10325588402199494", - "Likelihood: 0.11585551848463742", - "Likelihood: 0.20406091296976864", - "Likelihood: 0.22608373415278815", - "Likelihood: 0.22687782663495232", - "Likelihood: 0.1397203998054284", - "Likelihood: 0.28514552342950694", - "Likelihood: 0.030294745610152583", - "Likelihood: 0.22749444983250974", - "Likelihood: 0.0785766843726044", - "Likelihood: 0.1224161644327386", - "Likelihood: 0.2271650341151257", - "Likelihood: 0.20940841009880864", - "Likelihood: 0.22062729547296683", - "Likelihood: 0.1407651026871852", - "Likelihood: 0.19240544976994073", - "Likelihood: 0.25950074186749184", - "Likelihood: 0.11663823479770581", - "Likelihood: 0.2196439958801792", - "Likelihood: 0.2356014812134128", - "Likelihood: 0.11912816788151878", - "Likelihood: 0.18786577293049264", - "Likelihood: 0.1663683229636696", - "Likelihood: 0.21981673689140518", - "Likelihood: 0.09361241032800471", - "Likelihood: 0.2786444145890921", - "Likelihood: 0.22040131519679088", - "Likelihood: 0.14971457710168817", - "Likelihood: 0.21362817736907005", - "Likelihood: 0.275073894666264", - "Likelihood: 0.13719588747761868", - "Likelihood: 0.12472166763060928", - "Likelihood: 0.1684888342077581", - "Likelihood: 0.2563022504205936", - "Likelihood: 0.03512969130600213", - "Likelihood: 0.2560455089155258", - "Likelihood: 0.243478789304505", - "Likelihood: 0.2129328142446181", - "Likelihood: 0.2811950826873484", - "Likelihood: 0.1752915129834491", - "Likelihood: 0.020151000883002795", - "Likelihood: 0.06276419159310298", - "Likelihood: 0.17051560822626521", - "Likelihood: 0.18520295678448015", - "Likelihood: 0.15086542150955976", - "Likelihood: 0.2848809450550973", - "Likelihood: 0.14206461980370386", - "Likelihood: 0.24263911408897312", - "Likelihood: 0.2881080980988952", - "Likelihood: 0.18320161939355828", - "Likelihood: 0.27306224984635025", - "Likelihood: 0.2507045357422596", - "Likelihood: 0.24868085868288867", - "Likelihood: 0.21404607742827078", - "Likelihood: 0.14400985635900454", - "Likelihood: 0.15746451662598246", - "Likelihood: 0.20643530462959836", - "Likelihood: 0.1889870793311353", - "Likelihood: 0.2762886574371107", - "Likelihood: 0.16092462518575962", - "Likelihood: 0.12636994603527849", - "Likelihood: 0.12313829710285239", - "Likelihood: 0.052712167547721095", - "Likelihood: 0.13927112749418655", - "Likelihood: 0.20333420204070699", - "Likelihood: 0.13276470813272934", - "Likelihood: 0.2159110209033979", - "Likelihood: 0.19918315901795125", - "Likelihood: 0.030588896516420137", - "Likelihood: 0.14311535276043777", - "Likelihood: 0.1663643315160453", - "Likelihood: 0.1386213858325495", - "Likelihood: 0.15718153060876394", - "Likelihood: 0.1429249875803254", - "Likelihood: 0.2196511997048784", - "Likelihood: 0.17187297657749068", - "Likelihood: 0.1608464421250571", - "Likelihood: 0.14543224826586518", - "Likelihood: 0.21368607086914526", - "Likelihood: 0.2220286669914046", - "Likelihood: 0.023269804272936723", - "Likelihood: 0.20300679409104067", - "Likelihood: 0.12365067635618705", - "Likelihood: 0.2855576223595898", - "Likelihood: 0.29977501305385545", - "Likelihood: 0.1939634889901969", - "Likelihood: 0.2626041643888681", - "Likelihood: 0.07006885970430463", - "Likelihood: 0.2920189411094323", - "Likelihood: 0.2789787901606706", - "Likelihood: 0.29560087879974184", - "Likelihood: 0.17417950325051987", - "Likelihood: 0.21624942059885965", - "Likelihood: 0.026755294044304143", - "Likelihood: 0.29479799507270066", - "Likelihood: 0.03948196383855162", - "Likelihood: 0.11308662285078162", - "Likelihood: 0.14660677265701968", - "Likelihood: 0.22490657447989246", - "Likelihood: 0.25801918068950735", - "Likelihood: 0.12298722143019448", - "Likelihood: 0.29244950837031575", - "Likelihood: 0.26298833167057084", - "Likelihood: 0.21206988578293487", - "Likelihood: 0.10318340586076957", - "Likelihood: 0.19377423842293356", - "Likelihood: 0.09300153239370831", - "Likelihood: 0.20721132602959663", - "Likelihood: 0.191713102339566", - "Likelihood: 0.2190597307326278", - "Likelihood: 0.2800518098099094", - "Likelihood: 0.18321493567387703", - "Likelihood: 0.1389322954277713", - "Likelihood: 0.2741144071310574", - "Likelihood: 0.29475674565731785", - "Likelihood: 0.1644192130776883", - "Likelihood: 0.1395705759770367", - "Likelihood: 0.24762384576240376", - "Likelihood: 0.16180999574539426", - "Likelihood: 0.10951813561516045", - "Likelihood: 0.1369204708230705", - "Likelihood: 0.24268495901316758", - "Likelihood: 0.12975845748367776", - "Likelihood: 0.061582966394391696", - "Likelihood: 0.024152287767371137", - "Likelihood: 0.2231982349315616", - "Likelihood: 0.18021559779808266", - "Likelihood: 0.09442537173236858", - "Likelihood: 0.26249529411393996", - "Likelihood: 0.26628140174082965", - "Likelihood: 0.10001794315803575", - "Likelihood: 0.27249790665291607", - "Likelihood: 0.2674741744928634", - "Likelihood: 0.23169817055653513", - "Likelihood: 0.10691677622448742", - "Likelihood: 0.18844608162750037", - "Likelihood: 0.18862476263266018", - "Likelihood: 0.13482747185115865", - "Likelihood: 0.25729859530755106", - "Likelihood: 0.1707374745190978", - "Likelihood: 0.19628283775713537", - "Likelihood: 0.1250920511602489", - "Likelihood: 0.11696477372182688", - "Likelihood: 0.19015001690455569", - "Likelihood: 0.07669152396223003", - "Likelihood: 0.15423480020367283", - "Likelihood: 0.15106668161762613", - "Likelihood: 0.29477624205908187", - "Likelihood: 0.21056065713963537", - "Likelihood: 0.2145877572754939", - "Likelihood: 0.04314601821386248", - "Likelihood: 0.2009954714386768", - "Likelihood: 0.18921519203174025", - "Likelihood: 0.19164298193933504", - "Likelihood: 0.2442793884510625", - "Likelihood: 0.2062214615139318", - "Likelihood: 0.2044724227398196", - "Likelihood: 0.21806024778694952", - "Likelihood: 0.07868956472146094", - "Likelihood: 0.19471902500027605", - "Likelihood: 0.28753602568703146", - "Likelihood: 0.2712924087171743", - "Likelihood: 0.22469773350090852", - "Likelihood: 0.21744534218473413", - "Likelihood: 0.2596993644919844", - "Likelihood: 0.21601484979063457", - "Likelihood: 0.10997278578037126", - "Likelihood: 0.26799952308090397", - "Likelihood: 0.2606352285894381", - "Likelihood: 0.251201839161064", - "Likelihood: 0.10776621141907991", - "Likelihood: 0.11356323033666274", - "Likelihood: 0.0901642655867856", - "Likelihood: 0.17019372244372197", - "Likelihood: 0.2038370593933569", - "Likelihood: 0.27865720611105116", - "Likelihood: 0.04308870410344923", - "Likelihood: 0.16883009985286992", - "Likelihood: 0.25950685509529825", - "Likelihood: 0.30330643905871013", - "Likelihood: 0.22366675064381614", - "Likelihood: 0.1894789360383902", - "Likelihood: 0.2893096715523195", - "Likelihood: 0.15045828605146577", - "Likelihood: 0.22286469454894636", - "Likelihood: 0.2606944873655842", - "Likelihood: 0.2543059310535893", - "Likelihood: 0.08674821923306344", - "Likelihood: 0.19952647669826937", - "Likelihood: 0.29284043474098964", - "Likelihood: 0.28440553992085665", - "Likelihood: 0.22017208095957452", - "Likelihood: 0.23302821972962734", - "Likelihood: 0.18041417743725677", - "Likelihood: 0.2898711086883847", - "Likelihood: 0.1885812191100616", - "Likelihood: 0.13295506383283637", - "Likelihood: 0.1181316266726634", - "Likelihood: 0.19273911111586545", - "Likelihood: 0.1695366704267783", - "Likelihood: 0.2612476718029628", - "Likelihood: 0.16144240045818728", - "Likelihood: 0.2335492490668", - "Likelihood: 0.0980482438155786", - "Likelihood: 0.26409775922336637", - "Likelihood: 0.29044995883894587", - "Likelihood: 0.09794129288310724", - "Likelihood: 0.254284507508154", - "Likelihood: 0.061944005296166144", - "Likelihood: 0.06270147595018054", - "Likelihood: 0.20954640770596017", - "Likelihood: 0.20883631462009986", - "Likelihood: 0.20937227620780666", - "Likelihood: 0.21293953559305498", - "Likelihood: 0.2329905269551205", - "Likelihood: 0.19495689171639238", - "Likelihood: 0.2606092543018635", - "Likelihood: 0.08862215926207785", - "Likelihood: 0.196592929744247", - "Likelihood: 0.21969984891368163", - "Likelihood: 0.18365167989552905", - "Likelihood: 0.10652824558143965", - "Likelihood: 0.2476485255387191", - "Likelihood: 0.17021424275064798", - "Likelihood: 0.09895762171446276", - "Likelihood: 0.21553041282085672", - "Likelihood: 0.2950124221586617", - "Likelihood: 0.2106942092812543", - "Likelihood: 0.23624793908111652", - "Likelihood: 0.10785134586789095", - "Likelihood: 0.1882147425408471", - "Likelihood: 0.22885695089773436", - "Likelihood: 0.2207131280700589", - "Likelihood: 0.21655385503216154", - "Likelihood: 0.23992120273306908", - "Likelihood: 0.21318113242317538", - "Likelihood: 0.16102074613781808", - "Likelihood: 0.2562858586121093", - "Likelihood: 0.23177172483291875", - "Likelihood: 0.18984773394524748", - "Likelihood: 0.3044383953764837", - "Likelihood: 0.12262724199004264", - "Likelihood: 0.2448966757957638", - "Likelihood: 0.10286525078663439", - "Likelihood: 0.22846656927542086", - "Likelihood: 0.06905654242955324", - "Likelihood: 0.24999950436942503", - "Likelihood: 0.14461100919514452", - "Likelihood: 0.288943629085604", - "Likelihood: 0.14307449340129533", - "Likelihood: 0.27847803153586553", - "Likelihood: 0.23675949008953381", - "Likelihood: 0.29935232106081233", - "Likelihood: 0.2780307534882343", - "Likelihood: 0.2866529455201227", - "Likelihood: 0.20738702761498082", - "Likelihood: 0.23469387034100808", - "Likelihood: 0.20637516735606387", - "Likelihood: 0.20317037645627867", - "Likelihood: 0.19378850943919484", - "Likelihood: 0.017319459708759866", - "Likelihood: 0.07821655532174694", - "Likelihood: 0.15461228561306123", - "Likelihood: 0.04635098280087555", - "Likelihood: 0.2910152489161408", - "Likelihood: 0.11206782307635195", - "Likelihood: 0.2055242973663919", - "Likelihood: 0.25291278564678465", - "Likelihood: 0.27185923520986455", - "Likelihood: 0.16790049024783552", - "Likelihood: 0.16079006331031717", - "Likelihood: 0.16908291771378828", - "Likelihood: 0.2793913463774878", - "Likelihood: 0.173531970781791", - "Likelihood: 0.23197641134438615", - "Likelihood: 0.2583698174172488", - "Likelihood: 0.2971002432768537", - "Likelihood: 0.11217250021762558", - "Likelihood: 0.18426891845593935", - "Likelihood: 0.12603791891005658", - "Likelihood: 0.16258899163085427", - "Likelihood: 0.11515568703108442", - "Likelihood: 0.03521097380371991", - "Likelihood: 0.22260374034706684", - "Likelihood: 0.01729299338376037", - "Likelihood: 0.17350304739041822", - "Likelihood: 0.12237421132922155", - "Likelihood: 0.18694950401673097", - "Likelihood: 0.2716771337115123", - "Likelihood: 0.09248718799467992", - "Likelihood: 0.1589903209207462", - "Likelihood: 0.07146853480245943", - "Likelihood: 0.03841259099523109", - "Likelihood: 0.28457494598886895", - "Likelihood: 0.21217875902605865", - "Likelihood: 0.1402626553746525", - "Likelihood: 0.0726297079638921", - "Likelihood: 0.20402020681904065", - "Likelihood: 0.24128399524129215", - "Likelihood: 0.25997318806412223", - "Likelihood: 0.2965063161099138", - "Likelihood: 0.2954626953801377", - "Likelihood: 0.20567590535281619", - "Likelihood: 0.10356109702386321", - "Likelihood: 0.19577305917457702", - "Likelihood: 0.19739740260836683", - "Likelihood: 0.2084932963135926", - "Likelihood: 0.2376430890200649", - "Likelihood: 0.2208393428305659", - "Likelihood: 0.2925702637145508", - "Likelihood: 0.233586447035641", - "Likelihood: 0.22212390741877838", - "Likelihood: 0.16615538699525279", - "Likelihood: 0.26652551682378234", - "Likelihood: 0.03249162423669155", - "Likelihood: 0.25153287712863626", - "Likelihood: 0.22008155075306476", - "Likelihood: 0.18701940807468392", - "Likelihood: 0.21942992919782134", - "Likelihood: 0.23209113434160986", - "Likelihood: 0.14675603904275908", - "Likelihood: 0.10899964246332637", - "Likelihood: 0.2729298211155522", - "Likelihood: 0.2628254575521281", - "Likelihood: 0.1785239849741979", - "Likelihood: 0.048977016556591056", - "Likelihood: 0.15212929806896455", - "Likelihood: 0.03190439896988375", - "Likelihood: 0.0809395108931612", - "Likelihood: 0.12088764136055076", - "Likelihood: 0.0975714047329108", - "Likelihood: 0.07412304111612643", - "Likelihood: 0.19166602540931793", - "Likelihood: 0.09109382233630858", - "Likelihood: 0.27043927455698846", - "Likelihood: 0.14694150604333098", - "Likelihood: 0.18264583654417757", - "Likelihood: 0.2742652350465098", - "Likelihood: 0.2052383402323942", - "Likelihood: 0.28725996906859236", - "Likelihood: 0.10196895451999458", - "Likelihood: 0.14865249321070415", - "Likelihood: 0.23244765686034885", - "Likelihood: 0.17722486478847316", - "Likelihood: 0.1546254531096568", - "Likelihood: 0.1545950985206179", - "Likelihood: 0.0996657496844028", - "Likelihood: 0.24443998870436817", - "Likelihood: 0.22744649210791645", - "Likelihood: 0.2929273156052515", - "Likelihood: 0.21597216241418585", - "Likelihood: 0.2693927953095559", - "Likelihood: 0.24855007006005853", - "Likelihood: 0.29743460898572793", - "Likelihood: 0.07407889779917753", - "Likelihood: 0.25105094845778775", - "Likelihood: 0.22899857102290902", - "Likelihood: 0.05869630726839829", - "Likelihood: 0.14589431029083821", - "Likelihood: 0.09638206711887905", - "Likelihood: 0.09499641113491007", - "Likelihood: 0.2622867463521042", - "Likelihood: 0.23015021410861372", - "Likelihood: 0.1927904285588973", - "Likelihood: 0.24101026658907967", - "Likelihood: 0.06240595579544518", - "Likelihood: 0.29931566241959634", - "Likelihood: 0.11642806996047773", - "Likelihood: 0.23462620704720694", - "Likelihood: 0.2918485342029859", - "Likelihood: 0.27277669852031666", - "Likelihood: 0.06607356103874548", - "Likelihood: 0.2185170196066328", - "Likelihood: 0.09343682796400196", - "Likelihood: 0.16038858955978413", - "Likelihood: 0.052579708197600175", - "Likelihood: 0.1592871468009192", - "Likelihood: 0.29884327819442247", - "Likelihood: 0.2792663682830827", - "Likelihood: 0.25242285464983916", - "Likelihood: 0.17634989357855876", - "Likelihood: 0.252988120764727", - "Likelihood: 0.26543162587423086", - "Likelihood: 0.12087689310911919", - "Likelihood: 0.17663074818034585", - "Likelihood: 0.23382420193113898", - "Likelihood: 0.1391774639461417", - "Likelihood: 0.14704266203751717", - "Likelihood: 0.2652348070420524", - "Likelihood: 0.05392326694471071", - "Likelihood: 0.1265781062496791", - "Likelihood: 0.06316684743236807", - "Likelihood: 0.27283113617397536", - "Likelihood: 0.24268676193996577", - "Likelihood: 0.047916616418205014", - "Likelihood: 0.2557237076735053", - "Likelihood: 0.2949245747896", - "Likelihood: 0.23430388226130927", - "Likelihood: 0.26541790007041516", - "Likelihood: 0.2050645826006895", - "Likelihood: 0.2854587108952687", - "Likelihood: 0.10652043268619243", - "Likelihood: 0.20754533497481759", - "Likelihood: 0.0756744843161966", - "Likelihood: 0.26917947652725344", - "Likelihood: 0.17138041047238284", - "Likelihood: 0.24067709026563178", - "Likelihood: 0.11463523440807448", - "Likelihood: 0.252310660400343", - "Likelihood: 0.07016696274191762", - "Likelihood: 0.1625489799745978", - "Likelihood: 0.23364902938374482", - "Likelihood: 0.12271955669202404", - "Likelihood: 0.23203806662541657", - "Likelihood: 0.21480888570090015", - "Likelihood: 0.280063343129494", - "Likelihood: 0.15062486368438233", - "Likelihood: 0.23253772866169656", - "Likelihood: 0.1459803054390105", - "Likelihood: 0.23809986867575897", - "Likelihood: 0.05986347143730266", - "Likelihood: 0.29210820541330784", - "Likelihood: 0.11892629908667063", - "Likelihood: 0.25157604391850874", - "Likelihood: 0.08970682727506733", - "Likelihood: 0.16767307213076882", - "Likelihood: 0.14422570770301463", - "Likelihood: 0.18514511355627628", - "Likelihood: 0.10701328223699835", - "Likelihood: 0.24538421882856987", - "Likelihood: 0.2544019502014157", - "Likelihood: 0.15148897509327508", - "Likelihood: 0.03765161313165135", - "Likelihood: 0.18734406081134655", - "Likelihood: 0.27803014946228777", - "Likelihood: 0.1649989988553078", - "Likelihood: 0.2767730397782814", - "Likelihood: 0.2561145814251085", - "Likelihood: 0.17339912814208103", - "Likelihood: 0.13620522611054048", - "Likelihood: 0.2689265086738353", - "Likelihood: 0.0785951019453602", - "Likelihood: 0.2784466847671094", - "Likelihood: 0.10181460647584747", - "Likelihood: 0.24696693503755862", - "Likelihood: 0.1332966265070652", - "Likelihood: 0.2803543592295483", - "Likelihood: 0.13268727082873183", - "Likelihood: 0.08188468015723852", - "Likelihood: 0.21439677438017654", - "Likelihood: 0.2303168218536126", - "Likelihood: 0.21376546950144135", - "Likelihood: 0.2729798790585068", - "Likelihood: 0.22818351754142965", - "Likelihood: 0.26972524592045577", - "Likelihood: 0.13537963224405478", - "Likelihood: 0.20744595128852286", - "Likelihood: 0.09328209159384175", - "Likelihood: 0.20140452098827408", - "Likelihood: 0.03871618487653495", - "Likelihood: 0.205866890922576", - "Likelihood: 0.2909659569882231", - "Likelihood: 0.1886852495140537", - "Likelihood: 0.18347712679224035", - "Likelihood: 0.2424353495287385", - "Likelihood: 0.08761158029258036", - "Likelihood: 0.1467019083955299", - "Likelihood: 0.050183959308157576", - "Likelihood: 0.2623966796639639", - "Likelihood: 0.2034237549252033", - "Likelihood: 0.17615905486788727", - "Likelihood: 0.10299945925526542", - "Likelihood: 0.15053774984836477", - "Likelihood: 0.2992087739187341", - "Likelihood: 0.20180507002313344", - "Likelihood: 0.18615169167398582", - "Likelihood: 0.20598515590475794", - "Likelihood: 0.1482722426730725", - "Likelihood: 0.11340974709132347", - "Likelihood: 0.16960118804464044", - "Likelihood: 0.19838422788935328", - "Likelihood: 0.2782617136193784", - "Likelihood: 0.2762531597158834", - "Likelihood: 0.19691738614483822", - "Likelihood: 0.2260301211613087", - "Likelihood: 0.03604396450691811", - "Likelihood: 0.08757516893141269", - "Likelihood: 0.2708130865162271", - "Likelihood: 0.10662968801285018", - "Likelihood: 0.26507015523701744", - "Likelihood: 0.2839640112994011", - "Likelihood: 0.1722653880110443", - "Likelihood: 0.19740366512983054", - "Likelihood: 0.21743317238473", - "Likelihood: 0.2470580862031524", - "Likelihood: 0.0920079407693626", - "Likelihood: 0.3002426283469433", - "Likelihood: 0.1298532105065835", - "Likelihood: 0.09313873688287833", - "Likelihood: 0.044168390842286964", - "Likelihood: 0.2644806517454654", - "Likelihood: 0.22298747736909796", - "Likelihood: 0.17919573658424717", - "Likelihood: 0.19129086815491278", - "Likelihood: 0.29024681490488696", - "Likelihood: 0.19175092484820896", - "Likelihood: 0.16182194643723757", - "Likelihood: 0.21402451724603416", - "Likelihood: 0.22120191681352203", - "Likelihood: 0.2854605097639801", - "Likelihood: 0.2043524246284437", - "Likelihood: 0.26442582353609484", - "Likelihood: 0.218074792536681", - "Likelihood: 0.15142541656346367", - "Likelihood: 0.2277987990007179", - "Likelihood: 0.13503019736682267", - "Likelihood: 0.2128190434643665", - "Likelihood: 0.24903539761904214", - "Likelihood: 0.16085218185383268", - "Likelihood: 0.24212856440214187", - "Likelihood: 0.10175100869105264", - "Likelihood: 0.1069151202549678", - "Likelihood: 0.2838273745829864", - "Likelihood: 0.12236598422354544", - "Likelihood: 0.2405216641307114", - "Likelihood: 0.12410614997012363", - "Likelihood: 0.2510836392688061", - "Likelihood: 0.2572495878472259", - "Likelihood: 0.08787832033496559", - "Likelihood: 0.2195324167223904", - "Likelihood: 0.2077444937282018", - "Likelihood: 0.17590689138504229", - "Likelihood: 0.029028572525713118", - "Likelihood: 0.26731074964485724", - "Likelihood: 0.19454245158062894", - "Likelihood: 0.1888546311625103", - "Likelihood: 0.13427415831000364", - "Likelihood: 0.2779730703413729", - "Likelihood: 0.08427103450363972", - "Likelihood: 0.22144674847367993", - "Likelihood: 0.1995340250445127", - "Likelihood: 0.12475518182191032", - "Likelihood: 0.07915750848200676", - "Likelihood: 0.21988806837602248", - "Likelihood: 0.2968093151727777", - "Likelihood: 0.13921887237441358", - "Likelihood: 0.2306559610012118", - "Likelihood: 0.19465372894393052", - "Likelihood: 0.267812748447754", - "Likelihood: 0.19560362411320656", - "Likelihood: 0.12553204515267882", - "Likelihood: 0.23588576847508236", - "Likelihood: 0.10184984228192011", - "Likelihood: 0.24347475432839277", - "Likelihood: 0.17901538523999622", - "Likelihood: 0.22023282339600297", - "Likelihood: 0.22400559715242105", - "Likelihood: 0.19760937121204986", - "Likelihood: 0.27833541611917473", - "Likelihood: 0.1584550090996059", - "Likelihood: 0.20754534990541937", - "Likelihood: 0.07461029377900386", - "Likelihood: 0.20052596579875465", - "Likelihood: 0.13071672773186443", - "Likelihood: 0.2782414136457918", - "Likelihood: 0.27372282439208534", - "Likelihood: 0.2768408048741568", - "Likelihood: 0.29856741832947326", - "Likelihood: 0.28793922671302635", - "Likelihood: 0.22223017036130685", - "Likelihood: 0.1658287380864205", - "Likelihood: 0.25422465164620517", - "Likelihood: 0.26116187444112804", - "Likelihood: 0.07800588833059638", - "Likelihood: 0.2790251306662057", - "Likelihood: 0.2591416878209692", - "Likelihood: 0.14391555469514813", - "Likelihood: 0.30495408818947184", - "Likelihood: 0.1256729534196164", - "Likelihood: 0.30349312753016777", - "Likelihood: 0.1735117525957839", - "Likelihood: 0.16216225452774874", - "Likelihood: 0.2552159609507429", - "Likelihood: 0.23433381494490765", - "Likelihood: 0.141433814686817", - "Likelihood: 0.18078422335695787", - "Likelihood: 0.09392884679144806", - "Likelihood: 0.16684840505077875", - "Likelihood: 0.2593633235223832", - "Likelihood: 0.23541141106574803", - "Likelihood: 0.17665621996276643", - "Likelihood: 0.14906650691688053", - "Likelihood: 0.20053404841027014", - "Likelihood: 0.0659695699712886", - "Likelihood: 0.2879579209725064", - "Likelihood: 0.09485194491010544", - "Likelihood: 0.21497040496284675", - "Likelihood: 0.16807913185236922", - "Likelihood: 0.297985522745685", - "Likelihood: 0.15462675031727235", - "Likelihood: 0.25347687928929735", - "Likelihood: 0.23683408182368906", - "Likelihood: 0.1983872239311829", - "Likelihood: 0.2482358352937575", - "Likelihood: 0.14976753881702903", - "Likelihood: 0.21610054254364533", - "Likelihood: 0.0378509126122541", - "Likelihood: 0.17849573517154763", - "Likelihood: 0.2699629453664462", - "Likelihood: 0.16962297127658582", - "Likelihood: 0.25327659476093284", - "Likelihood: 0.2476685395713947", - "Likelihood: 0.02806452053300696", - "Likelihood: 0.23260900318702535", - "Likelihood: 0.17064714083043142", - "Likelihood: 0.2098605862503563", - "Likelihood: 0.2674868384366377", - "Likelihood: 0.10279089376982573", - "Likelihood: 0.09587398014578402", - "Likelihood: 0.06556229873336523", - "Likelihood: 0.2614402016497092", - "Likelihood: 0.19509863306554281", - "Likelihood: 0.08252164583858147", - "Likelihood: 0.17139796144017835", - "Likelihood: 0.18448859428791367", - "Likelihood: 0.22240339295496683", - "Likelihood: 0.29343046288594954", - "Likelihood: 0.09518404844566533", - "Likelihood: 0.18766703796772466", - "Likelihood: 0.29406541589571616", - "Likelihood: 0.1813655137134376", - "Likelihood: 0.23073330688242225", - "Likelihood: 0.11488820042926777", - "Likelihood: 0.1331967303065785", - "Likelihood: 0.26781743774783406", - "Likelihood: 0.19668911659034094", - "Likelihood: 0.2793002745940442", - "Likelihood: 0.23335313221401047", - "Likelihood: 0.22360453862858048", - "Likelihood: 0.09202431864079026", - "Likelihood: 0.2521886504795316", - "Likelihood: 0.22824988714403208", - "Likelihood: 0.15992337813115604", - "Likelihood: 0.12282462317930587", - "Likelihood: 0.24032890837463863", - "Likelihood: 0.20362365755034595", - "Likelihood: 0.21683021352194645", - "Likelihood: 0.2571130560009515", - "Likelihood: 0.16091978501718887", - "Likelihood: 0.24175423584781505", - "Likelihood: 0.24222892345166408", - "Likelihood: 0.1718864011388615", - "Likelihood: 0.13532627400207195", - "Likelihood: 0.1111080226540442", - "Likelihood: 0.07844551877587554", - "Likelihood: 0.12368087693706818", - "Likelihood: 0.2552703120376804", - "Likelihood: 0.21711857983901017", - "Likelihood: 0.1360910657400197", - "Likelihood: 0.1832319870573771", - "Likelihood: 0.28191659664956986", - "Likelihood: 0.275372472769042", - "Likelihood: 0.22199021096677657", - "Likelihood: 0.23352754514603416", - "Likelihood: 0.1830371784303611", - "Likelihood: 0.17353160540058066", - "Likelihood: 0.17513013523525084", - "Likelihood: 0.20588773306685362", - "Likelihood: 0.09585533284527113", - "Likelihood: 0.1129005266628755", - "Likelihood: 0.2183027020723918", - "Likelihood: 0.25079665871175527", - "Likelihood: 0.17947682898583897", - "Likelihood: 0.16893837029929978", - "Likelihood: 0.039450087947877924", - "Likelihood: 0.30190048850152956", - "Likelihood: 0.09653739154047382", - "Likelihood: 0.21169324020216587", - "Likelihood: 0.16729581210636604", - "Likelihood: 0.2046922405037021", - "Likelihood: 0.19846120022420524", - "Likelihood: 0.26231020883420975", - "Likelihood: 0.18023736899390772", - "Likelihood: 0.2862611096746094", - "Likelihood: 0.13323756270703566", - "Likelihood: 0.1328630067444117", - "Likelihood: 0.04701521849244883", - "Likelihood: 0.10660966985930859", - "Likelihood: 0.27570286277583184", - "Likelihood: 0.16075727788153477", - "Likelihood: 0.061622193750161564", - "Likelihood: 0.2935679961088398", - "Likelihood: 0.29911553943382174", - "Likelihood: 0.15070883946484082", - "Likelihood: 0.2346842934161601", - "Likelihood: 0.17758941631548317", - "Likelihood: 0.2485647829441674", - "Likelihood: 0.15525569619067814", - "Likelihood: 0.18327298662769173", - "Likelihood: 0.12190926637533221", - "Likelihood: 0.12477366646325094", - "Likelihood: 0.1698191532951339", - "Likelihood: 0.29029410697560754", - "Likelihood: 0.24295675506668094", - "Likelihood: 0.09465717804141893", - "Likelihood: 0.052936139202931394", - "Likelihood: 0.2980142809339341", - "Likelihood: 0.14117560026538498", - "Likelihood: 0.23738279916774216", - "Likelihood: 0.23471837675024698", - "Likelihood: 0.2853457035132007", - "Likelihood: 0.13500371097270628", - "Likelihood: 0.2754683772343798", - "Likelihood: 0.19019480415608225", - "Likelihood: 0.15570948954545108", - "Likelihood: 0.12970435246880854", - "Likelihood: 0.20507487045528336", - "Likelihood: 0.18545736815120337", - "Likelihood: 0.22843034399461204", - "Likelihood: 0.24752440845375656", - "Likelihood: 0.26947329576092544", - "Likelihood: 0.2724341110229931", - "Likelihood: 0.16932038417815318", - "Likelihood: 0.21673104829492784", - "Likelihood: 0.12520850601243086", - "Likelihood: 0.15689176302723154", - "Likelihood: 0.12975201611145637", - "Likelihood: 0.06209454308937531", - "Likelihood: 0.1508107533212955", - "Likelihood: 0.26200814383957316", - "Likelihood: 0.24913496969767568", - "Likelihood: 0.18756084502070514", - "Likelihood: 0.22143587522303942", - "Likelihood: 0.14696839509678258", - "Likelihood: 0.11927051984875092", - "Likelihood: 0.2139192032879219", - "Likelihood: 0.2880750184987202", - "Likelihood: 0.12340180179828883", - "Likelihood: 0.13114388497940802", - "Likelihood: 0.21620045275832964", - "Likelihood: 0.19230424602908822", - "Likelihood: 0.1813580969251072", - "Likelihood: 0.2156765888450221", - "Likelihood: 0.1885746553402076", - "Likelihood: 0.060168263604363725", - "Likelihood: 0.20481400304263797", - "Likelihood: 0.20411610160357124", - "Likelihood: 0.12007763103083621", - "Likelihood: 0.23311488772959946", - "Likelihood: 0.17610839974804546", - "Likelihood: 0.19761453950719202", - "Likelihood: 0.23207247098709657", - "Likelihood: 0.02931943258265294", - "Likelihood: 0.2668979562640318", - "Likelihood: 0.06288160725079821", - "Likelihood: 0.17732260729279234", - "Likelihood: 0.26805707017702896", - "Likelihood: 0.08290732190625208", - "Likelihood: 0.1851464777350242", - "Likelihood: 0.10061599098241922", - "Likelihood: 0.13458772548182377", - "Likelihood: 0.18331610960519118", - "Likelihood: 0.1963367732802584", - "Likelihood: 0.17834302295484616", - "Likelihood: 0.09850967329407342", - "Likelihood: 0.18973879212446143", - "Likelihood: 0.12562934259797273", - "Likelihood: 0.27073485810622483", - "Likelihood: 0.2337812502948699", - "Likelihood: 0.03238243450008821", - "Likelihood: 0.20261727295219983", - "Likelihood: 0.1205810774702094", - "Likelihood: 0.13720303360831348", - "Likelihood: 0.14651698176335493", - "Likelihood: 0.27319618097567167", - "Likelihood: 0.260046662304998", - "Likelihood: 0.15846146568601532", - "Likelihood: 0.20309820369177647", - "Likelihood: 0.2670050556990683", - "Likelihood: 0.1349215947498154", - "Likelihood: 0.058255152396836825", - "Likelihood: 0.23609818198933602", - "Likelihood: 0.07534720336385564", - "Likelihood: 0.28818535776714305", - "Likelihood: 0.20359146535833708", - "Likelihood: 0.2406812254288444", - "Likelihood: 0.23377969794822326", - "Likelihood: 0.11688267468830772", - "Likelihood: 0.07918023220908796", - "Likelihood: 0.11194600390075093", - "Likelihood: 0.21235009724616594", - "Likelihood: 0.2487016304337906", - "Likelihood: 0.15959718117000818", - "Likelihood: 0.05366376344345603", - "Likelihood: 0.04454487494155729", - "Likelihood: 0.1906812296430624", - "Likelihood: 0.19440813601949922", - "Likelihood: 0.24326917118911578", - "Likelihood: 0.18884014719657866", - "Likelihood: 0.22548291756366576", - "Likelihood: 0.2668236334784724", - "Likelihood: 0.16936414551216925", - "Likelihood: 0.2630709490561354", - "Likelihood: 0.2651229641949324", - "Likelihood: 0.27572247020738877", - "Likelihood: 0.15231147264206898", - "Likelihood: 0.29132547429189654", - "Likelihood: 0.1940014181121557", - "Likelihood: 0.1217358276556339", - "Likelihood: 0.1846360137456656", - "Likelihood: 0.18076776232762087", - "Likelihood: 0.09070838202230537", - "Likelihood: 0.2661698960551719", - "Likelihood: 0.2860131197760874", - "Likelihood: 0.16721122711020397", - "Likelihood: 0.23082252843485562", - "Likelihood: 0.1315628751318888", - "Likelihood: 0.26769563268096996", - "Likelihood: 0.04107729451582515", - "Likelihood: 0.06899092779196672", - "Likelihood: 0.23342698599833978", - "Likelihood: 0.10309917819725081", - "Likelihood: 0.28686140137857097", - "Likelihood: 0.23820015050433163", - "Likelihood: 0.20630596937979315", - "Likelihood: 0.25110467815820725", - "Likelihood: 0.12900228455049162", - "Likelihood: 0.12056403834616435", - "Likelihood: 0.17114734921879382", - "Likelihood: 0.07022834405969579", - "Likelihood: 0.26705491541557597", - "Likelihood: 0.2822478938797246", - "Likelihood: 0.08956772797335524", - "Likelihood: 0.21278357954783914", - "Likelihood: 0.17194116375408372", - "Likelihood: 0.15438958436065603", - "Likelihood: 0.19763231484752083", - "Likelihood: 0.2579724788575258", - "Likelihood: 0.2197704970674212", - "Likelihood: 0.28899832896610594", - "Likelihood: 0.2577159684622302", - "Likelihood: 0.23506217388478193", - "Likelihood: 0.25173485323956535", - "Likelihood: 0.2584741630251752", - "Likelihood: 0.17893365425549157", - "Likelihood: 0.18678431154523936", - "Likelihood: 0.23543445263232585", - "Likelihood: 0.2720443902017717", - "Likelihood: 0.10917700917058316", - "Likelihood: 0.14908150736426246", - "Likelihood: 0.2071698153930145", - "Likelihood: 0.21239246076967785", - "Likelihood: 0.2523325355683828", - "Likelihood: 0.28947565429297467", - "Likelihood: 0.2950169587742273", - "Likelihood: 0.10477668591544145", - "Likelihood: 0.21279589909646374", - "Likelihood: 0.26703666604961346", - "Likelihood: 0.07555195844304785", - "Likelihood: 0.18432692276495277", - "Likelihood: 0.18520918443920528", - "Likelihood: 0.09212176338671334", - "Likelihood: 0.24549408054538197", - "Likelihood: 0.2698568376747854", - "Likelihood: 0.19986358856608497", - "Likelihood: 0.16906585411785657", - "Likelihood: 0.2958238650858085", - "Likelihood: 0.08326499542177002", - "Likelihood: 0.15534731636010313", - "Likelihood: 0.044684645943282274", - "Likelihood: 0.14565022857255455", - "Likelihood: 0.2981807848101089", - "Likelihood: 0.2762809269713834", - "Likelihood: 0.19200258124034109", - "Likelihood: 0.14188724577329861", - "Likelihood: 0.2700407569758332", - "Likelihood: 0.18553847703129664", - "Likelihood: 0.14391944343555352", - "Likelihood: 0.2683680295452143", - "Likelihood: 0.23618843024299965", - "Likelihood: 0.2924217781823653", - "Likelihood: 0.12964712868924394", - "Likelihood: 0.2003857323237578", - "Likelihood: 0.1736647163622968", - "Likelihood: 0.14762725530928242", - "Likelihood: 0.11993532138287469", - "Likelihood: 0.2410529207358764", - "Likelihood: 0.08048697893854188", - "Likelihood: 0.15330832008768233", - "Likelihood: 0.17036361810799147", - "Likelihood: 0.2947720894252494", - "Likelihood: 0.29147199698384596", - "Likelihood: 0.1953583783365111", - "Likelihood: 0.19794658559927064", - "Likelihood: 0.23826379780096893", - "Likelihood: 0.12711832269704423", - "Likelihood: 0.18746303250724075", - "Likelihood: 0.2314990459967369", - "Likelihood: 0.19231894583312942", - "Likelihood: 0.24905452852122756", - "Likelihood: 0.21636992698053437", - "Likelihood: 0.12769709299421164", - "Likelihood: 0.09309448640075445", - "Likelihood: 0.18246797331892936", - "Likelihood: 0.15950109887604538", - "Likelihood: 0.10998606449241616", - "Likelihood: 0.15009395654944294", - "Likelihood: 0.3013852138872356", - "Likelihood: 0.23981735099123244", - "Likelihood: 0.16442748910602215", - "Likelihood: 0.18566106586991174", - "Likelihood: 0.2740780654007686", - "Likelihood: 0.22177317688432813", - "Likelihood: 0.02416861444798085", - "Likelihood: 0.11710232370200596", - "Likelihood: 0.2502012673298704", - "Likelihood: 0.20814545011612748", - "Likelihood: 0.13186251040207214", - "Likelihood: 0.25700826746949257", - "Likelihood: 0.16125024306143795", - "Likelihood: 0.11967801090865907", - "Likelihood: 0.24174522115281707", - "Likelihood: 0.18990282295552455", - "Likelihood: 0.10166394834677152", - "Likelihood: 0.09995286491262238", - "Likelihood: 0.20713374450301184", - "Likelihood: 0.20251219586609495", - "Likelihood: 0.21834372792686757", - "Likelihood: 0.11685643234478431", - "Likelihood: 0.03765650919823759", - "Likelihood: 0.2648553285716715", - "Likelihood: 0.2220650988011139", - "Likelihood: 0.2629472983264285", - "Likelihood: 0.275532457172384", - "Likelihood: 0.1785447576407883", - "Likelihood: 0.13908441374555747", - "Likelihood: 0.26248615731982455", - "Likelihood: 0.2804021211824284", - "Likelihood: 0.04643636180191451", - "Likelihood: 0.13092841192565102", - "Likelihood: 0.20437460789048972", - "Likelihood: 0.21029997453994026", - "Likelihood: 0.29910862240051184", - "Likelihood: 0.24240589592534756", - "Likelihood: 0.235361299379993", - "Likelihood: 0.1588516634293354", - "Likelihood: 0.19385580344495987", - "Likelihood: 0.1796904062312912", - "Likelihood: 0.2610873441283979", - "Likelihood: 0.2976571065267217", - "Likelihood: 0.11605976188482744", - "Likelihood: 0.17382973907332538", - "Likelihood: 0.274746291046984", - "Likelihood: 0.21129279075668717", - "Likelihood: 0.24617027573796305", - "Likelihood: 0.2685166025989095", - "Likelihood: 0.208543228868503", - "Likelihood: 0.06614930330956124", - "Likelihood: 0.16439861690931443", - "Likelihood: 0.12462699660316659", - "Likelihood: 0.02979609644912206", - "Likelihood: 0.19957814333315477", - "Likelihood: 0.08922370558820598", - "Likelihood: 0.12297251634098104", - "Likelihood: 0.24081178381224874", - "Likelihood: 0.22647513161051253", - "Likelihood: 0.17300855994285474", - "Likelihood: 0.10346935114409261", - "Likelihood: 0.0672593847801836", - "Likelihood: 0.26100363615216543", - "Likelihood: 0.07884013146271683", - "Likelihood: 0.22776925944549936", - "Likelihood: 0.11363264285775493", - "Likelihood: 0.2588904981271024", - "Likelihood: 0.2171666472916359", - "Likelihood: 0.25960152258072683", - "Likelihood: 0.2656393059730312", - "Likelihood: 0.22639617643854784", - "Likelihood: 0.2320699409720359", - "Likelihood: 0.19807291254091458", - "Likelihood: 0.06791382738109082", - "Likelihood: 0.2823656741158864", - "Likelihood: 0.283090378610868", - "Likelihood: 0.17472858578778488", - "Likelihood: 0.2203900162733744", - "Likelihood: 0.13070276498893635", - "Likelihood: 0.06604929991638529", - "Likelihood: 0.22838662982619343", - "Likelihood: 0.13374059172933486", - "Likelihood: 0.13362573227952362", - "Likelihood: 0.0184595681054568", - "Likelihood: 0.08194063534091625", - "Likelihood: 0.2370859548005179", - "Likelihood: 0.2422204036847598", - "Likelihood: 0.29279140777577406", - "Likelihood: 0.2005279982519961", - "Likelihood: 0.2238973299710146", - "Likelihood: 0.09038936153105827", - "Likelihood: 0.2173319680831825", - "Likelihood: 0.20281134945702697", - "Likelihood: 0.27070543977586603", - "Likelihood: 0.08655154829764067", - "Likelihood: 0.24410248296170084", - "Likelihood: 0.16190927039635564", - "Likelihood: 0.27933281753537775", - "Likelihood: 0.13036932709923735", - "Likelihood: 0.2580953956401353", - "Likelihood: 0.08087685247115903", - "Likelihood: 0.27131969432368563", - "Likelihood: 0.27832384498046175", - "Likelihood: 0.29007502138527486", - "Likelihood: 0.23498724326698783", - "Likelihood: 0.3049817302312203", - "Likelihood: 0.2819709294975654", - "Likelihood: 0.16139851586374265", - "Likelihood: 0.06181656119465449", - "Likelihood: 0.20637638960771393", - "Likelihood: 0.2982111017319344", - "Likelihood: 0.21934918057612632", - "Likelihood: 0.24701199753092842", - "Likelihood: 0.18216961544445523", - "Likelihood: 0.22902950305638534", - "Likelihood: 0.177265194913707", - "Likelihood: 0.2187669062533121", - "Likelihood: 0.2776365731194596", - "Likelihood: 0.26040886979906647", - "Likelihood: 0.21401443462011083", - "Likelihood: 0.13513963117519073", - "Likelihood: 0.25114678363231424", - "Likelihood: 0.2685212102496195", - "Likelihood: 0.2583263732777794", - "Likelihood: 0.055016581592611906", - "Likelihood: 0.1725447498827684", - "Likelihood: 0.14088176792061252", - "Likelihood: 0.1003191875898981", - "Likelihood: 0.10077403018953991", - "Likelihood: 0.2567738842330446", - "Likelihood: 0.12214135053568219", - "Likelihood: 0.24728886370261363", - "Likelihood: 0.2745499559244698", - "Likelihood: 0.2573030792074793", - "Likelihood: 0.2836779198166239", - "Likelihood: 0.2891710316435786", - "Likelihood: 0.16890319944500445", - "Likelihood: 0.13039103422651602", - "Likelihood: 0.29487036442222697", - "Likelihood: 0.05274349940807365", - "Likelihood: 0.2018716396475534", - "Likelihood: 0.18433287176294808", - "Likelihood: 0.18099467545126288", - "Likelihood: 0.2661783275266855", - "Likelihood: 0.016334802409633958", - "Likelihood: 0.2742524500243591", - "Likelihood: 0.29538179213155585", - "Likelihood: 0.24349224638544295", - "Likelihood: 0.27969486400278654", - "Likelihood: 0.14176229184156972", - "Likelihood: 0.1950425788829083", - "Likelihood: 0.23237291694366824", - "Likelihood: 0.20480818526844596", - "Likelihood: 0.30235385427651784", - "Likelihood: 0.27416255412717894", - "Likelihood: 0.05199431454453911", - "Likelihood: 0.2354290617243491", - "Likelihood: 0.18790697532770836", - "Likelihood: 0.11476208537673648", - "Likelihood: 0.28640719683620075", - "Likelihood: 0.1367926165755038", - "Likelihood: 0.18833071114620836", - "Likelihood: 0.18984523685565577", - "Likelihood: 0.2941005201285737", - "Likelihood: 0.10715621486783708", - "Likelihood: 0.2566570911750187", - "Likelihood: 0.2690629296287679", - "Likelihood: 0.1442785189512151", - "Likelihood: 0.21420939498693742", - "Likelihood: 0.26702171299369437", - "Likelihood: 0.1816103535116336", - "Likelihood: 0.30392351311798343", - "Likelihood: 0.012008301374457802", - "Likelihood: 0.2025681306151914", - "Likelihood: 0.22388717125387497", - "Likelihood: 0.10021052550999346", - "Likelihood: 0.24875976880207906", - "Likelihood: 0.07731622621937007", - "Likelihood: 0.2585698770745073", - "Likelihood: 0.07715228821272288", - "Likelihood: 0.1255358053833815", - "Likelihood: 0.2372999967013207", - "Likelihood: 0.24385676155225441", - "Likelihood: 0.24479526605294433", - "Likelihood: 0.21721695724386153", - "Likelihood: 0.17421719964176682", - "Likelihood: 0.17776746267447824", - "Likelihood: 0.22414256358110005", - "Likelihood: 0.26134831342051734", - "Likelihood: 0.2053879824607158", - "Likelihood: 0.24589021565841324", - "Likelihood: 0.24485721197896837", - "Likelihood: 0.27547442410531464", - "Likelihood: 0.2105710537310177", - "Likelihood: 0.28738988286086925", - "Likelihood: 0.25576891124956264", - "Likelihood: 0.20413646781122727", - "Likelihood: 0.16630319956609274", - "Likelihood: 0.19740284317233206", - "Likelihood: 0.12727928605317682", - "Likelihood: 0.21614722090865457", - "Likelihood: 0.20288137628661976", - "Likelihood: 0.1536475103703583", - "Likelihood: 0.09227871303485642", - "Likelihood: 0.2850676907499034", - "Likelihood: 0.14334898049098926", - "Likelihood: 0.23464159670731466", - "Likelihood: 0.2318292536423547", - "Likelihood: 0.19026319174178438", - "Likelihood: 0.08779540207780262", - "Likelihood: 0.2056058591066326", - "Likelihood: 0.16203000052452513", - "Likelihood: 0.22771432423546312", - "Likelihood: 0.10538717363612685", - "Likelihood: 0.16915005797850735", - "Likelihood: 0.2642998468630977", - "Likelihood: 0.19436174150956556", - "Likelihood: 0.3025278551270929", - "Likelihood: 0.1588447577591593", - "Likelihood: 0.1601599299078283", - "Likelihood: 0.12178032840670039", - "Likelihood: 0.19771913262368163", - "Likelihood: 0.12374572616967032", - "Likelihood: 0.29910628794220195", - "Likelihood: 0.2375496231313557", - "Likelihood: 0.20031219300549769", - "Likelihood: 0.163878588463951", - "Likelihood: 0.14218527280760224", - "Likelihood: 0.21519270495289444", - "Likelihood: 0.1954516538988161", - "Likelihood: 0.12173204259414025", - "Likelihood: 0.17776074396531027", - "Likelihood: 0.2356024463781822", - "Likelihood: 0.2729881752559688", - "Likelihood: 0.1519699566504658", - "Likelihood: 0.22999916122464484", - "Likelihood: 0.13417856882084012", - "Likelihood: 0.2709434410212926", - "Likelihood: 0.17860477940292005", - "Likelihood: 0.24159006075658543", - "Likelihood: 0.19178770379075952", - "Likelihood: 0.16563574362553687", - "Likelihood: 0.2652002435109653", - "Likelihood: 0.1388834679980543", - "Likelihood: 0.20843782903768407", - "Likelihood: 0.20476467452683778", - "Likelihood: 0.036656303816139324", - "Likelihood: 0.2681810673356862", - "Likelihood: 0.25420536038226904", - "Likelihood: 0.12989240254044376", - "Likelihood: 0.20737967370896218", - "Likelihood: 0.1558772424648749", - "Likelihood: 0.15760308665673015", - "Likelihood: 0.20156012005456794", - "Likelihood: 0.19031199224181491", - "Likelihood: 0.14828198657380137", - "Likelihood: 0.05238399322938532", - "Likelihood: 0.1277124494620755", - "Likelihood: 0.2554561817345248", - "Likelihood: 0.16250397873402722", - "Likelihood: 0.19134732839981441", - "Likelihood: 0.2514481247317301", - "Likelihood: 0.17386135174486056", - "Likelihood: 0.15567836066842214", - "Likelihood: 0.14820499160562592", - "Likelihood: 0.14308194393738335", - "Likelihood: 0.3005349672641853", - "Likelihood: 0.09078950483880104", - "Likelihood: 0.20664303883342483", - "Likelihood: 0.18499172363828065", - "Likelihood: 0.1339520378610635", - "Likelihood: 0.1927000278627178", - "Likelihood: 0.23946837447084032", - "Likelihood: 0.2795833186265405", - "Likelihood: 0.23784397118284445", - "Likelihood: 0.11616349155592745", - "Likelihood: 0.1874725512392416", - "Likelihood: 0.2310145549407882", - "Likelihood: 0.2444824917083357", - "Likelihood: 0.11257305063305197", - "Likelihood: 0.25755802572387654", - "Likelihood: 0.2397776827908704", - "Likelihood: 0.18217058176047132", - "Likelihood: 0.22868785672337802", - "Likelihood: 0.1856878307260963", - "Likelihood: 0.2292036642875071", - "Likelihood: 0.1283813161457038", - "Likelihood: 0.04082766651666613", - "Likelihood: 0.26711611049282125", - "Likelihood: 0.055269784270910706", - "Likelihood: 0.17888682776342035", - "Likelihood: 0.16530454707862027", - "Likelihood: 0.1425899127710042", - "Likelihood: 0.2763064904261103", - "Likelihood: 0.293412160367548", - "Likelihood: 0.13832558377390955", - "Likelihood: 0.1705020511467774", - "Likelihood: 0.224702305645966", - "Likelihood: 0.2627441741151187", - "Likelihood: 0.06531149197824027", - "Likelihood: 0.2847136553198675", - "Likelihood: 0.2544078937137236", - "Likelihood: 0.27534638581084925", - "Likelihood: 0.19469232211580526", - "Likelihood: 0.21007668567881874", - "Likelihood: 0.08623358775519867", - "Likelihood: 0.17008301791387495", - "Likelihood: 0.12295392847099677", - "Likelihood: 0.10301706213983775", - "Likelihood: 0.287707205083104", - "Likelihood: 0.2621336121494923", - "Likelihood: 0.06390911101364603", - "Likelihood: 0.16715425557785718", - "Likelihood: 0.24962757416083292", - "Likelihood: 0.2614845987322003", - "Likelihood: 0.24838874249827145", - "Likelihood: 0.10795732895899686", - "Likelihood: 0.14316288857550022", - "Likelihood: 0.12517540777975722", - "Likelihood: 0.14177213508899936", - "Likelihood: 0.1336418555470747", - "Likelihood: 0.25926359668505217", - "Likelihood: 0.15280609532045542", - "Likelihood: 0.2837219598413001", - "Likelihood: 0.2022535771967488", - "Likelihood: 0.14073046753938495", - "Likelihood: 0.10315536927049739", - "Likelihood: 0.08487283626867652", - "Likelihood: 0.2287812054129356", - "Likelihood: 0.28729174372868094", - "Likelihood: 0.2881566720958147", - "Likelihood: 0.06736013543181463", - "Likelihood: 0.29335074062594635", - "Likelihood: 0.29343219615419713", - "Likelihood: 0.18100959585825271", - "Likelihood: 0.22218082015977159", - "Likelihood: 0.13340588071273343", - "Likelihood: 0.04920459585669149", - "Likelihood: 0.29643324492553347", - "Likelihood: 0.13664576361246805", - "Likelihood: 0.20316243754604724", - "Likelihood: 0.18185658769058288", - "Likelihood: 0.18614881409705386", - "Likelihood: 0.07913530140431475", - "Likelihood: 0.21312447579698998", - "Likelihood: 0.1961131028299737", - "Likelihood: 0.16648750717299596", - "Likelihood: 0.11431917627577129", - "Likelihood: 0.2435297533186739", - "Likelihood: 0.2622610221759784", - "Likelihood: 0.2903478449693954", - "Likelihood: 0.14305261167393657", - "Likelihood: 0.2953018255507666", - "Likelihood: 0.2808168367407713", - "Likelihood: 0.2898246301863183", - "Likelihood: 0.21070965043905007", - "Likelihood: 0.14378223913606555", - "Likelihood: 0.09371127147900166", - "Likelihood: 0.293910450040184", - "Likelihood: 0.18688706577396355", - "Likelihood: 0.1767593407801962", - "Likelihood: 0.23613599724691467", - "Likelihood: 0.22613498407181454", - "Likelihood: 0.031183156076459786", - "Likelihood: 0.019960119878058877", - "Likelihood: 0.080265103050794", - "Likelihood: 0.13382228220783843", - "Likelihood: 0.2540734407854029", - "Likelihood: 0.23347425861275375", - "Likelihood: 0.0902884856269588", - "Likelihood: 0.2571213162679318", - "Likelihood: 0.07606441485902421", - "Likelihood: 0.08794090024671052", - "Likelihood: 0.23348267648157395", - "Likelihood: 0.14509661445421726", - "Likelihood: 0.1298564055213083", - "Likelihood: 0.10825013052457184", - "Likelihood: 0.12023440567038204", - "Likelihood: 0.2630864230161384", - "Likelihood: 0.22389591214187332", - "Likelihood: 0.22569243345746373", - "Likelihood: 0.10908934327074375", - "Likelihood: 0.29139825811787945", - "Likelihood: 0.09445006117231801", - "Likelihood: 0.08995008978762548", - "Likelihood: 0.1611749345882324", - "Likelihood: 0.10516221995861852", - "Likelihood: 0.1979243711141986", - "Likelihood: 0.10118425436566512", - "Likelihood: 0.19759668526382407", - "Likelihood: 0.29502874463026274", - "Likelihood: 0.20985562797632334", - "Likelihood: 0.22252202067974053", - "Likelihood: 0.20697812589219106", - "Likelihood: 0.25637551642370154", - "Likelihood: 0.1591133899981291", - "Likelihood: 0.28411395447897114", - "Likelihood: 0.1328310577453367", - "Likelihood: 0.2821939602697079", - "Likelihood: 0.282615442405364", - "Likelihood: 0.1418873404430667", - "Likelihood: 0.2700559623379181", - "Likelihood: 0.23055310905272852", - "Likelihood: 0.2606099331187619", - "Likelihood: 0.30103853902562866", - "Likelihood: 0.1785623275343553", - "Likelihood: 0.06507341572373264", - "Likelihood: 0.20164668210990505", - "Likelihood: 0.13418989170895448", - "Likelihood: 0.25907380178986533", - "Likelihood: 0.18439588003119045", - "Likelihood: 0.18265637270605992", - "Likelihood: 0.154906220811531", - "Likelihood: 0.22632052457566867", - "Likelihood: 0.0455506630798691", - "Likelihood: 0.15963099540013836", - "Likelihood: 0.19200494249788022", - "Likelihood: 0.13044880671092055", - "Likelihood: 0.22117429571054184", - "Likelihood: 0.21456234159610277", - "Likelihood: 0.20745337814180423", - "Likelihood: 0.10385092307387461", - "Likelihood: 0.18091141527664809", - "Likelihood: 0.21762158817219776", - "Likelihood: 0.055509229721254154", - "Likelihood: 0.2915204631827151", - "Likelihood: 0.059888588864284296", - "Likelihood: 0.17659909347841604", - "Likelihood: 0.273362094314917", - "Likelihood: 0.24794715591560818", - "Likelihood: 0.29734003986252316", - "Likelihood: 0.1717661823253763", - "Likelihood: 0.24730832550016113", - "Likelihood: 0.25444497694945645", - "Likelihood: 0.13563557563164505", - "Likelihood: 0.11151950197260675", - "Likelihood: 0.2778292657406465", - "Likelihood: 0.2812211035709156", - "Likelihood: 0.12018232832973687", - "Likelihood: 0.0563570057544671", - "Likelihood: 0.2381779714170544", - "Likelihood: 0.13986062000927832", - "Likelihood: 0.1479526666184142", - "Likelihood: 0.24627067779368503", - "Likelihood: 0.12656283146321787", - "Likelihood: 0.08501668333041651", - "Likelihood: 0.14722417694805293", - "Likelihood: 0.2971110390189072", - "Likelihood: 0.0631257052095643", - "Likelihood: 0.29431552615401996", - "Likelihood: 0.14645906445638082", - "Likelihood: 0.2861266153368352", - "Likelihood: 0.04609854885530248", - "Likelihood: 0.23250440924192436", - "Likelihood: 0.232364091389313", - "Likelihood: 0.1843605918533857", - "Likelihood: 0.20276865934116683", - "Likelihood: 0.2794127819774682", - "Likelihood: 0.19127039430471135", - "Likelihood: 0.28452415652611385", - "Likelihood: 0.023596219862323933", - "Likelihood: 0.2775271308596862", - "Likelihood: 0.14921637109696018", - "Likelihood: 0.1542218318332079", - "Likelihood: 0.1989611110515247", - "Likelihood: 0.252548692484411", - "Likelihood: 0.13069489995596847", - "Likelihood: 0.2199940105954661", - "Likelihood: 0.2633284389192036", - "Likelihood: 0.2476724225807944", - "Likelihood: 0.24918078325758383", - "Likelihood: 0.16218962525748168", - "Likelihood: 0.025758172492450465", - "Likelihood: 0.2091891826231027", - "Likelihood: 0.15031403958552644", - "Likelihood: 0.20479750626493318", - "Likelihood: 0.1715813266887942", - "Likelihood: 0.24791146469118602", - "Likelihood: 0.21210684091208637", - "Likelihood: 0.29470798232146506", - "Likelihood: 0.1282122677700438", - "Likelihood: 0.2374978795835429", - "Likelihood: 0.29284614805530174", - "Likelihood: 0.22964352359384996", - "Likelihood: 0.27449187726496066", - "Likelihood: 0.1639097843790071", - "Likelihood: 0.2511480610000017", - "Likelihood: 0.22481194627713705", - "Likelihood: 0.1667603261703727", - "Likelihood: 0.07318932029888235", - "Likelihood: 0.29781764631589086", - "Likelihood: 0.05369321023973304", - "Likelihood: 0.17590929421313448", - "Likelihood: 0.25509030192055054", - "Likelihood: 0.24539084117893686", - "Likelihood: 0.06584698561389246", - "Likelihood: 0.13197143024443064", - "Likelihood: 0.10558199970836467", - "Likelihood: 0.23899327684726196", - "Likelihood: 0.2352576178746611", - "Likelihood: 0.2296101833583848", - "Likelihood: 0.17103140156231772", - "Likelihood: 0.1339105132878214", - "Likelihood: 0.10811459598674457", - "Likelihood: 0.29092926672277913", - "Likelihood: 0.26325556237012554", - "Likelihood: 0.2816606172865995", - "Likelihood: 0.2705793155007007", - "Likelihood: 0.2880764525969483", - "Likelihood: 0.24050527776990946", - "Likelihood: 0.16233943638295975", - "Likelihood: 0.23212910048423835", - "Likelihood: 0.24090486591755844", - "Likelihood: 0.28668215416686665", - "Likelihood: 0.26491401579873164", - "Likelihood: 0.2431573582946893", - "Likelihood: 0.26250986704892", - "Likelihood: 0.2582271005282511", - "Likelihood: 0.13878817712136887", - "Likelihood: 0.2182458048398721", - "Likelihood: 0.132874794634922", - "Likelihood: 0.25914232024903533", - "Likelihood: 0.1484869804260936", - "Likelihood: 0.2603180418951686", - "Likelihood: 0.06855331058162868", - "Likelihood: 0.16074255955329336", - "Likelihood: 0.2751507516468864", - "Likelihood: 0.23920510598593894", - "Likelihood: 0.1516342652523346", - "Likelihood: 0.1777877619577412", - "Likelihood: 0.25260389636773534", - "Likelihood: 0.12667209810608107", - "Likelihood: 0.2596965517177458", - "Likelihood: 0.2892794229347164", - "Likelihood: 0.2815829566304334", - "Likelihood: 0.1698337624049068", - "Likelihood: 0.20136098331182378", - "Likelihood: 0.18272976599639332", - "Likelihood: 0.14298554849897183", - "Likelihood: 0.23463861449899898", - "Likelihood: 0.2797126745947251", - "Likelihood: 0.0778069076231206", - "Likelihood: 0.20030562010289835", - "Likelihood: 0.2229613366680784", - "Likelihood: 0.1901927364305741", - "Likelihood: 0.2191582006636226", - "Likelihood: 0.13906313198720194", - "Likelihood: 0.23212312296787854", - "Likelihood: 0.10661142365115153", - "Likelihood: 0.07027261581820313", - "Likelihood: 0.1034511524656586", - "Likelihood: 0.23361019821305898", - "Likelihood: 0.15096732713365552", - "Likelihood: 0.1711586752938495", - "Likelihood: 0.22507603642325275", - "Likelihood: 0.23480828354711053", - "Likelihood: 0.15107905845055888", - "Likelihood: 0.25155666227211665", - "Likelihood: 0.2228843197088964", - "Likelihood: 0.19524712216961643", - "Likelihood: 0.24395942941891732", - "Likelihood: 0.27817169952609055", - "Likelihood: 0.11929906261604471", - "Likelihood: 0.08381607486497886", - "Likelihood: 0.18686387308397204", - "Likelihood: 0.20999527443255434", - "Likelihood: 0.2570698567367582", - "Likelihood: 0.058901103615292535", - "Likelihood: 0.2769591414548384", - "Likelihood: 0.27598310469673965", - "Likelihood: 0.2821505565843805", - "Likelihood: 0.28988528255097973", - "Likelihood: 0.05150051976118358", - "Likelihood: 0.15917999577585787", - "Likelihood: 0.25845358187973827", - "Likelihood: 0.27567299678000473", - "Likelihood: 0.22712024034889114", - "Likelihood: 0.276056003426197", - "Likelihood: 0.08640450269500653", - "Likelihood: 0.02646427282611677", - "Likelihood: 0.30289304276107915", - "Likelihood: 0.14952170278655394", - "Likelihood: 0.16084149250573554", - "Likelihood: 0.2622273058587041", - "Likelihood: 0.09832097707040319", - "Likelihood: 0.10535687166608367", - "Likelihood: 0.12691995350217322", - "Likelihood: 0.2035466847757874", - "Likelihood: 0.18202658696236074", - "Likelihood: 0.07446019805892079", - "Likelihood: 0.2656465484535515", - "Likelihood: 0.2711285055626988", - "Likelihood: 0.22482925553118643", - "Likelihood: 0.25398286523008856", - "Likelihood: 0.16646727790097074", - "Likelihood: 0.24563383616873244", - "Likelihood: 0.2261751857684485", - "Likelihood: 0.26640574273520945", - "Likelihood: 0.2631150815241893", - "Likelihood: 0.2325710311881632", - "Likelihood: 0.1681044757631614", - "Likelihood: 0.11711730124727035", - "Likelihood: 0.07966142075152963", - "Likelihood: 0.2191049571217024", - "Likelihood: 0.2902400178693884", - "Likelihood: 0.10644830712406292", - "Likelihood: 0.2734186652020395", - "Likelihood: 0.05197372660595629", - "Likelihood: 0.2948437546327784", - "Likelihood: 0.0950447683957894", - "Likelihood: 0.1819747189040945", - "Likelihood: 0.29067807629121567", - "Likelihood: 0.2738071502300164", - "Likelihood: 0.1027402586162576", - "Likelihood: 0.22979926786649296", - "Likelihood: 0.2581198399241554", - "Likelihood: 0.1935230404257859", - "Likelihood: 0.26171016927876856", - "Likelihood: 0.2857504996355755", - "Likelihood: 0.1491065075023348", - "Likelihood: 0.13227002287531273", - "Likelihood: 0.1406349485702548", - "Likelihood: 0.18161239415688687", - "Likelihood: 0.2739526363397502", - "Likelihood: 0.28852227016697357", - "Likelihood: 0.15061969784929008", - "Likelihood: 0.08869769612624691", - "Likelihood: 0.08920488338294533", - "Likelihood: 0.21496296212623742", - "Likelihood: 0.1589270944718574", - "Likelihood: 0.09429671067632348", - "Likelihood: 0.12610326437934152", - "Likelihood: 0.18852826820984375", - "Likelihood: 0.13896682794340937", - "Likelihood: 0.13559429584529026", - "Likelihood: 0.17840671626330562", - "Likelihood: 0.2118762248199594", - "Likelihood: 0.15176296059884758", - "Likelihood: 0.17496609910952976", - "Likelihood: 0.27723091089520785", - "Likelihood: 0.22873123430149936", - "Likelihood: 0.23247948518827175", - "Likelihood: 0.2954303951287984", - "Likelihood: 0.10067455655193522", - "Likelihood: 0.10484096443118701", - "Likelihood: 0.17388538638057435", - "Likelihood: 0.2164255964570831", - "Likelihood: 0.11220858341425656", - "Likelihood: 0.22913393407062316", - "Likelihood: 0.08310746487784026", - "Likelihood: 0.29005203751767944", - "Likelihood: 0.19648120331757826", - "Likelihood: 0.2750156403137095", - "Likelihood: 0.13428214213617715", - "Likelihood: 0.25915318315472013", - "Likelihood: 0.29514821127774976", - "Likelihood: 0.2156651370866097", - "Likelihood: 0.21571405610106476", - "Likelihood: 0.09541439104492301", - "Likelihood: 0.14324857911909925", - "Likelihood: 0.17862493999369725", - "Likelihood: 0.24441387018288055", - "Likelihood: 0.13300505548491182", - "Likelihood: 0.28652791410040623", - "Likelihood: 0.2901024908284707", - "Likelihood: 0.26513000154928634", - "Likelihood: 0.27032952967988066", - "Likelihood: 0.13607242395644384", - "Likelihood: 0.27328699895226916", - "Likelihood: 0.24476462985024153", - "Likelihood: 0.2221337734487119", - "Likelihood: 0.19988996539019074", - "Likelihood: 0.1375661815416032", - "Likelihood: 0.2047169478798668", - "Likelihood: 0.16593681461401125", - "Likelihood: 0.26036623592703373", - "Likelihood: 0.03391959733533532", - "Likelihood: 0.15368185608735727", - "Likelihood: 0.20555870907446236", - "Likelihood: 0.2562585189852513", - "Likelihood: 0.26358082353943524", - "Likelihood: 0.3053053033175505", - "Likelihood: 0.24020758796209857", - "Likelihood: 0.119669491821398", - "Likelihood: 0.0939473443124866", - "Likelihood: 0.22632025528861616", - "Likelihood: 0.23864922916008616", - "Likelihood: 0.10675002407667013", - "Likelihood: 0.26757712390709204", - "Likelihood: 0.2888246077255077" + "Likelihood: 0.037390354701688756", + "Likelihood: 0.1366727257673293", + "Likelihood: 0.01896497711355174", + "Likelihood: 0.1781084082181187", + "Likelihood: 0.16583431190340636", + "Likelihood: 0.16933992352720612", + "Likelihood: 0.02721398308320946", + "Likelihood: 0.05444590031344", + "Likelihood: 0.1602076965090202", + "Likelihood: 0.028660090870436354", + "Likelihood: 0.1431557751074098", + "Likelihood: 0.17781852725840952", + "Likelihood: 0.03915164588910641", + "Likelihood: 0.039346890648079516", + "Likelihood: 0.07420562653595361", + "Likelihood: 0.2690757579602086", + "Likelihood: 0.22420389550455166", + "Likelihood: 0.14265936138123578", + "Likelihood: 0.1012185970580372", + "Likelihood: 0.08046826193309256", + "Likelihood: 0.013757350834253623", + "Likelihood: 0.26583073666915924", + "Likelihood: 0.14896841524152138", + "Likelihood: 0.025169403311690135", + "Likelihood: 0.29616796169523407", + "Likelihood: 0.1161562210830151", + "Likelihood: 0.07577931807491205", + "Likelihood: 0.1186321934808284", + "Likelihood: 0.13097497941091385", + "Likelihood: 0.04538348401387904", + "Likelihood: 0.12105646828489361", + "Likelihood: 0.15825600023159617", + "Likelihood: 0.16806005874813063", + "Likelihood: 0.11434010703653359", + "Likelihood: 0.07562044835890457", + "Likelihood: 0.1292573679517499", + "Likelihood: 0.0720257151671472", + "Likelihood: 0.06685533169077722", + "Likelihood: 0.18107277376513067", + "Likelihood: 0.08689201478802383", + "Likelihood: 0.22711803350352475", + "Likelihood: 0.21400770814789916", + "Likelihood: 0.09394683587270067", + "Likelihood: 0.24699644943865698", + "Likelihood: 0.05217024078456527", + "Likelihood: 0.008168181581510694", + "Likelihood: 0.12458107120475687", + "Likelihood: 0.040131074724923166", + "Likelihood: 0.09215418951150434", + "Likelihood: 0.037076436397982956", + "Likelihood: 0.23986591318152484", + "Likelihood: 0.24834936397403087", + "Likelihood: 0.07112240356146864", + "Likelihood: 0.14756377597295253", + "Likelihood: 0.13906460325256811", + "Likelihood: 0.28183437612563766", + "Likelihood: 0.06445770669491747", + "Likelihood: 0.07929029014512225", + "Likelihood: 0.18691920750910693", + "Likelihood: 0.29047566635698585", + "Likelihood: 0.06977353425954941", + "Likelihood: 0.16985473722980285", + "Likelihood: 0.11927894459182405", + "Likelihood: 0.27554083471493135", + "Likelihood: 0.2638704219191374", + "Likelihood: 0.037698611273599074", + "Likelihood: 0.08765672469307195", + "Likelihood: 0.2551184026579383", + "Likelihood: 0.04479248715799298", + "Likelihood: 0.18833584946963758", + "Likelihood: 0.05365328777366469", + "Likelihood: 0.19010394082986073", + "Likelihood: 0.17057472327614367", + "Likelihood: 0.19413141789467478", + "Likelihood: 0.012314385430265253", + "Likelihood: 0.08976455885413014", + "Likelihood: 0.25802764946762025", + "Likelihood: 0.05217105920451346", + "Likelihood: 0.10956852203854534", + "Likelihood: 0.1829343883492156", + "Likelihood: 0.15670689339315882", + "Likelihood: 0.22449430898170175", + "Likelihood: 0.05516095102663021", + "Likelihood: 0.06761287286416509", + "Likelihood: 0.09657006525640585", + "Likelihood: 0.08201488338606042", + "Likelihood: 0.21219708397847553", + "Likelihood: 0.17182451111762792", + "Likelihood: 0.22730980335481715", + "Likelihood: 0.05179461275531549", + "Likelihood: 0.06417155122782495", + "Likelihood: 0.18632749593189948", + "Likelihood: 0.14308697032718945", + "Likelihood: 0.24563238948541416", + "Likelihood: 0.30632640058443444", + "Likelihood: 0.27809744271368386", + "Likelihood: 0.09128200782344359", + "Likelihood: 0.16947201717043245", + "Likelihood: 0.14390543981104117", + "Likelihood: 0.2812818281430726", + "Likelihood: 0.2269864984466092", + "Likelihood: 0.1576547927858872", + "Likelihood: 0.1521525777582648", + "Likelihood: 0.017345185505449626", + "Likelihood: 0.014544298545731355", + "Likelihood: 0.10100091554766766", + "Likelihood: 0.12494558936862724", + "Likelihood: 0.270705463474896", + "Likelihood: 0.3114283085351552", + "Likelihood: 0.14342124107828644", + "Likelihood: 0.10867509021543283", + "Likelihood: 0.2505549616315266", + "Likelihood: 0.11979220445408388", + "Likelihood: 0.1183436601614714", + "Likelihood: 0.10597843646702096", + "Likelihood: 0.28306519741260566", + "Likelihood: 0.2025726666874207", + "Likelihood: 0.26778050365271927", + "Likelihood: 0.284737364413629", + "Likelihood: 0.1848205640835622", + "Likelihood: 0.28209034579135284", + "Likelihood: 0.24076095811533585", + "Likelihood: 0.07404124130587243", + "Likelihood: 0.06859982320067719", + "Likelihood: 0.05476439818438498", + "Likelihood: 0.061984750961177296", + "Likelihood: 0.09249907472740998", + "Likelihood: 0.1582724038459138", + "Likelihood: 0.2802185940450926", + "Likelihood: 0.2310934193419602", + "Likelihood: 0.0169486819283101", + "Likelihood: 0.18889388320254208", + "Likelihood: 0.04233677574523349", + "Likelihood: 0.16291137991901686", + "Likelihood: 0.08991673199695902", + "Likelihood: 0.22851017728378395", + "Likelihood: 0.03707762426888005", + "Likelihood: 0.2477034868157516", + "Likelihood: 0.31012170968338243", + "Likelihood: 0.057547651381646386", + "Likelihood: 0.06910938789937934", + "Likelihood: 0.08943576062955265", + "Likelihood: 0.10885126797690561", + "Likelihood: 0.25989295132635337", + "Likelihood: 0.06175157078637069", + "Likelihood: 0.14466367160807347", + "Likelihood: 0.012001254143065963", + "Likelihood: 0.13697017256153382", + "Likelihood: 0.1515447564164071", + "Likelihood: 0.10354253440595829", + "Likelihood: 0.13263016217843196", + "Likelihood: 0.08339730322331182", + "Likelihood: 0.092876941480302", + "Likelihood: 0.0667980644784893", + "Likelihood: 0.14922034940866544", + "Likelihood: 0.12316702833971015", + "Likelihood: 0.18739293749275732", + "Likelihood: 0.14592582521223602", + "Likelihood: 0.050402774792625026", + "Likelihood: 0.2456764208073022", + "Likelihood: 0.1464079400011995", + "Likelihood: 0.17453892347876118", + "Likelihood: 0.12115653843590997", + "Likelihood: 0.2944426349386998", + "Likelihood: 0.16992961015625008", + "Likelihood: 0.06456888508329289", + "Likelihood: 0.0889149448277325", + "Likelihood: 0.06513967495625926", + "Likelihood: 0.15733379676448592", + "Likelihood: 0.15727456303035708", + "Likelihood: 0.30255454591089376", + "Likelihood: 0.022119538076550805", + "Likelihood: 0.21024649906352574", + "Likelihood: 0.15702855769858656", + "Likelihood: 0.2531143263378646", + "Likelihood: 0.04639587742158651", + "Likelihood: 0.2868116519788101", + "Likelihood: 0.28326204623095724", + "Likelihood: 0.12050972760432808", + "Likelihood: 0.26998529634942914", + "Likelihood: 0.07311635191789931", + "Likelihood: 0.1389173608322929", + "Likelihood: 0.07576590116292836", + "Likelihood: 0.2870659743909647", + "Likelihood: 0.26439731398829286", + "Likelihood: 0.28875167354843684", + "Likelihood: 0.3119664191263936", + "Likelihood: 0.04119013897407925", + "Likelihood: 0.08774845705901865", + "Likelihood: 0.13905230299111973", + "Likelihood: 0.11585984592554271", + "Likelihood: 0.24307520088506723", + "Likelihood: 0.09362553170901208", + "Likelihood: 0.25813285477762604", + "Likelihood: 0.05542728024470627", + "Likelihood: 0.1800892950396037", + "Likelihood: 0.15718593904707162", + "Likelihood: 0.14186427606694121", + "Likelihood: 0.06407438043952352", + "Likelihood: 0.2850908262332049", + "Likelihood: 0.057155910792663064", + "Likelihood: 0.22364675306050086", + "Likelihood: 0.25620892266442946", + "Likelihood: 0.06308374281672613", + "Likelihood: 0.12245583695358699", + "Likelihood: 0.2880770221527392", + "Likelihood: 0.2539065582793193", + "Likelihood: 0.23303860678855118", + "Likelihood: 0.1860188233589474", + "Likelihood: 0.15943830545543375", + "Likelihood: 0.005612765836499478", + "Likelihood: 0.09179254059500014", + "Likelihood: 0.01989433534179809", + "Likelihood: 0.21311567805774448", + "Likelihood: 0.055084239263074285", + "Likelihood: 0.06010704432208926", + "Likelihood: 0.02125308128211427", + "Likelihood: 0.19793964010282528", + "Likelihood: 0.22669921297966836", + "Likelihood: 0.16764449049056923", + "Likelihood: 0.28636423995182014", + "Likelihood: 0.16406179410012134", + "Likelihood: 0.014417644866165669", + "Likelihood: 0.29602470943556825", + "Likelihood: 0.25736284318087577", + "Likelihood: 0.2865546940614866", + "Likelihood: 0.07241299840703161", + "Likelihood: 0.18730160195824005", + "Likelihood: 0.0983520098814089", + "Likelihood: 0.27978405010478263", + "Likelihood: 0.2363057870928036", + "Likelihood: 0.028860436684587484", + "Likelihood: 0.10893165769270723", + "Likelihood: 0.12529520863588933", + "Likelihood: 0.14285574814434635", + "Likelihood: 0.17001103776622137", + "Likelihood: 0.22909293443476303", + "Likelihood: 0.16871481395459045", + "Likelihood: 0.2844961529074517", + "Likelihood: 0.14901140559947154", + "Likelihood: 0.23952427287553713", + "Likelihood: 0.10871315480648969", + "Likelihood: 0.0835895452745341", + "Likelihood: 0.1896080684997517", + "Likelihood: 0.06289381063305763", + "Likelihood: 0.28928643231810863", + "Likelihood: 0.2775396024280474", + "Likelihood: 0.06164220706332981", + "Likelihood: 0.24104581553633497", + "Likelihood: 0.040372109076121314", + "Likelihood: 0.02338741139462028", + "Likelihood: 0.02765464673872183", + "Likelihood: 0.20067557682549572", + "Likelihood: 0.07203073969847852", + "Likelihood: 0.2722556655896279", + "Likelihood: 0.2386291200689921", + "Likelihood: 0.0869354514994288", + "Likelihood: 0.1839993920185191", + "Likelihood: 0.09629810136338722", + "Likelihood: 0.19172187335675786", + "Likelihood: 0.2297839260207359", + "Likelihood: 0.1625634979567364", + "Likelihood: 0.18363401437436785", + "Likelihood: 0.19371720281284166", + "Likelihood: 0.0624395655073948", + "Likelihood: 0.056753070491058544", + "Likelihood: 0.1484064221991734", + "Likelihood: 0.3009468043738178", + "Likelihood: 0.05472529333407213", + "Likelihood: 0.010026456958008705", + "Likelihood: 0.0644629073869422", + "Likelihood: 0.28046106060444465", + "Likelihood: 0.018937056813718593", + "Likelihood: 0.15544510176434365", + "Likelihood: 0.07217019476015314", + "Likelihood: 0.13539142919109118", + "Likelihood: 0.21379340440899824", + "Likelihood: 0.1702622426575686", + "Likelihood: 0.07147903910919663", + "Likelihood: 0.12957217886184944", + "Likelihood: 0.1666247953919825", + "Likelihood: 0.05655184883643386", + "Likelihood: 0.1900726483952778", + "Likelihood: 0.12080857573162945", + "Likelihood: 0.09663097500080756", + "Likelihood: 0.1303349496256968", + "Likelihood: 0.16424053652652132", + "Likelihood: 0.157680780995639", + "Likelihood: 0.07515297882560547", + "Likelihood: 0.13858133406497183", + "Likelihood: 0.26091977465432203", + "Likelihood: 0.05801573806927941", + "Likelihood: 0.31061437304955086", + "Likelihood: 0.25874175785606374", + "Likelihood: 0.11362959876821907", + "Likelihood: 0.09281011285718187", + "Likelihood: 0.3043812325840951", + "Likelihood: 0.044370753140443", + "Likelihood: 0.08476744239667537", + "Likelihood: 0.2284746189179548", + "Likelihood: 0.07039873649563973", + "Likelihood: 0.16121212205431862", + "Likelihood: 0.046546690121115016", + "Likelihood: 0.2603353252277492", + "Likelihood: 0.19952494711557345", + "Likelihood: 0.08233339581767601", + "Likelihood: 0.0666618708980124", + "Likelihood: 0.04313051508780929", + "Likelihood: 0.18315322973049025", + "Likelihood: 0.038290413207342236", + "Likelihood: 0.048529579826456816", + "Likelihood: 0.25748117428559275", + "Likelihood: 0.18432789731316926", + "Likelihood: 0.1911195336218904", + "Likelihood: 0.10312961438658656", + "Likelihood: 0.10419684836845533", + "Likelihood: 0.0006878943549733938", + "Likelihood: 0.12322319750640644", + "Likelihood: 0.2787145269695932", + "Likelihood: 0.14229223541554395", + "Likelihood: 0.17142058960668216", + "Likelihood: 0.28296360109941887", + "Likelihood: 0.16028406803518444", + "Likelihood: 0.2016589093548264", + "Likelihood: 0.2185691404342069", + "Likelihood: 0.21084122903730795", + "Likelihood: 0.1739201014596444", + "Likelihood: 0.30147535753121324", + "Likelihood: 0.2361605186520935", + "Likelihood: 0.23746404701726562", + "Likelihood: 0.08041384029913029", + "Likelihood: 0.3024720605394624", + "Likelihood: 0.25974926463819875", + "Likelihood: 0.13385231688214982", + "Likelihood: 0.041807958144447044", + "Likelihood: 0.08489833429540121", + "Likelihood: 0.013253252947006565", + "Likelihood: 0.16875113266839784", + "Likelihood: 0.20551383153739847", + "Likelihood: 0.3210968478180208", + "Likelihood: 0.12248068787012983", + "Likelihood: 0.1315956241597149", + "Likelihood: 0.2022432087521108", + "Likelihood: 0.046903508483207235", + "Likelihood: 0.040690274943260614", + "Likelihood: 0.11249258812354665", + "Likelihood: 0.1613150501833823", + "Likelihood: 0.07910211348402024", + "Likelihood: 0.21514768591471484", + "Likelihood: 0.15063500062137872", + "Likelihood: 0.011436482234230261", + "Likelihood: 0.1476130941227302", + "Likelihood: 0.23208529162531108", + "Likelihood: 0.1553150548036827", + "Likelihood: 0.0745752152857773", + "Likelihood: 0.1966642395982448", + "Likelihood: 0.1840122141381398", + "Likelihood: 0.04533920537143628", + "Likelihood: 0.07389786273648326", + "Likelihood: 0.18855889835891676", + "Likelihood: 0.19104706530370946", + "Likelihood: 0.30498190504825706", + "Likelihood: 0.09728517636791645", + "Likelihood: 0.15119024987701946", + "Likelihood: 0.03309797110313541", + "Likelihood: 0.08885910256450315", + "Likelihood: 0.06869225504132587", + "Likelihood: 0.21435441791967105", + "Likelihood: 0.012120884335118482", + "Likelihood: 0.20474913318999347", + "Likelihood: 0.20787077850251853", + "Likelihood: 0.04233837339243749", + "Likelihood: 0.2759725958184817", + "Likelihood: 0.004456926909421235", + "Likelihood: 0.19426428085785785", + "Likelihood: 0.04474721682800546", + "Likelihood: 0.3110527015779766", + "Likelihood: 0.27274458005402247", + "Likelihood: 0.23216848617416602", + "Likelihood: 0.21520558494996245", + "Likelihood: 0.26011048186606023", + "Likelihood: 0.26574370051204005", + "Likelihood: 0.028700361129410604", + "Likelihood: 0.08024350039708135", + "Likelihood: 0.2694621611520205", + "Likelihood: 0.14105813674628528", + "Likelihood: 0.04469650140464048", + "Likelihood: 0.21764987725764517", + "Likelihood: 0.029436226254445592", + "Likelihood: 0.120830017987284", + "Likelihood: 0.07931813901190346", + "Likelihood: 0.07979118985111497", + "Likelihood: 0.21166153870076584", + "Likelihood: 0.023075187168515615", + "Likelihood: 0.10781665048627216", + "Likelihood: 0.22225544936115135", + "Likelihood: 0.12136633096687977", + "Likelihood: 0.17734799839932436", + "Likelihood: 0.1463504281804764", + "Likelihood: 0.2618969140332372", + "Likelihood: 0.29442152649365305", + "Likelihood: 0.03875938207188401", + "Likelihood: 0.1676285869951907", + "Likelihood: 0.09123905895486757", + "Likelihood: 0.31853783156471743", + "Likelihood: 0.18198440871574612", + "Likelihood: 0.2744447396481863", + "Likelihood: 0.2763082265537312", + "Likelihood: 0.12127467760006821", + "Likelihood: 0.21405774743553818", + "Likelihood: 0.26715231853199856", + "Likelihood: 0.06473995107214833", + "Likelihood: 0.09181133914753972", + "Likelihood: 0.0192827321450764", + "Likelihood: 0.2647432864726643", + "Likelihood: 0.07539691689110647", + "Likelihood: 0.2511019957716314", + "Likelihood: 0.26420356427854524", + "Likelihood: 0.164559178331794", + "Likelihood: 0.25936198784519343", + "Likelihood: 0.006008251069719346", + "Likelihood: 0.09269213139446777", + "Likelihood: 0.19363400976746423", + "Likelihood: 0.08638592714661604", + "Likelihood: 0.06074287201631729", + "Likelihood: 0.13462113103004572", + "Likelihood: 0.08673910854234358", + "Likelihood: 0.009046009485896078", + "Likelihood: 0.21172368958668", + "Likelihood: 0.057168652829430976", + "Likelihood: 0.21962709032565159", + "Likelihood: 0.1124677754150115", + "Likelihood: 0.08806798087217999", + "Likelihood: 0.2418120996898827", + "Likelihood: 0.1715148966319566", + "Likelihood: 0.25347948992695046", + "Likelihood: 0.11766007194844899", + "Likelihood: 0.02478503668489332", + "Likelihood: 0.29598321675642136", + "Likelihood: 0.009777848409478946", + "Likelihood: 0.23262637853128162", + "Likelihood: 0.3154474305945269", + "Likelihood: 0.2937866108722873", + "Likelihood: 0.040335761348141264", + "Likelihood: 0.0709138453449375", + "Likelihood: 0.16320488889905005", + "Likelihood: 0.1681089063368948", + "Likelihood: 0.014710112394317153", + "Likelihood: 0.08124140152056424", + "Likelihood: 0.17570488670733933", + "Likelihood: 0.2852231701145934", + "Likelihood: 0.2520457485344845", + "Likelihood: 0.05506251815314024", + "Likelihood: 0.2566515252178652", + "Likelihood: 0.23849399931058116", + "Likelihood: 0.019914527296732147", + "Likelihood: 0.089539080460643", + "Likelihood: 0.0558520376985593", + "Likelihood: 0.030893194148677375", + "Likelihood: 0.12924650971932397", + "Likelihood: 0.2766188911657455", + "Likelihood: 0.22110134259749434", + "Likelihood: 0.302340310722322", + "Likelihood: 0.051460409931508265", + "Likelihood: 0.23491416158881376", + "Likelihood: 0.034643266708189915", + "Likelihood: 0.28961036156722625", + "Likelihood: 0.010734157141604327", + "Likelihood: 0.16554292842982024", + "Likelihood: 0.08098179581329118", + "Likelihood: 0.29083340530123875", + "Likelihood: 0.15024859303253238", + "Likelihood: 0.2679770199096094", + "Likelihood: 0.04754760685291781", + "Likelihood: 0.01064231643640605", + "Likelihood: 0.10855132648097973", + "Likelihood: 0.2533969570348023", + "Likelihood: 0.07015424528401548", + "Likelihood: 0.09535422381671287", + "Likelihood: 0.1855028467264692", + "Likelihood: 0.029817915975498967", + "Likelihood: 0.09368131935008177", + "Likelihood: 0.024384268506193713", + "Likelihood: 0.04736271612961317", + "Likelihood: 0.019603246402633508", + "Likelihood: 0.19811870503501885", + "Likelihood: 0.158271003756756", + "Likelihood: 0.12478639830441199", + "Likelihood: 0.2704305090941256", + "Likelihood: 0.11701252991786915", + "Likelihood: 0.25686102618225276", + "Likelihood: 0.0023586436905214322", + "Likelihood: 0.26448799106442866", + "Likelihood: 0.016422722459717938", + "Likelihood: 0.005609572356114014", + "Likelihood: 0.20024024176367375", + "Likelihood: 0.11972706099973023", + "Likelihood: 0.09106126485347386", + "Likelihood: 0.30782351461856594", + "Likelihood: 0.2868889734975145", + "Likelihood: 0.1269794225807527", + "Likelihood: 0.15013655510807894", + "Likelihood: 0.058656807757214297", + "Likelihood: 0.14032338269660424", + "Likelihood: 0.07928016756189524", + "Likelihood: 0.21225978011992405", + "Likelihood: 0.015484619539704378", + "Likelihood: 0.1899487436889696", + "Likelihood: 0.2166419774172967", + "Likelihood: 0.02262437549578951", + "Likelihood: 0.2340424501723673", + "Likelihood: 0.21136316163296368", + "Likelihood: 0.3129493083802818", + "Likelihood: 0.09553566562082266", + "Likelihood: 0.026949454135069967", + "Likelihood: 0.12030728113784753", + "Likelihood: 0.20388895714822544", + "Likelihood: 0.2009772071396901", + "Likelihood: 0.08010477694465919", + "Likelihood: 0.0035200372135009584", + "Likelihood: 0.20069179850595123", + "Likelihood: 0.14648921525202055", + "Likelihood: 0.18137089335779089", + "Likelihood: 0.043505817800930845", + "Likelihood: 0.26162206966635493", + "Likelihood: 0.14537681724240445", + "Likelihood: 0.13156605075173358", + "Likelihood: 0.2643622304968965", + "Likelihood: 0.013033657203694277", + "Likelihood: 0.07908781720564384", + "Likelihood: 0.19366916164598175", + "Likelihood: 0.03684012722714205", + "Likelihood: 0.06998980710526537", + "Likelihood: 0.10429634591967274", + "Likelihood: 0.2354044589857911", + "Likelihood: 0.30268837378421404", + "Likelihood: 0.09374320595923501", + "Likelihood: 0.17140679460120242", + "Likelihood: 0.04338670932309578", + "Likelihood: 0.13634656661281214", + "Likelihood: 0.23600736107491993", + "Likelihood: 0.013105374842983476", + "Likelihood: 0.24021188739611585", + "Likelihood: 0.10651700550941787", + "Likelihood: 0.1909502201831947", + "Likelihood: 0.15670781168429831", + "Likelihood: 0.13962122979951913", + "Likelihood: 0.30085441009880165", + "Likelihood: 0.005423067916975437", + "Likelihood: 0.27231761973768454", + "Likelihood: 0.0033823489159892574", + "Likelihood: 0.21137642206242935", + "Likelihood: 0.23931811828320368", + "Likelihood: 0.14741121481615402", + "Likelihood: 0.26870982924821224", + "Likelihood: 0.24845493229508528", + "Likelihood: 0.23476192062562748", + "Likelihood: 0.0411347002683363", + "Likelihood: 0.11236347702980654", + "Likelihood: 0.09744748096826493", + "Likelihood: 0.28486876688006324", + "Likelihood: 0.3185188875440203", + "Likelihood: 0.027663775250103925", + "Likelihood: 0.08056095844183303", + "Likelihood: 0.2083980329167701", + "Likelihood: 0.27747846285374794", + "Likelihood: 0.0031100333192370447", + "Likelihood: 0.22785963756046101", + "Likelihood: 0.10467761623704319", + "Likelihood: 0.25209534587629856", + "Likelihood: 0.2605766912833886", + "Likelihood: 0.1572995759985723", + "Likelihood: 0.21748253975764475", + "Likelihood: 0.09479836891263184", + "Likelihood: 0.22668035725810398", + "Likelihood: 0.15060141140223476", + "Likelihood: 0.105767916509277", + "Likelihood: 0.05629281077575179", + "Likelihood: 0.07470796504524699", + "Likelihood: 0.03456610436440543", + "Likelihood: 0.16513173859484093", + "Likelihood: 0.19503647605858754", + "Likelihood: 0.26051437806442557", + "Likelihood: 0.12679856102028497", + "Likelihood: 0.16949203856384631", + "Likelihood: 0.03394241160125979", + "Likelihood: 0.2676731671495032", + "Likelihood: 0.01739830172896302", + "Likelihood: 0.18320988089091905", + "Likelihood: 0.09764042538192724", + "Likelihood: 0.073512739531846", + "Likelihood: 0.1725737524133686", + "Likelihood: 0.012865675720960935", + "Likelihood: 0.07225052258372322", + "Likelihood: 0.06286681180325605", + "Likelihood: 0.08033670070526552", + "Likelihood: 0.13244158567583422", + "Likelihood: 0.012252387136824083", + "Likelihood: 0.10346032428566239", + "Likelihood: 0.043038880564915796", + "Likelihood: 0.1361233920771905", + "Likelihood: 0.22881023996425015", + "Likelihood: 0.26635725702355023", + "Likelihood: 0.019347530608091284", + "Likelihood: 0.26812454691751186", + "Likelihood: 0.13570245918156087", + "Likelihood: 0.1133396119701106", + "Likelihood: 0.11789619111881314", + "Likelihood: 0.06663679489376075", + "Likelihood: 0.08440278484694276", + "Likelihood: 0.09279429971658641", + "Likelihood: 0.16528907053762348", + "Likelihood: 0.3231263163534197", + "Likelihood: 0.21800434344081593", + "Likelihood: 0.22242703652461868", + "Likelihood: 0.13525083432630436", + "Likelihood: 0.03573839882491076", + "Likelihood: 0.08541329358762863", + "Likelihood: 0.056326741536113924", + "Likelihood: 0.027639223098813774", + "Likelihood: 0.26924736931485127", + "Likelihood: 0.15026053580192525", + "Likelihood: 0.23029486062051002", + "Likelihood: 0.29945462985722116", + "Likelihood: 0.07981539295001433", + "Likelihood: 0.287121812376841", + "Likelihood: 0.18202050502159275", + "Likelihood: 0.09524061867733055", + "Likelihood: 0.01914375639863388", + "Likelihood: 0.09407103001237933", + "Likelihood: 0.03234485373808768", + "Likelihood: 0.2668764815132888", + "Likelihood: 0.13747345648321443", + "Likelihood: 0.2779085313814282", + "Likelihood: 0.12710704530143482", + "Likelihood: 0.07906658552485675", + "Likelihood: 0.08844285860756744", + "Likelihood: 0.10749933394601573", + "Likelihood: 0.26689765374270547", + "Likelihood: 0.1675608185597545", + "Likelihood: 0.18722762074296723", + "Likelihood: 0.09198935171929194", + "Likelihood: 0.1838821797194548", + "Likelihood: 0.04679616027245693", + "Likelihood: 0.27680801388721993", + "Likelihood: 0.27253498398588555", + "Likelihood: 0.019939435241194445", + "Likelihood: 0.2723021064255231", + "Likelihood: 0.012986314945504784", + "Likelihood: 0.03423399993816921", + "Likelihood: 0.10507421615825663", + "Likelihood: 0.06135476100208841", + "Likelihood: 0.2967114691273634", + "Likelihood: 0.08406072822411448", + "Likelihood: 0.12617259405056966", + "Likelihood: 0.26419852850535996", + "Likelihood: 0.126856502887811", + "Likelihood: 0.2306887647348236", + "Likelihood: 0.17731705917555202", + "Likelihood: 0.06105191554295843", + "Likelihood: 0.2277201263285725", + "Likelihood: 0.0561585105693956", + "Likelihood: 0.13531575927036743", + "Likelihood: 0.12039016434287007", + "Likelihood: 0.06869435261078545", + "Likelihood: 0.006086044039618263", + "Likelihood: 0.06173571550202768", + "Likelihood: 0.09610810408484621", + "Likelihood: 0.14508766042973284", + "Likelihood: 0.17585339003258263", + "Likelihood: 0.2782861605489981", + "Likelihood: 0.17485411545094068", + "Likelihood: 0.04883045539592729", + "Likelihood: 0.08205601354734847", + "Likelihood: 0.25400873204979013", + "Likelihood: 0.2959046236440269", + "Likelihood: 0.08196495168675544", + "Likelihood: 0.26099319753419614", + "Likelihood: 0.08463977524779298", + "Likelihood: 0.013871130048640105", + "Likelihood: 0.1834092440400771", + "Likelihood: 0.12326338342377981", + "Likelihood: 0.1829769184645282", + "Likelihood: 0.020169800760894117", + "Likelihood: 0.15691830436594748", + "Likelihood: 0.07886715064024798", + "Likelihood: 0.07791058623029719", + "Likelihood: 0.12129863664718427", + "Likelihood: 0.2004581687863168", + "Likelihood: 0.24185176205079909", + "Likelihood: 0.09351776159353177", + "Likelihood: 0.3229768232659855", + "Likelihood: 0.17847667959737284", + "Likelihood: 0.08913978384852905", + "Likelihood: 0.038040105773807384", + "Likelihood: 0.17554403246475386", + "Likelihood: 0.11724895594216041", + "Likelihood: 0.27849378216611725", + "Likelihood: 0.2896415303263999", + "Likelihood: 0.0951583828337081", + "Likelihood: 0.04748764565268596", + "Likelihood: 0.12474206027163941", + "Likelihood: 0.06954385310404156", + "Likelihood: 0.2469482496152361", + "Likelihood: 0.26520010450703524", + "Likelihood: 0.24506107772687388", + "Likelihood: 0.25945926116209367", + "Likelihood: 0.004890414369085221", + "Likelihood: 0.032940157910355525", + "Likelihood: 0.2874382233206009", + "Likelihood: 0.18324318774150383", + "Likelihood: 0.016042625037773962", + "Likelihood: 0.08522521406045316", + "Likelihood: 0.2389796695871749", + "Likelihood: 0.1938644654305161", + "Likelihood: 0.16106900749549194", + "Likelihood: 0.18084468491487313", + "Likelihood: 0.2774268577484394", + "Likelihood: 0.13080647464167233", + "Likelihood: 0.17881350837701568", + "Likelihood: 0.32379410489038923", + "Likelihood: 0.007237835984648147", + "Likelihood: 0.034337520218445876", + "Likelihood: 0.04290847111918474", + "Likelihood: 0.017110315288516177", + "Likelihood: 0.07844883984898211", + "Likelihood: 0.24903993298747015", + "Likelihood: 0.2594396016059051", + "Likelihood: 0.14317215351216594", + "Likelihood: 0.07506261911543302", + "Likelihood: 0.06025049671527401", + "Likelihood: 0.2784286194684102", + "Likelihood: 0.1290449883087207", + "Likelihood: 0.08324548507718933", + "Likelihood: 0.1707445472316085", + "Likelihood: 0.1295538593625649", + "Likelihood: 0.17264801211067723", + "Likelihood: 0.133557766647656", + "Likelihood: 0.1415497974360007", + "Likelihood: 0.18281612908209155", + "Likelihood: 0.04325905071974633", + "Likelihood: 0.11448890618186688", + "Likelihood: 0.21248169356145985", + "Likelihood: 0.05355266064914738", + "Likelihood: 0.13030425108449722", + "Likelihood: 0.16500348924009037", + "Likelihood: 0.26385193274457214", + "Likelihood: 0.1739445518548748", + "Likelihood: 0.15527203475376214", + "Likelihood: 0.012154646021106831", + "Likelihood: 0.07750740964988406", + "Likelihood: 0.06316209321179309", + "Likelihood: 0.15072565883813674", + "Likelihood: 0.10411598530923609", + "Likelihood: 0.18046183336908056", + "Likelihood: 0.267603425060809", + "Likelihood: 0.06683535294285128", + "Likelihood: 0.019107885962069145", + "Likelihood: 0.01601776460257786", + "Likelihood: 0.1358544219910166", + "Likelihood: 0.04098232269481165", + "Likelihood: 0.020464348890613628", + "Likelihood: 0.25956823118884215", + "Likelihood: 0.16622165787512583", + "Likelihood: 0.30063793153589113", + "Likelihood: 0.2542268955010146", + "Likelihood: 0.3007890934030086", + "Likelihood: 0.28509168236947785", + "Likelihood: 0.1388197976363875", + "Likelihood: 0.19470406778880253", + "Likelihood: 0.12132472606262523", + "Likelihood: 0.2810737578761821", + "Likelihood: 0.1216225308343109", + "Likelihood: 0.027793264696759776", + "Likelihood: 0.2563160405230134", + "Likelihood: 0.2505947060677133", + "Likelihood: 0.10048441531045549", + "Likelihood: 0.049423313326498894", + "Likelihood: 0.0471516363860733", + "Likelihood: 0.05268865979734355", + "Likelihood: 0.2667214655164066", + "Likelihood: 0.20501946679508395", + "Likelihood: 0.09594417385671644", + "Likelihood: 0.11488599396482022", + "Likelihood: 0.13051806886487202", + "Likelihood: 0.16795343017691855", + "Likelihood: 0.004326883478969674", + "Likelihood: 0.16157046203946365", + "Likelihood: 0.060056805543070975", + "Likelihood: 0.07129861502966714", + "Likelihood: 0.14912494552650482", + "Likelihood: 0.07421921174179723", + "Likelihood: 0.10060223247289947", + "Likelihood: 0.034401856368640356", + "Likelihood: 0.07406427456211762", + "Likelihood: 0.17423470702502078", + "Likelihood: 0.010542277752143059", + "Likelihood: 0.0035375126511588825", + "Likelihood: 0.038762201663979576", + "Likelihood: 0.22699679721535912", + "Likelihood: 0.23263855020702556", + "Likelihood: 0.19036291527276383", + "Likelihood: 0.11588941973261233", + "Likelihood: 0.03622511552090539", + "Likelihood: 0.16120270059219766", + "Likelihood: 0.16098524808510414", + "Likelihood: 0.021625978037522656", + "Likelihood: 0.049848343454194144", + "Likelihood: 0.14685978864019691", + "Likelihood: 0.04950904556189122", + "Likelihood: 0.2919583814543811", + "Likelihood: 0.2043669709819495", + "Likelihood: 0.13358822401346437", + "Likelihood: 0.10026884225662416", + "Likelihood: 0.21359739658010457", + "Likelihood: 0.23800750056235867", + "Likelihood: 0.08272889416443441", + "Likelihood: 0.22280693929316528", + "Likelihood: 0.2004373877416652", + "Likelihood: 0.14544334606701378", + "Likelihood: 0.156528115921887", + "Likelihood: 0.1166957421861834", + "Likelihood: 0.2291258326602174", + "Likelihood: 0.007799713678795769", + "Likelihood: 0.3084638862527371", + "Likelihood: 0.08025049584428681", + "Likelihood: 0.14650913568813173", + "Likelihood: 0.060727140412687515", + "Likelihood: 0.041538466386100745", + "Likelihood: 0.10920759680140481", + "Likelihood: 0.22933789872141436", + "Likelihood: 0.0415273379527035", + "Likelihood: 0.01744885381630706", + "Likelihood: 0.19625860373643442", + "Likelihood: 0.2779260752064068", + "Likelihood: 0.19618732296151362", + "Likelihood: 0.14584997292374496", + "Likelihood: 0.29099705014720634", + "Likelihood: 0.2573374242960751", + "Likelihood: 0.172057767887375", + "Likelihood: 0.12106736617213971", + "Likelihood: 0.02950693398610937", + "Likelihood: 0.2284182580257074", + "Likelihood: 0.029918306393012673", + "Likelihood: 0.05986473259650994", + "Likelihood: 0.1795664753757983", + "Likelihood: 0.05630619119841054", + "Likelihood: 0.3010521480289277", + "Likelihood: 0.015039133056528582", + "Likelihood: 0.15856312637595152", + "Likelihood: 0.06612254319126981", + "Likelihood: 0.020238492521910074", + "Likelihood: 0.19904421080836654", + "Likelihood: 0.1252994880635412", + "Likelihood: 0.17016207616194545", + "Likelihood: 0.28247592937310895", + "Likelihood: 0.08054480663904255", + "Likelihood: 0.15811085309831913", + "Likelihood: 0.052212597841361404", + "Likelihood: 0.262153778590849", + "Likelihood: 0.24778291010733003", + "Likelihood: 0.14600981865512558", + "Likelihood: 0.2566534772749161", + "Likelihood: 0.0940165765646458", + "Likelihood: 0.18984343463836348", + "Likelihood: 0.09717602566891502", + "Likelihood: 0.15221795928268111", + "Likelihood: 0.0662600620022854", + "Likelihood: 0.11026013195541869", + "Likelihood: 0.09127234344828768", + "Likelihood: 0.07992633333106991", + "Likelihood: 0.07283550233421454", + "Likelihood: 0.10422300391982267", + "Likelihood: 0.28601084816390604", + "Likelihood: 0.08045256574978886", + "Likelihood: 0.07335577278352767", + "Likelihood: 0.1919085156439959", + "Likelihood: 0.03788400603864854", + "Likelihood: 0.21494824108432684", + "Likelihood: 0.015743866353177954", + "Likelihood: 0.008791717632443418", + "Likelihood: 0.2048432009288833", + "Likelihood: 0.057971645168096116", + "Likelihood: 0.2625079774826456", + "Likelihood: 0.25390203293401936", + "Likelihood: 0.21600677601543058", + "Likelihood: 0.19628823710909335", + "Likelihood: 0.07081838823624653", + "Likelihood: 0.08920642194014844", + "Likelihood: 0.1770145337307182", + "Likelihood: 0.2508876229093182", + "Likelihood: 0.0681762948469317", + "Likelihood: 0.13433707599204547", + "Likelihood: 0.3151470792496528", + "Likelihood: 0.1623219160711135", + "Likelihood: 0.12936503256036738", + "Likelihood: 0.11725548595618106", + "Likelihood: 0.18523183946160823", + "Likelihood: 0.14185941129187218", + "Likelihood: 0.23783745177732388", + "Likelihood: 0.21352369706325927", + "Likelihood: 0.0392600945029365", + "Likelihood: 0.2582297016658002", + "Likelihood: 0.12294091871724089", + "Likelihood: 0.10827543764000323", + "Likelihood: 0.2173859177250226", + "Likelihood: 0.10726970783137078", + "Likelihood: 0.22933708973509798", + "Likelihood: 0.1087262562577601", + "Likelihood: 0.3184782303183177", + "Likelihood: 0.26698644063190613", + "Likelihood: 0.10800483158431681", + "Likelihood: 0.2159993088883378", + "Likelihood: 0.1393302401886606", + "Likelihood: 0.1289186187395799", + "Likelihood: 0.06509896302083082", + "Likelihood: 0.10814289503647917", + "Likelihood: 0.2586969802865805", + "Likelihood: 0.03346537596142192", + "Likelihood: 0.12537238744982832", + "Likelihood: 0.10524907260936987", + "Likelihood: 0.011083585439828916", + "Likelihood: 0.13124828651894482", + "Likelihood: 0.2624242238397329", + "Likelihood: 0.23439509676925116", + "Likelihood: 0.18095193549927358", + "Likelihood: 0.14808119542896703", + "Likelihood: 0.12937268539495328", + "Likelihood: 0.2916558766444828", + "Likelihood: 0.23932732954907782", + "Likelihood: 0.12494561856156963", + "Likelihood: 0.21900016961344146", + "Likelihood: 0.09341093963549822", + "Likelihood: 0.040638738578767736", + "Likelihood: 0.28536324838505", + "Likelihood: 0.2520209791179764", + "Likelihood: 0.18195446211934815", + "Likelihood: 0.12817207641947959", + "Likelihood: 0.21453983623362413", + "Likelihood: 0.16116778455186168", + "Likelihood: 0.17836902642597113", + "Likelihood: 0.1974389551763164", + "Likelihood: 0.08710079125401782", + "Likelihood: 0.1966320421376524", + "Likelihood: 0.01522886688801002", + "Likelihood: 0.045703972435429605", + "Likelihood: 0.21664262793482394", + "Likelihood: 0.050295929118717095", + "Likelihood: 0.1440920835564822", + "Likelihood: 0.10817756649447448", + "Likelihood: 0.21970221153666683", + "Likelihood: 0.19201659317909225", + "Likelihood: 0.03291772362165671", + "Likelihood: 0.019267825002806993", + "Likelihood: 0.10689858066191024", + "Likelihood: 0.1267287832888889", + "Likelihood: 0.0759280593840592", + "Likelihood: 0.026805557615881583", + "Likelihood: 0.07819148122493784", + "Likelihood: 0.26893653826647645", + "Likelihood: 0.05162611074851631", + "Likelihood: 0.17015389584343613", + "Likelihood: 0.28402248148912324", + "Likelihood: 0.04278870253837794", + "Likelihood: 0.3041911982339415", + "Likelihood: 0.0388623177896374", + "Likelihood: 0.13004006501375712", + "Likelihood: 0.08327979322432652", + "Likelihood: 0.18430970777046504", + "Likelihood: 0.037825594400210036", + "Likelihood: 0.039521229218840666", + "Likelihood: 0.04082101979539533", + "Likelihood: 0.018378206922577904", + "Likelihood: 0.1169942201917526", + "Likelihood: 0.20214261761502214", + "Likelihood: 0.05012272391573885", + "Likelihood: 0.04201861860453182", + "Likelihood: 0.2851375202926841", + "Likelihood: 0.05604793428521345", + "Likelihood: 0.2589842824820623", + "Likelihood: 0.024327177618824497", + "Likelihood: 0.31676941957700777", + "Likelihood: 0.2794655024634765", + "Likelihood: 0.05038761871411391", + "Likelihood: 0.28005770659753476", + "Likelihood: 0.2664560455201984", + "Likelihood: 0.2602583235829368", + "Likelihood: 0.12264129634101152", + "Likelihood: 0.04892579114113519", + "Likelihood: 0.031254787822172184", + "Likelihood: 0.27951694564759205", + "Likelihood: 0.148657650534062", + "Likelihood: 0.0836690143572187", + "Likelihood: 0.16744429337007388", + "Likelihood: 0.19873372370421816", + "Likelihood: 0.2523132460838398", + "Likelihood: 0.2215047113474611", + "Likelihood: 0.23124189447140292", + "Likelihood: 0.1687229832811503", + "Likelihood: 0.2856976041791215", + "Likelihood: 0.25940237728539683", + "Likelihood: 0.12819946814829888", + "Likelihood: 0.04583556939213675", + "Likelihood: 0.23974527102844925", + "Likelihood: 0.2186249503083089", + "Likelihood: 0.049576143144602895", + "Likelihood: 0.13657289875725867", + "Likelihood: 0.24929882242209517", + "Likelihood: 0.09670670145253522", + "Likelihood: 0.2479487356718115", + "Likelihood: 0.05775315585891035", + "Likelihood: 0.12460053204184302", + "Likelihood: 0.08685758888684036", + "Likelihood: 0.2397362801837297", + "Likelihood: 0.19903021135657115", + "Likelihood: 0.01747644281352202", + "Likelihood: 0.20111221329491413", + "Likelihood: 0.14300360221748964", + "Likelihood: 0.07428060243009309", + "Likelihood: 0.2729794455259552", + "Likelihood: 0.1469152276974097", + "Likelihood: 0.18584885302312265", + "Likelihood: 0.22967093436237768", + "Likelihood: 0.21805284944288314", + "Likelihood: 0.28292806931490877", + "Likelihood: 0.30596481256637575", + "Likelihood: 0.08288119891277287", + "Likelihood: 0.014774765456531273", + "Likelihood: 0.0706859612309871", + "Likelihood: 0.2329566330752741", + "Likelihood: 0.26207939040798145", + "Likelihood: 0.00662190615605111", + "Likelihood: 0.11134708770707465", + "Likelihood: 0.023598791155653553", + "Likelihood: 0.1115195839667207", + "Likelihood: 0.03504901543255403", + "Likelihood: 0.16407681469276936", + "Likelihood: 0.03226181484938101", + "Likelihood: 0.23344535223344234", + "Likelihood: 0.10208079603196488", + "Likelihood: 0.26189276632657726", + "Likelihood: 0.11536918670512976", + "Likelihood: 0.0200002818972866", + "Likelihood: 0.2807433995613068", + "Likelihood: 0.1389541934843479", + "Likelihood: 0.2641622422440206", + "Likelihood: 0.1520810367488046", + "Likelihood: 0.27508723492010756", + "Likelihood: 0.13187107937915585", + "Likelihood: 0.08749828600369122", + "Likelihood: 0.11186003502208638", + "Likelihood: 0.16661066986630668", + "Likelihood: 0.23634389645920112", + "Likelihood: 0.14086786265152323", + "Likelihood: 0.2083714388274246", + "Likelihood: 0.2180017707330216", + "Likelihood: 0.04579850969954948", + "Likelihood: 0.08364570617793059", + "Likelihood: 0.062437356410157734", + "Likelihood: 0.13344229746672073", + "Likelihood: 0.28728637143877417", + "Likelihood: 0.21866126156585003", + "Likelihood: 0.2730342695782791", + "Likelihood: 0.1643550986852482", + "Likelihood: 0.3012025548039374", + "Likelihood: 0.13959548549813502", + "Likelihood: 0.2462317393218925", + "Likelihood: 0.06202812147528391", + "Likelihood: 0.00770685105763856", + "Likelihood: 0.0506688976198487", + "Likelihood: 0.2467621788653706", + "Likelihood: 0.08185700829887349", + "Likelihood: 0.04030008239576575", + "Likelihood: 0.09124855030270203", + "Likelihood: 0.14220882671963028", + "Likelihood: 0.1503224674188733", + "Likelihood: 0.1069994466058465", + "Likelihood: 0.06332713226078991", + "Likelihood: 0.30392084978862693", + "Likelihood: 0.25036512550627354", + "Likelihood: 0.030683269721877262", + "Likelihood: 0.24579364611252608", + "Likelihood: 0.20914904417532296", + "Likelihood: 0.022497026131098167", + "Likelihood: 0.19353200112017188", + "Likelihood: 0.08440594820212621", + "Likelihood: 0.003140463124821306", + "Likelihood: 0.25436297026482113", + "Likelihood: 0.22274007651627412", + "Likelihood: 0.2694128260558258", + "Likelihood: 0.1743619415747088", + "Likelihood: 0.08005243644737252", + "Likelihood: 0.3138628665581115", + "Likelihood: 0.14319588255777843", + "Likelihood: 0.08894098559588758", + "Likelihood: 0.10374042801303629", + "Likelihood: 0.2454800742128148", + "Likelihood: 0.2747945927200944", + "Likelihood: 0.07901951971254817", + "Likelihood: 0.046306823344341955", + "Likelihood: 0.02018528187073139", + "Likelihood: 0.2104919487152605", + "Likelihood: 0.026986728323210474", + "Likelihood: 0.17410678562141005", + "Likelihood: 0.18454213560280797", + "Likelihood: 0.14837566649175313", + "Likelihood: 0.27780278564129807", + "Likelihood: 0.047875234506425356", + "Likelihood: 0.18441432441084663", + "Likelihood: 0.3207033688657823", + "Likelihood: 0.18575828488232943", + "Likelihood: 0.03839228083927504", + "Likelihood: 0.10238868944617271", + "Likelihood: 0.011765314755276804", + "Likelihood: 0.15660019328391708", + "Likelihood: 0.19811483956399087", + "Likelihood: 0.25765893902155584", + "Likelihood: 0.2739017721127224", + "Likelihood: 0.13566082199362672", + "Likelihood: 0.2816721936136623", + "Likelihood: 0.26783659045182523", + "Likelihood: 0.0287143467798471", + "Likelihood: 0.1954307361398289", + "Likelihood: 0.1958667509459525", + "Likelihood: 0.24738422785810926", + "Likelihood: 0.05006035596981205", + "Likelihood: 0.16034662455161405", + "Likelihood: 0.09371554717668053", + "Likelihood: 0.14100821274549177", + "Likelihood: 0.09575061073001473", + "Likelihood: 0.06798411945625837", + "Likelihood: 0.13049400046004966", + "Likelihood: 0.30862578667860424", + "Likelihood: 0.03609402771514361", + "Likelihood: 0.2739088144767002", + "Likelihood: 0.04608329773353352", + "Likelihood: 0.042686818946115486", + "Likelihood: 0.05696473284565965", + "Likelihood: 0.23540046123671418", + "Likelihood: 0.25620089528768925", + "Likelihood: 0.1251146583885655", + "Likelihood: 0.28138855977057786", + "Likelihood: 0.06832906789177152", + "Likelihood: 0.15587644531210246", + "Likelihood: 0.04420002778647306", + "Likelihood: 0.14011005580195157", + "Likelihood: 0.11150062415518378", + "Likelihood: 0.1853113164827464", + "Likelihood: 0.224108817587809", + "Likelihood: 0.03643902581205899", + "Likelihood: 0.30568952851067305", + "Likelihood: 0.22795147245173356", + "Likelihood: 0.05202322590303519", + "Likelihood: 0.010913756560556244", + "Likelihood: 0.056821152852864036", + "Likelihood: 0.044096599064469895", + "Likelihood: 0.11460831275441637", + "Likelihood: 0.20865589262540757", + "Likelihood: 0.2441443640592249", + "Likelihood: 0.2917184108232406", + "Likelihood: 0.10134730427410259", + "Likelihood: 0.12294012933672238", + "Likelihood: 0.028336363233584416", + "Likelihood: 0.11389891087754633", + "Likelihood: 0.08903428813930264", + "Likelihood: 0.19788962566587623", + "Likelihood: 0.13685866733599752", + "Likelihood: 0.2836322579223263", + "Likelihood: 0.18451422666568176", + "Likelihood: 0.019713887961990625", + "Likelihood: 0.0492656862155773", + "Likelihood: 0.1974989594877588", + "Likelihood: 0.1092608751464925", + "Likelihood: 0.15633849585428752", + "Likelihood: 0.1568875351958891", + "Likelihood: 0.06262130810557232", + "Likelihood: 0.259277594273429", + "Likelihood: 0.31381541337436486", + "Likelihood: 0.19921914049234735", + "Likelihood: 0.10666797655012344", + "Likelihood: 0.28539669388699285", + "Likelihood: 0.31339679472890103", + "Likelihood: 0.3227180433648511", + "Likelihood: 0.19405117585231257", + "Likelihood: 0.06433821031385688", + "Likelihood: 0.16605644670533973", + "Likelihood: 0.20920851765073004", + "Likelihood: 0.1449468169402153", + "Likelihood: 0.17392400541720945", + "Likelihood: 0.32384239988251357", + "Likelihood: 0.0956429739175776", + "Likelihood: 0.26437579770931924", + "Likelihood: 0.05281214970182415", + "Likelihood: 0.13228756559424557", + "Likelihood: 0.3045909282346713", + "Likelihood: 0.015014971501927278", + "Likelihood: 0.25238919941820215", + "Likelihood: 0.043987964387830814", + "Likelihood: 0.13335600993542876", + "Likelihood: 0.10008466827397323", + "Likelihood: 0.007904739308362944", + "Likelihood: 0.10114749307426593", + "Likelihood: 0.13195162732898996", + "Likelihood: 0.06763855436029587", + "Likelihood: 0.07759225247701726", + "Likelihood: 0.018020655124385058", + "Likelihood: 0.31742864129233594", + "Likelihood: 0.05526713822640674", + "Likelihood: 0.1510130097786693", + "Likelihood: 0.14541969489563475", + "Likelihood: 0.1762137783187799", + "Likelihood: 0.06532682242724643", + "Likelihood: 0.11620699032933128", + "Likelihood: 0.19101502455853617", + "Likelihood: 0.13608437074797217", + "Likelihood: 0.20283034142969342", + "Likelihood: 0.13416399243270588", + "Likelihood: 0.037377534787980185", + "Likelihood: 0.1511198623401761", + "Likelihood: 0.2963593037021726", + "Likelihood: 0.03142653787748108", + "Likelihood: 0.30382684053423886", + "Likelihood: 0.1856385015142021", + "Likelihood: 0.26646829785685316", + "Likelihood: 0.07055603455920727", + "Likelihood: 0.24301388929022133", + "Likelihood: 0.03528980908347865", + "Likelihood: 0.06669309825028118", + "Likelihood: 0.07377296086232232", + "Likelihood: 0.05709374318815286", + "Likelihood: 0.26258633372324464", + "Likelihood: 0.0678048710899244", + "Likelihood: 0.271148658765319", + "Likelihood: 0.16706747972848499", + "Likelihood: 0.10643443255943018", + "Likelihood: 0.02202957077994246", + "Likelihood: 0.0113133885760095", + "Likelihood: 0.11522674313699383", + "Likelihood: 0.2541742329614886", + "Likelihood: 0.11644351714498472", + "Likelihood: 0.26033820062379487", + "Likelihood: 0.27844581901086757", + "Likelihood: 0.21658854129371177", + "Likelihood: 0.23476613879239483", + "Likelihood: 0.07569674083299462", + "Likelihood: 0.2869867299971129", + "Likelihood: 0.08911024221206104", + "Likelihood: 0.06992850593143003", + "Likelihood: 0.22486169824682606", + "Likelihood: 0.11002156634190706", + "Likelihood: 0.17389914942220036", + "Likelihood: 0.1392527169312095", + "Likelihood: 0.18056943861981456", + "Likelihood: 0.2809572418386304", + "Likelihood: 0.14605301342802873", + "Likelihood: 0.04548791090307977", + "Likelihood: 0.2021732781447896", + "Likelihood: 0.0523021515541227", + "Likelihood: 0.19941762789191556", + "Likelihood: 0.025839779825950066", + "Likelihood: 0.02386151092723476", + "Likelihood: 0.1501050610345071", + "Likelihood: 0.2879576165760482", + "Likelihood: 0.07455794052089793", + "Likelihood: 0.248006061491653", + "Likelihood: 0.061868513406987534", + "Likelihood: 0.1092869792257687", + "Likelihood: 0.2951190747414865", + "Likelihood: 0.008723550723090539", + "Likelihood: 0.15439138478670156", + "Likelihood: 0.0992835102768211", + "Likelihood: 0.20008144322773752", + "Likelihood: 0.09089083951116504", + "Likelihood: 0.279963295575963", + "Likelihood: 0.2963345488002846", + "Likelihood: 0.017474794029057494", + "Likelihood: 0.23683912839976595", + "Likelihood: 0.2710584538981511", + "Likelihood: 0.3005735057463336", + "Likelihood: 0.2166742082370282", + "Likelihood: 0.08096114507004608", + "Likelihood: 0.007588023758473338", + "Likelihood: 0.3212959741510208", + "Likelihood: 0.08859510373624124", + "Likelihood: 0.280777678491844", + "Likelihood: 0.2741575067406154", + "Likelihood: 0.2983781979072928", + "Likelihood: 0.010555147834683271", + "Likelihood: 0.10811702887468938", + "Likelihood: 0.15340761748755935", + "Likelihood: 0.12250479248104106", + "Likelihood: 0.051255065690903136", + "Likelihood: 0.21772762949445246", + "Likelihood: 0.15768951062974748", + "Likelihood: 0.07956225453042765", + "Likelihood: 0.31067929808310346", + "Likelihood: 0.21922166773917337", + "Likelihood: 0.0695963282251502", + "Likelihood: 0.0841455954859209", + "Likelihood: 0.27718917153390643", + "Likelihood: 0.1693800673456462", + "Likelihood: 0.10838554966930584", + "Likelihood: 0.0599063911548958", + "Likelihood: 0.21783918750461093", + "Likelihood: 0.11602125661966613", + "Likelihood: 0.1111735990284887", + "Likelihood: 0.0687958363279993", + "Likelihood: 0.18131278535409798", + "Likelihood: 0.0854471697591065", + "Likelihood: 0.0988464302712859", + "Likelihood: 0.04827567519656401", + "Likelihood: 0.01826297516498391", + "Likelihood: 0.2878377996553523", + "Likelihood: 0.10616558930540826", + "Likelihood: 0.18678083542953783", + "Likelihood: 0.3055312466400548", + "Likelihood: 0.1463449081227671", + "Likelihood: 0.05926409815507347", + "Likelihood: 0.3034284976780731", + "Likelihood: 0.13552928149987695", + "Likelihood: 0.22304192849506949", + "Likelihood: 0.16221400372960565", + "Likelihood: 0.273441427246133", + "Likelihood: 0.1357979625566973", + "Likelihood: 0.00646267577288305", + "Likelihood: 0.012129484959892918", + "Likelihood: 0.17675650071680218", + "Likelihood: 0.21437005716781274", + "Likelihood: 0.2305842228467256", + "Likelihood: 0.0663523644055097", + "Likelihood: 0.02112321381779374", + "Likelihood: 0.2609820699541133", + "Likelihood: 0.21060651077049614", + "Likelihood: 0.22524858511613594", + "Likelihood: 0.08477631406355055", + "Likelihood: 0.0965716027079768", + "Likelihood: 0.0788654164413753", + "Likelihood: 0.30608899681219837", + "Likelihood: 0.0777512608528036", + "Likelihood: 0.06493706781415459", + "Likelihood: 0.08017014839730971", + "Likelihood: 0.13131726151597276", + "Likelihood: 0.02769776717849074", + "Likelihood: 0.23378707147299327", + "Likelihood: 0.28456001929053143", + "Likelihood: 0.2254227164018312", + "Likelihood: 0.18824362900618014", + "Likelihood: 0.08414593352644317", + "Likelihood: 0.09945465540984919", + "Likelihood: 0.29254270888586525", + "Likelihood: 0.26692605570841965", + "Likelihood: 0.3088045231345376", + "Likelihood: 0.09250412528079545", + "Likelihood: 0.11231581257334611", + "Likelihood: 0.01688287418140138", + "Likelihood: 0.10147467842316955", + "Likelihood: 0.10715737909053377", + "Likelihood: 0.2765319863302336", + "Likelihood: 0.18111240421901992", + "Likelihood: 0.24951463758615733", + "Likelihood: 0.11292260963870117", + "Likelihood: 0.15201512900454797", + "Likelihood: 0.23737134088688355", + "Likelihood: 0.2970638562996334", + "Likelihood: 0.24968784375014808", + "Likelihood: 0.12410418667406663", + "Likelihood: 0.21487280640812362", + "Likelihood: 0.25538644957922757", + "Likelihood: 0.15409271991135393", + "Likelihood: 0.24210436625432633", + "Likelihood: 0.3043173778497105", + "Likelihood: 0.24165492426401422", + "Likelihood: 0.21805570808419797", + "Likelihood: 0.27062888910248106", + "Likelihood: 0.1540902680073873", + "Likelihood: 0.26991601894686895", + "Likelihood: 0.12947799875508914", + "Likelihood: 0.17195326933814917", + "Likelihood: 0.06561877333306596", + "Likelihood: 0.059269615686156844", + "Likelihood: 0.25303161424138926", + "Likelihood: 0.20962178436093082", + "Likelihood: 0.14931304244578386", + "Likelihood: 0.09821066872027019", + "Likelihood: 0.10240629989147755", + "Likelihood: 0.014636097446205826", + "Likelihood: 0.1211995892572228", + "Likelihood: 0.14967658972256082", + "Likelihood: 0.005889870871037451", + "Likelihood: 0.19242987110924686", + "Likelihood: 0.2904426129665113", + "Likelihood: 0.11509084526943135", + "Likelihood: 0.13706749069642157", + "Likelihood: 0.03111079020249485", + "Likelihood: 0.09156328154272679", + "Likelihood: 0.16415529063676126", + "Likelihood: 0.31132294524331156", + "Likelihood: 0.1804265875012563", + "Likelihood: 0.2582354337649134", + "Likelihood: 0.03371324249290835", + "Likelihood: 0.15660788271687234", + "Likelihood: 0.07992234115888792", + "Likelihood: 0.24738464087583542", + "Likelihood: 0.20591738681511718", + "Likelihood: 0.22582331734652067", + "Likelihood: 0.015466442866601038", + "Likelihood: 0.19887910294775105", + "Likelihood: 0.1753234696784616", + "Likelihood: 0.21696948373693736", + "Likelihood: 0.20284976960275855", + "Likelihood: 0.1851084854272286", + "Likelihood: 0.2750796965901694", + "Likelihood: 0.11972241838755153", + "Likelihood: 0.19050598344412892", + "Likelihood: 0.06021696352049316", + "Likelihood: 0.024510335110259008", + "Likelihood: 0.24632712985603591", + "Likelihood: 0.1982319601182395", + "Likelihood: 0.03874633810096579", + "Likelihood: 0.1137600058031298", + "Likelihood: 0.15290282949132605", + "Likelihood: 0.0932776261693346", + "Likelihood: 0.2924899701652006", + "Likelihood: 0.28163782857048236", + "Likelihood: 0.18118411168227697", + "Likelihood: 0.23932863145060324", + "Likelihood: 0.28346416527548346", + "Likelihood: 0.015953344732775883", + "Likelihood: 0.17374314249137066", + "Likelihood: 0.11426239302279419", + "Likelihood: 0.054095528031851865", + "Likelihood: 0.022716640323681977", + "Likelihood: 0.18589243623035387", + "Likelihood: 0.09779565221621747", + "Likelihood: 0.19544153935354638", + "Likelihood: 0.08557997990278364", + "Likelihood: 0.1386625671460921", + "Likelihood: 0.2500841891442262", + "Likelihood: 0.05331359297217607", + "Likelihood: 0.009057236929040223", + "Likelihood: 0.1520278349867288", + "Likelihood: 0.02400846186980959", + "Likelihood: 0.08434213044779185", + "Likelihood: 0.07674340918929816", + "Likelihood: 0.2426367518068753", + "Likelihood: 0.1293589303095615", + "Likelihood: 0.2075985063239719", + "Likelihood: 0.10016094024467055", + "Likelihood: 0.03342162067948957", + "Likelihood: 0.06145236704854368", + "Likelihood: 0.07955283830568986", + "Likelihood: 0.1838604873802597", + "Likelihood: 0.17420031163609084", + "Likelihood: 0.0077898336485594894", + "Likelihood: 0.08600720545161422", + "Likelihood: 0.22418192269554713", + "Likelihood: 0.09655285101041451", + "Likelihood: 0.22463071233783488", + "Likelihood: 0.30748349879838255", + "Likelihood: 0.20825880369501445", + "Likelihood: 0.11040858862928488", + "Likelihood: 0.13558903614397647", + "Likelihood: 0.07787961544660307", + "Likelihood: 0.09131169775117551", + "Likelihood: 0.1770165071452904", + "Likelihood: 0.09376555913309959", + "Likelihood: 0.14389888090091796", + "Likelihood: 0.09667064098752862", + "Likelihood: 0.3032018077069834", + "Likelihood: 0.16871869496798098", + "Likelihood: 0.3059664068640524", + "Likelihood: 0.18099989383793907", + "Likelihood: 0.05656870140624004", + "Likelihood: 0.01010638755204864", + "Likelihood: 0.035177744277187346", + "Likelihood: 0.14717959819031343", + "Likelihood: 0.10816349795262703", + "Likelihood: 0.07385481758196014", + "Likelihood: 0.014966021045173741", + "Likelihood: 0.16455606111860782", + "Likelihood: 0.06583698559782059", + "Likelihood: 0.2402366860993762", + "Likelihood: 0.21448090954685106", + "Likelihood: 0.08861067550622198", + "Likelihood: 0.04929806088788683", + "Likelihood: 0.19040756149100455", + "Likelihood: 0.02785489945373499", + "Likelihood: 0.24497428741093089", + "Likelihood: 0.23294931460898807", + "Likelihood: 0.10061409733993747", + "Likelihood: 0.15847009377941346", + "Likelihood: 0.2970371186895077", + "Likelihood: 0.1994856021779031", + "Likelihood: 0.2657552964953019", + "Likelihood: 0.16256669313338418", + "Likelihood: 0.22315059633690898", + "Likelihood: 0.18726515308972522", + "Likelihood: 0.23546338379452764", + "Likelihood: 0.015711687370783222", + "Likelihood: 0.059601107393011304", + "Likelihood: 0.23217294659220325", + "Likelihood: 0.0366684198115524", + "Likelihood: 0.18679325483066672", + "Likelihood: 0.25623174789464886", + "Likelihood: 0.24941707264308385", + "Likelihood: 0.0912236290102279", + "Likelihood: 0.28426638729235276", + "Likelihood: 0.07371286618607631", + "Likelihood: 0.23360876800717506", + "Likelihood: 0.11543470448915827", + "Likelihood: 0.06956502387572198", + "Likelihood: 0.04626202083674618", + "Likelihood: 0.2839948609964122", + "Likelihood: 0.10493211041836778", + "Likelihood: 0.2914691672991703", + "Likelihood: 0.2460689578044049", + "Likelihood: 0.03102150930308726", + "Likelihood: 0.18197579730914049", + "Likelihood: 0.05469560169472085", + "Likelihood: 0.06701108963342792", + "Likelihood: 0.15492325921187095", + "Likelihood: 0.0768432666020462", + "Likelihood: 0.08279078448572888", + "Likelihood: 0.17133247160136514", + "Likelihood: 0.0575693157900172", + "Likelihood: 0.014844788357957784", + "Likelihood: 0.22322215602776202", + "Likelihood: 0.27801198863682175", + "Likelihood: 0.3026258876078206", + "Likelihood: 0.07053793202359517", + "Likelihood: 0.14121937337456608", + "Likelihood: 0.018131536353108064", + "Likelihood: 0.31834070932408776", + "Likelihood: 0.050344439791055934", + "Likelihood: 0.24361340699392656", + "Likelihood: 0.1124074933523163", + "Likelihood: 0.21643352041959932", + "Likelihood: 0.29094999413077727", + "Likelihood: 0.13268140157866387", + "Likelihood: 0.2615018310188922", + "Likelihood: 0.11897170517543319", + "Likelihood: 0.11637076248939736", + "Likelihood: 0.0635533822344316", + "Likelihood: 0.2343820581266395", + "Likelihood: 0.1241247876309141", + "Likelihood: 0.2923159973001698", + "Likelihood: 0.12468670560585222", + "Likelihood: 0.23535607504638464", + "Likelihood: 0.12652749410959716", + "Likelihood: 0.19639128918510992", + "Likelihood: 0.2415576613596178", + "Likelihood: 0.09604707058376027", + "Likelihood: 0.28750764180437866", + "Likelihood: 0.24919591544474512", + "Likelihood: 0.274778227098305", + "Likelihood: 0.2374325225438439", + "Likelihood: 0.04026561403649194", + "Likelihood: 0.30851987252199525", + "Likelihood: 0.2539326614123119", + "Likelihood: 0.22240336708649686", + "Likelihood: 0.06308085231933079", + "Likelihood: 0.29691304824544335", + "Likelihood: 0.012924245331227907", + "Likelihood: 0.13357263345599762", + "Likelihood: 0.09127224211132522", + "Likelihood: 0.1266870065762547", + "Likelihood: 0.012317956530270189", + "Likelihood: 0.2959606000341796", + "Likelihood: 0.10529457211718106", + "Likelihood: 0.1633647269018937", + "Likelihood: 0.07753950010356818", + "Likelihood: 0.04601490267012351", + "Likelihood: 0.16832088271177892", + "Likelihood: 0.11306601044796183", + "Likelihood: 0.035752176180569355", + "Likelihood: 0.20018458853477847", + "Likelihood: 0.10357599631968964", + "Likelihood: 0.059203269755036585", + "Likelihood: 0.09755562175052834", + "Likelihood: 0.0118669969695027", + "Likelihood: 0.20409757576300083", + "Likelihood: 0.14146255089478577", + "Likelihood: 0.09844307356305221", + "Likelihood: 0.27664125197319683", + "Likelihood: 0.14629027399203542", + "Likelihood: 0.044800849945163077", + "Likelihood: 0.10721413687798743", + "Likelihood: 0.032917038774235054", + "Likelihood: 0.30817117531304794", + "Likelihood: 0.02342674750367045", + "Likelihood: 0.0778049896806776", + "Likelihood: 0.23090805824277394", + "Likelihood: 0.27274279162753634", + "Likelihood: 0.30725766535893934", + "Likelihood: 0.04474933375044851", + "Likelihood: 0.0975122217369741", + "Likelihood: 0.20114385552779196", + "Likelihood: 0.08075410891280169", + "Likelihood: 0.1267805230428327", + "Likelihood: 0.15253364523496202", + "Likelihood: 0.2193612063668295", + "Likelihood: 0.185147775583987", + "Likelihood: 0.2579746378868788", + "Likelihood: 0.17799175066867035", + "Likelihood: 0.15924699072104195", + "Likelihood: 0.1346365129110876", + "Likelihood: 0.2662571154541173", + "Likelihood: 0.18360844758799444", + "Likelihood: 0.030271387514711895", + "Likelihood: 0.09431224010006911", + "Likelihood: 0.10629135881078418", + "Likelihood: 0.09067163765497888", + "Likelihood: 0.2698491886267719", + "Likelihood: 0.1074381074175823", + "Likelihood: 0.26901654100619005", + "Likelihood: 0.13904602997913457", + "Likelihood: 0.020635172590878284", + "Likelihood: 0.0012030053737768732", + "Likelihood: 0.035326718538929415", + "Likelihood: 0.157088687295661", + "Likelihood: 0.019194151007662474", + "Likelihood: 0.15817675241928897", + "Likelihood: 0.24161034311240853", + "Likelihood: 0.05983804716684733", + "Likelihood: 0.307518943991126", + "Likelihood: 0.30764784573421106", + "Likelihood: 0.12181377779438138", + "Likelihood: 0.19499883093156298", + "Likelihood: 0.27862342731985723", + "Likelihood: 0.24148567228040838", + "Likelihood: 0.014385438494390815", + "Likelihood: 0.10830123123638587", + "Likelihood: 0.25323160030991376", + "Likelihood: 0.2578540647809833", + "Likelihood: 0.12259439536663229", + "Likelihood: 0.19480174425040497", + "Likelihood: 0.2586908662186438", + "Likelihood: 0.03217724113962828", + "Likelihood: 0.06457665020495006", + "Likelihood: 0.20197560472470436", + "Likelihood: 0.276747976279015", + "Likelihood: 0.22861803383411788", + "Likelihood: 0.1278025596392696", + "Likelihood: 0.10628811836460192", + "Likelihood: 0.0596580711389709", + "Likelihood: 0.19667168516840516", + "Likelihood: 0.14475075567298434", + "Likelihood: 0.1780651552662241", + "Likelihood: 0.2134776635206307", + "Likelihood: 0.06410633060614045", + "Likelihood: 0.03126326736444316", + "Likelihood: 0.13048188108623396", + "Likelihood: 0.05831233204496781", + "Likelihood: 0.2162557831608072", + "Likelihood: 0.029990481747231006", + "Likelihood: 0.061476385390187245", + "Likelihood: 0.28184967450631043", + "Likelihood: 0.1605458960164334", + "Likelihood: 0.042062046758536094", + "Likelihood: 0.30807701105561863", + "Likelihood: 0.03481683232569585", + "Likelihood: 0.1650526596636246", + "Likelihood: 0.22194739333525343", + "Likelihood: 0.12095212220425061", + "Likelihood: 0.30451298816687794", + "Likelihood: 0.06351120345796944", + "Likelihood: 0.1866371519392235", + "Likelihood: 0.027142328810145326", + "Likelihood: 0.2121181590866515", + "Likelihood: 0.16745697661697004", + "Likelihood: 0.2575704756297839", + "Likelihood: 0.21602666776410473", + "Likelihood: 0.11096922127925404", + "Likelihood: 0.16793133143408034", + "Likelihood: 0.14861730240975185", + "Likelihood: 0.05023850549870651", + "Likelihood: 0.05060874074247244", + "Likelihood: 0.08720595548273757", + "Likelihood: 0.017594139705375447", + "Likelihood: 0.3025998625695838", + "Likelihood: 0.10520566811590722", + "Likelihood: 0.09108578504687391", + "Likelihood: 0.06868085902022232", + "Likelihood: 0.23122366846244577", + "Likelihood: 0.059366778735689775", + "Likelihood: 0.26959725980577665", + "Likelihood: 0.02889491198603959", + "Likelihood: 0.13763521926764447", + "Likelihood: 0.3034231478153148", + "Likelihood: 0.11869833845630993", + "Likelihood: 0.10690830965597924", + "Likelihood: 0.2546975936456455", + "Likelihood: 0.11520575474812818", + "Likelihood: 0.010427260019763478", + "Likelihood: 0.12906618264537287", + "Likelihood: 0.038462561157925346", + "Likelihood: 0.2536188535112179", + "Likelihood: 0.02270241191818071", + "Likelihood: 0.2852247521638583", + "Likelihood: 0.046928088419171114", + "Likelihood: 0.055777648966237374", + "Likelihood: 0.056573905343925215", + "Likelihood: 0.2754356543842008", + "Likelihood: 0.06405834058195387", + "Likelihood: 0.17540203280651656", + "Likelihood: 0.0642460115649518", + "Likelihood: 0.10736490430816187", + "Likelihood: 0.043233843869353986", + "Likelihood: 0.2821368233651277", + "Likelihood: 0.23229871299576155", + "Likelihood: 0.23737565056402948", + "Likelihood: 0.11714186089487479", + "Likelihood: 0.2643305101023996", + "Likelihood: 0.2563470888275016", + "Likelihood: 0.14005609062442637", + "Likelihood: 0.22355016098941388", + "Likelihood: 0.0403065091330471", + "Likelihood: 0.14944468648824388", + "Likelihood: 0.22568855898587664", + "Likelihood: 0.3126794685647815", + "Likelihood: 0.2105186492245128", + "Likelihood: 0.08251454534698092", + "Likelihood: 0.03263443827633579", + "Likelihood: 0.14817827998980812", + "Likelihood: 0.002125566377687852", + "Likelihood: 0.21284353388929653", + "Likelihood: 0.015996169180001532", + "Likelihood: 0.1766822617580179", + "Likelihood: 0.05900500519080943", + "Likelihood: 0.042336416541452045", + "Likelihood: 0.017204302750339066", + "Likelihood: 0.20121923451011695", + "Likelihood: 0.1793412163994307", + "Likelihood: 0.2481899365865573", + "Likelihood: 0.11345678336058308", + "Likelihood: 0.3174987798949667", + "Likelihood: 0.2623642550694098", + "Likelihood: 0.01835930402370236", + "Likelihood: 0.14349860508681933", + "Likelihood: 0.1448918024639299", + "Likelihood: 0.18439529894665324", + "Likelihood: 0.04166884364972409", + "Likelihood: 0.17161796484485142", + "Likelihood: 0.17309786296333793", + "Likelihood: 0.22147533409129258", + "Likelihood: 0.1563625464348293", + "Likelihood: 0.12980739170248665", + "Likelihood: 0.05540608026367823", + "Likelihood: 0.006891317072621018", + "Likelihood: 0.23571018275978264", + "Likelihood: 0.32143709964127837", + "Likelihood: 0.21731384880167076", + "Likelihood: 0.02024260525840962", + "Likelihood: 0.024912778757500833", + "Likelihood: 0.20570015264662497", + "Likelihood: 0.23217768244711132", + "Likelihood: 0.14558384697334134", + "Likelihood: 0.2936573700550818", + "Likelihood: 0.11010312574112172", + "Likelihood: 0.2794041732167157", + "Likelihood: 0.09997040582015607", + "Likelihood: 0.14146770550069337", + "Likelihood: 0.14949017500071468", + "Likelihood: 0.25959116315753167", + "Likelihood: 0.17017685203916486", + "Likelihood: 0.2582180312790977", + "Likelihood: 0.2607511504308378", + "Likelihood: 0.1940459641802936", + "Likelihood: 0.034401506259649266", + "Likelihood: 0.17745625633033207", + "Likelihood: 0.2103742118347415", + "Likelihood: 0.09271008332512337", + "Likelihood: 0.23277207353139545", + "Likelihood: 0.035406593318874274", + "Likelihood: 0.1922682727127224", + "Likelihood: 0.00851129908845363", + "Likelihood: 0.08326834193552975", + "Likelihood: 0.27742042688606655", + "Likelihood: 0.03319004108163855", + "Likelihood: 0.11457311995357725", + "Likelihood: 0.10750274577715777", + "Likelihood: 0.09092483521499958", + "Likelihood: 0.10687658962394483", + "Likelihood: 0.05468273310517307", + "Likelihood: 0.021720167161855097", + "Likelihood: 0.04725070964449167", + "Likelihood: 0.07205162752298291", + "Likelihood: 0.09140540276131902", + "Likelihood: 0.11361126025668791", + "Likelihood: 0.3069313293967986", + "Likelihood: 0.19809724117803476", + "Likelihood: 0.21009726610712354", + "Likelihood: 0.06828009500759896", + "Likelihood: 0.2675215142598872", + "Likelihood: 0.1705002399274131", + "Likelihood: 0.31650288196562415", + "Likelihood: 0.08033909376665496", + "Likelihood: 0.27234134216613654", + "Likelihood: 0.26689158395685403", + "Likelihood: 0.15868824357716277", + "Likelihood: 0.07322111764843202", + "Likelihood: 0.29820826741389206", + "Likelihood: 0.04126253876680423", + "Likelihood: 0.14400523452028255", + "Likelihood: 0.0047972160876476695", + "Likelihood: 0.25475805715493294", + "Likelihood: 0.31120672156599616", + "Likelihood: 0.18226117659501004", + "Likelihood: 0.11711566817476596", + "Likelihood: 0.22775717516153865", + "Likelihood: 0.03757292397809907", + "Likelihood: 0.02012320950490989", + "Likelihood: 0.19214091609382802", + "Likelihood: 0.14029110720932395", + "Likelihood: 0.06691957409664359", + "Likelihood: 0.2639758814179168", + "Likelihood: 0.208147824259082", + "Likelihood: 0.02140034867715702", + "Likelihood: 0.11039854442651958", + "Likelihood: 0.21059596377293238", + "Likelihood: 0.02965112501298849", + "Likelihood: 0.07979100080083942", + "Likelihood: 0.15808295161644859", + "Likelihood: 0.2105934945573907", + "Likelihood: 0.15698240342802258", + "Likelihood: 0.2476094411467324", + "Likelihood: 0.13476370037427593", + "Likelihood: 0.13125243597265648", + "Likelihood: 0.21008156815759127", + "Likelihood: 0.02364246515558471", + "Likelihood: 0.023917976219436372", + "Likelihood: 0.09206620076250302", + "Likelihood: 0.15154147526645032", + "Likelihood: 0.035362091540294696", + "Likelihood: 0.08346407677642166", + "Likelihood: 0.2085069997184432", + "Likelihood: 0.2687580700965404", + "Likelihood: 0.03893853914272468", + "Likelihood: 0.06877718337994787", + "Likelihood: 0.004317475905587865", + "Likelihood: 0.2768870360448832", + "Likelihood: 0.15833931576908747", + "Likelihood: 0.2749835314336819", + "Likelihood: 0.09557135977579682", + "Likelihood: 0.16709337121119885", + "Likelihood: 0.20661166656638766", + "Likelihood: 0.11096402404294416", + "Likelihood: 0.028324266273224506", + "Likelihood: 0.19990358795998392", + "Likelihood: 0.002625163399267099", + "Likelihood: 0.20326387844769622", + "Likelihood: 0.21629277341319328", + "Likelihood: 0.20519533842968196", + "Likelihood: 0.30515196698965363", + "Likelihood: 0.216750536125592", + "Likelihood: 0.055081270772431565", + "Likelihood: 0.0919390900848464", + "Likelihood: 0.12436830095923553", + "Likelihood: 0.10950322459447448", + "Likelihood: 0.22087220628904516", + "Likelihood: 0.06911193016344762", + "Likelihood: 0.05875600813734538", + "Likelihood: 0.043405979228010046", + "Likelihood: 0.028875939298918588", + "Likelihood: 0.20728115620391996", + "Likelihood: 0.0664889926066232", + "Likelihood: 0.1954130218917373", + "Likelihood: 0.04931841837569984", + "Likelihood: 0.166985112650432", + "Likelihood: 0.19527859980923004", + "Likelihood: 0.218016999472748", + "Likelihood: 0.09009570346502702", + "Likelihood: 0.15065025484271174", + "Likelihood: 0.28595766751122453", + "Likelihood: 0.272437969259055", + "Likelihood: 0.3139397696172959", + "Likelihood: 0.03158120946619017", + "Likelihood: 0.013723392542419183", + "Likelihood: 0.060371107575977176", + "Likelihood: 0.04065652165216404", + "Likelihood: 0.24662719029456853", + "Likelihood: 0.2697790936871906", + "Likelihood: 0.2812567512289653", + "Likelihood: 0.13935379242120285", + "Likelihood: 0.07179330136533568", + "Likelihood: 0.2521599343685908", + "Likelihood: 0.11694633602728224", + "Likelihood: 0.015689289768155968", + "Likelihood: 0.23825255765165645", + "Likelihood: 0.1400965993405384", + "Likelihood: 0.058487193220690334", + "Likelihood: 0.19782084941763778", + "Likelihood: 0.30514739826859094", + "Likelihood: 0.13778516310626054", + "Likelihood: 0.06260611196470736", + "Likelihood: 0.27587660364541877", + "Likelihood: 0.09193822617623665", + "Likelihood: 0.1489556435244977", + "Likelihood: 0.06550718386266008", + "Likelihood: 0.22622531105441707", + "Likelihood: 0.29842166152319854", + "Likelihood: 0.07674206340979263", + "Likelihood: 0.04935678547455577", + "Likelihood: 0.18827161373547946", + "Likelihood: 0.004726176869760197", + "Likelihood: 0.10599999374555992", + "Likelihood: 0.24079919993209611", + "Likelihood: 0.11877337943731849", + "Likelihood: 0.011074860679057351", + "Likelihood: 0.1256507342733128", + "Likelihood: 0.23745010856366502", + "Likelihood: 0.21497570589620296", + "Likelihood: 0.1777074486351679", + "Likelihood: 0.2778289094936174", + "Likelihood: 0.319163151658687", + "Likelihood: 0.04671906811841161", + "Likelihood: 0.24532406803528015", + "Likelihood: 0.009918613350459717", + "Likelihood: 0.12705502090412077", + "Likelihood: 0.0895670772390444", + "Likelihood: 0.27964857207906063", + "Likelihood: 0.24951031700613124", + "Likelihood: 0.28833047891837715", + "Likelihood: 0.08132725984423979", + "Likelihood: 0.21861553867456085", + "Likelihood: 0.05026015486824147", + "Likelihood: 0.0954008128333171", + "Likelihood: 0.09988933988390353", + "Likelihood: 0.2002740548697938", + "Likelihood: 0.07738584614085757", + "Likelihood: 0.03694444612827588", + "Likelihood: 0.20146199179416463", + "Likelihood: 0.0862156283627414", + "Likelihood: 0.261590725359016", + "Likelihood: 0.08631882051231554", + "Likelihood: 0.22390871992967865", + "Likelihood: 0.10887489684979171", + "Likelihood: 0.0032541425234557646", + "Likelihood: 0.19252587204636554", + "Likelihood: 0.1332047921987199", + "Likelihood: 0.27935258547189196", + "Likelihood: 0.29425964681115957", + "Likelihood: 0.3223664269930873", + "Likelihood: 0.05847227363667512", + "Likelihood: 0.07970583532816639", + "Likelihood: 0.24254586731851477", + "Likelihood: 0.12651951492459781", + "Likelihood: 0.2525508002808903", + "Likelihood: 0.06944064657529418", + "Likelihood: 0.10393722849391958", + "Likelihood: 0.17872043677659782", + "Likelihood: 0.0174799829257536", + "Likelihood: 0.2825469481104415", + "Likelihood: 0.10991066383516579", + "Likelihood: 0.14148694467301756", + "Likelihood: 0.018703623911508763", + "Likelihood: 0.03197018296068721", + "Likelihood: 0.30532660205194856", + "Likelihood: 0.03131187576319525", + "Likelihood: 0.21616158105412814", + "Likelihood: 0.18769999032462586", + "Likelihood: 0.11129237993609466", + "Likelihood: 0.21521905516268222", + "Likelihood: 0.19827996839402615", + "Likelihood: 0.10141338791547412", + "Likelihood: 0.2643867104653616", + "Likelihood: 0.1094980990839153", + "Likelihood: 0.04243724859037626", + "Likelihood: 0.11908474709939319", + "Likelihood: 0.04891691829051669", + "Likelihood: 0.17349408308143835", + "Likelihood: 0.16438193927979386", + "Likelihood: 0.16516734409990863", + "Likelihood: 0.0941750566809898", + "Likelihood: 0.15361741057560663", + "Likelihood: 0.07283988515734226", + "Likelihood: 0.1250241221868541", + "Likelihood: 0.056680920051566", + "Likelihood: 0.08666264912732262", + "Likelihood: 0.15511978958084324", + "Likelihood: 0.32325963779949524", + "Likelihood: 0.2975333407446941", + "Likelihood: 0.03463240656920151", + "Likelihood: 0.2195935784535235", + "Likelihood: 0.24900494679491422", + "Likelihood: 0.1392699240186077", + "Likelihood: 0.07159144366069907", + "Likelihood: 0.15851595252555398", + "Likelihood: 0.2206257205122031", + "Likelihood: 0.17353256304156556", + "Likelihood: 0.010466896845686609", + "Likelihood: 0.08654200604460417", + "Likelihood: 0.06707563539770305", + "Likelihood: 0.22298217027019052", + "Likelihood: 0.06300363724026181", + "Likelihood: 0.24994935948933517", + "Likelihood: 0.19676793225165268", + "Likelihood: 0.1770037999542928", + "Likelihood: 0.15618801661063209", + "Likelihood: 0.11976318005089398", + "Likelihood: 0.15661557950747268", + "Likelihood: 0.2733918862871629", + "Likelihood: 0.09578796332534645", + "Likelihood: 0.05434168447315235", + "Likelihood: 0.04134456174545046", + "Likelihood: 0.2100305473688497", + "Likelihood: 0.07422354129177207", + "Likelihood: 0.09024569069877596", + "Likelihood: 0.06802562528183602", + "Likelihood: 0.20114208254131744", + "Likelihood: 0.05396663687478327", + "Likelihood: 0.2111185218936651", + "Likelihood: 0.2965659022630742", + "Likelihood: 0.26592795992934815", + "Likelihood: 0.056976809212110624", + "Likelihood: 0.10534213045395595", + "Likelihood: 0.04554946073272281", + "Likelihood: 0.17530782478013615", + "Likelihood: 0.22311706069860568", + "Likelihood: 0.033106328202969305", + "Likelihood: 0.1500022087793055", + "Likelihood: 0.1627454693359542", + "Likelihood: 0.13027911910055226", + "Likelihood: 0.15837835587302335", + "Likelihood: 0.16623268688690518", + "Likelihood: 0.09296233762215475", + "Likelihood: 0.25826878548891674", + "Likelihood: 0.07072675438103883", + "Likelihood: 0.31467680944667364", + "Likelihood: 0.2622532040308649", + "Likelihood: 0.059878883402762144", + "Likelihood: 0.0694028318249895", + "Likelihood: 0.13988692911609743", + "Likelihood: 0.23898483019234842", + "Likelihood: 0.2968057924795872", + "Likelihood: 0.022408290658250913", + "Likelihood: 0.10155785743511796", + "Likelihood: 0.209097077553315", + "Likelihood: 0.053622246990535374", + "Likelihood: 0.023098568790740716", + "Likelihood: 0.2140901945843001", + "Likelihood: 0.11349253648556024", + "Likelihood: 0.06990067244716139", + "Likelihood: 0.32108799784174236", + "Likelihood: 0.07665648735189717", + "Likelihood: 0.22207497419406486", + "Likelihood: 0.2588596049895245", + "Likelihood: 0.16734446924934993", + "Likelihood: 0.10036397705228874", + "Likelihood: 0.1707684305426654", + "Likelihood: 0.1759863169110055", + "Likelihood: 0.2164804013408232", + "Likelihood: 0.27983298319689376", + "Likelihood: 0.2594341836696699", + "Likelihood: 0.0033549228933689476", + "Likelihood: 0.13071345663369877", + "Likelihood: 0.16099115971136171", + "Likelihood: 0.23482682447971992", + "Likelihood: 0.0701368556619368", + "Likelihood: 0.21319788169752757", + "Likelihood: 0.13565264243398376", + "Likelihood: 0.28085281053128874", + "Likelihood: 0.22688446783275135", + "Likelihood: 0.1433963065600874", + "Likelihood: 0.23869633826775916", + "Likelihood: 0.24661733676194303", + "Likelihood: 0.06683408198399833", + "Likelihood: 0.32212686501511195", + "Likelihood: 0.155283278792899", + "Likelihood: 0.05418324087558911", + "Likelihood: 0.04925360594595951", + "Likelihood: 0.31865005252174095", + "Likelihood: 0.14330966613494228", + "Likelihood: 0.14561863630981775", + "Likelihood: 0.27399713554159816", + "Likelihood: 0.2615795527939423", + "Likelihood: 0.19459655467437068", + "Likelihood: 0.2777710146757132", + "Likelihood: 0.1151959824446337", + "Likelihood: 0.04937104120144556", + "Likelihood: 0.017934008861104023", + "Likelihood: 0.24680349233878085", + "Likelihood: 0.025053410059846386", + "Likelihood: 0.12175133021948499", + "Likelihood: 0.306816990335239", + "Likelihood: 0.09016380459091906", + "Likelihood: 0.12872670440855138", + "Likelihood: 0.032429876431466914", + "Likelihood: 0.24336586309708544", + "Likelihood: 0.02487250905305853", + "Likelihood: 0.062134291881366134", + "Likelihood: 0.29269367879590313", + "Likelihood: 0.052543574161261965", + "Likelihood: 0.08524011333085756", + "Likelihood: 0.1453462966690393", + "Likelihood: 0.023916878605452885", + "Likelihood: 0.26227240310241834", + "Likelihood: 0.14668135271455257", + "Likelihood: 0.026370217028023987", + "Likelihood: 0.20444384199182014", + "Likelihood: 0.09462701613347302", + "Likelihood: 0.0766024456284141", + "Likelihood: 0.24006725228162906", + "Likelihood: 0.040414562824117935", + "Likelihood: 0.11251260896357711", + "Likelihood: 0.09549650527494685", + "Likelihood: 0.19458142755535565", + "Likelihood: 0.18990762278748305", + "Likelihood: 0.2711606444958198", + "Likelihood: 0.254433774073057", + "Likelihood: 0.13320224010026788", + "Likelihood: 0.15935608197977455", + "Likelihood: 0.24784180936940484", + "Likelihood: 0.007063940641053073", + "Likelihood: 0.18244496610476282", + "Likelihood: 0.26005222705007897", + "Likelihood: 0.2894705758529006", + "Likelihood: 0.19921342117575302", + "Likelihood: 0.18662866936077452", + "Likelihood: 0.19391358092229843", + "Likelihood: 0.02307624603679313", + "Likelihood: 0.19472975439082002", + "Likelihood: 0.016577620273254004", + "Likelihood: 0.10750146374553729", + "Likelihood: 0.04536123850946084", + "Likelihood: 0.05718052394784842", + "Likelihood: 0.24221112060957967", + "Likelihood: 0.19970755754395075", + "Likelihood: 0.29792503939841214", + "Likelihood: 0.0029405471408439857", + "Likelihood: 0.184365890341908", + "Likelihood: 0.20914915771836942", + "Likelihood: 0.29578492123476585", + "Likelihood: 0.22368678377561563", + "Likelihood: 0.10248339568650283", + "Likelihood: 0.17236953324301363", + "Likelihood: 0.017325504162680142", + "Likelihood: 0.27711237603762034", + "Likelihood: 0.0691222001577861", + "Likelihood: 0.04353532200155048", + "Likelihood: 0.10882767311775406", + "Likelihood: 0.08266585544728605", + "Likelihood: 0.19693887319488185", + "Likelihood: 0.1784809174738944", + "Likelihood: 0.09648335039159876", + "Likelihood: 0.093455428203795", + "Likelihood: 0.29914259688552053", + "Likelihood: 0.16442961299593586", + "Likelihood: 0.2919343409774493", + "Likelihood: 0.0077983513568743645", + "Likelihood: 0.05156785112124006", + "Likelihood: 0.17938749883416763", + "Likelihood: 0.027787701515850655", + "Likelihood: 0.12827631144538307", + "Likelihood: 0.11221748792926727", + "Likelihood: 0.06594506865999868", + "Likelihood: 0.1010835011060415", + "Likelihood: 0.09326423568949326", + "Likelihood: 0.16085064098893526", + "Likelihood: 0.23959695906666892", + "Likelihood: 0.09358322714594634", + "Likelihood: 0.1638126310778908", + "Likelihood: 0.21904293259689972", + "Likelihood: 0.10404950804217872", + "Likelihood: 0.13333352655586392", + "Likelihood: 0.24616465759269937", + "Likelihood: 0.28294700591468064", + "Likelihood: 0.14001996604436467", + "Likelihood: 0.029948282387481154", + "Likelihood: 0.1704713320130741", + "Likelihood: 0.2165465592460891", + "Likelihood: 0.3080500693446403", + "Likelihood: 0.2405573870248584", + "Likelihood: 0.2665854278359214", + "Likelihood: 0.2753008550965409", + "Likelihood: 0.2235215573369762", + "Likelihood: 0.2586234477098668", + "Likelihood: 0.23305417343357127", + "Likelihood: 0.09101016714551508", + "Likelihood: 0.2560083217538093", + "Likelihood: 0.20556319868939052", + "Likelihood: 0.2212038926178159", + "Likelihood: 0.05149599291429548", + "Likelihood: 0.2935021831636647", + "Likelihood: 0.1947353333802959", + "Likelihood: 0.17134305685133516", + "Likelihood: 0.045182525988193355", + "Likelihood: 0.13125332363079364", + "Likelihood: 0.004168359417385088", + "Likelihood: 0.012345847002295908", + "Likelihood: 0.29563897276578927", + "Likelihood: 0.09949244341593967", + "Likelihood: 0.06082866044871284", + "Likelihood: 0.0020646978655663325", + "Likelihood: 0.1465711428197996", + "Likelihood: 0.1406437405416253", + "Likelihood: 0.2783359280495716", + "Likelihood: 0.20197208027356", + "Likelihood: 0.3034878447815952", + "Likelihood: 0.178838073202521", + "Likelihood: 0.030016839956771627", + "Likelihood: 0.18488256796104754", + "Likelihood: 0.24357259962333486", + "Likelihood: 0.18108032470267882", + "Likelihood: 0.32003990291144124", + "Likelihood: 0.2464236574327885", + "Likelihood: 0.07982157763715712", + "Likelihood: 0.19278871713089638", + "Likelihood: 0.1718802204142227", + "Likelihood: 0.03047338254694096", + "Likelihood: 0.05690091396223237", + "Likelihood: 0.01597370907848816", + "Likelihood: 0.010321678675423848", + "Likelihood: 0.2767075918434004", + "Likelihood: 0.2922496459106174", + "Likelihood: 0.2661004206785118", + "Likelihood: 0.11618426212404925", + "Likelihood: 0.19722844070373113", + "Likelihood: 0.20304687594601561", + "Likelihood: 0.16971160437714342", + "Likelihood: 0.26449179788408855", + "Likelihood: 0.19476138426102255", + "Likelihood: 0.07837327249692579", + "Likelihood: 0.1252137795209896", + "Likelihood: 0.2896455103403659", + "Likelihood: 0.036006150888931464", + "Likelihood: 0.00969718044720563", + "Likelihood: 0.05290896546538171", + "Likelihood: 0.09733658148519761", + "Likelihood: 0.1313549767460562", + "Likelihood: 0.09482350492613038", + "Likelihood: 0.280996850183214", + "Likelihood: 0.14176197520329276", + "Likelihood: 0.10357514254647229", + "Likelihood: 0.036048275734567405", + "Likelihood: 0.18513064551724528", + "Likelihood: 0.010197245175223489", + "Likelihood: 0.2065779985017766", + "Likelihood: 0.047397203401226884", + "Likelihood: 0.16681555671617393", + "Likelihood: 0.025055949485654268", + "Likelihood: 0.1766156627680464", + "Likelihood: 0.12612366981290787", + "Likelihood: 0.05173998819760383", + "Likelihood: 0.193340302808469", + "Likelihood: 0.18185060812136716", + "Likelihood: 0.12504480193032705", + "Likelihood: 0.16878056820520895", + "Likelihood: 0.03785336057337525", + "Likelihood: 0.016030706172907496", + "Likelihood: 0.0447904645858992", + "Likelihood: 0.12895903292834168", + "Likelihood: 0.07218925637141202", + "Likelihood: 0.04417364907187509", + "Likelihood: 0.1440391887921619", + "Likelihood: 0.08850934007461059", + "Likelihood: 0.017011068588304225", + "Likelihood: 0.17125115059749207", + "Likelihood: 0.21360522753570016", + "Likelihood: 0.012392318476747289", + "Likelihood: 0.24334431463451275", + "Likelihood: 0.30814551451540195", + "Likelihood: 0.16844489550101283", + "Likelihood: 0.16260466062828105", + "Likelihood: 0.24024919401161143", + "Likelihood: 0.29120258585277997", + "Likelihood: 0.03316882941425265", + "Likelihood: 0.1852453132543558", + "Likelihood: 0.019778258076019947", + "Likelihood: 0.19655581476848258", + "Likelihood: 0.178447529209965", + "Likelihood: 0.09041280139243363", + "Likelihood: 0.15912089365463897", + "Likelihood: 0.05048422386343573", + "Likelihood: 0.0865279902709634", + "Likelihood: 0.04350463729176894", + "Likelihood: 0.1406678929902689", + "Likelihood: 0.2076560321811661", + "Likelihood: 0.1961873938459254", + "Likelihood: 0.08083484936692305", + "Likelihood: 0.06697009796981507", + "Likelihood: 0.037601304797340494", + "Likelihood: 0.032205653060328555", + "Likelihood: 0.13838451930639206", + "Likelihood: 0.17408019943168948", + "Likelihood: 0.045253895999163664", + "Likelihood: 0.05459820369816108", + "Likelihood: 0.069600287202832", + "Likelihood: 0.1043255528285284", + "Likelihood: 0.18187346768845086", + "Likelihood: 0.2922044727753451", + "Likelihood: 0.1953946298951597", + "Likelihood: 0.1940036550073875", + "Likelihood: 0.08651236135758493", + "Likelihood: 0.23552349261353187", + "Likelihood: 0.051186367392744", + "Likelihood: 0.13725218333066758", + "Likelihood: 0.3162810819303398", + "Likelihood: 0.14214038383364663", + "Likelihood: 0.2604850080176812", + "Likelihood: 0.2848780921040411", + "Likelihood: 0.028384466734436436", + "Likelihood: 0.020690995574330538", + "Likelihood: 0.019767113820587795", + "Likelihood: 0.23990563418084423", + "Likelihood: 0.16050085099555034", + "Likelihood: 0.21328410513218837", + "Likelihood: 0.18798546899905974", + "Likelihood: 0.2590651290061526", + "Likelihood: 0.22949822133728348", + "Likelihood: 0.31317438833029376", + "Likelihood: 0.1661070905137651", + "Likelihood: 0.24398009899805126", + "Likelihood: 0.017592068223328556", + "Likelihood: 0.27293204225435475", + "Likelihood: 0.08898114358085685", + "Likelihood: 0.06826610170693", + "Likelihood: 0.20775212125268722", + "Likelihood: 0.24996064859413641", + "Likelihood: 0.17955957428931102", + "Likelihood: 0.26785729610408393", + "Likelihood: 0.09029673985316893", + "Likelihood: 0.18321529732327388", + "Likelihood: 0.2057721078950934", + "Likelihood: 0.04536261651276833", + "Likelihood: 0.17364458577686684", + "Likelihood: 0.1489950232515898", + "Likelihood: 0.21384856722973863", + "Likelihood: 0.07737341044096782", + "Likelihood: 0.023844864406640486", + "Likelihood: 0.22683286015745058", + "Likelihood: 0.1292211977882412", + "Likelihood: 0.04169435755394817", + "Likelihood: 0.2916535673298963", + "Likelihood: 0.2717399128135376", + "Likelihood: 0.003414028015648644", + "Likelihood: 0.1849183381830735", + "Likelihood: 0.24254406578305676", + "Likelihood: 0.13175728498937342", + "Likelihood: 0.06021265221794055", + "Likelihood: 0.2925713058425434", + "Likelihood: 0.09177176935399506", + "Likelihood: 0.1272447005344317", + "Likelihood: 0.04844747717907579", + "Likelihood: 0.23454246983392932", + "Likelihood: 0.0401503516781159", + "Likelihood: 0.05543146208892015", + "Likelihood: 0.1094418814785909", + "Likelihood: 0.03802207674814082", + "Likelihood: 0.10909943749042425", + "Likelihood: 0.022888071243956604", + "Likelihood: 0.25050200675464984", + "Likelihood: 0.053100363489543737", + "Likelihood: 0.12943766981053764", + "Likelihood: 0.1409389404843201", + "Likelihood: 0.21095615473934404", + "Likelihood: 0.2632446181620843", + "Likelihood: 0.03934992512413706", + "Likelihood: 0.24345192360762816", + "Likelihood: 0.3182870046933624", + "Likelihood: 0.2595134949773875", + "Likelihood: 0.24271985962631695", + "Likelihood: 0.047750543063613336", + "Likelihood: 0.3031962972162401", + "Likelihood: 0.07429613955967852", + "Likelihood: 0.10647927739908757", + "Likelihood: 0.2538048511913272", + "Likelihood: 0.11718144876262086", + "Likelihood: 0.21210428942159748", + "Likelihood: 0.2547425180889467", + "Likelihood: 0.05787330276070248", + "Likelihood: 0.19296492505233634", + "Likelihood: 0.03561617494639305", + "Likelihood: 0.168366155013624", + "Likelihood: 0.14947424749832025", + "Likelihood: 0.19103561930019686", + "Likelihood: 0.04939537206030004", + "Likelihood: 0.00207877108206773", + "Likelihood: 0.1612270943173625", + "Likelihood: 0.06404570861301558", + "Likelihood: 0.05834044849162826", + "Likelihood: 0.26287006197243107", + "Likelihood: 0.04403861344201299", + "Likelihood: 0.31233396538101366", + "Likelihood: 0.2840076302970903", + "Likelihood: 0.18325680534318894", + "Likelihood: 0.20330421341341723", + "Likelihood: 0.01988107116921178", + "Likelihood: 0.05324807793488442", + "Likelihood: 0.25299939088151163", + "Likelihood: 0.2028515260626711", + "Likelihood: 0.18707311031916368", + "Likelihood: 0.06002587105424368", + "Likelihood: 0.15364888413575462", + "Likelihood: 0.16365435582992088", + "Likelihood: 0.2406594439892895", + "Likelihood: 0.30893151644482003", + "Likelihood: 0.17856603095682777", + "Likelihood: 0.047065299898151225", + "Likelihood: 0.08921698728068687", + "Likelihood: 0.14122477895286992", + "Likelihood: 0.23052782469436423", + "Likelihood: 0.3080802399558309", + "Likelihood: 0.21813892800329837", + "Likelihood: 0.30134671132681157", + "Likelihood: 0.08433206354528441", + "Likelihood: 0.03912135059145844", + "Likelihood: 0.16762171567815268", + "Likelihood: 0.32415117575961067", + "Likelihood: 0.23186694316458195", + "Likelihood: 0.10203927095145404", + "Likelihood: 0.1968238899918459", + "Likelihood: 0.1444424259879095", + "Likelihood: 0.0350534308733113", + "Likelihood: 0.2679026986368898", + "Likelihood: 0.21963192782017205", + "Likelihood: 0.1775490463330152", + "Likelihood: 0.3091785694414404", + "Likelihood: 0.24806577579035133", + "Likelihood: 0.24171037587646807", + "Likelihood: 0.2790047640485742", + "Likelihood: 0.08398276869471025", + "Likelihood: 0.27111775862714355", + "Likelihood: 0.07211145783377503", + "Likelihood: 0.23756249338427654", + "Likelihood: 0.1254547822418057", + "Likelihood: 0.019710467555221076", + "Likelihood: 0.08680266105373748", + "Likelihood: 0.30375305474282355", + "Likelihood: 0.21529044079895324", + "Likelihood: 0.13304876427072157", + "Likelihood: 0.19444553005317927", + "Likelihood: 0.05239562999206824", + "Likelihood: 0.09524208135726844", + "Likelihood: 0.055330673789913694", + "Likelihood: 0.040337445534063515", + "Likelihood: 0.059366366395610375", + "Likelihood: 0.19763277227420878", + "Likelihood: 0.25042775065220074", + "Likelihood: 0.25984719057620664", + "Likelihood: 0.0011414902487738765", + "Likelihood: 0.19363078214612248", + "Likelihood: 0.05422246659582356", + "Likelihood: 0.25431637880218744", + "Likelihood: 0.11667564159703628", + "Likelihood: 0.07168391323111109", + "Likelihood: 0.15185245121061425", + "Likelihood: 0.040017284535356815", + "Likelihood: 0.1311709786715032", + "Likelihood: 0.029556885463892374", + "Likelihood: 0.2931054742142504", + "Likelihood: 0.05799979472935344", + "Likelihood: 0.10625413268102347", + "Likelihood: 0.273035761073767", + "Likelihood: 0.1254700790233716", + "Likelihood: 0.11659986604328344", + "Likelihood: 0.11440245075270977", + "Likelihood: 0.036668383207299746", + "Likelihood: 0.1013862352180302", + "Likelihood: 0.16338301601186533", + "Likelihood: 0.10173434728790048", + "Likelihood: 0.2635034134915153", + "Likelihood: 0.19719237454573185", + "Likelihood: 0.07405317639475091", + "Likelihood: 0.18505163652044668", + "Likelihood: 0.013931732605568035", + "Likelihood: 0.01835119002468043", + "Likelihood: 0.08839980484914255", + "Likelihood: 0.10734657172002783", + "Likelihood: 0.2790052782363265", + "Likelihood: 0.2969357280807069", + "Likelihood: 0.05050981174164169", + "Likelihood: 0.16204710497267272", + "Likelihood: 0.018474694234647256", + "Likelihood: 0.20497909263430092", + "Likelihood: 0.15411110550186424", + "Likelihood: 0.2696110261967548", + "Likelihood: 0.12712433270233994", + "Likelihood: 0.17365442283973515", + "Likelihood: 0.25373624545461904", + "Likelihood: 0.12324604493730355", + "Likelihood: 0.09498593157480716", + "Likelihood: 0.08488741131230572", + "Likelihood: 0.09009663236572261", + "Likelihood: 0.20294066174129247", + "Likelihood: 0.07592329505602798", + "Likelihood: 0.06771657102155672", + "Likelihood: 0.16979075413846775", + "Likelihood: 0.13207610348090937", + "Likelihood: 0.24867440690143625", + "Likelihood: 0.05398585111190434", + "Likelihood: 0.09080586437881936", + "Likelihood: 0.06645881061201651", + "Likelihood: 0.13619578097897336", + "Likelihood: 0.2511370779866724", + "Likelihood: 0.026424747789094892", + "Likelihood: 0.3208152821344131", + "Likelihood: 0.21702390797970467", + "Likelihood: 0.19666836929378373", + "Likelihood: 0.08309094063159654", + "Likelihood: 0.11422125564296555", + "Likelihood: 0.07586741210114697", + "Likelihood: 0.21721196046821972", + "Likelihood: 0.1488396076970617", + "Likelihood: 0.2789652214602697", + "Likelihood: 0.08267174765982938", + "Likelihood: 0.3161189828472671", + "Likelihood: 0.061220803789664914", + "Likelihood: 0.25942085119982133", + "Likelihood: 0.27636852389973576", + "Likelihood: 0.02380553415159517", + "Likelihood: 0.23362470851046105", + "Likelihood: 0.30249258803717866", + "Likelihood: 0.10612282967173138", + "Likelihood: 0.059082465186918655", + "Likelihood: 0.10057255215603209", + "Likelihood: 0.11388162268975692", + "Likelihood: 0.01632484900589689", + "Likelihood: 0.18812938181013614", + "Likelihood: 0.1985754290698123", + "Likelihood: 0.07907146290405583", + "Likelihood: 0.1044137021871511", + "Likelihood: 0.30506363136330766", + "Likelihood: 0.16960237897593955", + "Likelihood: 0.15207561157102298", + "Likelihood: 0.1659353312126974", + "Likelihood: 0.1477119732358105", + "Likelihood: 0.20972139892999403", + "Likelihood: 0.18589661190511528", + "Likelihood: 0.0564413293677911", + "Likelihood: 0.2509822202311551", + "Likelihood: 0.07306140947088874", + "Likelihood: 0.16769559130752834", + "Likelihood: 0.30184721511538437", + "Likelihood: 0.14829291280263243", + "Likelihood: 0.13134345567860345", + "Likelihood: 0.20647675797616782", + "Likelihood: 0.24657885093007412", + "Likelihood: 0.0413520204117196", + "Likelihood: 0.0599263589576732", + "Likelihood: 0.19611215103816493", + "Likelihood: 0.047043113067791756", + "Likelihood: 0.24276876719917911", + "Likelihood: 0.13869579808743085", + "Likelihood: 0.009013804858064378", + "Likelihood: 0.039802941234309185", + "Likelihood: 0.08816366699114912", + "Likelihood: 0.04950107913171409", + "Likelihood: 0.052107496433270444", + "Likelihood: 0.2643789825518892", + "Likelihood: 0.09933073431006847", + "Likelihood: 0.0806618142855531", + "Likelihood: 0.24434549609871364", + "Likelihood: 0.16681546005148082", + "Likelihood: 0.01642358749738109", + "Likelihood: 0.18357916618899675", + "Likelihood: 0.3227473367357342", + "Likelihood: 0.06239500659822258", + "Likelihood: 0.05019984641204454", + "Likelihood: 0.20570413829024206", + "Likelihood: 0.30748035797873446", + "Likelihood: 0.04098039313253422", + "Likelihood: 0.15455530743822174", + "Likelihood: 0.02709744754498464", + "Likelihood: 0.005740925557824203", + "Likelihood: 0.22298204299623856", + "Likelihood: 0.06927546698059169", + "Likelihood: 0.23955098903624458", + "Likelihood: 0.029791326426943533", + "Likelihood: 0.2386212594015335", + "Likelihood: 0.005538770585229066", + "Likelihood: 0.19985928456115454", + "Likelihood: 0.058772906612582956", + "Likelihood: 0.2098115501572896", + "Likelihood: 0.23419123276436063", + "Likelihood: 0.23330091266784217", + "Likelihood: 0.10493045080608962", + "Likelihood: 0.09582679945095679", + "Likelihood: 0.02340854647775694", + "Likelihood: 0.21456116862687352", + "Likelihood: 0.29227291221690993", + "Likelihood: 0.2761932379595184", + "Likelihood: 0.14692293213393895", + "Likelihood: 0.12139475239045198", + "Likelihood: 0.16221987523546447", + "Likelihood: 0.26485929219672855", + "Likelihood: 0.19546814511756952", + "Likelihood: 0.22616783507068133", + "Likelihood: 0.06804178863323382", + "Likelihood: 0.18866346444235915", + "Likelihood: 0.025808746341856575", + "Likelihood: 0.04787332371728277", + "Likelihood: 0.14268477262436224", + "Likelihood: 0.11707715750661511", + "Likelihood: 0.10143400354644408", + "Likelihood: 0.266555950410028", + "Likelihood: 0.15343716244749842", + "Likelihood: 0.07813294351648514", + "Likelihood: 0.010430262957327359", + "Likelihood: 0.10411916281119044", + "Likelihood: 0.033469198001118985", + "Likelihood: 0.17302383855957956", + "Likelihood: 0.06998426577705107", + "Likelihood: 0.06522008099667849", + "Likelihood: 0.32224101283632745", + "Likelihood: 0.1294972557942411", + "Likelihood: 0.3119086175051279", + "Likelihood: 0.2747133673164904", + "Likelihood: 0.21238900408996728", + "Likelihood: 0.12176935588382277", + "Likelihood: 0.0738794702526578", + "Likelihood: 0.13951985140881465", + "Likelihood: 0.034637168513945105", + "Likelihood: 0.03146382430932738", + "Likelihood: 0.25356824825251906", + "Likelihood: 0.05945875075791529", + "Likelihood: 0.23423542065262595", + "Likelihood: 0.24655225410358314", + "Likelihood: 0.24027418280838023", + "Likelihood: 0.2096296756666013", + "Likelihood: 0.11413268395916158", + "Likelihood: 0.07243392135083943", + "Likelihood: 0.11227966342062604", + "Likelihood: 0.13431411755533967", + "Likelihood: 0.07290814675693698", + "Likelihood: 0.12070821085201104", + "Likelihood: 0.03504621993744241", + "Likelihood: 0.06064709977873582", + "Likelihood: 0.2356415516196298", + "Likelihood: 0.16562147607173977", + "Likelihood: 0.014829202385980136", + "Likelihood: 0.1779076242812238", + "Likelihood: 0.16424854516071988", + "Likelihood: 0.15763897539653424", + "Likelihood: 0.21814554206486034", + "Likelihood: 0.3194264555736467", + "Likelihood: 0.2788347146780925", + "Likelihood: 0.3223840203663431", + "Likelihood: 0.1942047355372466", + "Likelihood: 0.2813011475419609", + "Likelihood: 0.0936377390581825", + "Likelihood: 0.1330297010709277", + "Likelihood: 0.28473271715085924", + "Likelihood: 0.007399697977409521", + "Likelihood: 0.04065068030683999", + "Likelihood: 0.01799305033632992", + "Likelihood: 0.18373661383470913", + "Likelihood: 0.30829273650970673", + "Likelihood: 0.04905323467340019", + "Likelihood: 0.044505594401712444", + "Likelihood: 0.1546950803842874", + "Likelihood: 0.20031047993353665", + "Likelihood: 0.2598995488764196", + "Likelihood: 0.21245998291494925", + "Likelihood: 0.046535472046024075", + "Likelihood: 0.22943406527409155", + "Likelihood: 0.017926510871029477", + "Likelihood: 0.31644873601003576", + "Likelihood: 0.21584198399633994", + "Likelihood: 0.20745114139022597", + "Likelihood: 0.14760059053384453", + "Likelihood: 0.04002488553680977", + "Likelihood: 0.16414451317883177", + "Likelihood: 0.1423806252435174", + "Likelihood: 0.0994708158897513", + "Likelihood: 0.24659122728414398", + "Likelihood: 0.2705113212395764", + "Likelihood: 0.25621395678167197", + "Likelihood: 0.013403938311359793", + "Likelihood: 0.050433382493201215", + "Likelihood: 0.1710937113885312", + "Likelihood: 0.02634742576419027", + "Likelihood: 0.15297150817000948", + "Likelihood: 0.10897948806969747", + "Likelihood: 0.11066951933211161", + "Likelihood: 0.2201373569276441", + "Likelihood: 0.24502326607368216", + "Likelihood: 0.11764478202141265", + "Likelihood: 0.24743663143485511", + "Likelihood: 0.18171094739568427", + "Likelihood: 0.1844487464871674", + "Likelihood: 0.18867149117770163", + "Likelihood: 0.12517514944401653", + "Likelihood: 0.1625562044275287", + "Likelihood: 0.007682612849725105", + "Likelihood: 0.192776386832435", + "Likelihood: 0.2590062506317009", + "Likelihood: 0.23825354317950073", + "Likelihood: 0.24750283727693118", + "Likelihood: 0.20941584835029925", + "Likelihood: 0.1479603037639854", + "Likelihood: 0.19099024282948482", + "Likelihood: 0.13721409175134022", + "Likelihood: 0.30350171081605437", + "Likelihood: 0.06022923474158729", + "Likelihood: 0.039102350460951084", + "Likelihood: 0.0357738032500437", + "Likelihood: 0.12090406289514277", + "Likelihood: 0.17420038748327993", + "Likelihood: 0.3226281228958755", + "Likelihood: 0.1239712061180854", + "Likelihood: 0.13721432948748996", + "Likelihood: 0.04085683925250503", + "Likelihood: 0.21312821988724015", + "Likelihood: 0.06561126728077868", + "Likelihood: 0.21808702769101948", + "Likelihood: 0.22250771967706032", + "Likelihood: 0.2097690054743992", + "Likelihood: 0.19476342624097553", + "Likelihood: 0.04711882944878688", + "Likelihood: 0.1646108930047375", + "Likelihood: 0.22927854084826246", + "Likelihood: 0.13494942913618393", + "Likelihood: 0.061625525861580335", + "Likelihood: 0.006788640275316281", + "Likelihood: 0.10483364089048237", + "Likelihood: 0.15467341099583704", + "Likelihood: 0.00874550744512288", + "Likelihood: 0.07679977248058471", + "Likelihood: 0.07189355894324455", + "Likelihood: 0.17086516579705832", + "Likelihood: 0.13442479437461244", + "Likelihood: 0.11724638858227829", + "Likelihood: 0.21641629666069487", + "Likelihood: 0.024487380479330238", + "Likelihood: 0.24021856394512178", + "Likelihood: 0.09360277275415596", + "Likelihood: 0.27641452974329805", + "Likelihood: 0.038486749376556294", + "Likelihood: 0.033961827153138245", + "Likelihood: 0.1396566725652269", + "Likelihood: 0.12883591788465862", + "Likelihood: 0.004303176460485466", + "Likelihood: 0.10028045782422723", + "Likelihood: 0.2204697596972189", + "Likelihood: 0.09296592469485086", + "Likelihood: 0.15651824007236795", + "Likelihood: 0.20775664318727877", + "Likelihood: 0.02322288327729164", + "Likelihood: 0.2595895126967374", + "Likelihood: 0.30886352315630755", + "Likelihood: 0.29874284385796446", + "Likelihood: 0.13577041798761716", + "Likelihood: 0.19124294067858044", + "Likelihood: 0.007128119986339611", + "Likelihood: 0.03936636443101732", + "Likelihood: 0.1625720039881789", + "Likelihood: 0.28886440117259427", + "Likelihood: 0.21704132840163562", + "Likelihood: 0.10609490706772964", + "Likelihood: 0.31361344764709803", + "Likelihood: 0.14190697034971858", + "Likelihood: 0.06547734491113769", + "Likelihood: 0.09282261603255873", + "Likelihood: 0.17579120757590483", + "Likelihood: 0.11291998279409388", + "Likelihood: 0.21747462058794423", + "Likelihood: 0.04631350065778329", + "Likelihood: 0.25419858595238337", + "Likelihood: 0.301022563972158", + "Likelihood: 0.2851763957989837", + "Likelihood: 0.23780507233542392", + "Likelihood: 0.242589469528289", + "Likelihood: 0.2469404771781565", + "Likelihood: 0.19642638670027082", + "Likelihood: 0.03669077712500581", + "Likelihood: 0.12739133516109805", + "Likelihood: 0.09817876588318923", + "Likelihood: 0.14206918715548006", + "Likelihood: 0.039020105663792236", + "Likelihood: 0.26373563016073964", + "Likelihood: 0.26097410063098353", + "Likelihood: 0.27574943246393435", + "Likelihood: 0.0602524759806687", + "Likelihood: 0.030773796303025003", + "Likelihood: 0.26332163351910326", + "Likelihood: 0.2257778508182674", + "Likelihood: 0.15871592994893136", + "Likelihood: 0.06785739889197057", + "Likelihood: 0.2610128993843403", + "Likelihood: 0.24706749721058993", + "Likelihood: 0.21798758524355377", + "Likelihood: 0.057455368620562546", + "Likelihood: 0.2665564613141104", + "Likelihood: 0.1190378812086775", + "Likelihood: 0.24063830107142675", + "Likelihood: 0.06276019803130213", + "Likelihood: 0.18522166633294754", + "Likelihood: 0.270674370288608", + "Likelihood: 0.20310919437270472", + "Likelihood: 0.264845310801677", + "Likelihood: 0.2732987993580522", + "Likelihood: 0.24446635685387005", + "Likelihood: 0.2708639158709", + "Likelihood: 0.2613603839751038", + "Likelihood: 0.07223546810489427", + "Likelihood: 0.03574309587773457", + "Likelihood: 0.23258029587570317", + "Likelihood: 0.0499934464710171", + "Likelihood: 0.21910919371854637", + "Likelihood: 0.19177225982702503", + "Likelihood: 0.10410076654463657", + "Likelihood: 0.10433286624548195", + "Likelihood: 0.2236397146264101", + "Likelihood: 0.25644198996398443", + "Likelihood: 0.3169615859558352", + "Likelihood: 0.15352806718857334", + "Likelihood: 0.1943798139194885", + "Likelihood: 0.14678493626491382", + "Likelihood: 0.14004807022066654", + "Likelihood: 0.18142647686042443", + "Likelihood: 0.0888047012262782", + "Likelihood: 0.03081752274511015", + "Likelihood: 0.022566746129895756", + "Likelihood: 0.19116301700757637", + "Likelihood: 0.07995924803851849", + "Likelihood: 0.07167569420287007", + "Likelihood: 0.22564605864207068", + "Likelihood: 0.016200715029413275", + "Likelihood: 0.12038410516774016", + "Likelihood: 0.10386226134448823", + "Likelihood: 0.012400498781198158", + "Likelihood: 0.24374985484619838", + "Likelihood: 0.02805673444786284", + "Likelihood: 0.2514157688900636", + "Likelihood: 0.17315454573739594", + "Likelihood: 0.1626516453347625", + "Likelihood: 0.12059877034551499", + "Likelihood: 0.10689864311192933", + "Likelihood: 0.07557082476419204", + "Likelihood: 0.20189471013153837", + "Likelihood: 0.29847486155031516", + "Likelihood: 0.2844455423756465", + "Likelihood: 0.25752953762890696", + "Likelihood: 0.18448234751264442", + "Likelihood: 0.2722404003664796", + "Likelihood: 0.2813621311487776", + "Likelihood: 0.03891041167710826", + "Likelihood: 0.19384853454427337", + "Likelihood: 0.1525011421723293", + "Likelihood: 0.19278571205044637", + "Likelihood: 0.30006104321841837", + "Likelihood: 0.10228918037882152", + "Likelihood: 0.1547610423829063", + "Likelihood: 0.013235687747120448", + "Likelihood: 0.10690371117455383", + "Likelihood: 0.27321474703871096", + "Likelihood: 0.14251901771624714", + "Likelihood: 0.21725127567917968", + "Likelihood: 0.20354076305990396", + "Likelihood: 0.1049884792200897", + "Likelihood: 0.04343792729895125", + "Likelihood: 0.12449257774708287", + "Likelihood: 0.13173674288184098", + "Likelihood: 0.24841291030443854", + "Likelihood: 0.1535009500715905", + "Likelihood: 0.09956027414500077", + "Likelihood: 0.05558894153690475", + "Likelihood: 0.1516504249982617", + "Likelihood: 0.21916873900780498", + "Likelihood: 0.28901718122286196", + "Likelihood: 0.045881466552238875", + "Likelihood: 0.04207447183610984", + "Likelihood: 0.055813598526348034", + "Likelihood: 0.14599321110782784", + "Likelihood: 0.2837420655174675", + "Likelihood: 0.15709054826494454", + "Likelihood: 0.16087119794857965", + "Likelihood: 0.003500471213984427", + "Likelihood: 0.11367962469290645", + "Likelihood: 0.11667021797991885", + "Likelihood: 0.1199370610197878", + "Likelihood: 0.16423610951758472", + "Likelihood: 0.21705313065196155", + "Likelihood: 0.09964761055064655", + "Likelihood: 0.04891521064009924", + "Likelihood: 0.19906909616187582", + "Likelihood: 0.31038794987343543", + "Likelihood: 0.31868998619205025", + "Likelihood: 0.2891388870228015", + "Likelihood: 0.010888520097307109", + "Likelihood: 0.2134927222426513", + "Likelihood: 0.25193008196041417", + "Likelihood: 0.10046995747590913", + "Likelihood: 0.22186354043810547", + "Likelihood: 0.07881884943464233", + "Likelihood: 0.214868061385039", + "Likelihood: 0.1678928380685143", + "Likelihood: 0.18940601150670303", + "Likelihood: 0.1621539789544772", + "Likelihood: 0.24992980769319012", + "Likelihood: 0.18289470215339268", + "Likelihood: 0.029762084932850066", + "Likelihood: 0.18445234704007982", + "Likelihood: 0.07921195969975615", + "Likelihood: 0.2941384428351301", + "Likelihood: 0.03263889864495672", + "Likelihood: 0.0094044285128181", + "Likelihood: 0.136681702177945", + "Likelihood: 0.25083639241928307", + "Likelihood: 0.22810808939240632", + "Likelihood: 0.0723453868744947", + "Likelihood: 0.015733873372316604", + "Likelihood: 0.22974991005778467", + "Likelihood: 0.1374951223857434", + "Likelihood: 0.23461857633094974", + "Likelihood: 0.232955286328861", + "Likelihood: 0.020920779797960816", + "Likelihood: 0.20978331871716324", + "Likelihood: 0.21716345696486838", + "Likelihood: 0.04460333568448142", + "Likelihood: 0.060890063156408346", + "Likelihood: 0.16163810400333625", + "Likelihood: 0.16774080732416502", + "Likelihood: 0.027133399108977416", + "Likelihood: 0.11048942040329379", + "Likelihood: 0.13104993959938882", + "Likelihood: 0.02918245967237712", + "Likelihood: 0.2206409369525186", + "Likelihood: 0.2762063013007982", + "Likelihood: 0.20491958022334855", + "Likelihood: 0.058922145616613", + "Likelihood: 0.11728473149969186", + "Likelihood: 0.05381585970575245", + "Likelihood: 0.3071022760251058", + "Likelihood: 0.2021716572180271", + "Likelihood: 0.13034444269247172", + "Likelihood: 0.09898527145523055", + "Likelihood: 0.10817817265727411", + "Likelihood: 0.30715795705738647", + "Likelihood: 0.3188502998692093", + "Likelihood: 0.11409916677613287", + "Likelihood: 0.30730479701247126", + "Likelihood: 0.22850740923135668", + "Likelihood: 0.28120641379225314", + "Likelihood: 0.09301346391655999", + "Likelihood: 0.05577441071045505", + "Likelihood: 0.2560167568800074", + "Likelihood: 0.06747784052337162", + "Likelihood: 0.19159071037405914", + "Likelihood: 0.23041226298066864", + "Likelihood: 0.03241747021675781", + "Likelihood: 0.13619096156742086", + "Likelihood: 0.13857358881188003", + "Likelihood: 0.23201863876149523", + "Likelihood: 0.32048129907542566", + "Likelihood: 0.2299213890199135", + "Likelihood: 0.02455510639554216", + "Likelihood: 0.19343597327672649", + "Likelihood: 0.09533053460457337", + "Likelihood: 0.18154155462167895", + "Likelihood: 0.2774030580156461", + "Likelihood: 0.067806112803177", + "Likelihood: 0.05555696224563808", + "Likelihood: 0.06117661471723505", + "Likelihood: 0.21340323893380844", + "Likelihood: 0.14398820597022335", + "Likelihood: 0.05194027905589254", + "Likelihood: 0.0466330482424279", + "Likelihood: 0.04233087599882853", + "Likelihood: 0.01094260408730457", + "Likelihood: 0.10921579047118714", + "Likelihood: 0.12446191533822092", + "Likelihood: 0.27187737623313063", + "Likelihood: 0.25387011221614786", + "Likelihood: 0.020295649943600294", + "Likelihood: 0.305130018163218", + "Likelihood: 0.045706580251537385", + "Likelihood: 0.16490478469414693", + "Likelihood: 0.02911124976778092", + "Likelihood: 0.21667288448822586", + "Likelihood: 0.04777104449858289", + "Likelihood: 0.19895770812652705", + "Likelihood: 0.02005613100594492", + "Likelihood: 0.04031883375957403", + "Likelihood: 0.03855961722143748", + "Likelihood: 0.11396655861186927", + "Likelihood: 0.22804344987845437", + "Likelihood: 0.10676801147844703", + "Likelihood: 0.16563004402098344", + "Likelihood: 0.29345214692076177", + "Likelihood: 0.012374242423077665", + "Likelihood: 0.1816311743711642", + "Likelihood: 0.2413003565789571", + "Likelihood: 0.29708481835496536", + "Likelihood: 0.1926472121027401", + "Likelihood: 0.22496636719799867", + "Likelihood: 0.1092225571351704", + "Likelihood: 0.19377036164472028", + "Likelihood: 0.2874209227418949", + "Likelihood: 0.31943373991245544", + "Likelihood: 0.25641684462618036", + "Likelihood: 0.15234537391764127", + "Likelihood: 0.14770462449241253", + "Likelihood: 0.023681102020294876", + "Likelihood: 0.19967467212984372", + "Likelihood: 0.025352632380086924", + "Likelihood: 0.26092999596392513", + "Likelihood: 0.08905210107618676", + "Likelihood: 0.16980296657120753", + "Likelihood: 0.020653334852424005", + "Likelihood: 0.11914405773313883", + "Likelihood: 0.05761210830681725", + "Likelihood: 0.24658080447275313", + "Likelihood: 0.21562173775215018", + "Likelihood: 0.29176471980730573", + "Likelihood: 0.11625504288795241", + "Likelihood: 0.30094411973757546", + "Likelihood: 0.05095660732555856", + "Likelihood: 0.32051566310572066", + "Likelihood: 0.049817092430502204", + "Likelihood: 0.28298252941549473", + "Likelihood: 0.049109008978362234", + "Likelihood: 0.26382943134125736", + "Likelihood: 0.12721876154142697", + "Likelihood: 0.001961381641537423", + "Likelihood: 0.3028034664239406", + "Likelihood: 0.1881227178960861", + "Likelihood: 0.006712940440500905", + "Likelihood: 0.20836223021120026", + "Likelihood: 0.05810500165526543", + "Likelihood: 0.1975455813971333", + "Likelihood: 0.16581380524929235", + "Likelihood: 0.20462084372054617", + "Likelihood: 0.10143326466638633", + "Likelihood: 0.14057258951969276", + "Likelihood: 0.18553940701170332", + "Likelihood: 0.046320248544513734", + "Likelihood: 0.12290258744726792", + "Likelihood: 0.011651595596190079", + "Likelihood: 0.29184640582894683", + "Likelihood: 0.10561139974735943", + "Likelihood: 0.2769663070650989", + "Likelihood: 0.044008450752481255", + "Likelihood: 0.25419792446734046", + "Likelihood: 0.02241865167266878", + "Likelihood: 0.31686893564647334", + "Likelihood: 0.26119737005413", + "Likelihood: 0.19698302213038704", + "Likelihood: 0.05946524387131893", + "Likelihood: 0.0014017103356671044", + "Likelihood: 0.19224359730524276", + "Likelihood: 0.037482495011483576", + "Likelihood: 0.19527877844499647", + "Likelihood: 0.016476019164156436", + "Likelihood: 0.05235900727477211", + "Likelihood: 0.31381421637448215", + "Likelihood: 0.0376426818599033", + "Likelihood: 0.08770498462531186", + "Likelihood: 0.1722188428206219", + "Likelihood: 0.0851826453276371", + "Likelihood: 0.026539022351707565", + "Likelihood: 0.22734560563361497", + "Likelihood: 0.07299770522359245", + "Likelihood: 0.10968539864946883", + "Likelihood: 0.09249903161923292", + "Likelihood: 0.11603435539833193", + "Likelihood: 0.13256990766760657", + "Likelihood: 0.03454732100482982", + "Likelihood: 0.16372188453226788", + "Likelihood: 0.20293249634182434", + "Likelihood: 0.04835546778914684", + "Likelihood: 0.187811698880726", + "Likelihood: 0.05928892616342396", + "Likelihood: 0.031054114876620333", + "Likelihood: 0.2613089340105763", + "Likelihood: 0.02342288757989806", + "Likelihood: 0.16204610859828036", + "Likelihood: 0.23577685468455697", + "Likelihood: 0.1595278754090812", + "Likelihood: 0.059377247402905384", + "Likelihood: 0.25212083334613344", + "Likelihood: 0.28343274687047154", + "Likelihood: 0.2534033098796594", + "Likelihood: 0.20621455585298507", + "Likelihood: 0.18702451920989077", + "Likelihood: 0.1262816617658752", + "Likelihood: 0.22835257553724328", + "Likelihood: 0.08610531653739571", + "Likelihood: 0.03433614529101398", + "Likelihood: 0.30024058906101997", + "Likelihood: 0.04116026636701693", + "Likelihood: 0.19940304531066388", + "Likelihood: 0.2574077118959507", + "Likelihood: 0.17125729397107825", + "Likelihood: 0.1015226589997761", + "Likelihood: 0.258366693416869", + "Likelihood: 0.12763761934549508", + "Likelihood: 0.22227405312358678", + "Likelihood: 0.1074235806610516", + "Likelihood: 0.018613159301553623", + "Likelihood: 0.24910419105776774", + "Likelihood: 0.10341496938386956", + "Likelihood: 0.049145398156519554", + "Likelihood: 0.20964341103415937", + "Likelihood: 0.03175974544639368", + "Likelihood: 0.0506081600846966", + "Likelihood: 0.1529032491681603", + "Likelihood: 0.2660992670849838", + "Likelihood: 0.07944763897233259", + "Likelihood: 0.10009100339640747", + "Likelihood: 0.10082182991861438", + "Likelihood: 0.1963549247171767", + "Likelihood: 0.3175816362740764", + "Likelihood: 0.2887420514992646", + "Likelihood: 0.26822280604713966", + "Likelihood: 0.16106509391200832", + "Likelihood: 0.03399779495976913", + "Likelihood: 0.02447236168890762", + "Likelihood: 0.012988969056481264", + "Likelihood: 0.2096958660456746", + "Likelihood: 0.06646465083764967", + "Likelihood: 0.18664528221024204", + "Likelihood: 0.06870754578388234", + "Likelihood: 0.14611675888680328", + "Likelihood: 0.10032473609499398", + "Likelihood: 0.06081032256987722", + "Likelihood: 0.15580108251496852", + "Likelihood: 0.17730870971713067", + "Likelihood: 0.24809300170885296", + "Likelihood: 0.13289397938092257", + "Likelihood: 0.19236179425103914", + "Likelihood: 0.07385482980019588", + "Likelihood: 0.27541720322876384", + "Likelihood: 0.2703772685485274", + "Likelihood: 0.1292644186600001", + "Likelihood: 0.30365478706712334", + "Likelihood: 0.030083790308197137", + "Likelihood: 0.1387348621350419", + "Likelihood: 0.11758038858890604", + "Likelihood: 0.17549489158454146", + "Likelihood: 0.09025009560510656", + "Likelihood: 0.24422164210522723", + "Likelihood: 0.08788960588455048", + "Likelihood: 0.22235583574209605", + "Likelihood: 0.08079631957108421", + "Likelihood: 0.26532998659675683", + "Likelihood: 0.18095670538713698", + "Likelihood: 0.05120038649567998", + "Likelihood: 0.1227664056745012", + "Likelihood: 0.09470235497460627", + "Likelihood: 0.09660690257405694", + "Likelihood: 0.01724293337432965", + "Likelihood: 0.31117732252806835", + "Likelihood: 0.013224241641845725", + "Likelihood: 0.13505054395086108", + "Likelihood: 0.17685727739036247", + "Likelihood: 0.08347508000708158", + "Likelihood: 0.17152682970764702", + "Likelihood: 0.030037448847751235", + "Likelihood: 0.08053251919286153", + "Likelihood: 0.023137093608918562", + "Likelihood: 0.27759459240991896", + "Likelihood: 0.04288994128588033", + "Likelihood: 0.18489096572780986", + "Likelihood: 0.22910730060102755", + "Likelihood: 0.1647247456909151", + "Likelihood: 0.021284756979470503", + "Likelihood: 0.2295222129850152", + "Likelihood: 0.23829701908780948", + "Likelihood: 0.3030547969761725", + "Likelihood: 0.009439115631423156", + "Likelihood: 0.2274823589290137", + "Likelihood: 0.18994172340160553", + "Likelihood: 0.11646952912072435", + "Likelihood: 0.0016273244574570398", + "Likelihood: 0.10590577764450738", + "Likelihood: 0.1419420989695256", + "Likelihood: 0.13337670324395287", + "Likelihood: 0.09907045549949242", + "Likelihood: 0.22043767955527607", + "Likelihood: 0.24281641213114852", + "Likelihood: 0.06542950198733319", + "Likelihood: 0.29365575173883657", + "Likelihood: 0.16420431999186788", + "Likelihood: 0.3104967077490559", + "Likelihood: 0.2606637605486834", + "Likelihood: 0.1146454975843521", + "Likelihood: 0.18936566086085585", + "Likelihood: 0.1564127686753322", + "Likelihood: 0.11529362933664396", + "Likelihood: 0.03374943899826442", + "Likelihood: 0.18862027890477795", + "Likelihood: 0.2356287280926576", + "Likelihood: 0.16019012183818318", + "Likelihood: 0.3144589224100923", + "Likelihood: 0.10963091070149032", + "Likelihood: 0.0958672422757053", + "Likelihood: 0.023935922654621127", + "Likelihood: 0.009438511175041306", + "Likelihood: 0.29269952177024344", + "Likelihood: 0.05219424739137062", + "Likelihood: 0.2709885081763418", + "Likelihood: 0.2627569849242476", + "Likelihood: 0.029946172544679232", + "Likelihood: 0.01850069066640692", + "Likelihood: 0.16867470968056675", + "Likelihood: 0.026837420123532657", + "Likelihood: 0.013573757045152787", + "Likelihood: 0.2738803964925796", + "Likelihood: 0.042712469594539955", + "Likelihood: 0.06822417255570151", + "Likelihood: 0.2999254832548879", + "Likelihood: 0.14949386157875524", + "Likelihood: 0.2690557966736404", + "Likelihood: 0.3110991102810256", + "Likelihood: 0.19017884811027339", + "Likelihood: 0.03404201830706232", + "Likelihood: 0.09839568942714828", + "Likelihood: 0.19699083183743515", + "Likelihood: 0.2052122862820023", + "Likelihood: 0.15986104095799272", + "Likelihood: 0.06098080187242092", + "Likelihood: 0.015509478872013715", + "Likelihood: 0.049198787652128234", + "Likelihood: 0.23729681221774923", + "Likelihood: 0.024860993012034212", + "Likelihood: 0.10599566564979769", + "Likelihood: 0.00840832028347558", + "Likelihood: 0.22399879775868264", + "Likelihood: 0.037142784768037944", + "Likelihood: 0.14545901525798552", + "Likelihood: 0.10439589246711727", + "Likelihood: 0.21630109526929434", + "Likelihood: 0.007863828047541797", + "Likelihood: 0.12978582628406748", + "Likelihood: 0.08674154349549813", + "Likelihood: 0.11261053049773276", + "Likelihood: 0.04147314360082913", + "Likelihood: 0.08207855239680495", + "Likelihood: 0.31360438574183497", + "Likelihood: 0.06317795720350455", + "Likelihood: 0.2527442886254074", + "Likelihood: 0.05643439043383069", + "Likelihood: 0.060988445446009266", + "Likelihood: 0.005868421683726778", + "Likelihood: 0.1038541002784468", + "Likelihood: 0.2946054852446167", + "Likelihood: 0.1483855808833999", + "Likelihood: 0.2026157474587129", + "Likelihood: 0.042955078494541415", + "Likelihood: 0.2466012265019828", + "Likelihood: 0.03513674849877089", + "Likelihood: 0.08136288167939931", + "Likelihood: 0.15286555269097007", + "Likelihood: 0.17586879971280653", + "Likelihood: 0.31382466544724724", + "Likelihood: 0.1904538243384553", + "Likelihood: 0.10961671082055194", + "Likelihood: 0.07215177987610916", + "Likelihood: 0.1354025763957001", + "Likelihood: 0.020001048047249184", + "Likelihood: 0.02165444864619052", + "Likelihood: 0.15791018027696674", + "Likelihood: 0.09654113544583173", + "Likelihood: 0.08485653145854162", + "Likelihood: 0.2468296697911449", + "Likelihood: 0.21395168868212447", + "Likelihood: 0.18961946809388508", + "Likelihood: 0.064718242977769", + "Likelihood: 0.16464884026011356", + "Likelihood: 0.045192389968121784", + "Likelihood: 0.26146932823560987", + "Likelihood: 0.1898314783379402", + "Likelihood: 0.004631321823511424", + "Likelihood: 0.007571435193369461", + "Likelihood: 0.024749739511708408", + "Likelihood: 0.29088718162128374", + "Likelihood: 0.20964230961924596", + "Likelihood: 0.22154684121406584", + "Likelihood: 0.10908909734587804", + "Likelihood: 0.1459208787400911", + "Likelihood: 0.06794264068018724", + "Likelihood: 0.3025269815489891", + "Likelihood: 0.06763598573727639", + "Likelihood: 0.18801587185319968", + "Likelihood: 0.24499876056576603", + "Likelihood: 0.30062694088487857", + "Likelihood: 0.11893056685165566", + "Likelihood: 0.2830993339986224", + "Likelihood: 0.2812711704994448", + "Likelihood: 0.009456913137408566", + "Likelihood: 0.06147082562534903", + "Likelihood: 0.20614882269864013", + "Likelihood: 0.09260811898629619", + "Likelihood: 0.02451743298833641", + "Likelihood: 0.27802646138662573", + "Likelihood: 0.26726418639799804", + "Likelihood: 0.20839215287553406", + "Likelihood: 0.14674338310898533", + "Likelihood: 0.2053079335393592", + "Likelihood: 0.14414940827104955", + "Likelihood: 0.16656459767672535", + "Likelihood: 0.132220412796274", + "Likelihood: 0.0808188082469353", + "Likelihood: 0.09558969653353533", + "Likelihood: 0.09530868313564352", + "Likelihood: 0.116865426871101", + "Likelihood: 0.04634595224104042", + "Likelihood: 0.06645731323221708", + "Likelihood: 0.2959620797031816", + "Likelihood: 0.1360992773748621", + "Likelihood: 0.02622216565472807", + "Likelihood: 0.2347470789222352", + "Likelihood: 0.04233059067427222", + "Likelihood: 0.255753675940993", + "Likelihood: 0.050426853880716785", + "Likelihood: 0.1511907394680479", + "Likelihood: 0.31177062137367617", + "Likelihood: 0.2509419042770058", + "Likelihood: 0.08918390677531897", + "Likelihood: 0.15535718299691345", + "Likelihood: 0.1519419540414298", + "Likelihood: 0.08281223826690655", + "Likelihood: 0.17656767684978705", + "Likelihood: 0.15994972322420517", + "Likelihood: 0.03165858457747675", + "Likelihood: 0.07158449942070752", + "Likelihood: 0.02881484981754625", + "Likelihood: 0.23863419460896954", + "Likelihood: 0.19657028802806922", + "Likelihood: 0.04899427994076908", + "Likelihood: 0.0930974470622995", + "Likelihood: 0.16260766301190122", + "Likelihood: 0.20627481875805445", + "Likelihood: 0.17581575286761153", + "Likelihood: 0.11451523880504075", + "Likelihood: 0.007705306067080138", + "Likelihood: 0.2471761037139694", + "Likelihood: 0.025781843300135544", + "Likelihood: 0.08064574234015189", + "Likelihood: 0.3022733876341074", + "Likelihood: 0.1303787476486188", + "Likelihood: 0.29978606044932454", + "Likelihood: 0.12387291643169893", + "Likelihood: 0.04128984199638534", + "Likelihood: 0.16843925351341107", + "Likelihood: 0.2869343036837952", + "Likelihood: 0.07918543876306226", + "Likelihood: 0.06668340680274122", + "Likelihood: 0.19396828069581631", + "Likelihood: 0.1042349951242317", + "Likelihood: 0.03082832927038769", + "Likelihood: 0.026135776802276474", + "Likelihood: 0.2024045421936392", + "Likelihood: 0.29096772697872", + "Likelihood: 0.1287237123353115", + "Likelihood: 0.24969981881624223", + "Likelihood: 0.3165510556058472", + "Likelihood: 0.077853790022555", + "Likelihood: 0.2722018980682566", + "Likelihood: 0.3145544495668701", + "Likelihood: 0.07689123214054937", + "Likelihood: 0.1706499482982905", + "Likelihood: 0.04625026162470714", + "Likelihood: 0.2358751408464517", + "Likelihood: 0.1280602761010164", + "Likelihood: 0.03996301255990084", + "Likelihood: 0.21384707009498788", + "Likelihood: 0.235054573598938", + "Likelihood: 0.06404685697767247", + "Likelihood: 0.2763088548534766", + "Likelihood: 0.025970223801430048", + "Likelihood: 0.01212542844782918", + "Likelihood: 0.1588994655778274", + "Likelihood: 0.10060252849410721", + "Likelihood: 0.08402628026586491", + "Likelihood: 0.012944646724654455", + "Likelihood: 0.17942564338826078", + "Likelihood: 0.07364560685060126", + "Likelihood: 0.08707913259162613", + "Likelihood: 0.08585741986418095", + "Likelihood: 0.07759075259930467", + "Likelihood: 0.005036712241434339", + "Likelihood: 0.18306497537058758", + "Likelihood: 0.189295469949836", + "Likelihood: 0.19781755499822704", + "Likelihood: 0.29151298729904424", + "Likelihood: 0.059894861027526565", + "Likelihood: 0.06580535013937959", + "Likelihood: 0.14738917498663484", + "Likelihood: 0.19629403494003234", + "Likelihood: 0.1636712335260618", + "Likelihood: 0.14010648351527538", + "Likelihood: 0.018077615767830308", + "Likelihood: 0.09413355846678187", + "Likelihood: 0.279298529272339", + "Likelihood: 0.1399029892773882", + "Likelihood: 0.09627273751769287", + "Likelihood: 0.07277937541350521", + "Likelihood: 0.15848717303390153", + "Likelihood: 0.14823571072742048", + "Likelihood: 0.1317107084418439", + "Likelihood: 0.24605086932221806", + "Likelihood: 0.15652661552241962", + "Likelihood: 0.18250497398867757", + "Likelihood: 0.012166115832097837", + "Likelihood: 0.13298830644097556", + "Likelihood: 0.26694407492896693", + "Likelihood: 0.18688108940843903", + "Likelihood: 0.3110396801101089", + "Likelihood: 0.00808135658604539", + "Likelihood: 0.2542411959384788", + "Likelihood: 0.14054213427314832", + "Likelihood: 0.019647838007868346", + "Likelihood: 0.20527556903017652", + "Likelihood: 0.12338501670441948", + "Likelihood: 0.10852218001499572", + "Likelihood: 0.30188661944030265", + "Likelihood: 0.14800337585266013", + "Likelihood: 0.19344490136894954", + "Likelihood: 0.20304155788345016", + "Likelihood: 0.19478933371617776", + "Likelihood: 0.2689788789452439", + "Likelihood: 0.09862755003914045", + "Likelihood: 0.01883419499896165", + "Likelihood: 0.07949659324533781", + "Likelihood: 0.17723147256408497", + "Likelihood: 0.1259304916106471", + "Likelihood: 0.14502596311396296", + "Likelihood: 0.15334807858092725", + "Likelihood: 0.15420284287700228", + "Likelihood: 0.2608850767418884", + "Likelihood: 0.14963657983574769", + "Likelihood: 0.3078361098047339", + "Likelihood: 0.048169749118183246", + "Likelihood: 0.2428580692664161", + "Likelihood: 0.09793728022179812", + "Likelihood: 0.030031640089999333", + "Likelihood: 0.15397068590210888", + "Likelihood: 0.2932810154610519", + "Likelihood: 0.3053757344454008", + "Likelihood: 0.19511179685641122", + "Likelihood: 0.2693966180482973", + "Likelihood: 0.07148394256994214", + "Likelihood: 0.12557233893660605", + "Likelihood: 0.010133702267173196", + "Likelihood: 0.18421307956939276", + "Likelihood: 0.15176832357947054", + "Likelihood: 0.04952502784442002", + "Likelihood: 0.2642274712549161", + "Likelihood: 0.15095580059757394", + "Likelihood: 0.2850362831120361", + "Likelihood: 0.09529163171563912", + "Likelihood: 0.2272961167217938", + "Likelihood: 0.2868432066653512", + "Likelihood: 0.18599935518014366", + "Likelihood: 0.19999203124646728", + "Likelihood: 0.12547876840479552", + "Likelihood: 0.2945041497141064", + "Likelihood: 0.19553464611941232", + "Likelihood: 0.234345212724757", + "Likelihood: 0.023646286193486132", + "Likelihood: 0.2059493634786188", + "Likelihood: 0.2722127782088083", + "Likelihood: 0.042981780699244", + "Likelihood: 0.20947025202288316", + "Likelihood: 0.07417294874098632", + "Likelihood: 0.2161197338237977", + "Likelihood: 0.1170514002335398", + "Likelihood: 0.2667728142293874", + "Likelihood: 0.04950999679480169", + "Likelihood: 0.2930313290889802", + "Likelihood: 0.05151972685488714", + "Likelihood: 0.3124207085446234", + "Likelihood: 0.21240015863285122", + "Likelihood: 0.20504079780874757", + "Likelihood: 0.09148293945359084", + "Likelihood: 0.10223709773159625", + "Likelihood: 0.12053476995236855", + "Likelihood: 0.28421348778222566", + "Likelihood: 0.07713928799227812", + "Likelihood: 0.0348072401238958", + "Likelihood: 0.1280589299460543", + "Likelihood: 0.1682609762326081", + "Likelihood: 0.17820152727254132", + "Likelihood: 0.03799719141795042", + "Likelihood: 0.12534516605711532", + "Likelihood: 0.22496953242081966", + "Likelihood: 0.16017011151504518", + "Likelihood: 0.28421837750296075", + "Likelihood: 0.13507360338444813", + "Likelihood: 0.10994821823644468", + "Likelihood: 0.06553558647070262", + "Likelihood: 0.14182093954679645", + "Likelihood: 0.20836089645051709", + "Likelihood: 0.10604114528667923", + "Likelihood: 0.22161394428161385", + "Likelihood: 0.17480153013345182", + "Likelihood: 0.1253983690254647", + "Likelihood: 0.26052468416537666", + "Likelihood: 0.16695573049502385", + "Likelihood: 0.11005518945043098", + "Likelihood: 0.20022553245421235", + "Likelihood: 0.1776228564726482", + "Likelihood: 0.24244943387303422", + "Likelihood: 0.005839437180482993", + "Likelihood: 0.19607228595098583", + "Likelihood: 0.20954365652299742", + "Likelihood: 0.23433783427626922", + "Likelihood: 0.11932738451498905", + "Likelihood: 0.07750482269056395", + "Likelihood: 0.2272412718545153", + "Likelihood: 0.110690914240807", + "Likelihood: 0.10108366930760887", + "Likelihood: 0.06691941006800707", + "Likelihood: 0.09164151041380675", + "Likelihood: 0.28663259488487175", + "Likelihood: 0.15240650150816068", + "Likelihood: 0.06373764775546707", + "Likelihood: 0.10365286951117661", + "Likelihood: 0.04831565311809911", + "Likelihood: 0.1127514891437931", + "Likelihood: 0.008822440098091407", + "Likelihood: 0.17711697669968562", + "Likelihood: 0.2066404889175201", + "Likelihood: 0.16313016851197817", + "Likelihood: 0.0856558050120054", + "Likelihood: 0.1649684935210718", + "Likelihood: 0.2901316439580305", + "Likelihood: 0.2662933818610331", + "Likelihood: 0.03477248767914121", + "Likelihood: 0.025600578790981213", + "Likelihood: 0.16618045457248262", + "Likelihood: 0.05533768531850621", + "Likelihood: 0.15747562514536043", + "Likelihood: 0.11989703056515395", + "Likelihood: 0.2911738573609724", + "Likelihood: 0.19152852099013953", + "Likelihood: 0.20310561292155868", + "Likelihood: 0.10800411236074998", + "Likelihood: 0.2618863541224218", + "Likelihood: 0.05732027157709178", + "Likelihood: 0.17323811705407557", + "Likelihood: 0.09850975589499425", + "Likelihood: 0.24030866807110102", + "Likelihood: 0.17606683839537854", + "Likelihood: 0.07394735462596419", + "Likelihood: 0.3146588465363175", + "Likelihood: 0.02175159149687742", + "Likelihood: 0.10509349618632903", + "Likelihood: 0.2633564373385628", + "Likelihood: 0.31184608306091255", + "Likelihood: 0.11794720624869352", + "Likelihood: 0.18756726212184918", + "Likelihood: 0.10855969920507444", + "Likelihood: 0.2198558178312724", + "Likelihood: 0.06185201504724856", + "Likelihood: 0.037280248269146166", + "Likelihood: 0.0231444300994037", + "Likelihood: 0.12010475993847877", + "Likelihood: 0.20080231924139955", + "Likelihood: 0.2763814734092602", + "Likelihood: 0.1783169347971437", + "Likelihood: 0.014259622021787714", + "Likelihood: 0.09429395194354459", + "Likelihood: 0.02657200237869314", + "Likelihood: 0.30158049870962345", + "Likelihood: 0.20078437999135593", + "Likelihood: 0.11459486224375612", + "Likelihood: 0.14878391797544083", + "Likelihood: 0.06641235336425297", + "Likelihood: 0.1576596804613952", + "Likelihood: 0.22607969815757686", + "Likelihood: 0.1042170678207666", + "Likelihood: 0.27950660442316383", + "Likelihood: 0.2538316760499933", + "Likelihood: 0.13155365962510285", + "Likelihood: 0.29934038624637777", + "Likelihood: 0.029437188857142655", + "Likelihood: 0.10336324685141131", + "Likelihood: 0.02338965779869065", + "Likelihood: 0.12018940628111775", + "Likelihood: 0.2651221393973472", + "Likelihood: 0.030574695478787068", + "Likelihood: 0.14800233117696932", + "Likelihood: 0.022529217460263186", + "Likelihood: 0.20631007302919732", + "Likelihood: 0.11203003793321303", + "Likelihood: 0.2009236247399982", + "Likelihood: 0.023770594823861554", + "Likelihood: 0.24403144534678045", + "Likelihood: 0.15029179798755515", + "Likelihood: 0.16432122139243577", + "Likelihood: 0.10624768136218066", + "Likelihood: 0.020576741041496094", + "Likelihood: 0.17069588737081257", + "Likelihood: 0.03564301194505822", + "Likelihood: 0.010460709053018068", + "Likelihood: 0.05582172750859659", + "Likelihood: 0.018158096025382812", + "Likelihood: 0.20633967021891", + "Likelihood: 0.15842023192675023", + "Likelihood: 0.14352724082559873", + "Likelihood: 0.17101975452858464", + "Likelihood: 0.24894297556482767", + "Likelihood: 0.2834544888708678", + "Likelihood: 0.29321860667781935", + "Likelihood: 0.08062401740754203", + "Likelihood: 0.31456363143571675", + "Likelihood: 0.3205956853710712", + "Likelihood: 0.26384578195762837", + "Likelihood: 0.03056620837109748", + "Likelihood: 0.01681427959104208", + "Likelihood: 0.05298372728897094", + "Likelihood: 0.061123630073679054", + "Likelihood: 0.26202087347649194", + "Likelihood: 0.20298432400749084", + "Likelihood: 0.08077348339256203", + "Likelihood: 0.13786695475905075", + "Likelihood: 0.14217017820969247", + "Likelihood: 0.08339501963655269", + "Likelihood: 0.05745450837042729", + "Likelihood: 0.2923549413565086", + "Likelihood: 0.27777494079062276", + "Likelihood: 0.2852129235795315", + "Likelihood: 0.26414350708667994", + "Likelihood: 0.13846877309960512", + "Likelihood: 0.12372175321502993", + "Likelihood: 0.32011389895616954", + "Likelihood: 0.19413175474205005", + "Likelihood: 0.05558184732243175", + "Likelihood: 0.04098417706414764", + "Likelihood: 0.19741819680265774", + "Likelihood: 0.04659322697197481", + "Likelihood: 0.056166188303199395", + "Likelihood: 0.20503907377003472", + "Likelihood: 0.16727216922631347", + "Likelihood: 0.14274596879210075", + "Likelihood: 0.2614179445253419", + "Likelihood: 0.18548100726503777", + "Likelihood: 0.032968345350135604", + "Likelihood: 0.13159427244970084", + "Likelihood: 0.17192878796564698", + "Likelihood: 0.061357135627495576", + "Likelihood: 0.28227302418906614", + "Likelihood: 0.05336352577353864", + "Likelihood: 0.09643801683563227", + "Likelihood: 0.2684506135532059", + "Likelihood: 0.02751751445296895", + "Likelihood: 0.1761834537279669", + "Likelihood: 0.049718077764583896", + "Likelihood: 0.09236629009438245", + "Likelihood: 0.049002388986036656", + "Likelihood: 0.12495155196246925", + "Likelihood: 0.17263412794509336", + "Likelihood: 0.05327272844051029", + "Likelihood: 0.07775329870820173", + "Likelihood: 0.018269128123835764", + "Likelihood: 0.09807475064782047", + "Likelihood: 0.03130399876122359", + "Likelihood: 0.23349925098818228", + "Likelihood: 0.1816402314331302", + "Likelihood: 0.19699504705664989", + "Likelihood: 0.16880436097871965", + "Likelihood: 0.1246191154745916", + "Likelihood: 0.21112247676902787", + "Likelihood: 0.25998572573099143", + "Likelihood: 0.2577574507459949", + "Likelihood: 0.21989152815357824", + "Likelihood: 0.11862255599484255", + "Likelihood: 0.036732332068967415", + "Likelihood: 0.044484228577011516", + "Likelihood: 0.2293430178193605", + "Likelihood: 0.07336217726368595", + "Likelihood: 0.06134843127063915", + "Likelihood: 0.19516663666912643", + "Likelihood: 0.08827436833901833", + "Likelihood: 0.11810562183804588", + "Likelihood: 0.2665472140725538", + "Likelihood: 0.014421191367073186", + "Likelihood: 0.08902119860119959", + "Likelihood: 0.12162514507161803", + "Likelihood: 0.1961884988606215", + "Likelihood: 0.11912349342814016", + "Likelihood: 0.11406916050657076", + "Likelihood: 0.20699075159935426", + "Likelihood: 0.2686723498023687", + "Likelihood: 0.020570020578206873", + "Likelihood: 0.15970019411594752", + "Likelihood: 0.2111766687132786", + "Likelihood: 0.035646911339701146", + "Likelihood: 0.08847365768221757", + "Likelihood: 0.13634416625177398", + "Likelihood: 0.13805045658526116", + "Likelihood: 0.27897996838363887", + "Likelihood: 0.14658944669934731", + "Likelihood: 0.16830785968074666", + "Likelihood: 0.12112430593736727", + "Likelihood: 0.08607891573592154", + "Likelihood: 0.30124260433889194", + "Likelihood: 0.26084493146666893", + "Likelihood: 0.13539365316690002", + "Likelihood: 0.20232948864846637", + "Likelihood: 0.06625935994899344", + "Likelihood: 0.21904780149214215", + "Likelihood: 0.15485146199314406", + "Likelihood: 0.1882702761147007", + "Likelihood: 0.21875745405814534", + "Likelihood: 0.03483901893900281", + "Likelihood: 0.29695684628189223", + "Likelihood: 0.002975317906479649", + "Likelihood: 0.008947075483630093", + "Likelihood: 0.08589684783935747", + "Likelihood: 0.11010522996680333", + "Likelihood: 0.2955549885952869", + "Likelihood: 0.22254458308157316", + "Likelihood: 0.18229200762539427", + "Likelihood: 0.049064416424688104", + "Likelihood: 0.19443143595046666", + "Likelihood: 0.05583426157141649", + "Likelihood: 0.2436214360807213", + "Likelihood: 0.1375905024161023", + "Likelihood: 0.00939477884049595", + "Likelihood: 0.12674687318356262", + "Likelihood: 0.11927740420192733", + "Likelihood: 0.008459987055328825", + "Likelihood: 0.1365443008078542", + "Likelihood: 0.1635434446804173", + "Likelihood: 0.2503220053936474", + "Likelihood: 0.2296530995773307", + "Likelihood: 0.2189839199324456", + "Likelihood: 0.2264891057955213", + "Likelihood: 0.1389607036394293", + "Likelihood: 0.056866322604281365", + "Likelihood: 0.14539082119264063", + "Likelihood: 0.18551001575157883", + "Likelihood: 0.10747087896454516", + "Likelihood: 0.003893430730755824", + "Likelihood: 0.21638835943573823", + "Likelihood: 0.0964467736783709", + "Likelihood: 0.2815157280046125", + "Likelihood: 0.21479812498358947", + "Likelihood: 0.30733932911627926", + "Likelihood: 0.009330200444309296", + "Likelihood: 0.02798299802616283", + "Likelihood: 0.229748380724042", + "Likelihood: 0.290920207675114", + "Likelihood: 0.2702923242452836", + "Likelihood: 0.06828411351021686", + "Likelihood: 0.20965065809485353", + "Likelihood: 0.08134821278255563", + "Likelihood: 0.015059862885723113", + "Likelihood: 0.0380043238712491", + "Likelihood: 0.1768767904944647", + "Likelihood: 0.2254731444652414", + "Likelihood: 0.1804815188030676", + "Likelihood: 0.05217100161626248", + "Likelihood: 0.052593223034338", + "Likelihood: 0.1456930194407218", + "Likelihood: 0.23097460844909123", + "Likelihood: 0.2951899020403849", + "Likelihood: 0.08537332722860239", + "Likelihood: 0.08248798244353846", + "Likelihood: 0.23118238441705408", + "Likelihood: 0.24583883150348596", + "Likelihood: 0.13328611001897356", + "Likelihood: 0.2281142988091233", + "Likelihood: 0.29342263039592387", + "Likelihood: 0.18484313268247834", + "Likelihood: 0.2812621493122542", + "Likelihood: 0.0726623189097477", + "Likelihood: 0.27602217411302915", + "Likelihood: 0.07734232585311807", + "Likelihood: 0.09911434487457696", + "Likelihood: 0.06218419487600908", + "Likelihood: 0.24508078694916627", + "Likelihood: 0.2842110004016432", + "Likelihood: 0.011117279993152606", + "Likelihood: 0.2691930304479535", + "Likelihood: 0.09676267115051994", + "Likelihood: 0.30875931938143214", + "Likelihood: 0.19901640695110864", + "Likelihood: 0.23214068949932526", + "Likelihood: 0.1354218852471806", + "Likelihood: 0.06186038601149213", + "Likelihood: 0.23496431834087153", + "Likelihood: 0.18243854155302772", + "Likelihood: 0.20800627512570455", + "Likelihood: 0.28314950662892385", + "Likelihood: 0.23203064743623217", + "Likelihood: 0.11170000844417308", + "Likelihood: 0.2141261299795361", + "Likelihood: 0.2135038401708433", + "Likelihood: 0.2194197502753209", + "Likelihood: 0.10549186782384197", + "Likelihood: 0.08154473480812284", + "Likelihood: 0.06158686081063912", + "Likelihood: 0.03642314556408889", + "Likelihood: 0.03163764601839897", + "Likelihood: 0.18893237428888995", + "Likelihood: 0.0041766657603539165", + "Likelihood: 0.04190445128112531", + "Likelihood: 0.053074861528861955", + "Likelihood: 0.044585209830287235", + "Likelihood: 0.1502359588840134", + "Likelihood: 0.09612916654623048", + "Likelihood: 0.005987609276310971", + "Likelihood: 0.1627698883919916", + "Likelihood: 0.1872397918860358", + "Likelihood: 0.25132908979288704", + "Likelihood: 0.22739724862090704", + "Likelihood: 0.17877902687064398", + "Likelihood: 0.27733546131942655", + "Likelihood: 0.2602413738254304", + "Likelihood: 0.14880086316286997", + "Likelihood: 0.23205906134997617", + "Likelihood: 0.006562673056467419", + "Likelihood: 0.17809339996836054", + "Likelihood: 0.24684976134773717", + "Likelihood: 0.012057332235054487", + "Likelihood: 0.266175656894589", + "Likelihood: 0.14355511469130655", + "Likelihood: 0.29744537578210617", + "Likelihood: 0.09050287394756482", + "Likelihood: 0.0612383091674608", + "Likelihood: 0.1694845232627809", + "Likelihood: 0.07198244199828079", + "Likelihood: 0.16632580800964886", + "Likelihood: 0.22631744983257546", + "Likelihood: 0.04003099371566918", + "Likelihood: 0.01902453803493442", + "Likelihood: 0.010243281988680977", + "Likelihood: 0.011006873909398146", + "Likelihood: 0.11813940741246202", + "Likelihood: 0.10336277304532301", + "Likelihood: 0.009355251950191462", + "Likelihood: 0.11131824583357215", + "Likelihood: 0.25062514400384656", + "Likelihood: 0.05873744075483578", + "Likelihood: 0.03634208343935192", + "Likelihood: 0.043938182547500045", + "Likelihood: 0.280447640006844", + "Likelihood: 0.16887932146153117", + "Likelihood: 0.24268508778315925", + "Likelihood: 0.13801717926771181", + "Likelihood: 0.045815278011045374", + "Likelihood: 0.17205876010994609", + "Likelihood: 0.29437935114617886", + "Likelihood: 0.15102642284265114", + "Likelihood: 0.09390047361916616", + "Likelihood: 0.26040578568136896", + "Likelihood: 0.17015825653138814", + "Likelihood: 0.18575895698146122", + "Likelihood: 0.14294935035782105", + "Likelihood: 0.0013082884811308484", + "Likelihood: 0.04366674584302609", + "Likelihood: 0.20222220546904135", + "Likelihood: 0.17933486967183532", + "Likelihood: 0.3053200280398667", + "Likelihood: 0.2782980760649211", + "Likelihood: 0.1423517184210256", + "Likelihood: 0.07593985548763359", + "Likelihood: 0.2032476031251692", + "Likelihood: 0.22730188283214234", + "Likelihood: 0.1925932331383876", + "Likelihood: 0.1618259442128243", + "Likelihood: 0.16013869594818755", + "Likelihood: 0.07848494779856119", + "Likelihood: 0.13395300859296014", + "Likelihood: 0.1372125688576478", + "Likelihood: 0.005463393753968767", + "Likelihood: 0.020321537593914512", + "Likelihood: 0.11748420487129442", + "Likelihood: 0.10701267519318497", + "Likelihood: 0.2426453189335966", + "Likelihood: 0.12418779807983983", + "Likelihood: 0.20134825330532605", + "Likelihood: 0.29498136869613895", + "Likelihood: 0.21031381004354804", + "Likelihood: 0.19893857819284083", + "Likelihood: 0.022197913367741507", + "Likelihood: 0.14433564051012837", + "Likelihood: 0.06374737025087995", + "Likelihood: 0.23448600025246943", + "Likelihood: 0.0655487354560128", + "Likelihood: 0.03725675569219435", + "Likelihood: 0.24570381165914237", + "Likelihood: 0.009209651089734306", + "Likelihood: 0.019921481157271326", + "Likelihood: 0.25210513192929707", + "Likelihood: 0.15705618905794147", + "Likelihood: 0.022843243458563964", + "Likelihood: 0.2465708165243503", + "Likelihood: 0.10354673216063906", + "Likelihood: 0.21841787341286764", + "Likelihood: 0.21367147798954736", + "Likelihood: 0.09699778259607508", + "Likelihood: 0.2323579624049327", + "Likelihood: 0.0702153350942018", + "Likelihood: 0.14420369929268212", + "Likelihood: 0.08571826549904768", + "Likelihood: 0.23164840660133532", + "Likelihood: 0.059430628408160616", + "Likelihood: 0.15488558601686064", + "Likelihood: 0.07919844232157189", + "Likelihood: 0.004910254536827379", + "Likelihood: 0.22145944773556178", + "Likelihood: 0.2660762226884348", + "Likelihood: 0.08655916934206624", + "Likelihood: 0.15012445178061617", + "Likelihood: 0.30119412686716757", + "Likelihood: 0.10201175474191854", + "Likelihood: 0.2288480424429852", + "Likelihood: 0.211622373455718", + "Likelihood: 0.2823770835076777", + "Likelihood: 0.21540059523972666", + "Likelihood: 0.1907283484737892", + "Likelihood: 0.23970890342148987", + "Likelihood: 0.29094046605599644", + "Likelihood: 0.1202735783944546", + "Likelihood: 0.2731639787538731", + "Likelihood: 0.027599789112629922", + "Likelihood: 0.10454433592426439", + "Likelihood: 0.2203821439084967", + "Likelihood: 0.18441098806489908", + "Likelihood: 0.1888484667586659", + "Likelihood: 0.3039876331480313", + "Likelihood: 0.24343110206861587", + "Likelihood: 0.14393415993468353", + "Likelihood: 0.15726462420866852", + "Likelihood: 0.08461384243122931", + "Likelihood: 0.1582313104292861", + "Likelihood: 0.2661271526121148", + "Likelihood: 0.1409648808790466", + "Likelihood: 0.18412307205623074", + "Likelihood: 0.11831433385340404", + "Likelihood: 0.00636522896289137", + "Likelihood: 0.03987980109168228", + "Likelihood: 0.12943450805089918", + "Likelihood: 0.15915870978584734", + "Likelihood: 0.10413805943392605", + "Likelihood: 0.3004553972862299", + "Likelihood: 0.09577415402628435", + "Likelihood: 0.2923061136691342", + "Likelihood: 0.1648137387094411", + "Likelihood: 0.020712362376625205", + "Likelihood: 0.12227577508844925", + "Likelihood: 0.13993646398516285", + "Likelihood: 0.0987671191751548", + "Likelihood: 0.01763764319904014", + "Likelihood: 0.19736004689356593", + "Likelihood: 0.20422745382972418", + "Likelihood: 0.19983505512243677", + "Likelihood: 0.1682746607573137", + "Likelihood: 0.30337601824902305", + "Likelihood: 0.18918442794342805", + "Likelihood: 0.3033242400270611", + "Likelihood: 0.06355932951427352", + "Likelihood: 0.06244055096279047", + "Likelihood: 0.22779955420261241", + "Likelihood: 0.1139178837874982", + "Likelihood: 0.056117815228826286", + "Likelihood: 0.04578647269058828", + "Likelihood: 0.1969616712228184", + "Likelihood: 0.2050854246349959", + "Likelihood: 0.026302439103343223", + "Likelihood: 0.10693405904571335", + "Likelihood: 0.19898658076577141", + "Likelihood: 0.07929417574541256", + "Likelihood: 0.10115216732892773", + "Likelihood: 0.22540900648061263", + "Likelihood: 0.17481322523268786", + "Likelihood: 0.04542558059751553", + "Likelihood: 0.12951836984323467", + "Likelihood: 0.15605994119542194", + "Likelihood: 0.06546544238114438", + "Likelihood: 0.19087657737520727", + "Likelihood: 0.1941375400901104", + "Likelihood: 0.2677237667760549", + "Likelihood: 0.019456177700121983", + "Likelihood: 0.0885556764718562", + "Likelihood: 0.21741655916403843", + "Likelihood: 0.1333230893971366", + "Likelihood: 0.25096255909684145", + "Likelihood: 0.005797686130872302", + "Likelihood: 0.1657084516424722", + "Likelihood: 0.17137456215124025", + "Likelihood: 0.01661528169833462", + "Likelihood: 0.0290437633128777", + "Likelihood: 0.14605013038704734", + "Likelihood: 0.20374069044659981", + "Likelihood: 0.023969604108965308", + "Likelihood: 0.2574533966109796", + "Likelihood: 0.23121283994402453", + "Likelihood: 0.12338536636219898", + "Likelihood: 0.2712927641844408", + "Likelihood: 0.0022210115661760984", + "Likelihood: 0.13115481216914074", + "Likelihood: 0.03870640390152394", + "Likelihood: 0.08144826608983768", + "Likelihood: 0.27304369548299573", + "Likelihood: 0.1887428408536021", + "Likelihood: 0.10705923307767322", + "Likelihood: 0.20533705163981855", + "Likelihood: 0.15306967349984074", + "Likelihood: 0.3004201949504646", + "Likelihood: 0.306357116693404", + "Likelihood: 0.0739463074321585", + "Likelihood: 0.13697367129675111", + "Likelihood: 0.04120229584848031", + "Likelihood: 0.23263452531503986", + "Likelihood: 0.17569588216414112", + "Likelihood: 0.08287532975667135", + "Likelihood: 0.10849016285229268", + "Likelihood: 0.26044872999101193", + "Likelihood: 0.2607348424652687", + "Likelihood: 0.21426255497571634", + "Likelihood: 0.30853869843589327", + "Likelihood: 0.20379818780448952", + "Likelihood: 0.25810782940992477", + "Likelihood: 0.09146471468288526", + "Likelihood: 0.00928555901113324", + "Likelihood: 0.257483659338504", + "Likelihood: 0.0971974208561149", + "Likelihood: 0.19496472326507822", + "Likelihood: 0.020399907419248083", + "Likelihood: 0.212509765888328", + "Likelihood: 0.1464893147075384", + "Likelihood: 0.08923247427016319", + "Likelihood: 0.16140726847597478", + "Likelihood: 0.15140549600546022", + "Likelihood: 0.1370722647302931", + "Likelihood: 0.2538518333162618", + "Likelihood: 0.258337554194617", + "Likelihood: 0.15340860457349792", + "Likelihood: 0.2914402586097388", + "Likelihood: 0.015150184013781175", + "Likelihood: 0.18518018466190136", + "Likelihood: 0.036838725712993375", + "Likelihood: 0.06572762174428214", + "Likelihood: 0.13816379844982882", + "Likelihood: 0.20430738947201207", + "Likelihood: 0.02319838907825957", + "Likelihood: 0.11126247123648038", + "Likelihood: 0.01417038680772304", + "Likelihood: 0.24538388123621863", + "Likelihood: 0.19882219433714715", + "Likelihood: 0.03841166739806583", + "Likelihood: 0.22717436695045187", + "Likelihood: 0.21299622188190284", + "Likelihood: 0.1355113005955408", + "Likelihood: 0.13226712702212684", + "Likelihood: 0.22314864406547982", + "Likelihood: 0.19840054080770445", + "Likelihood: 0.014341412790025846", + "Likelihood: 0.28168969938319605", + "Likelihood: 0.08754337764940512", + "Likelihood: 0.02402327103692299", + "Likelihood: 0.03382616026214944", + "Likelihood: 0.12142258886677226", + "Likelihood: 0.2629667857431377", + "Likelihood: 0.08747837322121108", + "Likelihood: 0.16783453398271658", + "Likelihood: 0.07435739453565912", + "Likelihood: 0.05568726124206783", + "Likelihood: 0.03416803760745859", + "Likelihood: 0.020027639898719512", + "Likelihood: 0.2622799324706445", + "Likelihood: 0.28736215891540484", + "Likelihood: 0.0320065563112554", + "Likelihood: 0.09042756349543311", + "Likelihood: 0.03808894679297944", + "Likelihood: 0.05615172101837627", + "Likelihood: 0.19331832880059843", + "Likelihood: 0.2043266074527171", + "Likelihood: 0.018437795586444355", + "Likelihood: 0.3048808236127398", + "Likelihood: 0.15852299903924938", + "Likelihood: 0.12796646611952164", + "Likelihood: 0.046998292575561734", + "Likelihood: 0.1494929895029537", + "Likelihood: 0.046553749625438304", + "Likelihood: 0.005269976538080795", + "Likelihood: 0.29186363441659896", + "Likelihood: 0.307041288050445", + "Likelihood: 0.20469251861941584", + "Likelihood: 0.05686713829477231", + "Likelihood: 0.043270353976056455", + "Likelihood: 0.0343278394434463", + "Likelihood: 0.10268311151941699", + "Likelihood: 0.031028104926615625", + "Likelihood: 0.29452944426103606", + "Likelihood: 0.008783849254838522", + "Likelihood: 0.18681127245540882", + "Likelihood: 0.06396690709100429", + "Likelihood: 0.08149080593050333", + "Likelihood: 0.19104790136280042", + "Likelihood: 0.21641001646657484", + "Likelihood: 0.251999434877965", + "Likelihood: 0.25114908787522", + "Likelihood: 0.059042982668606483", + "Likelihood: 0.15918610806508976", + "Likelihood: 0.029545883856686245", + "Likelihood: 0.06010106093948204", + "Likelihood: 0.0649621354906516", + "Likelihood: 0.19313187193597708", + "Likelihood: 0.11295218253682987", + "Likelihood: 0.2093331535295614", + "Likelihood: 0.05645774154550585", + "Likelihood: 0.02525636101429283", + "Likelihood: 0.24724363165580812", + "Likelihood: 0.27898115444966287", + "Likelihood: 0.0632701939150581", + "Likelihood: 0.0839519825395797", + "Likelihood: 0.0654688896310595", + "Likelihood: 0.21060997183712646", + "Likelihood: 0.3114027943839424", + "Likelihood: 0.3064298906331288", + "Likelihood: 0.2740760067030924", + "Likelihood: 0.3195559935481534", + "Likelihood: 0.07749792761958893", + "Likelihood: 0.3003872213265561", + "Likelihood: 0.23047689848276973", + "Likelihood: 0.2136589906250219", + "Likelihood: 0.03309972201717694", + "Likelihood: 0.22492823720241598", + "Likelihood: 0.201868727357108", + "Likelihood: 0.3027758805373924", + "Likelihood: 0.2835539502902321", + "Likelihood: 0.24059695219903215", + "Likelihood: 0.11138396895765877", + "Likelihood: 0.11268856935562377", + "Likelihood: 0.3162593442741605", + "Likelihood: 0.2944227907665575", + "Likelihood: 0.1351321416586221", + "Likelihood: 0.285729484682759", + "Likelihood: 0.24352018781937174", + "Likelihood: 0.2376007392900046", + "Likelihood: 0.24259154757323373", + "Likelihood: 0.02534531865795615", + "Likelihood: 0.13854400665960098", + "Likelihood: 0.17557084961134292", + "Likelihood: 0.2468942194295475", + "Likelihood: 0.1375161616299761", + "Likelihood: 0.16010258287757406", + "Likelihood: 0.30656347503939546", + "Likelihood: 0.2955559578258399", + "Likelihood: 0.19458882208430603", + "Likelihood: 0.21623496092029246", + "Likelihood: 0.2904983668299791", + "Likelihood: 0.17750765978921657", + "Likelihood: 0.1347843526576717", + "Likelihood: 0.24249553690851755", + "Likelihood: 0.31402388355055744", + "Likelihood: 0.10474312588153875", + "Likelihood: 0.2916086024870162", + "Likelihood: 0.14009695131171268", + "Likelihood: 0.09709478410132788", + "Likelihood: 0.3146843806352462", + "Likelihood: 0.31251924582559015", + "Likelihood: 0.3217543788821077", + "Likelihood: 0.05362009038497432", + "Likelihood: 0.17779542623543446", + "Likelihood: 0.22059272635494095", + "Likelihood: 0.11047797603414694", + "Likelihood: 0.11840155883987699", + "Likelihood: 0.09596107805474487", + "Likelihood: 0.31714559826351435", + "Likelihood: 0.11414573256640369", + "Likelihood: 0.05870957822666993", + "Likelihood: 0.10100868113721856", + "Likelihood: 0.0468565233610647", + "Likelihood: 0.29459523761616", + "Likelihood: 0.22820683435152722", + "Likelihood: 0.16791159156872884", + "Likelihood: 0.32100092996109064", + "Likelihood: 0.06416324650440482", + "Likelihood: 0.2524845945962122", + "Likelihood: 0.2708271697273168", + "Likelihood: 0.3183442348728953", + "Likelihood: 0.23944136647304426", + "Likelihood: 0.21444311300552618", + "Likelihood: 0.2664533606367243", + "Likelihood: 0.15326962400640973", + "Likelihood: 0.11183797833077792", + "Likelihood: 0.27167414854922095", + "Likelihood: 0.31226900466721774", + "Likelihood: 0.11494507409750725", + "Likelihood: 0.2468173381493523", + "Likelihood: 0.01940562007911429", + "Likelihood: 0.25833930103051456", + "Likelihood: 0.1296741010061383", + "Likelihood: 0.29261125113620406", + "Likelihood: 0.2833732865170331", + "Likelihood: 0.2779528744144469", + "Likelihood: 0.06551727114476413", + "Likelihood: 0.3120694196436214", + "Likelihood: 0.012733616000406955", + "Likelihood: 0.30977697863354814", + "Likelihood: 0.1177642627579804", + "Likelihood: 0.1368945463262895", + "Likelihood: 0.1971052054161182", + "Likelihood: 0.268716646283398", + "Likelihood: 0.3166531201075028", + "Likelihood: 0.1521523877093263", + "Likelihood: 0.30999975419262504", + "Likelihood: 0.23250402059549646", + "Likelihood: 0.2983538499869923", + "Likelihood: 0.27513773851709916", + "Likelihood: 0.21696359231209075", + "Likelihood: 0.022989584516771553", + "Likelihood: 0.28778016999518197", + "Likelihood: 0.24700827772804415", + "Likelihood: 0.3014015918279045", + "Likelihood: 0.16154810056900765", + "Likelihood: 0.25670334071623085", + "Likelihood: 0.1387915873315839", + "Likelihood: 0.3123111779481489", + "Likelihood: 0.2867409797560852", + "Likelihood: 0.2921229519221381", + "Likelihood: 0.2648812280905177", + "Likelihood: 0.21388746537446798", + "Likelihood: 0.2543454996050511", + "Likelihood: 0.184015709501408", + "Likelihood: 0.14511810952688503", + "Likelihood: 0.07431560240849584", + "Likelihood: 0.25793575102659727", + "Likelihood: 0.23755417244781407", + "Likelihood: 0.29670696545724257", + "Likelihood: 0.2616854931899381", + "Likelihood: 0.24825926499296788", + "Likelihood: 0.3154672318836072", + "Likelihood: 0.29674442141148905", + "Likelihood: 0.19994480877630136", + "Likelihood: 0.29606033130327686", + "Likelihood: 0.0949134556429366", + "Likelihood: 0.1193625965617501", + "Likelihood: 0.3192975812854978", + "Likelihood: 0.0697267729263259", + "Likelihood: 0.2714865853585937", + "Likelihood: 0.1513134068933203", + "Likelihood: 0.2304505800903032", + "Likelihood: 0.07900390561216737", + "Likelihood: 0.10405214617243005", + "Likelihood: 0.3013363549187382", + "Likelihood: 0.3058847535883011", + "Likelihood: 0.19383270612232129", + "Likelihood: 0.3152064448349728", + "Likelihood: 0.14608807721941242", + "Likelihood: 0.190163292437463", + "Likelihood: 0.1030171492864831", + "Likelihood: 0.290927154202821", + "Likelihood: 0.25085345290534805", + "Likelihood: 0.26265971544536465", + "Likelihood: 0.25581139696821364", + "Likelihood: 0.19412731678336834", + "Likelihood: 0.017818461952671727", + "Likelihood: 0.12018998904324883", + "Likelihood: 0.3207535276925807", + "Likelihood: 0.04027008759771978", + "Likelihood: 0.22607724890779604", + "Likelihood: 0.20239078280085301", + "Likelihood: 0.12813992081954728", + "Likelihood: 0.2807993980062725", + "Likelihood: 0.2172712882214551", + "Likelihood: 0.20848987507892822", + "Likelihood: 0.06460169595457133", + "Likelihood: 0.11470022369523465", + "Likelihood: 0.3113818784535631", + "Likelihood: 0.00835575283530031", + "Likelihood: 0.28977196947973066", + "Likelihood: 0.2933559732104484", + "Likelihood: 0.04233191950124811", + "Likelihood: 0.09332430427480404", + "Likelihood: 0.2999398953681784", + "Likelihood: 0.11912031105275858", + "Likelihood: 0.011574700021703492", + "Likelihood: 0.23676271576543714", + "Likelihood: 0.2093603432002219", + "Likelihood: 0.009738105638666963", + "Likelihood: 0.23155314773298952", + "Likelihood: 0.19567810240598413", + "Likelihood: 0.09433506694172879", + "Likelihood: 0.2831139755765848", + "Likelihood: 0.26030326270446624", + "Likelihood: 0.20447322888448033", + "Likelihood: 0.251242188393036", + "Likelihood: 0.2543888181723918", + "Likelihood: 0.13129495709841213", + "Likelihood: 0.25910601954831775", + "Likelihood: 0.09455818285529197", + "Likelihood: 0.02179829188462674", + "Likelihood: 0.30506565059764235", + "Likelihood: 0.32373382923421695", + "Likelihood: 0.2843834993444984", + "Likelihood: 0.14885216736439083", + "Likelihood: 0.26707348749784754", + "Likelihood: 0.27821359836156884", + "Likelihood: 0.14622016560562484", + "Likelihood: 0.30137635318303774", + "Likelihood: 0.26603360912273366", + "Likelihood: 0.3121448234480715", + "Likelihood: 0.08648275362212184", + "Likelihood: 0.29957436156672684", + "Likelihood: 0.16518615548155366", + "Likelihood: 0.29955119365214133", + "Likelihood: 0.1885029646084964", + "Likelihood: 0.26746998487357065", + "Likelihood: 0.09407521598613873", + "Likelihood: 0.19840448697320467", + "Likelihood: 0.28825358153625724", + "Likelihood: 0.3172319146753494", + "Likelihood: 0.18489760763083024", + "Likelihood: 0.025413273413400383", + "Likelihood: 0.02440409552295456", + "Likelihood: 0.3123787110660724", + "Likelihood: 0.1242578121527304", + "Likelihood: 0.20525529317416819", + "Likelihood: 0.2369274585590322", + "Likelihood: 0.21593915507791864", + "Likelihood: 0.07468696681813908", + "Likelihood: 0.24381409597726172", + "Likelihood: 0.16965383482185514", + "Likelihood: 0.2369071742705042", + "Likelihood: 0.2517307070872527", + "Likelihood: 0.00890480977486671", + "Likelihood: 0.22337975509669525", + "Likelihood: 0.30883030599652256", + "Likelihood: 0.32079831787610685", + "Likelihood: 0.30203464841912364", + "Likelihood: 0.30480923695126905", + "Likelihood: 0.30018642192215617", + "Likelihood: 0.1558120504172084", + "Likelihood: 0.06715382248790026", + "Likelihood: 0.2297693245468581", + "Likelihood: 0.03864092479083949", + "Likelihood: 0.07564206956404504", + "Likelihood: 0.021474502822671007", + "Likelihood: 0.16831075777137774", + "Likelihood: 0.28929592277299837", + "Likelihood: 0.20843981998737462", + "Likelihood: 0.25072549238611075", + "Likelihood: 0.30437406457004884", + "Likelihood: 0.11168205336943582", + "Likelihood: 0.10449991970679179", + "Likelihood: 0.25124823274969116", + "Likelihood: 0.12864045915306638", + "Likelihood: 0.2892559083260384", + "Likelihood: 0.2864302413069665", + "Likelihood: 0.1869412964660205", + "Likelihood: 0.153434753072612", + "Likelihood: 0.29161682442872666", + "Likelihood: 0.3177492150351406", + "Likelihood: 0.0841753698500695", + "Likelihood: 0.15342924569276467", + "Likelihood: 0.27849502658684383", + "Likelihood: 0.19097316382840598", + "Likelihood: 0.09131011638938347", + "Likelihood: 0.3030381795598993", + "Likelihood: 0.0737192020582533", + "Likelihood: 0.32080504139670507", + "Likelihood: 0.3119492248129041", + "Likelihood: 0.009945996446357824", + "Likelihood: 0.2880727456390805", + "Likelihood: 0.2132417917775103", + "Likelihood: 0.31292503352710843", + "Likelihood: 0.1370699007227856", + "Likelihood: 0.19362965035235188", + "Likelihood: 0.302507739684522", + "Likelihood: 0.3040388024465033", + "Likelihood: 0.23726920744975538", + "Likelihood: 0.235822731071721", + "Likelihood: 0.1268632636857003", + "Likelihood: 0.22003886339236237", + "Likelihood: 0.24437261862859494", + "Likelihood: 0.2952148153177575", + "Likelihood: 0.2131884601480523", + "Likelihood: 0.2509013452545873", + "Likelihood: 0.05921137287039414", + "Likelihood: 0.1816081551653537", + "Likelihood: 0.23692103628837188", + "Likelihood: 0.14867168501697467", + "Likelihood: 0.300229328066917", + "Likelihood: 0.04942615864183684", + "Likelihood: 0.19037973957045845", + "Likelihood: 0.2178558635254142", + "Likelihood: 0.2689493682540116", + "Likelihood: 0.20319134141461337", + "Likelihood: 0.28418605868524394", + "Likelihood: 0.28649938922199814", + "Likelihood: 0.32222492984703477", + "Likelihood: 0.2784428416038638", + "Likelihood: 0.17130551714956965", + "Likelihood: 0.07832312206010741", + "Likelihood: 0.2957977836672897", + "Likelihood: 0.26489010505949195", + "Likelihood: 0.2794233502146301", + "Likelihood: 0.2901108403910513", + "Likelihood: 0.22345230379434589", + "Likelihood: 0.016528198249320124", + "Likelihood: 0.2505246442675582", + "Likelihood: 0.1581930690875049", + "Likelihood: 0.272369876101389", + "Likelihood: 0.2418219401996724", + "Likelihood: 0.21146053444293547", + "Likelihood: 0.1600967305756099", + "Likelihood: 0.21431943196869144", + "Likelihood: 0.11291814840762648", + "Likelihood: 0.2923894893421205", + "Likelihood: 0.19382472584270613", + "Likelihood: 0.14350115062518126", + "Likelihood: 0.1339013320758157", + "Likelihood: 0.24215196756591398", + "Likelihood: 0.32079520637755105", + "Likelihood: 0.08593730838550301", + "Likelihood: 0.0915671679082846", + "Likelihood: 0.17713325891950965", + "Likelihood: 0.1484190318951595", + "Likelihood: 0.1742373809288826", + "Likelihood: 0.30868613244880005", + "Likelihood: 0.1418649873365736", + "Likelihood: 0.20751495358259658", + "Likelihood: 0.06974209672276267", + "Likelihood: 0.15995283615469022", + "Likelihood: 0.279215243952012", + "Likelihood: 0.23066862378370262", + "Likelihood: 0.3179232768861153", + "Likelihood: 0.2888646828412087", + "Likelihood: 0.01229031683083869", + "Likelihood: 0.27089847747344253", + "Likelihood: 0.13979191910665173", + "Likelihood: 0.0977750248423647", + "Likelihood: 0.07704649018727258", + "Likelihood: 0.2099579387027825", + "Likelihood: 0.12943339532380152", + "Likelihood: 0.2673765385148939", + "Likelihood: 0.2951420413229434", + "Likelihood: 0.3229405397021885", + "Likelihood: 0.2780049058867088", + "Likelihood: 0.05840432065000765", + "Likelihood: 0.3081218321599393", + "Likelihood: 0.2266998238853881", + "Likelihood: 0.10300699143272309", + "Likelihood: 0.25224125990451673", + "Likelihood: 0.22233500793699928", + "Likelihood: 0.14646761445541256", + "Likelihood: 0.3187669100805705", + "Likelihood: 0.18868972208906118", + "Likelihood: 0.2296567945774517", + "Likelihood: 0.321199824268598", + "Likelihood: 0.07313645094318105", + "Likelihood: 0.29066796491633795", + "Likelihood: 0.3222652618319796", + "Likelihood: 0.16818706875726352", + "Likelihood: 0.04670084583101125", + "Likelihood: 0.12921206842572905", + "Likelihood: 0.29040313052728156", + "Likelihood: 0.2768763100977773", + "Likelihood: 0.23741507852009636", + "Likelihood: 0.132692290716283", + "Likelihood: 0.10199110938707606", + "Likelihood: 0.2697352970882652", + "Likelihood: 0.11488695247890897", + "Likelihood: 0.18827512453890075", + "Likelihood: 0.2369804330456866", + "Likelihood: 0.2697613592763056", + "Likelihood: 0.2916460229377242", + "Likelihood: 0.27322577692018585", + "Likelihood: 0.3127526800403761", + "Likelihood: 0.11074174805832011", + "Likelihood: 0.15109424293374588", + "Likelihood: 0.19833057164092943", + "Likelihood: 0.11703933645997922", + "Likelihood: 0.24117442550508958", + "Likelihood: 0.05400207875676287", + "Likelihood: 0.24527061328619354", + "Likelihood: 0.11709469689441065", + "Likelihood: 0.2887461464647274", + "Likelihood: 0.11695520169397988", + "Likelihood: 0.3144004859874502", + "Likelihood: 0.1494560346440628", + "Likelihood: 0.20321381576650072", + "Likelihood: 0.24057638881870513", + "Likelihood: 0.3121510426064254", + "Likelihood: 0.15407552911843364", + "Likelihood: 0.2919501990444823", + "Likelihood: 0.2823073259795071", + "Likelihood: 0.3119091757121985", + "Likelihood: 0.2775292365358909", + "Likelihood: 0.18085342670251076", + "Likelihood: 0.2991815266019529", + "Likelihood: 0.2238268793290549", + "Likelihood: 0.252165557843131", + "Likelihood: 0.16897756031987632", + "Likelihood: 0.20907812148515437", + "Likelihood: 0.30825539028074483", + "Likelihood: 0.14784640636204244", + "Likelihood: 0.1233581093577829", + "Likelihood: 0.2737917571458233", + "Likelihood: 0.24952016660717574", + "Likelihood: 0.2649857813977896", + "Likelihood: 0.2015682791675279", + "Likelihood: 0.3143724176597207", + "Likelihood: 0.15261381206650848", + "Likelihood: 0.3192149778192818", + "Likelihood: 0.13553386086914998", + "Likelihood: 0.23019825669960434", + "Likelihood: 0.2812262403762425", + "Likelihood: 0.21363903422793157", + "Likelihood: 0.2619369559437767", + "Likelihood: 0.2481928752032798", + "Likelihood: 0.21349802588007435", + "Likelihood: 0.15764843707150314", + "Likelihood: 0.3158610637176008", + "Likelihood: 0.11246087963136285", + "Likelihood: 0.27806004541427926", + "Likelihood: 0.2777183131206609", + "Likelihood: 0.025997437864934206", + "Likelihood: 0.21241303843978185", + "Likelihood: 0.28691888411770033", + "Likelihood: 0.22537699392863622", + "Likelihood: 0.3187986076206924", + "Likelihood: 0.2808772476208797", + "Likelihood: 0.1337180225829296", + "Likelihood: 0.18789512812384554", + "Likelihood: 0.11229407576833209", + "Likelihood: 0.053428955661142946", + "Likelihood: 0.17938781920312655", + "Likelihood: 0.25411518282484075", + "Likelihood: 0.08547337365259035", + "Likelihood: 0.03736533024768326", + "Likelihood: 0.26765662977790483", + "Likelihood: 0.05865321226555143", + "Likelihood: 0.12152560968592631", + "Likelihood: 0.20998531718428676", + "Likelihood: 0.29711819031352493", + "Likelihood: 0.065270759439233", + "Likelihood: 0.14561450602861853", + "Likelihood: 0.303409161866672", + "Likelihood: 0.29888302160993957", + "Likelihood: 0.2471842089194829", + "Likelihood: 0.2850433165407496", + "Likelihood: 0.2692854590134723", + "Likelihood: 0.2938153653873281", + "Likelihood: 0.12896096648048722", + "Likelihood: 0.3051883273138236", + "Likelihood: 0.17285048483584642", + "Likelihood: 0.050855170869212145", + "Likelihood: 0.1598159096036641", + "Likelihood: 0.24767228880743195", + "Likelihood: 0.07444348000075629", + "Likelihood: 0.19607726806369966", + "Likelihood: 0.31095868821520417", + "Likelihood: 0.2362380382943879", + "Likelihood: 0.23856284623022347", + "Likelihood: 0.13542329802944242", + "Likelihood: 0.20232764020885616", + "Likelihood: 0.13594623823717836", + "Likelihood: 0.2524947974468419", + "Likelihood: 0.2980016838805341", + "Likelihood: 0.3132260369732514", + "Likelihood: 0.08514678966056363", + "Likelihood: 0.2916776537077139", + "Likelihood: 0.18314301331961216", + "Likelihood: 0.19984650883660093", + "Likelihood: 0.19288157921151078", + "Likelihood: 0.28347461969188026", + "Likelihood: 0.2647998621487242", + "Likelihood: 0.28626921357044866", + "Likelihood: 0.2902710392234402", + "Likelihood: 0.05990310586513515", + "Likelihood: 0.2322836109233143", + "Likelihood: 0.3172300035815807", + "Likelihood: 0.04964135533413868", + "Likelihood: 0.19972547785578665", + "Likelihood: 0.221588609748743", + "Likelihood: 0.006682076131537961", + "Likelihood: 0.30713660614845206", + "Likelihood: 0.04079929872262811", + "Likelihood: 0.1929006202193605", + "Likelihood: 0.17847781459946346", + "Likelihood: 0.3032124136876006", + "Likelihood: 0.1364595637317656", + "Likelihood: 0.27456268167926545", + "Likelihood: 0.11715466433691674", + "Likelihood: 0.18991648498916255", + "Likelihood: 0.09933238269008132", + "Likelihood: 0.3070974066506395", + "Likelihood: 0.15236574993101715", + "Likelihood: 0.1657764142323044", + "Likelihood: 0.28199519154548697", + "Likelihood: 0.29476635550840047", + "Likelihood: 0.009806743766167284", + "Likelihood: 0.0699177276822157", + "Likelihood: 0.24271846944118064", + "Likelihood: 0.2586752565593006", + "Likelihood: 0.13770929963671355", + "Likelihood: 0.09720972105130364", + "Likelihood: 0.21013973409328848", + "Likelihood: 0.3007824562935286", + "Likelihood: 0.2837992058271253", + "Likelihood: 0.19892128634852774", + "Likelihood: 0.3175573393435412", + "Likelihood: 0.07670819177244362", + "Likelihood: 0.31478592450481785", + "Likelihood: 0.29252767184744927", + "Likelihood: 0.13005041639342566", + "Likelihood: 0.30546189128335066", + "Likelihood: 0.07080382055421754", + "Likelihood: 0.1526771104746443", + "Likelihood: 0.32069618839221864", + "Likelihood: 0.29340468710061807", + "Likelihood: 0.29046932781342716", + "Likelihood: 0.13149067854934482", + "Likelihood: 0.2777297281982996", + "Likelihood: 0.14002734507392323", + "Likelihood: 0.303851634477221", + "Likelihood: 0.1573123023071375", + "Likelihood: 0.23850694909890466", + "Likelihood: 0.11018484961992023", + "Likelihood: 0.2360453692251804", + "Likelihood: 0.09954429213804353", + "Likelihood: 0.28476450960640604", + "Likelihood: 0.06442719664679732", + "Likelihood: 0.1649354157510925", + "Likelihood: 0.2035677355172259", + "Likelihood: 0.07459083212370156", + "Likelihood: 0.08905134983520335", + "Likelihood: 0.30285633788345945", + "Likelihood: 0.1830736859682409", + "Likelihood: 0.13243311356128304", + "Likelihood: 0.30857932721303916", + "Likelihood: 0.24137037218279095", + "Likelihood: 0.1910334387630669", + "Likelihood: 0.30714628854556786", + "Likelihood: 0.2954137489009469", + "Likelihood: 0.11524007618949124", + "Likelihood: 0.14329940680481185", + "Likelihood: 0.1892581434284247", + "Likelihood: 0.24692784341587445", + "Likelihood: 0.2948514748380821", + "Likelihood: 0.29478033088496164", + "Likelihood: 0.018531072878121932", + "Likelihood: 0.009624495362920994", + "Likelihood: 0.21460528809022214", + "Likelihood: 0.30889295721640025", + "Likelihood: 0.306135894962206", + "Likelihood: 0.18323591176335627", + "Likelihood: 0.2497520037352582", + "Likelihood: 0.25020123784756415", + "Likelihood: 0.2361565996298872", + "Likelihood: 0.27476802132126854", + "Likelihood: 0.14058584417475636", + "Likelihood: 0.2975470813613464", + "Likelihood: 0.03860271234066933", + "Likelihood: 0.17982055933695792", + "Likelihood: 0.09902576322449642", + "Likelihood: 0.10942098652099287", + "Likelihood: 0.3145123769149998", + "Likelihood: 0.17761184527785995", + "Likelihood: 0.024524190707169918", + "Likelihood: 0.12874491775984306", + "Likelihood: 0.3039619465111921", + "Likelihood: 0.24371603148984433", + "Likelihood: 0.20341817780913476", + "Likelihood: 0.27045590956657684", + "Likelihood: 0.2583691935378612", + "Likelihood: 0.1512108557101298", + "Likelihood: 0.07570542874787539", + "Likelihood: 0.2334943551543351", + "Likelihood: 0.08497129682203314", + "Likelihood: 0.034196094406950546", + "Likelihood: 0.2858801742901744", + "Likelihood: 0.3154387567980009", + "Likelihood: 0.3115853513679572", + "Likelihood: 0.24255693704509554", + "Likelihood: 0.28093262223739385", + "Likelihood: 0.29188978281617195", + "Likelihood: 0.25587648118657014", + "Likelihood: 0.3069758410262109", + "Likelihood: 0.1664677186718195", + "Likelihood: 0.09188173717226439", + "Likelihood: 0.27844903579096925", + "Likelihood: 0.16405199740658188", + "Likelihood: 0.15415632649495786", + "Likelihood: 0.2778720521261735", + "Likelihood: 0.27209581267678495", + "Likelihood: 0.31857872662069947", + "Likelihood: 0.2855523471513844", + "Likelihood: 0.3121948009334693", + "Likelihood: 0.015060280890499786", + "Likelihood: 0.2678466674291499", + "Likelihood: 0.025038634458768895", + "Likelihood: 0.20377433490007987", + "Likelihood: 0.23268579734907455", + "Likelihood: 0.14789629147215974", + "Likelihood: 0.20886860000755547", + "Likelihood: 0.2565655366042359", + "Likelihood: 0.23526015499142164", + "Likelihood: 0.3034516067014563", + "Likelihood: 0.3245989548431352", + "Likelihood: 0.1979477710485385", + "Likelihood: 0.269726266616032", + "Likelihood: 0.25294469040819106", + "Likelihood: 0.3114783566489416", + "Likelihood: 0.04708332570015489", + "Likelihood: 0.24516137230688534", + "Likelihood: 0.22301981341581967", + "Likelihood: 0.11608647364234514", + "Likelihood: 0.26496468711036214", + "Likelihood: 0.26126057793572666", + "Likelihood: 0.13926285112139938", + "Likelihood: 0.2863369739153583", + "Likelihood: 0.27351261961295237", + "Likelihood: 0.29840795594432257", + "Likelihood: 0.11106524347924181", + "Likelihood: 0.31270198361264917", + "Likelihood: 0.025158125833099242", + "Likelihood: 0.3142253548152456", + "Likelihood: 0.2538738962422758", + "Likelihood: 0.23630102735528755", + "Likelihood: 0.07108252095539574", + "Likelihood: 0.2980084890767245", + "Likelihood: 0.3102346995249678", + "Likelihood: 0.19138753165019612", + "Likelihood: 0.28102208573583054", + "Likelihood: 0.24488736306117878", + "Likelihood: 0.05106808416666272", + "Likelihood: 0.3031165044549647", + "Likelihood: 0.2849445127852772", + "Likelihood: 0.25823967181106666", + "Likelihood: 0.2594048878081343", + "Likelihood: 0.07753723110439574", + "Likelihood: 0.29434250559452185", + "Likelihood: 0.15582593574845044", + "Likelihood: 0.24982264994006317", + "Likelihood: 0.2922399366625663", + "Likelihood: 0.2326403793858854", + "Likelihood: 0.259446116703626", + "Likelihood: 0.2527457787514931", + "Likelihood: 0.11429486838945137", + "Likelihood: 0.24249192018165205", + "Likelihood: 0.0864467249803181", + "Likelihood: 0.2585860808161118", + "Likelihood: 0.3164024473945526", + "Likelihood: 0.0160762332774737", + "Likelihood: 0.2743288920821871", + "Likelihood: 0.28969908553787976", + "Likelihood: 0.14938661099202644", + "Likelihood: 0.30547310497230734", + "Likelihood: 0.24144965095637533", + "Likelihood: 0.2680688231054674", + "Likelihood: 0.312348352701991", + "Likelihood: 0.21720101738092668", + "Likelihood: 0.23053250818796744", + "Likelihood: 0.24095937070647144", + "Likelihood: 0.18077338744499866", + "Likelihood: 0.25155155786547484", + "Likelihood: 0.31015421082663003", + "Likelihood: 0.14973846354076736", + "Likelihood: 0.23947757570795306", + "Likelihood: 0.23811649691390838", + "Likelihood: 0.04038318147186157", + "Likelihood: 0.2206460931228841", + "Likelihood: 0.28925665474497153", + "Likelihood: 0.058408739937004746", + "Likelihood: 0.2546135768560508", + "Likelihood: 0.30774493676480863", + "Likelihood: 0.25916949143630125", + "Likelihood: 0.30508252689216575", + "Likelihood: 0.1047537522264308", + "Likelihood: 0.19464211356865618", + "Likelihood: 0.07621666713863534", + "Likelihood: 0.2999504085775197", + "Likelihood: 0.2868726434373773", + "Likelihood: 0.06807100088870564", + "Likelihood: 0.2844135214551305", + "Likelihood: 0.18335956674063428", + "Likelihood: 0.1420820859520656", + "Likelihood: 0.1756953769199706", + "Likelihood: 0.305819845748924", + "Likelihood: 0.06946395903515035", + "Likelihood: 0.2499064302058957", + "Likelihood: 0.08402487189660332", + "Likelihood: 0.030482407444550986", + "Likelihood: 0.27053798180480554", + "Likelihood: 0.29949000680003723", + "Likelihood: 0.15804875866709336", + "Likelihood: 0.18847308754085362", + "Likelihood: 0.3089256286370262", + "Likelihood: 0.22917219871866915", + "Likelihood: 0.17382110673812526", + "Likelihood: 0.13669765694745376", + "Likelihood: 0.1092198969871246", + "Likelihood: 0.01249490831857202", + "Likelihood: 0.022737581688326063", + "Likelihood: 0.17290124063686482", + "Likelihood: 0.21220440137712576", + "Likelihood: 0.2969628010685857", + "Likelihood: 0.2530400890338978", + "Likelihood: 0.22415980927817114", + "Likelihood: 0.316428844231056", + "Likelihood: 0.22911000960155717", + "Likelihood: 0.28922904843579794", + "Likelihood: 0.21658858501866124", + "Likelihood: 0.10356507632792833", + "Likelihood: 0.31801355333926984", + "Likelihood: 0.2830674705601002", + "Likelihood: 0.10771764688189356", + "Likelihood: 0.1642012242045967", + "Likelihood: 0.019891584371996514", + "Likelihood: 0.14221131081443336", + "Likelihood: 0.22942893482019705", + "Likelihood: 0.1069109081023749", + "Likelihood: 0.26502599235860996", + "Likelihood: 0.19704288536443107", + "Likelihood: 0.12509086388412416", + "Likelihood: 0.2721472401877011", + "Likelihood: 0.2993007155134703", + "Likelihood: 0.19378610222740594", + "Likelihood: 0.3077275101688099", + "Likelihood: 0.021889859662693235", + "Likelihood: 0.028791219386701497", + "Likelihood: 0.31065408101678443", + "Likelihood: 0.19876124642878834", + "Likelihood: 0.23153106299021592", + "Likelihood: 0.21934341666988041", + "Likelihood: 0.04473388155761919", + "Likelihood: 0.22913292917351893", + "Likelihood: 0.020819662430281192", + "Likelihood: 0.30993019007803246", + "Likelihood: 0.29089536473871386", + "Likelihood: 0.09599195323281659", + "Likelihood: 0.2921349262467775", + "Likelihood: 0.2697988971858578", + "Likelihood: 0.1790152162395465", + "Likelihood: 0.06770988069503539", + "Likelihood: 0.15435792801485013", + "Likelihood: 0.315438207242484", + "Likelihood: 0.3159383493953981", + "Likelihood: 0.22344415928915423", + "Likelihood: 0.17769406337452232", + "Likelihood: 0.10116279404093263", + "Likelihood: 0.15427058814122746", + "Likelihood: 0.2065538649287449", + "Likelihood: 0.10896928330262844", + "Likelihood: 0.24581591167287264", + "Likelihood: 0.25807387674743126", + "Likelihood: 0.12103117577507673", + "Likelihood: 0.24981105034381507", + "Likelihood: 0.20267206428133663", + "Likelihood: 0.2337386327725435", + "Likelihood: 0.17707869279946617", + "Likelihood: 0.2796439097143129", + "Likelihood: 0.2047361431370857", + "Likelihood: 0.15957193186907448", + "Likelihood: 0.16956834716959407", + "Likelihood: 0.15095204588921446", + "Likelihood: 0.2967104153117351", + "Likelihood: 0.2892250944591763", + "Likelihood: 0.264635525141574", + "Likelihood: 0.20268899659876266", + "Likelihood: 0.31303143392003546", + "Likelihood: 0.28902704125884904", + "Likelihood: 0.1892897692661756", + "Likelihood: 0.2024130917124336", + "Likelihood: 0.3018609122407584", + "Likelihood: 0.3112649463027553", + "Likelihood: 0.29278556106630793", + "Likelihood: 0.25195797924624325", + "Likelihood: 0.18644247095229358", + "Likelihood: 0.22635451094410636", + "Likelihood: 0.1405889996369455", + "Likelihood: 0.26032439932237994", + "Likelihood: 0.3204082070093995", + "Likelihood: 0.07660203871853624", + "Likelihood: 0.18262724725784707", + "Likelihood: 0.1303618017722617", + "Likelihood: 0.10331250208905977", + "Likelihood: 0.20709531538212966", + "Likelihood: 0.2950384494884472", + "Likelihood: 0.12693500868646437", + "Likelihood: 0.28623013744774556", + "Likelihood: 0.3040325899418004", + "Likelihood: 0.26922111539239346", + "Likelihood: 0.04004261688100314", + "Likelihood: 0.3095102115000658", + "Likelihood: 0.31133999921422445", + "Likelihood: 0.314771302126099", + "Likelihood: 0.3118838275817921", + "Likelihood: 0.25370515175666764", + "Likelihood: 0.30239470683446773", + "Likelihood: 0.20239589084531032", + "Likelihood: 0.15143085485340402", + "Likelihood: 0.25204538839740465", + "Likelihood: 0.1778414284637215", + "Likelihood: 0.2234088942772311", + "Likelihood: 0.23268092273016633", + "Likelihood: 0.27018099070506346", + "Likelihood: 0.30933117098671326", + "Likelihood: 0.21389712231602606", + "Likelihood: 0.3019409866758076", + "Likelihood: 0.14013328819713344", + "Likelihood: 0.32431090941131097", + "Likelihood: 0.30030343175333074", + "Likelihood: 0.19604502005541602", + "Likelihood: 0.31674605210327433", + "Likelihood: 0.25235855524794104", + "Likelihood: 0.2205609132037727", + "Likelihood: 0.04011603255038648", + "Likelihood: 0.12851894524550297", + "Likelihood: 0.18709876599988717", + "Likelihood: 0.10784573721126278", + "Likelihood: 0.233170236480709", + "Likelihood: 0.23799683051240142", + "Likelihood: 0.039753756967053536", + "Likelihood: 0.26605559438356513", + "Likelihood: 0.21238230915884826", + "Likelihood: 0.2404909272249862", + "Likelihood: 0.07531166746797366", + "Likelihood: 0.030514550369428167", + "Likelihood: 0.23822803584430313", + "Likelihood: 0.30147906556074666", + "Likelihood: 0.22134134946944586", + "Likelihood: 0.2721493869625097", + "Likelihood: 0.1798286689641257", + "Likelihood: 0.3179264607557186", + "Likelihood: 0.26456368406206976", + "Likelihood: 0.2670820912672862", + "Likelihood: 0.08676767693508167", + "Likelihood: 0.31125446049809363", + "Likelihood: 0.3147726430088926", + "Likelihood: 0.21810116392801382", + "Likelihood: 0.10427194954562505", + "Likelihood: 0.1831353902209953", + "Likelihood: 0.06634013657718664", + "Likelihood: 0.2238642105838814", + "Likelihood: 0.15001268911698878", + "Likelihood: 0.30684038661123514", + "Likelihood: 0.32152768371164575", + "Likelihood: 0.05986288835788833", + "Likelihood: 0.12355756370857002", + "Likelihood: 0.23772230351400966", + "Likelihood: 0.12278944548669378", + "Likelihood: 0.30647015083451884", + "Likelihood: 0.15308429652070532", + "Likelihood: 0.3157217358324464", + "Likelihood: 0.17705341040598446", + "Likelihood: 0.22160505068806213", + "Likelihood: 0.12106646582395264", + "Likelihood: 0.19915264020720044", + "Likelihood: 0.3074247628734754", + "Likelihood: 0.19856381781268526", + "Likelihood: 0.10298184825870454", + "Likelihood: 0.311461009671775", + "Likelihood: 0.053364898552517956", + "Likelihood: 0.30882387201574824", + "Likelihood: 0.25028979945445884", + "Likelihood: 0.16386007184903842", + "Likelihood: 0.16361767342616934", + "Likelihood: 0.237662929981435", + "Likelihood: 0.07771368079307028", + "Likelihood: 0.17644077599040148", + "Likelihood: 0.20823096909252775", + "Likelihood: 0.3074782951556923", + "Likelihood: 0.045969395465592484", + "Likelihood: 0.3145684085672134", + "Likelihood: 0.2864543388821565", + "Likelihood: 0.26754755068157643", + "Likelihood: 0.2766593937022405", + "Likelihood: 0.31958915422870005", + "Likelihood: 0.17201170408023117", + "Likelihood: 0.09693942498586818", + "Likelihood: 0.2914035050905627", + "Likelihood: 0.3054377828314576", + "Likelihood: 0.22843184480415807", + "Likelihood: 0.30968785496394574", + "Likelihood: 0.2518942143828556", + "Likelihood: 0.2099758254722195", + "Likelihood: 0.08027188697949308", + "Likelihood: 0.16643801189697596", + "Likelihood: 0.30332625726552703", + "Likelihood: 0.16031058066872148", + "Likelihood: 0.3187605569295695", + "Likelihood: 0.21354544437543116", + "Likelihood: 0.31706666575711945", + "Likelihood: 0.323781599027803", + "Likelihood: 0.1484407270550038", + "Likelihood: 0.10608753046226499", + "Likelihood: 0.03855563374009703", + "Likelihood: 0.1518729683035541", + "Likelihood: 0.22827554024803098", + "Likelihood: 0.17999838547538877", + "Likelihood: 0.008128150553071919", + "Likelihood: 0.2460488268541951", + "Likelihood: 0.23082914304070204", + "Likelihood: 0.3138608586008805", + "Likelihood: 0.27575074672597183", + "Likelihood: 0.29573465998862364", + "Likelihood: 0.17703038107941904", + "Likelihood: 0.16968354164896837", + "Likelihood: 0.27624056381079165", + "Likelihood: 0.2973891691386823", + "Likelihood: 0.008181299109368429", + "Likelihood: 0.05854377107648863", + "Likelihood: 0.21221186891120428", + "Likelihood: 0.29906227026768634", + "Likelihood: 0.02823532962733171", + "Likelihood: 0.14175160593691222" ], "marker": { "color": [ - 0.2960051973772738, - 0.2635974014418118, - 0.2961502809293496, - 0.24383418113789573, - 0.2887295183970094, - 0.2823943705198645, - 0.24956378310538715, - 0.23778477851861288, - 0.11806185366215745, - 0.12159224815973602, - 0.269110410078513, - 0.23580291943781614, - 0.25495344657955277, - 0.2955781723092807, - 0.25706766173056445, - 0.279590899879218, - 0.25699796816183523, - 0.2728375195554467, - 0.23699914088567298, - 0.14061059152779215, - 0.21478260994432644, - 0.25252470776916447, - 0.13509486034575932, - 0.3031291604210207, - 0.2737190862395978, - 0.30073770544000517, - 0.16135949442440256, - 0.3032056718654632, - 0.2295320379629453, - 0.18872972584135736, - 0.20728403866794487, - 0.2500392660016838, - 0.023533580852094754, - 0.09261195612351694, - 0.30006312639562666, - 0.20617832857778134, - 0.21653222664654434, - 0.29017550122237257, - 0.2008344229030325, - 0.2050160750713673, - 0.23855719076563903, - 0.2172944008429403, - 0.24186450995555772, - 0.21864772293135398, - 0.1914478484038575, - 0.29523801449642434, - 0.2196511929285684, - 0.11500227281147939, - 0.2126862664209067, - 0.2933150694807476, - 0.23644121451450262, - 0.25484688787665516, - 0.2644166531625321, - 0.27841369296775537, - 0.09561406271963308, - 0.2102453045420369, - 0.2462282409310526, - 0.1541942903125031, - 0.201939214136583, - 0.2641975335636654, - 0.08588999534905599, - 0.21116177994038246, - 0.06273406982854238, - 0.14700378345905793, - 0.21640576636738587, - 0.22422828857945917, - 0.17788545212620985, - 0.29875229912760504, - 0.1404796862847426, - 0.2878687736767476, - 0.016572648158587375, - 0.27956650804865996, - 0.23870828512075742, - 0.28191599408486673, - 0.26991156495393315, - 0.2948064620205842, - 0.2848691505858482, - 0.22559801225618986, - 0.11786267204079678, - 0.28275955596874147, - 0.1240316390426622, - 0.14887828449355353, - 0.3036030368325772, - 0.23461744957449832, - 0.2866056729976452, - 0.282943100950079, - 0.30341190952991226, - 0.2343782115368479, - 0.29240527744838485, - 0.2828923153310132, - 0.26662493100299484, - 0.17521317645743623, - 0.27073650053728393, - 0.3034869089853294, - 0.22806442448016107, - 0.11931498113377373, - 0.24720157937725343, - 0.21268378630671353, - 0.21842626162369613, - 0.24003893092304415, - 0.26097437156246006, - 0.27985342972548405, - 0.20448022608716185, - 0.19862611141714973, - 0.24187716104248108, - 0.17488866682925794, - 0.051600309189276224, - 0.21477078493864352, - 0.19381747268488905, - 0.24260226747748018, - 0.10953479829572849, - 0.15713840452397737, - 0.19082573305131662, - 0.19765394513896142, - 0.22984265934658477, - 0.2693754927929895, - 0.269568075417542, - 0.29247702351381794, - 0.21447092243173788, - 0.298859439189825, - 0.2728075399918466, - 0.26963148316015534, - 0.2762321459241093, - 0.28131313590992174, - 0.2787452837045864, - 0.25536635605892644, - 0.2815559357316336, - 0.1919491181113979, - 0.23607796037118237, - 0.28030584631567274, - 0.2500602309691388, - 0.3010739482401385, - 0.22115037280240216, - 0.27183876055464706, - 0.2488751059911652, - 0.12463843918990865, - 0.2357268007478759, - 0.2900776768499681, - 0.13214949706642173, - 0.29843196087254714, - 0.30285653974328686, - 0.1423846744985272, - 0.14718018422719079, - 0.26940425833174597, - 0.21047736490379368, - 0.1252790983357328, - 0.2285340077106262, - 0.2850958040747654, - 0.2820481837911448, - 0.2981120133218698, - 0.29546719052366505, - 0.3043507116533075, - 0.2706056940509797, - 0.2582807934861423, - 0.2925235538364052, - 0.25343266918580276, - 0.20862314918912864, - 0.19796399998090686, - 0.15963105596419339, - 0.21448392317988269, - 0.2819898547377224, - 0.2402898023905061, - 0.23622951157002076, - 0.294375855751143, - 0.2391104597132889, - 0.3010519388747714, - 0.24121868743067995, - 0.1570366680774678, - 0.3015257205333031, - 0.3020541070676427, - 0.22415445416953475, - 0.29489793133683234, - 0.15753958690932446, - 0.07596739337500384, - 0.2401260157791593, - 0.1318246469636361, - 0.14929914340749842, - 0.2951410226538208, - 0.290941653830903, - 0.27391194445694267, - 0.28488210798316, - 0.16356617545055813, - 0.11232152841379293, - 0.13957894500520096, - 0.29117644592457365, - 0.26120698877807175, - 0.2551055117508274, - 0.2867431020787879, - 0.16539837091027249, - 0.29641892027276384, - 0.2714350940769336, - 0.19780662184254197, - 0.18495414708441799, - 0.30274710254966986, - 0.24034748874458303, - 0.3000310172551274, - 0.19425865019350205, - 0.26273783275965923, - 0.21118823847587156, - 0.2602340986082089, - 0.29729767255614253, - 0.29854536000005666, - 0.2885567107679648, - 0.2691490061288963, - 0.18699638524772863, - 0.19182427917388253, - 0.2933185316431407, - 0.2868418222926477, - 0.033619150000750664, - 0.26268050571100243, - 0.27663531699682736, - 0.27680583385067326, - 0.29988300981301885, - 0.2054330200726069, - 0.19223541250400958, - 0.30069670945008664, - 0.28659745793161084, - 0.2494113505786499, - 0.25809006968601694, - 0.27317155672121035, - 0.2957846314816964, - 0.28855169232006944, - 0.2795777366696988, - 0.30324336898895476, - 0.1952679089071436, - 0.22387250693778155, - 0.2464313735160234, - 0.28603038851303, - 0.23928561778995147, - 0.29357414655254627, - 0.2531573567016042, - 0.18296110638230265, - 0.24632753510408792, - 0.06206716413073452, - 0.15050936332446027, - 0.28185048456665573, - 0.29726634004960717, - 0.18269858065774947, - 0.28699831858752134, - 0.2369143171469688, - 0.16686748540115076, - 0.09402625017779871, - 0.2559396416807935, - 0.2543250841096261, - 0.29413510065485843, - 0.2805151728974315, - 0.25166432045200343, - 0.19944777379639697, - 0.26501236776712556, - 0.2996644891328505, - 0.20507621582101818, - 0.29089065199916625, - 0.1503981653611301, - 0.2535178231525427, - 0.27934801097316325, - 0.29989509021498983, - 0.09913148604284053, - 0.269375945126131, - 0.20878280944929853, - 0.11956242216596763, - 0.08495485673586783, - 0.2578293367552083, - 0.29540727286405744, - 0.29114184484101624, - 0.16753691044145685, - 0.2559573439917049, - 0.26666091109473616, - 0.2113889480080851, - 0.21229555840653777, - 0.042258911565124554, - 0.26769757448624126, - 0.21480688546414203, - 0.15954375119396205, - 0.20580264207238935, - 0.250542412701729, - 0.22503459508191392, - 0.27435715715220504, - 0.18256813697016305, - 0.18399375552229, - 0.1700961672398993, - 0.29289179614961997, - 0.22889766051874785, - 0.27798312794703506, - 0.20777740162764327, - 0.2980762758724712, - 0.28171847345072587, - 0.23658176511988172, - 0.1961872927637657, - 0.26287558198485234, - 0.25687416766385207, - 0.2803921737575837, - 0.28543475768889615, - 0.2630058576977688, - 0.27445905585827735, - 0.17553467663791578, - 0.28076381200526324, - 0.15649559773411326, - 0.15120828637054146, - 0.1829355880729986, - 0.24875899297934692, - 0.17713490630581288, - 0.28518504620759366, - 0.2774514297061875, - 0.28567041664473286, - 0.2884389538829595, - 0.16342400942122282, - 0.22698192109957482, - 0.28034335738368893, - 0.2857971262656073, - 0.21979741258361554, - 0.3032634563831829, - 0.1736977151154615, - 0.29705963236617533, - 0.14901602166217792, - 0.21328703922340767, - 0.2077622949442935, - 0.288320054797426, - 0.2612900199768941, - 0.15613994503788314, - 0.09749403425229707, - 0.22086328235952432, - 0.06923180729720761, - 0.13664206136594761, - 0.2454731671039702, - 0.18383474856941837, - 0.2395363874193355, - 0.28897699708888536, - 0.26190649375255415, - 0.1549726301080116, - 0.2511281389647274, - 0.25399139484198585, - 0.2289946078253289, - 0.1293788837627745, - 0.24656754108997064, - 0.24705555621553885, - 0.1339630268037889, - 0.3018188443557378, - 0.150485252107519, - 0.2671266646418594, - 0.28630402150370116, - 0.047172271555570064, - 0.2947868466668038, - 0.28146396173119326, - 0.17928679312555287, - 0.2146196760276306, - 0.15481419590593812, - 0.1704173538142748, - 0.24956133339181935, - 0.26323389355750526, - 0.295455150670845, - 0.21530802323005058, - 0.23072387517705775, - 0.11014779550449762, - 0.23357694871315618, - 0.19650192876377684, - 0.23333120904386093, - 0.16244585019110547, - 0.2711572891685677, - 0.10835505039967633, - 0.2913373181275813, - 0.1557298836982097, - 0.267211801174563, - 0.09062695899434588, - 0.2680990038842886, - 0.29905399908110414, - 0.131164930458136, - 0.28737874810491076, - 0.20663824558240343, - 0.29507577509108596, - 0.2531292304036051, - 0.28066534327524134, - 0.2760795892440463, - 0.13367256685216306, - 0.28597607056191554, - 0.28628707348088456, - 0.14939960112489276, - 0.23749142627335434, - 0.28935597880495917, - 0.1692207985361009, - 0.1744408349102826, - 0.14620102323697529, - 0.14706340664834355, - 0.17928800573560227, - 0.1458541590588936, - 0.21418727862031053, - 0.1431509472683106, - 0.22496139747819588, - 0.2831400505738617, - 0.29305026200752177, - 0.22586075837396352, - 0.09183719601538261, - 0.13794166472225533, - 0.300227269125567, - 0.2846146653863931, - 0.2970135215877043, - 0.18851785566576634, - 0.28160258368036767, - 0.28477977262469745, - 0.2941229395217518, - 0.2897108013809919, - 0.29726729265597224, - 0.03772006554782948, - 0.247277408531523, - 0.26235220978850177, - 0.2792854701680436, - 0.1818892670824121, - 0.27289583300719183, - 0.2954246579457717, - 0.21873066316863174, - 0.20072534114558643, - 0.22083152282690374, - 0.25929286924678385, - 0.19616136309545495, - 0.2814167625250302, - 0.23667697183665776, - 0.2744986207883696, - 0.10860370787369225, - 0.10304327489535654, - 0.2726971756426144, - 0.22282829618314334, - 0.10889764326899565, - 0.26315640035768056, - 0.005811409751917357, - 0.23641955986992347, - 0.29974598433915306, - 0.2916408861890767, - 0.2553976212524727, - 0.2996671195686481, - 0.25773869682697337, - 0.11729379192146351, - 0.24980373327350183, - 0.2860328721089231, - 0.09714522725471347, - 0.09547776887418687, - 0.2283136524422173, - 0.25095578479709213, - 0.23668489903472756, - 0.2512086658093602, - 0.2335240986050694, - 0.2935530986986391, - 0.24861629937736782, - 0.3024477408866091, - 0.2649748378880566, - 0.22573939752516053, - 0.26301003051194577, - 0.30163494521566186, - 0.10608788228471784, - 0.06946110871793945, - 0.2550933155545067, - 0.2980678356662104, - 0.28860578137641507, - 0.2869645782508876, - 0.30237995766479775, - 0.08316293227235626, - 0.19013455025694992, - 0.2639911638218235, - 0.2395091932849628, - 0.19492400891186903, - 0.22723101439876792, - 0.24992922175726545, - 0.24964983897769025, - 0.21439469004295728, - 0.25466091957814807, - 0.29213803633628405, - 0.301119692762104, - 0.28188540064141154, - 0.05946076363123784, - 0.16575893181495532, - 0.13995533532316515, - 0.2918660554134687, - 0.25854008637126213, - 0.22159740584042975, - 0.26244743006135113, - 0.29079986882078, - 0.26602051522310277, - 0.25519826236180726, - 0.28029064459555125, - 0.2755810488047902, - 0.23888827356283057, - 0.21143129566308114, - 0.21247540202700543, - 0.2869521671920473, - 0.17573151783780158, - 0.21855920371738338, - 0.24989152944083828, - 0.28812025950683784, - 0.28651243452083436, - 0.22162449023698402, - 0.2336540910856105, - 0.13621008336782467, - 0.2632381757171688, - 0.29474563278110477, - 0.2881186472452377, - 0.2981543445425233, - 0.27451434867283087, - 0.25556051496380916, - 0.14372829112485894, - 0.2859010322352819, - 0.2952965439335267, - 0.24493164320491168, - 0.2048724286145789, - 0.2540039348838295, - 0.08573297919891314, - 0.22649400991302482, - 0.2524756855252271, - 0.20364271093077335, - 0.19719023960774618, - 0.17094615168902588, - 0.2860387238025606, - 0.2742753391793435, - 0.2926617126535415, - 0.24284913904232633, - 0.30051281695678805, - 0.20483575827766629, - 0.23925147130243382, - 0.2705541805358004, - 0.27943346845577705, - 0.11300587730449582, - 0.24110266914038844, - 0.2698825386432986, - 0.2624566710219319, - 0.18759824118893967, - 0.280346873320084, - 0.27892422804490663, - 0.2855696214529743, - 0.2927388388373448, - 0.12416714120439445, - 0.2984952348606522, - 0.23415933045935716, - 0.240880377553291, - 0.2825604370797697, - 0.22503620290107557, - 0.1407237388416774, - 0.23291670009224588, - 0.3007689864197902, - 0.240867189082956, - 0.28410245720353494, - 0.2954757182774075, - 0.29830168475327395, - 0.22907011167503366, - 0.27925115680994794, - 0.2858492537781597, - 0.29451570030647606, - 0.2826854221791677, - 0.1508939485138827, - 0.1044205851214603, - 0.11513908379113098, - 0.29212138289822714, - 0.28345807034610065, - 0.30076325660272796, - 0.30030969537406976, - 0.25106597304918193, - 0.2750469504755384, - 0.24920135399387305, - 0.273666486838556, - 0.10481582045158627, - 0.2069498218242434, - 0.2707236427714333, - 0.09151421954592576, - 0.19821840041388383, - 0.2865009758610928, - 0.28935188545938034, - 0.18571169478629335, - 0.2981723969010715, - 0.19401389921293116, - 0.10425687916856417, - 0.2805703095135145, - 0.11125495918962044, - 0.26457106534861086, - 0.20098444757096248, - 0.24533592107446478, - 0.29754145560147793, - 0.27378839691518325, - 0.29025227882677423, - 0.29367202421226074, - 0.249823336329853, - 0.19654753180627674, - 0.2886076915481312, - 0.21961349511190964, - 0.1371109959123549, - 0.27404402761586255, - 0.2410679836956021, - 0.27678469422380086, - 0.2352327621695618, - 0.2996070015975585, - 0.20295615251765392, - 0.1396819613351756, - 0.06480404419372822, - 0.2975729083154207, - 0.28723910147710574, - 0.280846052519463, - 0.2897202693993566, - 0.12391792234812905, - 0.20009958406985623, - 0.09843973854141926, - 0.299093722924223, - 0.16920133519092354, - 0.1953896181061389, - 0.2886704391173958, - 0.22149032512813305, - 0.058286627629738255, - 0.30018593992244685, - 0.0690606029032214, - 0.1373701646047654, - 0.1233276600969845, - 0.28979036827627974, - 0.29067092837852376, - 0.16267730267971028, - 0.14135494500520301, - 0.159587481205658, - 0.20816907827086786, - 0.2133423741521511, - 0.2536191564954792, - 0.2603318130895654, - 0.28092669071409526, - 0.2846868401646544, - 0.2306443779049465, - 0.2104888907003376, - 0.2938190130005592, - 0.16244029142544128, - 0.25307860619930006, - 0.20455602399940623, - 0.18924791271893288, - 0.28993788471440807, - 0.18613821192267666, - 0.28970297853725674, - 0.21848015635407048, - 0.21589703651133924, - 0.27667468338393036, - 0.21312416659879677, - 0.2822247454800003, - 0.2671569689816849, - 0.24284653504577403, - 0.28853751591782717, - 0.14308564768597873, - 0.17604813147430756, - 0.2506493746853913, - 0.23020317817643926, - 0.17925017386434905, - 0.18846231586262333, - 0.24504385421784022, - 0.30234915687834113, - 0.2622108318419333, - 0.17706826438900308, - 0.2880273968082686, - 0.22917265870070969, - 0.22398236158118429, - 0.23094511587642252, - 0.29629704999004897, - 0.29643932069931833, - 0.12249737903763225, - 0.27683516456554846, - 0.06182481392856916, - 0.221100307091509, - 0.15513028797200218, - 0.2140711618680663, - 0.14278902280901576, - 0.26971335975853167, - 0.22373341510582695, - 0.23619108936451383, - 0.21053993777901508, - 0.23286241933459365, - 0.2836279020353891, - 0.1955157518975518, - 0.2938052728580348, - 0.2597852249799945, - 0.24501593073352157, - 0.28519739765407204, - 0.2798654553322318, - 0.2641044458939613, - 0.2079486058458403, - 0.17330439916894094, - 0.051725875718593176, - 0.22562881752417185, - 0.15157078443477903, - 0.1574620196260669, - 0.2997717369516266, - 0.16126438299351473, - 0.19746560557021337, - 0.1772593037776395, - 0.2936577701737042, - 0.27335642216071104, - 0.10591241124959835, - 0.20860278604563912, - 0.30302131473309973, - 0.18040822925342806, - 0.2292569959252749, - 0.26472057562820733, - 0.146778609344068, - 0.276007509500781, - 0.2281970473717115, - 0.24875276334988788, - 0.2601286098784966, - 0.22052809230154702, - 0.19104635241698537, - 0.260407880027994, - 0.28342501643192736, - 0.29494440772780284, - 0.2356655454193884, - 0.29292542156189794, - 0.28398585220820444, - 0.28636341326030795, - 0.28906732668100443, - 0.26407154528234644, - 0.23257884346475738, - 0.13837984616678894, - 0.209710834621091, - 0.2730226296859091, - 0.2644616494950432, - 0.2574058137730611, - 0.27216762915461823, - 0.23307390892732327, - 0.3038890617230413, - 0.293369418406101, - 0.26158812302866735, - 0.20404951646710479, - 0.2528272687924256, - 0.3036312155425935, - 0.2987198492378236, - 0.24201129660463402, - 0.17393343783613932, - 0.23174131690380861, - 0.23123199635198233, - 0.2823350772067628, - 0.2572129910077664, - 0.1523839391547686, - 0.13134746881560938, - 0.14674347409173694, - 0.15339654765367866, - 0.13223545479374127, - 0.21663348756744463, - 0.29809385695345153, - 0.15233553520164483, - 0.27992974063694104, - 0.1761302011577866, - 0.2547442005909253, - 0.20295232763726434, - 0.26909359208806666, - 0.10553104313690846, - 0.2613702439580583, - 0.2967124131528324, - 0.3003498871302205, - 0.2779558907931639, - 0.29313928192188454, - 0.18369850777614968, - 0.24466729735108408, - 0.25420217003814505, - 0.30272877337837245, - 0.0544167605014875, - 0.2552494256901108, - 0.24750089645939932, - 0.13272822681088337, - 0.21500218810716706, - 0.15201673634575372, - 0.1555220327859978, - 0.29928352251560464, - 0.14438181687203414, - 0.27113104188134646, - 0.15624765552140624, - 0.25389519017216994, - 0.2880129793797895, - 0.15046015612192765, - 0.3004127064029729, - 0.2768350794769215, - 0.2833116116789994, - 0.22491325722874192, - 0.2750220862994127, - 0.295802940875195, - 0.24960430082974816, - 0.1638475661394475, - 0.257858626485779, - 0.1951568094377378, - 0.2559311628028245, - 0.217532960883545, - 0.25304020124484644, - 0.11782028084365925, - 0.2687097694439468, - 0.2487857279814359, - 0.14892713187593662, - 0.03575144749134307, - 0.19037754313741392, - 0.16501584884640416, - 0.22089282577486544, - 0.20342999685942534, - 0.301714608947704, - 0.26453613607544724, - 0.27832555704745204, - 0.20983643032488328, - 0.27532725656462376, - 0.2083189183932531, - 0.18412092644965009, - 0.2698676832819896, - 0.19203365555625262, - 0.12385533073533418, - 0.2695124111978697, - 0.27406763059957484, - 0.12190207544181239, - 0.24032463637989573, - 0.2763190238258697, - 0.26430919279724785, - 0.1663111454701358, - 0.26507983326883405, - 0.2328587719308773, - 0.28817007079087836, - 0.06133743514886796, - 0.2537942619672616, - 0.2722521980595358, - 0.17792995688733942, - 0.2992757717408057, - 0.18935214000449732, - 0.1897292465091863, - 0.2597723884892549, - 0.2911544865044354, - 0.05846318649964085, - 0.13151189113837516, - 0.15828007988974346, - 0.10458833659850031, - 0.290130800260699, - 0.29240229142375945, - 0.2856322080309242, - 0.29135422418932305, - 0.3015275190856002, - 0.17501261922484238, - 0.2741878989780075, - 0.22860107029916732, - 0.2960928141877308, - 0.21596785939264562, - 0.21200176722273675, - 0.12269638840988077, - 0.2876969544570238, - 0.27491570733732856, - 0.03225299599294464, - 0.2877856523684416, - 0.27168171580460243, - 0.28810077169370457, - 0.13319659681129373, - 0.2735834484726898, - 0.2702312870593459, - 0.15778983151913162, - 0.15793326169039754, - 0.2553495166851402, - 0.15399971667587017, - 0.2280508218986353, - 0.300710640311969, - 0.2830964880347255, - 0.30411835362678374, - 0.22630745032387928, - 0.0932491169463781, - 0.21047693192081263, - 0.2576755305394904, - 0.18773988526410124, - 0.20598484485255422, - 0.29792603965254244, - 0.2980974908790451, - 0.19658148226768368, - 0.16009696542544563, - 0.0900757221269017, - 0.2438917553815996, - 0.24629968595958454, - 0.2541965439363413, - 0.16327400068702705, - 0.07114627983598008, - 0.2606534315825352, - 0.30336945035716434, - 0.11081911894416206, - 0.2803812638365542, - 0.28842264462794737, - 0.2547490611077962, - 0.2814323946342493, - 0.14919316745760333, - 0.2888090861108627, - 0.1859619116336988, - 0.17418014348354396, - 0.2815443327757822, - 0.1584962060848333, - 0.3048931818783448, - 0.2829442688279079, - 0.3019100720944198, - 0.2853839282799968, - 0.25202558554090304, - 0.1568230531106573, - 0.19722524157378987, - 0.2238011040455, - 0.285654117109514, - 0.1667981712523717, - 0.2924155073408582, - 0.21414331977070664, - 0.29970005734430544, - 0.24683519262041248, - 0.2752451276903912, - 0.26890183067351964, - 0.17377242856529243, - 0.26744042867633144, - 0.167933679026306, - 0.1680183676244491, - 0.2705836328226614, - 0.16734136646958825, - 0.2761543661943008, - 0.19478254190558084, - 0.2545639457043728, - 0.26175208627231505, - 0.1949888808809122, - 0.28262529889707627, - 0.25433508124308335, - 0.20165770793854207, - 0.29549212921166057, - 0.2899277293283511, - 0.2898905487061178, - 0.30193834750418874, - 0.1986963571272873, - 0.18470119673193378, - 0.24926983948812753, - 0.27448326702804055, - 0.2382160538158945, - 0.033291413377066564, - 0.19109127940072648, - 0.03345251525228836, - 0.08218096693717389, - 0.29088936855120323, - 0.08800595997622683, - 0.305112279911373, - 0.22324323758328068, - 0.10782903045214584, - 0.23913902825742286, - 0.24097702939748453, - 0.21231915379760893, - 0.19519405164509906, - 0.16996306628495964, - 0.04726056429674222, - 0.2321323024860711, - 0.1316126167777104, - 0.1733670061131893, - 0.18619223648747812, - 0.1104175140629014, - 0.1774772236376992, - 0.007531087583359291, - 0.29107968000970436, - 0.17657489851223168, - 0.21181426367278472, - 0.19584166581705464, - 0.23775209343983283, - 0.0754816080970455, - 0.24442495315792445, - 0.11838482174831942, - 0.15944193134235216, - 0.1765011234658163, - 0.2908190331206214, - 0.16879697277193773, - 0.21606567897054227, - 0.04361357997798882, - 0.10712233099111194, - 0.26116537022999103, - 0.20932905397616433, - 0.039624939315852356, - 0.12107064591675334, - 0.1467760886858863, - 0.25540950654128025, - 0.13787942821757213, - 0.09555263094087621, - 0.2738721190367032, - 0.1616753043804631, - 0.23463831340557556, - 0.1620781799664746, - 0.20989844698483356, - 0.19923758407274303, - 0.18727456503952697, - 0.27149681547128984, - 0.256933203690812, - 0.11402460088966629, - 0.3050900178291943, - 0.1608277080907704, - 0.21771443814148173, - 0.195296872516779, - 0.06138427769297077, - 0.043364134707698496, - 0.25617527972376614, - 0.19539465019125743, - 0.18703806904227072, - 0.207730644085514, - 0.13716321668545653, - 0.27504528266827205, - 0.24391657737237835, - 0.21573255646726072, - 0.24666501162975807, - 0.26732237934939607, - 0.1828286033883923, - 0.06415781798389382, - 0.058916879117314705, - 0.2345042423640075, - 0.2670130732045123, - 0.23887987176121203, - 0.20690284099183956, - 0.18411236735400327, - 0.29259091643876456, - 0.15028267395487685, - 0.09925371196132009, - 0.23654540873301297, - 0.2146876858417141, - 0.28128311538971235, - 0.18408145212690966, - 0.1365653750378884, - 0.21343007668649547, - 0.16372259263347044, - 0.24847030346685178, - 0.10876821894464692, - 0.2630988555042597, - 0.30319279324490594, - 0.19502684222616695, - 0.0841639732883481, - 0.279544712136446, - 0.16892660660363493, - 0.24451851638412636, - 0.24013712395957815, - 0.15811183716059185, - 0.30472917863553745, - 0.11388174890355485, - 0.13592438420473546, - 0.18558902670217647, - 0.22913220497002879, - 0.2838724492313794, - 0.2096407954150203, - 0.08606467906599463, - 0.16545814934165898, - 0.18866347236791892, - 0.138257964792312, - 0.24306474661246, - 0.18074579208418723, - 0.2575402772763422, - 0.22979778505138193, - 0.054147778014123085, - 0.11075099532323447, - 0.11926493948654013, - 0.21730573923016056, - 0.21492725864656098, - 0.1932982736312301, - 0.1932066204251951, - 0.17409988122618902, - 0.1690718342510549, - 0.17271499332392995, - 0.20029135531521214, - 0.1550297236503454, - 0.19325923934414568, - 0.24669801626793558, - 0.2403458305881896, - 0.13570134917147056, - 0.0318593236775221, - 0.18061523406811247, - 0.3014479396845426, - 0.24545523227583327, - 0.24755001795951942, - 0.09577480704131587, - 0.1157648588439342, - 0.2614712726074537, - 0.24923310095689089, - 0.20073312224856915, - 0.29391218214985826, - 0.19151339680034024, - 0.19268538714965308, - 0.28464229589541934, - 0.2591575892650212, - 0.2236049239589166, - 0.29912548299382713, - 0.23823268733684894, - 0.12799694524378102, - 0.16928945184174965, - 0.07836467659729589, - 0.30009811474534576, - 0.23394158965002837, - 0.2333289168618451, - 0.21386710459470398, - 0.2386472258976251, - 0.26203606333826274, - 0.28135526669981537, - 0.13648417589249348, - 0.07616722748895324, - 0.27456101647512704, - 0.2700319261998122, - 0.16997798046685547, - 0.054191243156702706, - 0.04155744740848175, - 0.18131214402092857, - 0.09949202873809292, - 0.190161777107382, - 0.28043455978279064, - 0.11691319736880243, - 0.19307908810123345, - 0.08234154531304508, - 0.1317114044230014, - 0.18807562032547828, - 0.11896850437630734, - 0.18797215252353855, - 0.21204153318102736, - 0.14040540619320088, - 0.19955064355664445, - 0.2933790459943371, - 0.12953111609954598, - 0.10425575996040035, - 0.10763332218648487, - 0.16965410488804517, - 0.25365233585716607, - 0.20243050807879817, - 0.21560580870482413, - 0.2441030229577517, - 0.12231758467873355, - 0.29460288781208316, - 0.0726616640091915, - 0.25566156241555454, - 0.2389122042686293, - 0.11098251615101051, - 0.03961067351572849, - 0.2715840614190186, - 0.23081817640299132, - 0.20013625526384282, - 0.07175816397325756, - 0.24549591859746464, - 0.1454283622038863, - 0.20883484207423725, - 0.06347293045725452, - 0.2873348139002063, - 0.27776623883543744, - 0.08003069236295654, - 0.16594229420860113, - 0.18620453586760413, - 0.09618332112351188, - 0.24275386498528173, - 0.24894586389026538, - 0.24976836704007033, - 0.022736343340402494, - 0.2580979238879956, - 0.1397184014423235, - 0.15522843679176326, - 0.19053951374965514, - 0.09959938598216131, - 0.22751280877772498, - 0.06829242368045933, - 0.12616590851644086, - 0.16810976609089218, - 0.22221584552067994, - 0.2155269432939214, - 0.28394375253496706, - 0.19819469423527136, - 0.23293063012207937, - 0.05190446776745225, - 0.2721137310153136, - 0.17636289125411822, - 0.21957885700814944, - 0.20195825359904723, - 0.2667371569399727, - 0.2746626380507134, - 0.12827898707636468, - 0.2274288479843043, - 0.029551136079996022, - 0.20143908426805418, - 0.2804435674185338, - 0.15833905371240015, - 0.2826493968288475, - 0.17444400453442196, - 0.25527549985248726, - 0.11438616396047241, - 0.15506816984591681, - 0.1335032269586358, - 0.08530391623030241, - 0.24437080002730707, - 0.24659884080992148, - 0.18898140893737075, - 0.29847954774576957, - 0.1508832573841655, - 0.09047094060415316, - 0.1999786098665686, - 0.15662486336888237, - 0.21971453532446542, - 0.20896141359818296, - 0.0656020731412141, - 0.10599085354900807, - 0.3009505280227678, - 0.18138588185202598, - 0.21621852981759493, - 0.10506762385760439, - 0.25102284571810035, - 0.14096359033479994, - 0.06389310410880107, - 0.11038200805893185, - 0.19196385569533003, - 0.23387772958221462, - 0.23706500094036204, - 0.038724657005628216, - 0.15758794490185216, - 0.2987098972750515, - 0.22944504438493568, - 0.2826589865231378, - 0.2827792760369573, - 0.2779108658050437, - 0.22747616329813497, - 0.1639217612067807, - 0.2707977832830238, - 0.29411651696722574, - 0.13516644232448807, - 0.17284230040718598, - 0.2627153760298775, - 0.19570462031062477, - 0.26839359811284386, - 0.04673840898478119, - 0.15302650500610326, - 0.053670676566372005, - 0.292336498942764, - 0.08294677045318995, - 0.25170316318255376, - 0.23639570021731013, - 0.21235682956537139, - 0.18341563589512513, - 0.1347244763396118, - 0.275108271484215, - 0.23459028514762587, - 0.2300772099373741, - 0.1426324450444451, - 0.18327551116842136, - 0.1942884866403007, - 0.2162143487717809, - 0.1928474081041427, - 0.11013511341226828, - 0.15762776776787749, - 0.25245661304467276, - 0.15551666061892672, - 0.1627706767276717, - 0.10549436759915497, - 0.2266285188603278, - 0.28460281053015124, - 0.13479478292196273, - 0.16405495968202, - 0.11013976885376327, - 0.27587911769765183, - 0.1848037713782701, - 0.08771032306142855, - 0.12492483985320008, - 0.24006760826985696, - 0.2536119656601371, - 0.22249403292802572, - 0.17686487663544354, - 0.17657412452756605, - 0.2643654816874487, - 0.2845130459986827, - 0.15781354953196247, - 0.11189564710058467, - 0.26327188923591865, - 0.09869711632911359, - 0.29114120489527495, - 0.23668974638153334, - 0.26594692252509833, - 0.252406022031699, - 0.021630441835911587, - 0.11369840478659449, - 0.2860895968152142, - 0.2345150581026916, - 0.24773006054048657, - 0.23259987483107877, - 0.18454260916465984, - 0.17230027066408843, - 0.23402913381102233, - 0.1709614806055704, - 0.12236273724588753, - 0.03966598989753502, - 0.16551917527808302, - 0.17272702602081264, - 0.24937358642302268, - 0.20035595866248768, - 0.3009183708290256, - 0.12500109371742782, - 0.07190773920281028, - 0.24732212381291116, - 0.09175051360663655, - 0.1814298593129246, - 0.13666359386067545, - 0.21593466756858956, - 0.09212524765849356, - 0.1498202113885425, - 0.29742245813305457, - 0.26931993731908727, - 0.11285257274849662, - 0.14045104479357173, - 0.05439386084608382, - 0.07237007555711757, - 0.13044353800044475, - 0.15272018669954035, - 0.27355688772605846, - 0.27377502586912666, - 0.29617811520206916, - 0.23443904662482234, - 0.17128889892286858, - 0.11227439694982111, - 0.20839321907085334, - 0.2278534835808811, - 0.2759106477405964, - 0.20023115313160775, - 0.15703429766987767, - 0.13911313578857082, - 0.04953695410839012, - 0.10560487236810226, - 0.19506236019989326, - 0.2605174358733478, - 0.10395254623898395, - 0.13356477117349208, - 0.27106696476232695, - 0.13565701148804496, - 0.12595700205011542, - 0.09950318378907434, - 0.24457722935066914, - 0.2729274077297739, - 0.17749482607577957, - 0.1403406033995485, - 0.05171886089554751, - 0.24404413911503406, - 0.1719760155935362, - 0.220174993426906, - 0.24482076034804615, - 0.20154792379629274, - 0.13987964510829295, - 0.247237539553854, - 0.2471637634782163, - 0.1696925810778644, - 0.16684430659044902, - 0.29257766412492087, - 0.25374895421834687, - 0.2707803875530861, - 0.19211813609659179, - 0.16065888470937287, - 0.29399442664347974, - 0.2440764120083932, - 0.22049000617390163, - 0.22061614421974438, - 0.24008714660537492, - 0.1397817966386081, - 0.23757981725140517, - 0.2089148514542091, - 0.17653084785596762, - 0.16597545847039238, - 0.13290570175431962, - 0.2650634356714364, - 0.25657302726307857, - 0.06505218450613923, - 0.19339362523869166, - 0.2660616286758842, - 0.2560016263174407, - 0.2563634416273239, - 0.054043865795941705, - 0.12676334655082103, - 0.21026977753554893, - 0.18175894361003925, - 0.18788135378632237, - 0.20295114934503752, - 0.24109265840499308, - 0.27237130329427117, - 0.23722140113605944, - 0.12412266941887566, - 0.16004256070343736, - 0.29918085407080486, - 0.21676567222973533, - 0.16777053627657368, - 0.17091356328166604, - 0.2810530999178123, - 0.08833707723884085, - 0.15997602237287123, - 0.22593158876522595, - 0.20751386816749634, - 0.12645631312908628, - 0.2992297039502094, - 0.05917621031563381, - 0.20535018385881149, - 0.23144884592209586, - 0.1133054465978782, - 0.22549518128901241, - 0.2952487634610577, - 0.14690860023804772, - 0.2395392627808987, - 0.21272572236863987, - 0.2738375788477263, - 0.19735475078019551, - 0.21054055260952004, - 0.2229613090264543, - 0.15615895512228742, - 0.14845564476563836, - 0.16893390668078617, - 0.26558558815796146, - 0.07238624651755536, - 0.24928837530270814, - 0.21422583763207834, - 0.19906966627119377, - 0.2650468434787773, - 0.14953251786359906, - 0.05172219716641924, - 0.2849790790502597, - 0.27048545274768543, - 0.27295019424400513, - 0.22179780569802493, - 0.21617755752906861, - 0.20132395424962485, - 0.2797219238982994, - 0.2309923514485878, - 0.2144310004144844, - 0.10161320303258811, - 0.16485082916776606, - 0.22211710782715194, - 0.06632074904412566, - 0.13823505300454517, - 0.19881951247108368, - 0.16585898272982444, - 0.07732007121659197, - 0.09873943341013029, - 0.14718136908386342, - 0.19974401716092657, - 0.24776195531348746, - 0.2297780184496713, - 0.21119526929350044, - 0.09933150530604527, - 0.12266108297393072, - 0.20131582786153193, - 0.21551018683950215, - 0.272886417847633, - 0.22800772197272742, - 0.24677091865965092, - 0.13747133979707005, - 0.17731835001953072, - 0.2316495524992777, - 0.12685367398134362, - 0.1833551041763661, - 0.2980093050230984, - 0.21728555093183335, - 0.12803342034496992, - 0.1951556108136913, - 0.06640706202073056, - 0.1285029906529403, - 0.2695608338231991, - 0.17403856509080398, - 0.28595448507509136, - 0.20517214103237527, - 0.2454379633261945, - 0.06259913469070623, - 0.2429889841219692, - 0.178351538499323, - 0.12339657691609691, - 0.20907126554996033, - 0.19753664573905588, - 0.20086420961015425, - 0.2227015695394197, - 0.28221011543567825, - 0.2838598617436372, - 0.09796056263922075, - 0.2159207005919831, - 0.29640183278645604, - 0.278142746951829, - 0.29413353142365306, - 0.18501933798641534, - 0.250317361904399, - 0.22287488549694418, - 0.2733775292371595, - 0.07085372700977158, - 0.23195064161343323, - 0.2595060710643127, - 0.16610404362681228, - 0.1721020382504013, - 0.1343477399513794, - 0.2181345853666833, - 0.17597329559277397, - 0.10528660006064616, - 0.2349865581553251, - 0.23342676304045173, - 0.2748387512118633, - 0.04090749019163001, - 0.18008237955353884, - 0.09863592250734422, - 0.14034745230524653, - 0.24189164044058178, - 0.17655783240820402, - 0.18617154577156578, - 0.2655019421978888, - 0.22360827179225895, - 0.22794161739538432, - 0.18088888586328272, - 0.12465645785608827, - 0.2682454320354297, - 0.28595546484900297, - 0.17056099303856465, - 0.09921174603923628, - 0.21726539489497826, - 0.19788421395509398, - 0.0671602365766904, - 0.26185846025021814, - 0.13528143912411358, - 0.2913180932660853, - 0.16320735258286906, - 0.14194226174902222, - 0.20150639696345485, - 0.19119460205245467, - 0.26808330289816107, - 0.16195608050816593, - 0.10700020249712115, - 0.14602363907383856, - 0.2677690510306172, - 0.21773751356034513, - 0.10518249707810175, - 0.18018266932165203, - 0.28705321719231003, - 0.2667040284277176, - 0.22451323714085375, - 0.16692484740466929, - 0.18368321217042874, - 0.183340421416651, - 0.24908306455430196, - 0.28483923769670894, - 0.28472285563198774, - 0.24583726751879884, - 0.23387516970520755, - 0.2449044535925918, - 0.15778445199344718, - 0.09696574901877066, - 0.09076576352410706, - 0.28793793417618974, - 0.2431074999438459, - 0.18821972345677973, - 0.14793617506921214, - 0.26261331059337295, - 0.26555083083429265, - 0.2792652058628759, - 0.16586563763391515, - 0.2128180817511142, - 0.2526551853509839, - 0.19346385964355417, - 0.2320766275982338, - 0.10298480481624447, - 0.0448363267520611, - 0.22950962291666577, - 0.14500595682182005, - 0.24050178794313426, - 0.23522834975612586, - 0.10748281317298992, - 0.15452172951386353, - 0.22592776474664242, - 0.1778483411085408, - 0.17231226993573626, - 0.27590309290084886, - 0.18733427198876879, - 0.19687114484618484, - 0.20797262281914328, - 0.1286539259941555, - 0.16386543364018694, - 0.2189382677283932, - 0.20407195089544672, - 0.2317663592578784, - 0.1577008524317086, - 0.23509455673267526, - 0.096366092552183, - 0.17282845702336522, - 0.1883491493764855, - 0.1836472525238907, - 0.21838256016593893, - 0.23100532635895812, - 0.2122399627514725, - 0.14514130314081009, - 0.2152749579247468, - 0.20893550827171864, - 0.09868415854130534, - 0.21709985156750897, - 0.20220912890181483, - 0.2121011149457165, - 0.16993181508491575, - 0.10528575280340344, - 0.202720699960693, - 0.018898118680344286, - 0.15212198893521187, - 0.15430680881639752, - 0.11869276627198795, - 0.2407146460280921, - 0.12277132657047167, - 0.2081377422867851, - 0.0644720686542784, - 0.0891675341808055, - 0.1036885455751936, - 0.29741627799545683, - 0.24400851646598026, - 0.26998867097590573, - 0.19909021441211966, - 0.20999285809362928, - 0.28462464671909854, - 0.26724257793357675, - 0.2249953141678716, - 0.23256548915356498, - 0.17507649228052968, - 0.25870518142425947, - 0.2326969219548261, - 0.11538118037763345, - 0.29762355814458374, - 0.18797180824939042, - 0.19723426631346339, - 0.13669155750871662, - 0.19785111730408741, - 0.21140412000066414, - 0.2542854643459774, - 0.21635537202769417, - 0.24651066198786292, - 0.2038272659053591, - 0.2911271686556825, - 0.29129413234546075, - 0.06304673832188881, - 0.17047173437359414, - 0.12408236712851713, - 0.10483241736119195, - 0.26735645089872434, - 0.14247891532441798, - 0.2246983245826498, - 0.2847962696382853, - 0.19019543906750686, - 0.18249727040048952, - 0.15326195730718517, - 0.06228611334669175, - 0.08392431226574858, - 0.1618731012489437, - 0.12210293143454827, - 0.08973973483840945, - 0.13178516373971627, - 0.25512766294819317, - 0.2061843907712517, - 0.11117719465830016, - 0.16884960839599666, - 0.21340646028301213, - 0.19341629058426787, - 0.22465262258740806, - 0.12073405791316368, - 0.27748425533627347, - 0.28567790232222245, - 0.18899697461378337, - 0.21636693100382504, - 0.1595420450941716, - 0.27224999239659126, - 0.27270283606732115, - 0.09219479986358699, - 0.0889822574728296, - 0.272214433818482, - 0.2357738820512381, - 0.1603877555431732, - 0.13147712807128994, - 0.12996587937675566, - 0.1319164862984217, - 0.21967668820263864, - 0.2417863912833152, - 0.07820982220782471, - 0.25227324698472586, - 0.0571075940344746, - 0.282911621111673, - 0.17712655333065833, - 0.055134508335885894, - 0.2997998403951188, - 0.15124872178961482, - 0.2662702741681715, - 0.27352201238064683, - 0.2253654727743762, - 0.11926321702624548, - 0.29728268854959256, - 0.25896263823525884, - 0.20534529758616857, - 0.27021356550946163, - 0.12876329323602248, - 0.08732450367967608, - 0.07300935699299847, - 0.23517321815613546, - 0.22969502108899734, - 0.13514672743720701, - 0.2739496254957244, - 0.2655035524753501, - 0.24027202327079447, - 0.299617222283339, - 0.2658901511087618, - 0.1164650888660763, - 0.2581299698594998, - 0.17248031230877212, - 0.2726969074901538, - 0.16975718276550777, - 0.1553770093302075, - 0.22026592929408212, - 0.2408679285683447, - 0.2279524194556734, - 0.10133452235374703, - 0.20949354473169898, - 0.1265279559644034, - 0.14247329494282412, - 0.22792557862156235, - 0.17978391696100954, - 0.2518933600078773, - 0.2622859420777334, - 0.1512852067419167, - 0.11459013011860342, - 0.015130586503977033, - 0.22889688625169366, - 0.2235924136561524, - 0.19920333904635154, - 0.24045615413674046, - 0.21261823316262732, - 0.06411953087256102, - 0.1608264010960205, - 0.08718615645496135, - 0.2946128170233322, - 0.022312549426751555, - 0.29906845498128776, - 0.2522675469740475, - 0.18686659736987588, - 0.169974316229605, - 0.21091165940631607, - 0.24714376930603, - 0.23502993126174065, - 0.22201518347545976, - 0.25878716083058817, - 0.15915207592522435, - 0.14345597592497095, - 0.20626797449069403, - 0.018009340072310923, - 0.20963605982173103, - 0.22021718029151982, - 0.08511308533115616, - 0.28529264101944785, - 0.1330465098885672, - 0.25786543033274417, - 0.15966427092214447, - 0.15527915763763186, - 0.192523339909868, - 0.28881039720438684, - 0.061330184021588977, - 0.1348130786089015, - 0.16838010237254564, - 0.29053808583857044, - 0.04275741936098256, - 0.20625268024858445, - 0.17504794516740538, - 0.17668948809198048, - 0.0788110977275982, - 0.029401726552997054, - 0.08291262296054666, - 0.2808888658484632, - 0.12513405187560844, - 0.22843983514055033, - 0.24234619434270824, - 0.16300931667187477, - 0.21696698526310765, - 0.16281375764842454, - 0.18331647478337876, - 0.19306379556186082, - 0.14899745969954592, - 0.24252135739699882, - 0.10135218648622535, - 0.2905973762988807, - 0.0626629433005062, - 0.2669591032645717, - 0.26286866753241106, - 0.23598634470601948, - 0.02192537654854545, - 0.11288601367012491, - 0.23150065267638165, - 0.18153679909511147, - 0.1848875724560143, - 0.25767928757177594, - 0.13226696840769148, - 0.08679016259352969, - 0.22781996373901875, - 0.1735768877234029, - 0.2645593206150752, - 0.17669133334672485, - 0.2360802676739949, - 0.28503118312480125, - 0.22057992393363343, - 0.08331019278014953, - 0.1735209834664876, - 0.30276550720632817, - 0.24426074717538374, - 0.15352811117531984, - 0.14849558911549865, - 0.0603418843424588, - 0.278767940105198, - 0.2808143366678585, - 0.20539717396249182, - 0.18363857178223134, - 0.2674946595103876, - 0.21609610226230477, - 0.14240912475269182, - 0.22141860864159052, - 0.18769416161371835, - 0.18202362623988252, - 0.21980090883892106, - 0.11247774811556134, - 0.267929494834779, - 0.10594398636942184, - 0.26721083276485535, - 0.13158943741495877, - 0.11799096180700692, - 0.15969495138385606, - 0.19894769793575126, - 0.24745249204732472, - 0.14405330791868992, - 0.08556565053325058, - 0.26164113324636556, - 0.2851429021308463, - 0.07946749748624364, - 0.12491628260986594, - 0.17518613604188224, - 0.27786626358856803, - 0.2548116921433457, - 0.2045121053137181, - 0.21936621343189244, - 0.2141764348363892, - 0.13821919520111084, - 0.19826211359345547, - 0.3031817690745593, - 0.22022365803405014, - 0.13558559383306587, - 0.2226994939808481, - 0.23602253763199738, - 0.1324597021271762, - 0.29580872497893446, - 0.19521694198747022, - 0.14286965708226862, - 0.25803896211864946, - 0.2700993826272165, - 0.14954922679450527, - 0.1891874277533951, - 0.16654285196400184, - 0.19915378274157491, - 0.28051148506879753, - 0.22062470833949466, - 0.2928553408421224, - 0.19968696951412204, - 0.2475104316649361, - 0.25126577420321006, - 0.2830483831344267, - 0.15193356273288425, - 0.14012947618572164, - 0.30339129136486515, - 0.07752719763168196, - 0.157776211878984, - 0.2876581589389093, - 0.26277784132679816, - 0.17378218056628345, - 0.13837069245486175, - 0.2464132408520835, - 0.09211993785829226, - 0.2568432396431044, - 0.1326718911341, - 0.20426084099648328, - 0.20618701418981364, - 0.16639557806880467, - 0.2564947192705591, - 0.2590054536296896, - 0.19692107077702092, - 0.29016191987489437, - 0.11072737499552697, - 0.11502719397793108, - 0.042473376573612234, - 0.15594683320548025, - 0.02152919750260241, - 0.2492749524952565, - 0.23021031474342307, - 0.2835082969849027, - 0.2567751619518954, - 0.227474764990129, - 0.09958096945389873, - 0.14337312351811696, - 0.1921286034103214, - 0.18311891139098477, - 0.2708376212168452, - 0.2164431307972528, - 0.27057337853301433, - 0.09019881536950383, - 0.2539998861700445, - 0.2227640332526775, - 0.20227848300005194, - 0.2550448131664871, - 0.11676706467916576, - 0.08737720287525745, - 0.2823517821332575, - 0.20307246227536244, - 0.2281356004404157, - 0.2242437214267084, - 0.0593126864918483, - 0.18260515526907625, - 0.09932288149204936, - 0.221378411192434, - 0.2878690272413046, - 0.10586430998895108, - 0.04914968548446518, - 0.16317221868056955, - 0.13767371896867817, - 0.12943129359996294, - 0.282107800648092, - 0.22789640365697172, - 0.1525515383420608, - 0.2525864749925585, - 0.2667262511206517, - 0.23483780000744992, - 0.2908478611941437, - 0.21095921104873244, - 0.23195859819824527, - 0.11438491406429792, - 0.2312315180734451, - 0.006541113636750487, - 0.17506971051919756, - 0.274107091283225, - 0.2755938207949834, - 0.2921773878803099, - 0.19495093655087542, - 0.2846052073857303, - 0.22297516330953546, - 0.24633836747778615, - 0.18620761468120098, - 0.13740152754620258, - 0.24370721709938614, - 0.16605949071503223, - 0.22485620834876266, - 0.16291678348072905, - 0.08316568441832774, - 0.12170657499398434, - 0.22984943233921384, - 0.17897865040039634, - 0.27352075195668113, - 0.2258027783551675, - 0.23569810438414693, - 0.19662019242760057, - 0.15602890988473564, - 0.13193994629769787, - 0.17955372211981446, - 0.0915777236524987, - 0.0662790049165268, - 0.29382241262053227, - 0.08247675876910794, - 0.09079194946567659, - 0.30100472876755596, - 0.266203693226217, - 0.14337888311347963, - 0.21650982718319306, - 0.27281387939104845, - 0.17278060768932785, - 0.055376795515479305, - 0.26382766375159433, - 0.23155414285638382, - 0.23162772095225495, - 0.1476692565775839, - 0.24300453799892116, - 0.2750345239865073, - 0.12800947830133574, - 0.21988497404808674, - 0.20067033458353886, - 0.18213926132505756, - 0.0348809068396792, - 0.17098213181368896, - 0.09297658748824598, - 0.20083992585949026, - 0.14860453377146896, - 0.24416946449476276, - 0.2675224834385586, - 0.2602844683511139, - 0.19980031960290054, - 0.20603766521574943, - 0.2413454205083339, - 0.10720789757882077, - 0.25722945847147605, - 0.1371543358414774, - 0.17141991213797245, - 0.16363664035865294, - 0.17195549750124645, - 0.14901824103100114, - 0.26617608089273626, - 0.170200889240268, - 0.11043689890224498, - 0.23546599877738644, - 0.2748836338853741, - 0.3039486234356906, - 0.13373090113987451, - 0.1802411958077837, - 0.19622603225000418, - 0.13668882868900262, - 0.2755762591603915, - 0.1488657003263755, - 0.2536525320694672, - 0.11018193916364533, - 0.25558809352948475, - 0.22463941744508997, - 0.1084838582946466, - 0.1668763329809771, - 0.2304690274147457, - 0.27769932014195814, - 0.24738165028805548, - 0.1984547634917522, - 0.22581053382101096, - 0.19869192754501946, - 0.16594936710936908, - 0.2719367485560884, - 0.25271148440035984, - 0.15013073590825543, - 0.15577025625694116, - 0.2830482238979884, - 0.1413981627825187, - 0.09526478023288378, - 0.1637264136109912, - 0.21562650379812529, - 0.1358326018751923, - 0.2915152923493532, - 0.24173779905272133, - 0.26034449301435997, - 0.07287305014139461, - 0.12026033202719683, - 0.1989684622200308, - 0.11805570303456628, - 0.268933495921877, - 0.26043471806279267, - 0.2964309624201217, - 0.2858779556986227, - 0.17985749223899375, - 0.09189067363158626, - 0.053799240077419826, - 0.1932260257276969, - 0.0934364794323832, - 0.26824139361154453, - 0.1710346050845573, - 0.2455804042419595, - 0.19969276083892798, - 0.27136439367254983, - 0.273214711477825, - 0.1982764834617303, - 0.10370283775319286, - 0.26670706870917205, - 0.02254576439763968, - 0.2274242860728687, - 0.15389654331268185, - 0.2955174850756024, - 0.17542834589196904, - 0.13687331998784477, - 0.24593402372169734, - 0.12479004907533689, - 0.07261256471166361, - 0.15325447876197343, - 0.05712526829238628, - 0.19877178254228778, - 0.20917425984953703, - 0.22690902891860595, - 0.16960488510831187, - 0.1390426168933149, - 0.18249195821498915, - 0.1733197966069247, - 0.12946403845745155, - 0.2356297722298361, - 0.23775873823984836, - 0.24530125859001645, - 0.17972185141827032, - 0.11783978125023345, - 0.1892724644135291, - 0.1014692244413603, - 0.22568844914062566, - 0.20289736746764384, - 0.23932200184071103, - 0.28135000392499754, - 0.27141422268602955, - 0.21531957100704505, - 0.16611866977063547, - 0.1287181381955705, - 0.2523287699806822, - 0.20501642642227144, - 0.13582956398265547, - 0.2083981995592043, - 0.24430039697244005, - 0.2617746797064583, - 0.24361405290204305, - 0.11109348078463738, - 0.08051013026758229, - 0.2812187021547169, - 0.28313966171857724, - 0.25479505276068937, - 0.15286960407214517, - 0.26464521939868085, - 0.2661617925739468, - 0.28021724606020704, - 0.06396913856667824, - 0.11406600556862026, - 0.18801260316993132, - 0.12021742601269492, - 0.16017272567158244, - 0.22637125836798924, - 0.25818049032398604, - 0.06455552440303162, - 0.09607225974803303, - 0.24907646063074362, - 0.2100667062905943, - 0.011474110040463713, - 0.1972430960031025, - 0.24312770854916071, - 0.28978956694396435, - 0.1560479264688962, - 0.1355604601961092, - 0.2359502658759168, - 0.13710867209403216, - 0.29815042865567454, - 0.17725967854705818, - 0.11675333852170483, - 0.1763234091868755, - 0.26769494617123096, - 0.14917732894766395, - 0.1981906097270498, - 0.24613996232765553, - 0.26815443801740235, - 0.13556771197668982, - 0.13759964245234485, - 0.1972805038923744, - 0.2280202307858229, - 0.19311761342971442, - 0.2897613125576324, - 0.19126592468158746, - 0.1341675737972313, - 0.1670687394361393, - 0.14084338904316526, - 0.12221827018068394, - 0.1271066310304912, - 0.2003638428643911, - 0.1824822011151203, - 0.055009352806502584, - 0.15364439660261875, - 0.19020885395819723, - 0.10820333613880877, - 0.20398637057208627, - 0.19949575818715934, - 0.1813460616699816, - 0.24610124722617338, - 0.037158807723262195, - 0.11349784440712356, - 0.23291955279367588, - 0.3033183705059726, - 0.17977502345309318, - 0.1703277632732763, - 0.16496902012423093, - 0.0753328168469319, - 0.27529502943457207, - 0.248369221952312, - 0.23666125128303495, - 0.03683672397943074, - 0.1451574744073546, - 0.2935851692811669, - 0.15038949962163084, - 0.1880901037674344, - 0.19521903893355502, - 0.2551825940727606, - 0.22345968998330729, - 0.2628738489040089, - 0.12405253465680044, - 0.23221398347933886, - 0.2089378934207066, - 0.2819024334090949, - 0.20498558846955947, - 0.12139586717793052, - 0.19443474277566858, - 0.22385682101268334, - 0.23672831100352673, - 0.1792062491859811, - 0.2756623497449613, - 0.16487082411528, - 0.18284203309091204, - 0.22615294004616554, - 0.16421046638512002, - 0.22838903683592807, - 0.30254073938521536, - 0.29884889786467006, - 0.22177611957259716, - 0.15469093475496382, - 0.18895975088416084, - 0.25226022237362117, - 0.2108550175228998, - 0.2554830530759696, - 0.2029167718067003, - 0.28274831440359116, - 0.24867783066804672, - 0.2667772895432627, - 0.27187101112208845, - 0.21343697283120278, - 0.1761940465667346, - 0.2959442062198631, - 0.17545921568653358, - 0.2700515329559339, - 0.18508765556785886, - 0.06370885775515209, - 0.28486643402206324, - 0.25297494296827155, - 0.264836328797687, - 0.2502108268353748, - 0.23876056811409435, - 0.26107351649076177, - 0.24366651329933506, - 0.26535572957444087, - 0.11176412598226478, - 0.2703523972159863, - 0.30117619095393516, - 0.1410150118040422, - 0.25368650795000697, - 0.20473935489875983, - 0.1398159180876657, - 0.2717310443797253, - 0.15725370503252764, - 0.17023952147003443, - 0.27927799756272353, - 0.2683206889196256, - 0.22485163257708232, - 0.30009345386583913, - 0.27786847867462616, - 0.2459501740308977, - 0.2751804304579441, - 0.2319142364590869, - 0.16567653904006807, - 0.0817651844571923, - 0.13885796133246614, - 0.2567296563356995, - 0.16040426456194334, - 0.155985434144907, - 0.179988783535012, - 0.22514606020028083, - 0.02708919341992422, - 0.09199633239676148, - 0.11263651153944436, - 0.07579885053466141, - 0.13868886167667094, - 0.19776984171332093, - 0.1121495220139872, - 0.16924183225446698, - 0.04611883092395974, - 0.15553229205469263, - 0.26995147185172885, - 0.2717852352208117, - 0.15597780510004944, - 0.12972050655564826, - 0.20258409329894214, - 0.2937874613348116, - 0.20827652524501378, - 0.10864025597069005, - 0.07980015777784119, - 0.15914104637811108, - 0.2888280269086792, - 0.16145039605353534, - 0.159453018595154, - 0.298373928222213, - 0.14404158114835172, - 0.1643672207780662, - 0.19394580287990817, - 0.061553671452141516, - 0.2110585102421283, - 0.2363082627588958, - 0.29932567012131145, - 0.27050128705943416, - 0.20282868286188613, - 0.20956346755814018, - 0.29430048150863586, - 0.11065833019440728, - 0.2626894540524518, - 0.17092689793892352, - 0.1765661420093829, - 0.14199724348001783, - 0.22630488331589899, - 0.10733490335821669, - 0.06024848199871234, - 0.16187835346536097, - 0.09854779822858734, - 0.16356609846822365, - 0.22696919251087724, - 0.2999430034145131, - 0.27237784805513243, - 0.09881733624837548, - 0.19275755981625423, - 0.16246933039100042, - 0.28665331463887056, - 0.22214946715628725, - 0.06655288384705803, - 0.29635424002132754, - 0.1784326720678221, - 0.11221932553448981, - 0.2960050767854066, - 0.21475726309867088, - 0.06775353723708231, - 0.28723845633015016, - 0.25311744139924774, - 0.14793069134849454, - 0.20564185449516645, - 0.2675754665826771, - 0.14963004706909813, - 0.1203445537423593, - 0.2567099344847782, - 0.14942228853943462, - 0.1662201855435933, - 0.19764437831469103, - 0.25370120505128596, - 0.26749049728629487, - 0.2532045933819046, - 0.28238045819369983, - 0.18615081796292707, - 0.1975274607751929, - 0.2530931171303836, - 0.2603557782477547, - 0.08873924389130562, - 0.1888739624334823, - 0.04255682941242666, - 0.2644356537223953, - 0.18382901278727307, - 0.26839185222498174, - 0.10867937804247745, - 0.27739521001875383, - 0.29875741732395866, - 0.1399563274421952, - 0.2127447212969073, - 0.29307761633698853, - 0.23755673335102606, - 0.1302686368665886, - 0.15352279282627243, - 0.15722445380776834, - 0.25493357693154506, - 0.11608097234719846, - 0.24347160346449487, - 0.29474812541640766, - 0.14727617852144873, - 0.2967837068676958, - 0.13215380081272587, - 0.204484726282082, - 0.17102335320341974, - 0.03701017197075056, - 0.14210075345485484, - 0.19172928861697128, - 0.0549699897525326, - 0.249266148290262, - 0.20492894375129114, - 0.22102451117091618, - 0.09995331348853695, - 0.1363108822412598, - 0.1160740197353326, - 0.15829418309590876, - 0.13052778161185788, - 0.2223599898517518, - 0.21793049232160067, - 0.2872601808781622, - 0.06831793229062412, - 0.18921505317563986, - 0.02671950987479404, - 0.1970305419955053, - 0.015815917264079143, - 0.20988583051453785, - 0.297732554193972, - 0.18830791174695025, - 0.14394477271161069, - 0.08116613936939579, - 0.2280646633295464, - 0.06658839522465713, - 0.2245108097393159, - 0.0667054617318554, - 0.29922761488236627, - 0.2241874350836583, - 0.09107708881799213, - 0.17842766276752872, - 0.24052564055925246, - 0.10134843756461397, - 0.276123779979496, - 0.22367926228497145, - 0.23563049283137139, - 0.3007040521631009, - 0.11514668292680415, - 0.18309554067477726, - 0.18469801778159434, - 0.2200397555859477, - 0.2676190860893067, - 0.20096215532155196, - 0.27841471878278945, - 0.03749038405211817, - 0.23746769483007055, - 0.23005750282462606, - 0.2859982330546782, - 0.0964714180192584, - 0.28758710237073, - 0.17381875896765256, - 0.03631522486614094, - 0.29963768947294245, - 0.25773429701024936, - 0.2870153091128544, - 0.16477516293375613, - 0.21152411135664245, - 0.28972495114219227, - 0.23030099882493021, - 0.14246424894803916, - 0.2013017930058462, - 0.20416090992763739, - 0.15638993179545874, - 0.14877223228780895, - 0.2897154705905388, - 0.16218696478264658, - 0.17938980208830635, - 0.22830846226528095, - 0.27206059087814916, - 0.2053640237114913, - 0.10611873418501504, - 0.20289132529307613, - 0.2421543367238845, - 0.27683372357405883, - 0.22820895983009362, - 0.17199807074127832, - 0.21759350772253655, - 0.14212900445055607, - 0.2633391663071907, - 0.2282843654376956, - 0.20237064009123668, - 0.18372002350765726, - 0.21077414029853622, - 0.0560216019136292, - 0.26331331722754153, - 0.2777357315732394, - 0.09994985146829272, - 0.1590520773607099, - 0.06402396505258556, - 0.21707908396698933, - 0.13873765591288828, - 0.04572038700534716, - 0.0559988624844678, - 0.21287202408659553, - 0.22741207028737065, - 0.1101922931701992, - 0.08775136853419827, - 0.06390712127809361, - 0.20622458421623885, - 0.25872812921458177, - 0.21275491331339608, - 0.2747493725710653, - 0.25362859249303943, - 0.13551902220528964, - 0.10907993339057354, - 0.22509653332401103, - 0.16289988679811687, - 0.2714036075870722, - 0.1187088373326918, - 0.11733647274555419, - 0.15063588850693863, - 0.18835962006100515, - 0.11618624461161679, - 0.10536778852882547, - 0.14784315692857422, - 0.2615363522358122, - 0.14381714492012307, - 0.12560318512890892, - 0.20646690457008499, - 0.1637150760815312, - 0.2750000919014876, - 0.18943310844313865, - 0.20639923537075874, - 0.20641958607839261, - 0.2935793432232652, - 0.18340445613910952, - 0.24607549563239126, - 0.25193910283384996, - 0.2713123824611651, - 0.2959565784306845, - 0.2826076187168084, - 0.26869942244548145, - 0.10006689949398219, - 0.26203026124148177, - 0.269603373782773, - 0.19128050575990274, - 0.10808402146447015, - 0.24595554928938476, - 0.273581771095687, - 0.243666702091334, - 0.15112727180290494, - 0.24635893006120443, - 0.25538239054589845, - 0.16148033221748603, - 0.1589438668094897, - 0.23735545309300735, - 0.2617130731936932, - 0.22261762242838645, - 0.04891509728989826, - 0.1740874071607521, - 0.29723840926292194, - 0.18840834958151617, - 0.2665843202334963, - 0.2134988304868592, - 0.2376083360140564, - 0.24088589181653675, - 0.25810581821148726, - 0.14294645167578832, - 0.06747735307418017, - 0.11759629220472773, - 0.2725244289669497, - 0.21974816942566064, - 0.09212079286821101, - 0.061708384565392176, - 0.11035773644393686, - 0.1271295577489391, - 0.14208215813262523, - 0.18571984767345623, - 0.137598261555489, - 0.08475270372713074, - 0.15725905358452327, - 0.22863999185932127, - 0.24925307483167253, - 0.13565706290462745, - 0.21728219473392194, - 0.17822892351283454, - 0.16491820337059934, - 0.027501131916890718, - 0.18433752417659707, - 0.28083173422254454, - 0.2714879450844847, - 0.12863588856719813, - 0.08602100877412228, - 0.24793315992692552, - 0.24365565078677723, - 0.20280769900924, - 0.19516814015564923, - 0.1869002631157674, - 0.11584312772614504, - 0.23728072059608302, - 0.08984010793614708, - 0.2288479699816595, - 0.1053164820465474, - 0.26365462169940374, - 0.21796004936498375, - 0.29283561187055895, - 0.23770342256730104, - 0.17438873040924777, - 0.21125712936539542, - 0.148668518842153, - 0.23297957842260153, - 0.2983781875850028, - 0.27452690127861346, - 0.17277893520072823, - 0.18885520464144853, - 0.10771635708779746, - 0.21011099313942258, - 0.2628866930299805, - 0.2249171719353691, - 0.25614724624447216, - 0.15566423696182052, - 0.18047116900909704, - 0.0947649014078679, - 0.28993472712961305, - 0.1549377168432127, - 0.18769159931133383, - 0.05916492251941881, - 0.092667643802336, - 0.2439120850016802, - 0.18685368551341677, - 0.0803152614577204, - 0.2949247731266329, - 0.17792124242858726, - 0.03200483500897826, - 0.15295902620696594, - 0.04861844415835719, - 0.21367215807699763, - 0.06189951780483009, - 0.21283045949345542, - 0.22628398355560864, - 0.1535386978699327, - 0.296353375730741, - 0.11904515468591961, - 0.290766736145766, - 0.09206695445536967, - 0.137413503824892, - 0.1908353697376777, - 0.1382992641293992, - 0.11578285018807616, - 0.28597670063243386, - 0.27770152016956573, - 0.16169859145745386, - 0.06803375430150493, - 0.2673574847273275, - 0.13331132034184218, - 0.23233672116939155, - 0.27445843942277437, - 0.2688025876443324, - 0.23066564994429098, - 0.2925087264070046, - 0.247746720126777, - 0.257544359787317, - 0.24277750725141312, - 0.2776865983530913, - 0.20928164091575321, - 0.19582929457336792, - 0.24532950927369576, - 0.292728134938128, - 0.2649595454551072, - 0.17634615733225362, - 0.06938982025955495, - 0.1524835251120407, - 0.18965997966718756, - 0.16872087495855193, - 0.2544562618612752, - 0.2774185064772214, - 0.25132971342466714, - 0.18966955477006733, - 0.16421247518457865, - 0.15857527524300002, - 0.2722674331892163, - 0.18096701234532925, - 0.19042858857363898, - 0.1612766650523468, - 0.17144563156543047, - 0.18463000078303773, - 0.04623743885595052, - 0.20142550495880748, - 0.21270137631303643, - 0.28217657382811634, - 0.19342029759513008, - 0.1983022476865043, - 0.30213766794842734, - 0.2769664378782489, - 0.254301186158647, - 0.1813904200037245, - 0.1128367660957337, - 0.1503021289059715, - 0.16506982614461996, - 0.11455433635731176, - 0.25519947771235596, - 0.20529142851148532, - 0.2149216016664524, - 0.19915115685368961, - 0.24460845052828065, - 0.20743334726315776, - 0.050552009238711615, - 0.12451102453282047, - 0.08698955747438293, - 0.254378064172261, - 0.17314821383671097, - 0.1320164455863662, - 0.19599437974282946, - 0.09440245737056707, - 0.20318299823109848, - 0.2614509075482488, - 0.22982274099233813, - 0.09517064080969725, - 0.10392989878749377, - 0.10475076379279889, - 0.12947136200128204, - 0.2753369310269679, - 0.2651825810220236, - 0.19698802481118685, - 0.1429297957070095, - 0.1926719159808625, - 0.1964288800730238, - 0.21139276550255848, - 0.19891403434558064, - 0.24336426022731328, - 0.2659475835869698, - 0.0654084921687753, - 0.060893613584598494, - 0.2579361251721984, - 0.24090799038706925, - 0.14517828263701982, - 0.16548503167472897, - 0.07137047834222764, - 0.2119192050720958, - 0.1915301447779727, - 0.2765599168347364, - 0.2266379530228758, - 0.1502239265683238, - 0.2947726339887255, - 0.25095234511136044, - 0.03113889844584782, - 0.23988316142091676, - 0.20037508374084304, - 0.2914210203671921, - 0.13947980498844367, - 0.2656530270318265, - 0.28207690984769007, - 0.035994584209260105, - 0.17116015640956436, - 0.13531855517691826, - 0.2767613720166875, - 0.21442716841909018, - 0.2684881008723987, - 0.049935694185642275, - 0.2809148378175228, - 0.183439435654441, - 0.15770572318574158, - 0.13145990214534806, - 0.18247141298633326, - 0.1739048668846208, - 0.2941504109898054, - 0.25112025052837467, - 0.2212817341875433, - 0.24656871409059739, - 0.1709043498862508, - 0.15195143471184439, - 0.20126608668046134, - 0.2273936364123934, - 0.2463313580197324, - 0.20404943926141061, - 0.1589887770997928, - 0.1215932560296765, - 0.10812058584085463, - 0.13356701230119467, - 0.09281927539429474, - 0.23070066524858018, - 0.16556557961600968, - 0.2572018106470413, - 0.24857406306801544, - 0.21232756251677345, - 0.2788644417128806, - 0.11284326873365941, - 0.2388825729662311, - 0.1574146302919062, - 0.25572328934343946, - 0.1711271995760733, - 0.16917929822325234, - 0.0718777435908894, - 0.21308640026325154, - 0.24856874791860958, - 0.17594189193034257, - 0.17387433995627213, - 0.24893908577778956, - 0.1330632451279741, - 0.24758442741231157, - 0.0596992190044114, - 0.09953743006288746, - 0.27433752686587537, - 0.28802567239433835, - 0.05935415728341932, - 0.2787696789330513, - 0.11925993936887552, - 0.26740680404376416, - 0.23416676562112745, - 0.1568901580186192, - 0.26128695337966, - 0.16151897419032873, - 0.19728780206009916, - 0.23550902374170435, - 0.301174501036681, - 0.2533485336504923, - 0.046684284700389364, - 0.13268475060136736, - 0.16455126480846052, - 0.13990518792881765, - 0.295870918617254, - 0.14509019685959787, - 0.042492544868262205, - 0.14999079836026608, - 0.2618813631741553, - 0.21542799811749866, - 0.11250535020428067, - 0.07895640318849899, - 0.2725146701732617, - 0.10279140111879613, - 0.22138451733765102, - 0.11396381022502372, - 0.2771696692871002, - 0.13605878515128694, - 0.1170648230269685, - 0.17788613787086205, - 0.05925384462417591, - 0.27536242597138166, - 0.14860902193248218, - 0.12728754189194977, - 0.26852059027127634, - 0.06681374124282956, - 0.09850185545219756, - 0.26494181554944657, - 0.20976806138840084, - 0.1748322939415486, - 0.26912877174337557, - 0.0863410491904152, - 0.08637832403214933, - 0.14877441326817967, - 0.13669740470569533, - 0.2148172930380695, - 0.2612583901246702, - 0.23678715546356766, - 0.04947350617511751, - 0.26752952482827785, - 0.22428614961160068, - 0.29872684132073685, - 0.2008960408915122, - 0.05595729724642963, - 0.18788888423145567, - 0.23696443702751574, - 0.09813402074567709, - 0.11429043009383302, - 0.2112152648488134, - 0.21715458042031024, - 0.11677692899723566, - 0.29836694377338585, - 0.10501675271852595, - 0.06100965639976344, - 0.294710091103422, - 0.18307106333335083, - 0.256647067623878, - 0.2711666469704115, - 0.2439739914299956, - 0.2917562605577263, - 0.2932346372242866, - 0.11243099248069878, - 0.2750534665255552, - 0.21682215957347756, - 0.2403426683183695, - 0.3049574556622532, - 0.08932449744023185, - 0.13141357738789164, - 0.2944149419285522, - 0.1386882592925695, - 0.2946499219743973, - 0.05037087436836904, - 0.04848539550149805, - 0.2987892864219753, - 0.19545115291745843, - 0.11803834258696366, - 0.1527328659790965, - 0.2697455351402424, - 0.2330725132351514, - 0.2685649841420422, - 0.25670850534585243, - 0.2583924754918913, - 0.2612095800205337, - 0.13960105758466076, - 0.1893827762782471, - 0.062431601509258694, - 0.2077628663209051, - 0.24526523102399125, - 0.08942849944835024, - 0.07602544341197182, - 0.17401253756978383, - 0.07269655980676717, - 0.11966693021670884, - 0.13895033348013416, - 0.2235648783233332, - 0.23154443642133143, - 0.24093758157002293, - 0.14113668351751452, - 0.23607058952941373, - 0.23353734008684576, - 0.1780280952143999, - 0.277571698644259, - 0.19603874778457192, - 0.2723364206423367, - 0.18315587040921208, - 0.2144534184044388, - 0.1322228748094203, - 0.2763471224157263, - 0.15866730560059025, - 0.25132532639040567, - 0.23020385746448568, - 0.10374972921828333, - 0.195497301900063, - 0.2092215454539467, - 0.2596776019538848, - 0.22336220189857758, - 0.24208856132692058, - 0.15858843154447966, - 0.20983925235186235, - 0.24317983078583996, - 0.2597270539754326, - 0.200063594941608, - 0.17584710252521457, - 0.2950159424094801, - 0.06330414887324332, - 0.14428354269730093, - 0.21933052116384058, - 0.2859190608199167, - 0.05329986083652049, - 0.28431290483868943, - 0.13348107986245983, - 0.26841258670524376, - 0.26945685105487865, - 0.1866798098172761, - 0.18929038683130028, - 0.25048601236425916, - 0.26453251424262525, - 0.1791676157126125, - 0.07663716553439982, - 0.07976340734345949, - 0.10470632502333875, - 0.0631859210763834, - 0.26094793289614293, - 0.1270059330574097, - 0.1798510048319772, - 0.11766578785931397, - 0.09835708117490324, - 0.24758935700554535, - 0.21431955381901482, - 0.2738377267194303, - 0.2524451120194225, - 0.18407732878157348, - 0.2220264981451593, - 0.29377519096574495, - 0.2030492813286229, - 0.2253448398840221, - 0.2757545987936251, - 0.10881102277705022, - 0.23890105071477624, - 0.22355673583191865, - 0.06862411824155626, - 0.19058656848198213, - 0.12797879694933673, - 0.16643040052140934, - 0.19508305696052386, - 0.2775276567954545, - 0.09844236691039271, - 0.2903495515414531, - 0.2577099140153874, - 0.1359709145258848, - 0.12611998125174537, - 0.2578718123856432, - 0.16260711546558065, - 0.1558029719899216, - 0.21860497756437688, - 0.059648091402771275, - 0.13258077195545426, - 0.13254206195931797, - 0.023880905138725282, - 0.07653399337770829, - 0.23134023365054807, - 0.19387234851620314, - 0.18656961773862768, - 0.12935413820579403, - 0.21224313880077364, - 0.200003253759934, - 0.1490793181261236, - 0.19070244154691068, - 0.03178836718208688, - 0.2689986730158917, - 0.27289187100463425, - 0.24743829471058862, - 0.2423608388593911, - 0.24105162973731778, - 0.10413112764227919, - 0.19406368267108617, - 0.037029907965581144, - 0.23229694151963698, - 0.2545490150705274, - 0.06714103830487904, - 0.01621075636644242, - 0.17916429212349758, - 0.17114457121814147, - 0.12976032071275834, - 0.294451149712326, - 0.22084318496120867, - 0.19520444619551233, - 0.10589559337293186, - 0.23676314406960347, - 0.17865790178502633, - 0.2884388218304051, - 0.16327702831640167, - 0.193260322330855, - 0.14878558994894775, - 0.28705750283429154, - 0.20221098182351635, - 0.2068344223117404, - 0.20422864373623634, - 0.0867883963663297, - 0.25732290390823886, - 0.15459040029118504, - 0.13082549172034094, - 0.17127744055917224, - 0.21248688039806118, - 0.28129990209680783, - 0.09562540307234636, - 0.14181390906613653, - 0.13153745350542426, - 0.1511967129367401, - 0.21344153137430666, - 0.21913051344793147, - 0.20664639104874158, - 0.17760206738191905, - 0.19549078515384322, - 0.22992298461852279, - 0.2942144386459369, - 0.2882343808996561, - 0.22631132145513314, - 0.17157737389885389, - 0.16746187574291418, - 0.20653912763412477, - 0.26617874023380383, - 0.23135575530736502, - 0.17590267395907785, - 0.2458048108734482, - 0.2994726982319261, - 0.2742487148886411, - 0.1913447569433716, - 0.2049942166875808, - 0.2086765127353059, - 0.2670105630566214, - 0.14176579794318298, - 0.17820507739834776, - 0.17708446964670999, - 0.2264021161819211, - 0.22193116613440655, - 0.2556241005918659, - 0.16662357124814292, - 0.16248972962983527, - 0.10507074440363405, - 0.2967333663213511, - 0.2721635098082887, - 0.0647910240460424, - 0.26910987653285007, - 0.2506555402418606, - 0.27498511458937763, - 0.1590363707624451, - 0.24939013546697603, - 0.3033518367833507, - 0.10704379569346616, - 0.15216783061399414, - 0.21661633876770653, - 0.21924236597204957, - 0.28375055997989634, - 0.2552027673864118, - 0.1437194551927165, - 0.282447493395739, - 0.18197123753808264, - 0.09185175356594194, - 0.2171683338128877, - 0.1827730872878532, - 0.07017219368185806, - 0.2437202730343982, - 0.24080168629418852, - 0.2603295636481468, - 0.08525392525346295, - 0.08730934800954751, - 0.14750872288854097, - 0.1897436027517512, - 0.18586954293063346, - 0.2142616881801557, - 0.10418888455453847, - 0.27347364663225554, - 0.23949715489254603, - 0.17235834168944403, - 0.08890675743215926, - 0.20793826226808873, - 0.19169732141201432, - 0.11885031560762488, - 0.23471175742510494, - 0.27732688408450373, - 0.15139333147656397, - 0.23187950699885662, - 0.25989650895741384, - 0.2533076255587839, - 0.16611580922359212, - 0.08392455997103646, - 0.28098407467840936, - 0.14711675073649438, - 0.25728183643761005, - 0.17465811471978165, - 0.2646684968201291, - 0.2738021788229068, - 0.11436563926853924, - 0.09163524980402678, - 0.12157300963024494, - 0.1538548229549228, - 0.1457846901626721, - 0.24260725660387042, - 0.21829110614213873, - 0.2798070380848523, - 0.22064796698320147, - 0.28059701211064914, - 0.29013735117258405, - 0.23680390162865844, - 0.17052573423566558, - 0.08244057994597583, - 0.23960939933483688, - 0.2055608565416956, - 0.207092896280663, - 0.26596278163295584, - 0.2667975423194512, - 0.26486999684606455, - 0.08889072535634454, - 0.08137266645577122, - 0.30119976139202637, - 0.0876377916790137, - 0.07497609852549218, - 0.24587645291119586, - 0.19453060387412557, - 0.2109145656297156, - 0.23381146935442612, - 0.1542414567600134, - 0.1985466291560352, - 0.2849202193555577, - 0.26593912895385063, - 0.2727459923233786, - 0.2311185100018597, - 0.2014989062799403, - 0.22353352695965553, - 0.27529442422462574, - 0.1900596311928918, - 0.109992132685431, - 0.29349357738297044, - 0.24459798929059767, - 0.037401239517852236, - 0.11422338025062678, - 0.16499645454259704, - 0.24067402429431953, - 0.23875961197547224, - 0.25048637313555616, - 0.20442692736581494, - 0.24710141099488261, - 0.06284542806785955, - 0.1828771123190389, - 0.1755125830829071, - 0.28308844260027854, - 0.27590064271412545, - 0.13849828870751665, - 0.2517273624552892, - 0.2472371867548735, - 0.140894298165114, - 0.3003944825219128, - 0.24923249385613458, - 0.24525215793079355, - 0.24526101172965317, - 0.20857651674867705, - 0.24237142290011668, - 0.07213647247025529, - 0.1763367016930232, - 0.11795564570360091, - 0.12486102141122865, - 0.20508254779824306, - 0.18524772752775226, - 0.190894034230388, - 0.1062031428286803, - 0.21970495405654614, - 0.2846491557757646, - 0.2803152240418822, - 0.2335469747716439, - 0.15463096264536494, - 0.07634668896636192, - 0.18974330509762719, - 0.08726953527670324, - 0.24934471998801258, - 0.1730625067484582, - 0.08737024614240646, - 0.16248359877542382, - 0.28998484118023277, - 0.19113177842758503, - 0.23106438768595072, - 0.1148252050032318, - 0.11652711007722986, - 0.20812650881007194, - 0.10597058141393893, - 0.3006459822534042, - 0.20433238141015067, - 0.19593410366820035, - 0.28964939733661477, - 0.0868526655458777, - 0.23908171403402279, - 0.195920828282564, - 0.20109726970707906, - 0.20061517026922598, - 0.1448864234403762, - 0.22458339634923152, - 0.25428471431931887, - 0.27793251901031296, - 0.26905353931675646, - 0.28948057841037134, - 0.18098932440162213, - 0.06802525937894337, - 0.17730294717169048, - 0.20094750135774983, - 0.1821123914180863, - 0.21009221259200947, - 0.23176802571554186, - 0.26660798267837194, - 0.14206669730941535, - 0.2642749864975025, - 0.24473161320184791, - 0.14295103976660298, - 0.29664028021976113, - 0.1334296569926491, - 0.24495685434496983, - 0.2674554757978272, - 0.1455413571492778, - 0.15189242219120538, - 0.22624082397404982, - 0.2500747026708758, - 0.05560220979854107, - 0.19169353116524668, - 0.16193279990943604, - 0.1665633605180817, - 0.17111009068773445, - 0.2352965879516126, - 0.12925845567485975, - 0.2138841646557797, - 0.2438999473840945, - 0.2553038710163622, - 0.13728929425549155, - 0.29082665448344497, - 0.17069368751838102, - 0.19320096245616528, - 0.24586630869504517, - 0.1864919771760076, - 0.2618803473908039, - 0.20323621223669294, - 0.08466164256941368, - 0.27585772081489934, - 0.2908075848627869, - 0.23898975043780687, - 0.14726764926684696, - 0.0926740829962329, - 0.18103181073004387, - 0.1561010891870346, - 0.1038284806057399, - 0.2816949626128598, - 0.25839881146571275, - 0.10375090051304217, - 0.19645828345503452, - 0.19922873064572877, - 0.2940588301181771, - 0.2479189324399589, - 0.12299270056160906, - 0.1701540037737213, - 0.08925209801660774, - 0.2049452060811266, - 0.23900667148393606, - 0.2213713212795473, - 0.21535861476987248, - 0.24155808457986172, - 0.2969891225424423, - 0.2774677573441467, - 0.24012528493942895, - 0.259808230665337, - 0.13795915585931767, - 0.17176463370981337, - 0.26637529704786983, - 0.048745851653155016, - 0.23474852192782777, - 0.11399694116536523, - 0.20641334779132034, - 0.27099042875756063, - 0.1827735346449752, - 0.18999263989217466, - 0.10061072118063943, - 0.2251205950675202, - 0.2712791971192526, - 0.1850114211726369, - 0.13214613242645493, - 0.1386439758186536, - 0.2909488472766573, - 0.040597764613397445, - 0.2380366457529427, - 0.28508268044419643, - 0.22341760010058295, - 0.1013245704313373, - 0.1967088431271883, - 0.2508562325857625, - 0.2163661773986633, - 0.29816793747499354, - 0.09998548505517049, - 0.1292937329337788, - 0.08458663648388148, - 0.11311871119808095, - 0.14711873596277852, - 0.042578014104016335, - 0.022494255060539255, - 0.260808530496998, - 0.21848679773250673, - 0.1594657520636895, - 0.13206367646844525, - 0.2459618294153849, - 0.05983306091051088, - 0.23467252391927731, - 0.29037215505044445, - 0.21028058383215725, - 0.16272973987333256, - 0.2162327189883201, - 0.2519322816413202, - 0.2296566939121587, - 0.13991087054865034, - 0.21992542337738372, - 0.11786490125784768, - 0.1919429894806307, - 0.2901198869141247, - 0.18272401369406038, - 0.23166468900873688, - 0.1582874044623564, - 0.02862692236181499, - 0.07510730240764908, - 0.20492736714043985, - 0.2797334941834408, - 0.06550419022416579, - 0.1940805336281592, - 0.2533052426290743, - 0.3046880051108923, - 0.06094571220029496, - 0.24846438203288898, - 0.1854681800172875, - 0.10281325921319458, - 0.23628244606888155, - 0.21284220812138396, - 0.1652716035666159, - 0.21813534852123004, - 0.12521108039187076, - 0.1394688244526908, - 0.07548853060447387, - 0.15825301952124274, - 0.16429190801242918, - 0.20251106416621703, - 0.2760886939396213, - 0.13817025493221735, - 0.23967660812544297, - 0.26616697972725145, - 0.13728479774863275, - 0.26007857857113625, - 0.14847529883543542, - 0.30178255203701637, - 0.2889545687413967, - 0.13206265336543882, - 0.2645184772765739, - 0.12300619001149607, - 0.24044920973049566, - 0.14252185316535662, - 0.256311263705815, - 0.16250330449612407, - 0.18304060511949732, - 0.03295663468594081, - 0.2832816130405111, - 0.08651216877767635, - 0.1361541415159924, - 0.24888503465163847, - 0.2133130117622247, - 0.2673250716671947, - 0.08386981838355191, - 0.13912332472787384, - 0.11718325890029498, - 0.2779241603780239, - 0.2600404707708506, - 0.23429817483410484, - 0.1948963714920783, - 0.2396703760361919, - 0.2947730228346357, - 0.18345483247505853, - 0.1916685104356544, - 0.12687633597232864, - 0.239001978871302, - 0.06883075131578055, - 0.22471016752938378, - 0.2770861688101639, - 0.2523506168517875, - 0.1941426866779897, - 0.24560861421365088, - 0.22994028955297433, - 0.18511972793458006, - 0.11398236492261211, - 0.1840888121185323, - 0.14219981812272883, - 0.2564659449714686, - 0.23470947915565182, - 0.10884010184962925, - 0.1512680155899017, - 0.30078350284249, - 0.25016264900574303, - 0.24755091282209535, - 0.1501624711087172, - 0.21442840728839102, - 0.21648323539746828, - 0.049473733416550175, - 0.26877841873060043, - 0.05026438423654999, - 0.2158414688951642, - 0.20475191683030847, - 0.18070049104158048, - 0.1661822481082412, - 0.18609036899678788, - 0.26341826396555756, - 0.046932662149153655, - 0.1139918096511208, - 0.13483429958943316, - 0.23093093108138896, - 0.24146456515631096, - 0.22578190858856065, - 0.15147224630921405, - 0.23623287106038243, - 0.24295067190488298, - 0.07899526855862417, - 0.11678148677818391, - 0.1404915821099031, - 0.23453234906433845, - 0.07464930853728394, - 0.10507371965812154, - 0.21692510990580025, - 0.17033587612155493, - 0.2741787521294755, - 0.25599908995335025, - 0.1845217982777907, - 0.18266602974576354, - 0.1288942691251415, - 0.22227189854541465, - 0.2405721064800439, - 0.17714852283172575, - 0.29176413896878717, - 0.22241421462010488, - 0.1695562291715777, - 0.28469385717779705, - 0.2128086727568179, - 0.2259905410037472, - 0.19799297242552183, - 0.07290152056348623, - 0.11303507312534554, - 0.26549415746993216, - 0.25325013269569024, - 0.23772681687170671, - 0.23688008820393322, - 0.19149798200457466, - 0.19723975517533116, - 0.21006864729171199, - 0.206811358837785, - 0.28691816819774185, - 0.2568641463437059, - 0.0761888110265176, - 0.12813168697893576, - 0.2575065981513198, - 0.10325588402199494, - 0.11585551848463742, - 0.20406091296976864, - 0.22608373415278815, - 0.22687782663495232, - 0.1397203998054284, - 0.28514552342950694, - 0.030294745610152583, - 0.22749444983250974, - 0.0785766843726044, - 0.1224161644327386, - 0.2271650341151257, - 0.20940841009880864, - 0.22062729547296683, - 0.1407651026871852, - 0.19240544976994073, - 0.25950074186749184, - 0.11663823479770581, - 0.2196439958801792, - 0.2356014812134128, - 0.11912816788151878, - 0.18786577293049264, - 0.1663683229636696, - 0.21981673689140518, - 0.09361241032800471, - 0.2786444145890921, - 0.22040131519679088, - 0.14971457710168817, - 0.21362817736907005, - 0.275073894666264, - 0.13719588747761868, - 0.12472166763060928, - 0.1684888342077581, - 0.2563022504205936, - 0.03512969130600213, - 0.2560455089155258, - 0.243478789304505, - 0.2129328142446181, - 0.2811950826873484, - 0.1752915129834491, - 0.020151000883002795, - 0.06276419159310298, - 0.17051560822626521, - 0.18520295678448015, - 0.15086542150955976, - 0.2848809450550973, - 0.14206461980370386, - 0.24263911408897312, - 0.2881080980988952, - 0.18320161939355828, - 0.27306224984635025, - 0.2507045357422596, - 0.24868085868288867, - 0.21404607742827078, - 0.14400985635900454, - 0.15746451662598246, - 0.20643530462959836, - 0.1889870793311353, - 0.2762886574371107, - 0.16092462518575962, - 0.12636994603527849, - 0.12313829710285239, - 0.052712167547721095, - 0.13927112749418655, - 0.20333420204070699, - 0.13276470813272934, - 0.2159110209033979, - 0.19918315901795125, - 0.030588896516420137, - 0.14311535276043777, - 0.1663643315160453, - 0.1386213858325495, - 0.15718153060876394, - 0.1429249875803254, - 0.2196511997048784, - 0.17187297657749068, - 0.1608464421250571, - 0.14543224826586518, - 0.21368607086914526, - 0.2220286669914046, - 0.023269804272936723, - 0.20300679409104067, - 0.12365067635618705, - 0.2855576223595898, - 0.29977501305385545, - 0.1939634889901969, - 0.2626041643888681, - 0.07006885970430463, - 0.2920189411094323, - 0.2789787901606706, - 0.29560087879974184, - 0.17417950325051987, - 0.21624942059885965, - 0.026755294044304143, - 0.29479799507270066, - 0.03948196383855162, - 0.11308662285078162, - 0.14660677265701968, - 0.22490657447989246, - 0.25801918068950735, - 0.12298722143019448, - 0.29244950837031575, - 0.26298833167057084, - 0.21206988578293487, - 0.10318340586076957, - 0.19377423842293356, - 0.09300153239370831, - 0.20721132602959663, - 0.191713102339566, - 0.2190597307326278, - 0.2800518098099094, - 0.18321493567387703, - 0.1389322954277713, - 0.2741144071310574, - 0.29475674565731785, - 0.1644192130776883, - 0.1395705759770367, - 0.24762384576240376, - 0.16180999574539426, - 0.10951813561516045, - 0.1369204708230705, - 0.24268495901316758, - 0.12975845748367776, - 0.061582966394391696, - 0.024152287767371137, - 0.2231982349315616, - 0.18021559779808266, - 0.09442537173236858, - 0.26249529411393996, - 0.26628140174082965, - 0.10001794315803575, - 0.27249790665291607, - 0.2674741744928634, - 0.23169817055653513, - 0.10691677622448742, - 0.18844608162750037, - 0.18862476263266018, - 0.13482747185115865, - 0.25729859530755106, - 0.1707374745190978, - 0.19628283775713537, - 0.1250920511602489, - 0.11696477372182688, - 0.19015001690455569, - 0.07669152396223003, - 0.15423480020367283, - 0.15106668161762613, - 0.29477624205908187, - 0.21056065713963537, - 0.2145877572754939, - 0.04314601821386248, - 0.2009954714386768, - 0.18921519203174025, - 0.19164298193933504, - 0.2442793884510625, - 0.2062214615139318, - 0.2044724227398196, - 0.21806024778694952, - 0.07868956472146094, - 0.19471902500027605, - 0.28753602568703146, - 0.2712924087171743, - 0.22469773350090852, - 0.21744534218473413, - 0.2596993644919844, - 0.21601484979063457, - 0.10997278578037126, - 0.26799952308090397, - 0.2606352285894381, - 0.251201839161064, - 0.10776621141907991, - 0.11356323033666274, - 0.0901642655867856, - 0.17019372244372197, - 0.2038370593933569, - 0.27865720611105116, - 0.04308870410344923, - 0.16883009985286992, - 0.25950685509529825, - 0.30330643905871013, - 0.22366675064381614, - 0.1894789360383902, - 0.2893096715523195, - 0.15045828605146577, - 0.22286469454894636, - 0.2606944873655842, - 0.2543059310535893, - 0.08674821923306344, - 0.19952647669826937, - 0.29284043474098964, - 0.28440553992085665, - 0.22017208095957452, - 0.23302821972962734, - 0.18041417743725677, - 0.2898711086883847, - 0.1885812191100616, - 0.13295506383283637, - 0.1181316266726634, - 0.19273911111586545, - 0.1695366704267783, - 0.2612476718029628, - 0.16144240045818728, - 0.2335492490668, - 0.0980482438155786, - 0.26409775922336637, - 0.29044995883894587, - 0.09794129288310724, - 0.254284507508154, - 0.061944005296166144, - 0.06270147595018054, - 0.20954640770596017, - 0.20883631462009986, - 0.20937227620780666, - 0.21293953559305498, - 0.2329905269551205, - 0.19495689171639238, - 0.2606092543018635, - 0.08862215926207785, - 0.196592929744247, - 0.21969984891368163, - 0.18365167989552905, - 0.10652824558143965, - 0.2476485255387191, - 0.17021424275064798, - 0.09895762171446276, - 0.21553041282085672, - 0.2950124221586617, - 0.2106942092812543, - 0.23624793908111652, - 0.10785134586789095, - 0.1882147425408471, - 0.22885695089773436, - 0.2207131280700589, - 0.21655385503216154, - 0.23992120273306908, - 0.21318113242317538, - 0.16102074613781808, - 0.2562858586121093, - 0.23177172483291875, - 0.18984773394524748, - 0.3044383953764837, - 0.12262724199004264, - 0.2448966757957638, - 0.10286525078663439, - 0.22846656927542086, - 0.06905654242955324, - 0.24999950436942503, - 0.14461100919514452, - 0.288943629085604, - 0.14307449340129533, - 0.27847803153586553, - 0.23675949008953381, - 0.29935232106081233, - 0.2780307534882343, - 0.2866529455201227, - 0.20738702761498082, - 0.23469387034100808, - 0.20637516735606387, - 0.20317037645627867, - 0.19378850943919484, - 0.017319459708759866, - 0.07821655532174694, - 0.15461228561306123, - 0.04635098280087555, - 0.2910152489161408, - 0.11206782307635195, - 0.2055242973663919, - 0.25291278564678465, - 0.27185923520986455, - 0.16790049024783552, - 0.16079006331031717, - 0.16908291771378828, - 0.2793913463774878, - 0.173531970781791, - 0.23197641134438615, - 0.2583698174172488, - 0.2971002432768537, - 0.11217250021762558, - 0.18426891845593935, - 0.12603791891005658, - 0.16258899163085427, - 0.11515568703108442, - 0.03521097380371991, - 0.22260374034706684, - 0.01729299338376037, - 0.17350304739041822, - 0.12237421132922155, - 0.18694950401673097, - 0.2716771337115123, - 0.09248718799467992, - 0.1589903209207462, - 0.07146853480245943, - 0.03841259099523109, - 0.28457494598886895, - 0.21217875902605865, - 0.1402626553746525, - 0.0726297079638921, - 0.20402020681904065, - 0.24128399524129215, - 0.25997318806412223, - 0.2965063161099138, - 0.2954626953801377, - 0.20567590535281619, - 0.10356109702386321, - 0.19577305917457702, - 0.19739740260836683, - 0.2084932963135926, - 0.2376430890200649, - 0.2208393428305659, - 0.2925702637145508, - 0.233586447035641, - 0.22212390741877838, - 0.16615538699525279, - 0.26652551682378234, - 0.03249162423669155, - 0.25153287712863626, - 0.22008155075306476, - 0.18701940807468392, - 0.21942992919782134, - 0.23209113434160986, - 0.14675603904275908, - 0.10899964246332637, - 0.2729298211155522, - 0.2628254575521281, - 0.1785239849741979, - 0.048977016556591056, - 0.15212929806896455, - 0.03190439896988375, - 0.0809395108931612, - 0.12088764136055076, - 0.0975714047329108, - 0.07412304111612643, - 0.19166602540931793, - 0.09109382233630858, - 0.27043927455698846, - 0.14694150604333098, - 0.18264583654417757, - 0.2742652350465098, - 0.2052383402323942, - 0.28725996906859236, - 0.10196895451999458, - 0.14865249321070415, - 0.23244765686034885, - 0.17722486478847316, - 0.1546254531096568, - 0.1545950985206179, - 0.0996657496844028, - 0.24443998870436817, - 0.22744649210791645, - 0.2929273156052515, - 0.21597216241418585, - 0.2693927953095559, - 0.24855007006005853, - 0.29743460898572793, - 0.07407889779917753, - 0.25105094845778775, - 0.22899857102290902, - 0.05869630726839829, - 0.14589431029083821, - 0.09638206711887905, - 0.09499641113491007, - 0.2622867463521042, - 0.23015021410861372, - 0.1927904285588973, - 0.24101026658907967, - 0.06240595579544518, - 0.29931566241959634, - 0.11642806996047773, - 0.23462620704720694, - 0.2918485342029859, - 0.27277669852031666, - 0.06607356103874548, - 0.2185170196066328, - 0.09343682796400196, - 0.16038858955978413, - 0.052579708197600175, - 0.1592871468009192, - 0.29884327819442247, - 0.2792663682830827, - 0.25242285464983916, - 0.17634989357855876, - 0.252988120764727, - 0.26543162587423086, - 0.12087689310911919, - 0.17663074818034585, - 0.23382420193113898, - 0.1391774639461417, - 0.14704266203751717, - 0.2652348070420524, - 0.05392326694471071, - 0.1265781062496791, - 0.06316684743236807, - 0.27283113617397536, - 0.24268676193996577, - 0.047916616418205014, - 0.2557237076735053, - 0.2949245747896, - 0.23430388226130927, - 0.26541790007041516, - 0.2050645826006895, - 0.2854587108952687, - 0.10652043268619243, - 0.20754533497481759, - 0.0756744843161966, - 0.26917947652725344, - 0.17138041047238284, - 0.24067709026563178, - 0.11463523440807448, - 0.252310660400343, - 0.07016696274191762, - 0.1625489799745978, - 0.23364902938374482, - 0.12271955669202404, - 0.23203806662541657, - 0.21480888570090015, - 0.280063343129494, - 0.15062486368438233, - 0.23253772866169656, - 0.1459803054390105, - 0.23809986867575897, - 0.05986347143730266, - 0.29210820541330784, - 0.11892629908667063, - 0.25157604391850874, - 0.08970682727506733, - 0.16767307213076882, - 0.14422570770301463, - 0.18514511355627628, - 0.10701328223699835, - 0.24538421882856987, - 0.2544019502014157, - 0.15148897509327508, - 0.03765161313165135, - 0.18734406081134655, - 0.27803014946228777, - 0.1649989988553078, - 0.2767730397782814, - 0.2561145814251085, - 0.17339912814208103, - 0.13620522611054048, - 0.2689265086738353, - 0.0785951019453602, - 0.2784466847671094, - 0.10181460647584747, - 0.24696693503755862, - 0.1332966265070652, - 0.2803543592295483, - 0.13268727082873183, - 0.08188468015723852, - 0.21439677438017654, - 0.2303168218536126, - 0.21376546950144135, - 0.2729798790585068, - 0.22818351754142965, - 0.26972524592045577, - 0.13537963224405478, - 0.20744595128852286, - 0.09328209159384175, - 0.20140452098827408, - 0.03871618487653495, - 0.205866890922576, - 0.2909659569882231, - 0.1886852495140537, - 0.18347712679224035, - 0.2424353495287385, - 0.08761158029258036, - 0.1467019083955299, - 0.050183959308157576, - 0.2623966796639639, - 0.2034237549252033, - 0.17615905486788727, - 0.10299945925526542, - 0.15053774984836477, - 0.2992087739187341, - 0.20180507002313344, - 0.18615169167398582, - 0.20598515590475794, - 0.1482722426730725, - 0.11340974709132347, - 0.16960118804464044, - 0.19838422788935328, - 0.2782617136193784, - 0.2762531597158834, - 0.19691738614483822, - 0.2260301211613087, - 0.03604396450691811, - 0.08757516893141269, - 0.2708130865162271, - 0.10662968801285018, - 0.26507015523701744, - 0.2839640112994011, - 0.1722653880110443, - 0.19740366512983054, - 0.21743317238473, - 0.2470580862031524, - 0.0920079407693626, - 0.3002426283469433, - 0.1298532105065835, - 0.09313873688287833, - 0.044168390842286964, - 0.2644806517454654, - 0.22298747736909796, - 0.17919573658424717, - 0.19129086815491278, - 0.29024681490488696, - 0.19175092484820896, - 0.16182194643723757, - 0.21402451724603416, - 0.22120191681352203, - 0.2854605097639801, - 0.2043524246284437, - 0.26442582353609484, - 0.218074792536681, - 0.15142541656346367, - 0.2277987990007179, - 0.13503019736682267, - 0.2128190434643665, - 0.24903539761904214, - 0.16085218185383268, - 0.24212856440214187, - 0.10175100869105264, - 0.1069151202549678, - 0.2838273745829864, - 0.12236598422354544, - 0.2405216641307114, - 0.12410614997012363, - 0.2510836392688061, - 0.2572495878472259, - 0.08787832033496559, - 0.2195324167223904, - 0.2077444937282018, - 0.17590689138504229, - 0.029028572525713118, - 0.26731074964485724, - 0.19454245158062894, - 0.1888546311625103, - 0.13427415831000364, - 0.2779730703413729, - 0.08427103450363972, - 0.22144674847367993, - 0.1995340250445127, - 0.12475518182191032, - 0.07915750848200676, - 0.21988806837602248, - 0.2968093151727777, - 0.13921887237441358, - 0.2306559610012118, - 0.19465372894393052, - 0.267812748447754, - 0.19560362411320656, - 0.12553204515267882, - 0.23588576847508236, - 0.10184984228192011, - 0.24347475432839277, - 0.17901538523999622, - 0.22023282339600297, - 0.22400559715242105, - 0.19760937121204986, - 0.27833541611917473, - 0.1584550090996059, - 0.20754534990541937, - 0.07461029377900386, - 0.20052596579875465, - 0.13071672773186443, - 0.2782414136457918, - 0.27372282439208534, - 0.2768408048741568, - 0.29856741832947326, - 0.28793922671302635, - 0.22223017036130685, - 0.1658287380864205, - 0.25422465164620517, - 0.26116187444112804, - 0.07800588833059638, - 0.2790251306662057, - 0.2591416878209692, - 0.14391555469514813, - 0.30495408818947184, - 0.1256729534196164, - 0.30349312753016777, - 0.1735117525957839, - 0.16216225452774874, - 0.2552159609507429, - 0.23433381494490765, - 0.141433814686817, - 0.18078422335695787, - 0.09392884679144806, - 0.16684840505077875, - 0.2593633235223832, - 0.23541141106574803, - 0.17665621996276643, - 0.14906650691688053, - 0.20053404841027014, - 0.0659695699712886, - 0.2879579209725064, - 0.09485194491010544, - 0.21497040496284675, - 0.16807913185236922, - 0.297985522745685, - 0.15462675031727235, - 0.25347687928929735, - 0.23683408182368906, - 0.1983872239311829, - 0.2482358352937575, - 0.14976753881702903, - 0.21610054254364533, - 0.0378509126122541, - 0.17849573517154763, - 0.2699629453664462, - 0.16962297127658582, - 0.25327659476093284, - 0.2476685395713947, - 0.02806452053300696, - 0.23260900318702535, - 0.17064714083043142, - 0.2098605862503563, - 0.2674868384366377, - 0.10279089376982573, - 0.09587398014578402, - 0.06556229873336523, - 0.2614402016497092, - 0.19509863306554281, - 0.08252164583858147, - 0.17139796144017835, - 0.18448859428791367, - 0.22240339295496683, - 0.29343046288594954, - 0.09518404844566533, - 0.18766703796772466, - 0.29406541589571616, - 0.1813655137134376, - 0.23073330688242225, - 0.11488820042926777, - 0.1331967303065785, - 0.26781743774783406, - 0.19668911659034094, - 0.2793002745940442, - 0.23335313221401047, - 0.22360453862858048, - 0.09202431864079026, - 0.2521886504795316, - 0.22824988714403208, - 0.15992337813115604, - 0.12282462317930587, - 0.24032890837463863, - 0.20362365755034595, - 0.21683021352194645, - 0.2571130560009515, - 0.16091978501718887, - 0.24175423584781505, - 0.24222892345166408, - 0.1718864011388615, - 0.13532627400207195, - 0.1111080226540442, - 0.07844551877587554, - 0.12368087693706818, - 0.2552703120376804, - 0.21711857983901017, - 0.1360910657400197, - 0.1832319870573771, - 0.28191659664956986, - 0.275372472769042, - 0.22199021096677657, - 0.23352754514603416, - 0.1830371784303611, - 0.17353160540058066, - 0.17513013523525084, - 0.20588773306685362, - 0.09585533284527113, - 0.1129005266628755, - 0.2183027020723918, - 0.25079665871175527, - 0.17947682898583897, - 0.16893837029929978, - 0.039450087947877924, - 0.30190048850152956, - 0.09653739154047382, - 0.21169324020216587, - 0.16729581210636604, - 0.2046922405037021, - 0.19846120022420524, - 0.26231020883420975, - 0.18023736899390772, - 0.2862611096746094, - 0.13323756270703566, - 0.1328630067444117, - 0.04701521849244883, - 0.10660966985930859, - 0.27570286277583184, - 0.16075727788153477, - 0.061622193750161564, - 0.2935679961088398, - 0.29911553943382174, - 0.15070883946484082, - 0.2346842934161601, - 0.17758941631548317, - 0.2485647829441674, - 0.15525569619067814, - 0.18327298662769173, - 0.12190926637533221, - 0.12477366646325094, - 0.1698191532951339, - 0.29029410697560754, - 0.24295675506668094, - 0.09465717804141893, - 0.052936139202931394, - 0.2980142809339341, - 0.14117560026538498, - 0.23738279916774216, - 0.23471837675024698, - 0.2853457035132007, - 0.13500371097270628, - 0.2754683772343798, - 0.19019480415608225, - 0.15570948954545108, - 0.12970435246880854, - 0.20507487045528336, - 0.18545736815120337, - 0.22843034399461204, - 0.24752440845375656, - 0.26947329576092544, - 0.2724341110229931, - 0.16932038417815318, - 0.21673104829492784, - 0.12520850601243086, - 0.15689176302723154, - 0.12975201611145637, - 0.06209454308937531, - 0.1508107533212955, - 0.26200814383957316, - 0.24913496969767568, - 0.18756084502070514, - 0.22143587522303942, - 0.14696839509678258, - 0.11927051984875092, - 0.2139192032879219, - 0.2880750184987202, - 0.12340180179828883, - 0.13114388497940802, - 0.21620045275832964, - 0.19230424602908822, - 0.1813580969251072, - 0.2156765888450221, - 0.1885746553402076, - 0.060168263604363725, - 0.20481400304263797, - 0.20411610160357124, - 0.12007763103083621, - 0.23311488772959946, - 0.17610839974804546, - 0.19761453950719202, - 0.23207247098709657, - 0.02931943258265294, - 0.2668979562640318, - 0.06288160725079821, - 0.17732260729279234, - 0.26805707017702896, - 0.08290732190625208, - 0.1851464777350242, - 0.10061599098241922, - 0.13458772548182377, - 0.18331610960519118, - 0.1963367732802584, - 0.17834302295484616, - 0.09850967329407342, - 0.18973879212446143, - 0.12562934259797273, - 0.27073485810622483, - 0.2337812502948699, - 0.03238243450008821, - 0.20261727295219983, - 0.1205810774702094, - 0.13720303360831348, - 0.14651698176335493, - 0.27319618097567167, - 0.260046662304998, - 0.15846146568601532, - 0.20309820369177647, - 0.2670050556990683, - 0.1349215947498154, - 0.058255152396836825, - 0.23609818198933602, - 0.07534720336385564, - 0.28818535776714305, - 0.20359146535833708, - 0.2406812254288444, - 0.23377969794822326, - 0.11688267468830772, - 0.07918023220908796, - 0.11194600390075093, - 0.21235009724616594, - 0.2487016304337906, - 0.15959718117000818, - 0.05366376344345603, - 0.04454487494155729, - 0.1906812296430624, - 0.19440813601949922, - 0.24326917118911578, - 0.18884014719657866, - 0.22548291756366576, - 0.2668236334784724, - 0.16936414551216925, - 0.2630709490561354, - 0.2651229641949324, - 0.27572247020738877, - 0.15231147264206898, - 0.29132547429189654, - 0.1940014181121557, - 0.1217358276556339, - 0.1846360137456656, - 0.18076776232762087, - 0.09070838202230537, - 0.2661698960551719, - 0.2860131197760874, - 0.16721122711020397, - 0.23082252843485562, - 0.1315628751318888, - 0.26769563268096996, - 0.04107729451582515, - 0.06899092779196672, - 0.23342698599833978, - 0.10309917819725081, - 0.28686140137857097, - 0.23820015050433163, - 0.20630596937979315, - 0.25110467815820725, - 0.12900228455049162, - 0.12056403834616435, - 0.17114734921879382, - 0.07022834405969579, - 0.26705491541557597, - 0.2822478938797246, - 0.08956772797335524, - 0.21278357954783914, - 0.17194116375408372, - 0.15438958436065603, - 0.19763231484752083, - 0.2579724788575258, - 0.2197704970674212, - 0.28899832896610594, - 0.2577159684622302, - 0.23506217388478193, - 0.25173485323956535, - 0.2584741630251752, - 0.17893365425549157, - 0.18678431154523936, - 0.23543445263232585, - 0.2720443902017717, - 0.10917700917058316, - 0.14908150736426246, - 0.2071698153930145, - 0.21239246076967785, - 0.2523325355683828, - 0.28947565429297467, - 0.2950169587742273, - 0.10477668591544145, - 0.21279589909646374, - 0.26703666604961346, - 0.07555195844304785, - 0.18432692276495277, - 0.18520918443920528, - 0.09212176338671334, - 0.24549408054538197, - 0.2698568376747854, - 0.19986358856608497, - 0.16906585411785657, - 0.2958238650858085, - 0.08326499542177002, - 0.15534731636010313, - 0.044684645943282274, - 0.14565022857255455, - 0.2981807848101089, - 0.2762809269713834, - 0.19200258124034109, - 0.14188724577329861, - 0.2700407569758332, - 0.18553847703129664, - 0.14391944343555352, - 0.2683680295452143, - 0.23618843024299965, - 0.2924217781823653, - 0.12964712868924394, - 0.2003857323237578, - 0.1736647163622968, - 0.14762725530928242, - 0.11993532138287469, - 0.2410529207358764, - 0.08048697893854188, - 0.15330832008768233, - 0.17036361810799147, - 0.2947720894252494, - 0.29147199698384596, - 0.1953583783365111, - 0.19794658559927064, - 0.23826379780096893, - 0.12711832269704423, - 0.18746303250724075, - 0.2314990459967369, - 0.19231894583312942, - 0.24905452852122756, - 0.21636992698053437, - 0.12769709299421164, - 0.09309448640075445, - 0.18246797331892936, - 0.15950109887604538, - 0.10998606449241616, - 0.15009395654944294, - 0.3013852138872356, - 0.23981735099123244, - 0.16442748910602215, - 0.18566106586991174, - 0.2740780654007686, - 0.22177317688432813, - 0.02416861444798085, - 0.11710232370200596, - 0.2502012673298704, - 0.20814545011612748, - 0.13186251040207214, - 0.25700826746949257, - 0.16125024306143795, - 0.11967801090865907, - 0.24174522115281707, - 0.18990282295552455, - 0.10166394834677152, - 0.09995286491262238, - 0.20713374450301184, - 0.20251219586609495, - 0.21834372792686757, - 0.11685643234478431, - 0.03765650919823759, - 0.2648553285716715, - 0.2220650988011139, - 0.2629472983264285, - 0.275532457172384, - 0.1785447576407883, - 0.13908441374555747, - 0.26248615731982455, - 0.2804021211824284, - 0.04643636180191451, - 0.13092841192565102, - 0.20437460789048972, - 0.21029997453994026, - 0.29910862240051184, - 0.24240589592534756, - 0.235361299379993, - 0.1588516634293354, - 0.19385580344495987, - 0.1796904062312912, - 0.2610873441283979, - 0.2976571065267217, - 0.11605976188482744, - 0.17382973907332538, - 0.274746291046984, - 0.21129279075668717, - 0.24617027573796305, - 0.2685166025989095, - 0.208543228868503, - 0.06614930330956124, - 0.16439861690931443, - 0.12462699660316659, - 0.02979609644912206, - 0.19957814333315477, - 0.08922370558820598, - 0.12297251634098104, - 0.24081178381224874, - 0.22647513161051253, - 0.17300855994285474, - 0.10346935114409261, - 0.0672593847801836, - 0.26100363615216543, - 0.07884013146271683, - 0.22776925944549936, - 0.11363264285775493, - 0.2588904981271024, - 0.2171666472916359, - 0.25960152258072683, - 0.2656393059730312, - 0.22639617643854784, - 0.2320699409720359, - 0.19807291254091458, - 0.06791382738109082, - 0.2823656741158864, - 0.283090378610868, - 0.17472858578778488, - 0.2203900162733744, - 0.13070276498893635, - 0.06604929991638529, - 0.22838662982619343, - 0.13374059172933486, - 0.13362573227952362, - 0.0184595681054568, - 0.08194063534091625, - 0.2370859548005179, - 0.2422204036847598, - 0.29279140777577406, - 0.2005279982519961, - 0.2238973299710146, - 0.09038936153105827, - 0.2173319680831825, - 0.20281134945702697, - 0.27070543977586603, - 0.08655154829764067, - 0.24410248296170084, - 0.16190927039635564, - 0.27933281753537775, - 0.13036932709923735, - 0.2580953956401353, - 0.08087685247115903, - 0.27131969432368563, - 0.27832384498046175, - 0.29007502138527486, - 0.23498724326698783, - 0.3049817302312203, - 0.2819709294975654, - 0.16139851586374265, - 0.06181656119465449, - 0.20637638960771393, - 0.2982111017319344, - 0.21934918057612632, - 0.24701199753092842, - 0.18216961544445523, - 0.22902950305638534, - 0.177265194913707, - 0.2187669062533121, - 0.2776365731194596, - 0.26040886979906647, - 0.21401443462011083, - 0.13513963117519073, - 0.25114678363231424, - 0.2685212102496195, - 0.2583263732777794, - 0.055016581592611906, - 0.1725447498827684, - 0.14088176792061252, - 0.1003191875898981, - 0.10077403018953991, - 0.2567738842330446, - 0.12214135053568219, - 0.24728886370261363, - 0.2745499559244698, - 0.2573030792074793, - 0.2836779198166239, - 0.2891710316435786, - 0.16890319944500445, - 0.13039103422651602, - 0.29487036442222697, - 0.05274349940807365, - 0.2018716396475534, - 0.18433287176294808, - 0.18099467545126288, - 0.2661783275266855, - 0.016334802409633958, - 0.2742524500243591, - 0.29538179213155585, - 0.24349224638544295, - 0.27969486400278654, - 0.14176229184156972, - 0.1950425788829083, - 0.23237291694366824, - 0.20480818526844596, - 0.30235385427651784, - 0.27416255412717894, - 0.05199431454453911, - 0.2354290617243491, - 0.18790697532770836, - 0.11476208537673648, - 0.28640719683620075, - 0.1367926165755038, - 0.18833071114620836, - 0.18984523685565577, - 0.2941005201285737, - 0.10715621486783708, - 0.2566570911750187, - 0.2690629296287679, - 0.1442785189512151, - 0.21420939498693742, - 0.26702171299369437, - 0.1816103535116336, - 0.30392351311798343, - 0.012008301374457802, - 0.2025681306151914, - 0.22388717125387497, - 0.10021052550999346, - 0.24875976880207906, - 0.07731622621937007, - 0.2585698770745073, - 0.07715228821272288, - 0.1255358053833815, - 0.2372999967013207, - 0.24385676155225441, - 0.24479526605294433, - 0.21721695724386153, - 0.17421719964176682, - 0.17776746267447824, - 0.22414256358110005, - 0.26134831342051734, - 0.2053879824607158, - 0.24589021565841324, - 0.24485721197896837, - 0.27547442410531464, - 0.2105710537310177, - 0.28738988286086925, - 0.25576891124956264, - 0.20413646781122727, - 0.16630319956609274, - 0.19740284317233206, - 0.12727928605317682, - 0.21614722090865457, - 0.20288137628661976, - 0.1536475103703583, - 0.09227871303485642, - 0.2850676907499034, - 0.14334898049098926, - 0.23464159670731466, - 0.2318292536423547, - 0.19026319174178438, - 0.08779540207780262, - 0.2056058591066326, - 0.16203000052452513, - 0.22771432423546312, - 0.10538717363612685, - 0.16915005797850735, - 0.2642998468630977, - 0.19436174150956556, - 0.3025278551270929, - 0.1588447577591593, - 0.1601599299078283, - 0.12178032840670039, - 0.19771913262368163, - 0.12374572616967032, - 0.29910628794220195, - 0.2375496231313557, - 0.20031219300549769, - 0.163878588463951, - 0.14218527280760224, - 0.21519270495289444, - 0.1954516538988161, - 0.12173204259414025, - 0.17776074396531027, - 0.2356024463781822, - 0.2729881752559688, - 0.1519699566504658, - 0.22999916122464484, - 0.13417856882084012, - 0.2709434410212926, - 0.17860477940292005, - 0.24159006075658543, - 0.19178770379075952, - 0.16563574362553687, - 0.2652002435109653, - 0.1388834679980543, - 0.20843782903768407, - 0.20476467452683778, - 0.036656303816139324, - 0.2681810673356862, - 0.25420536038226904, - 0.12989240254044376, - 0.20737967370896218, - 0.1558772424648749, - 0.15760308665673015, - 0.20156012005456794, - 0.19031199224181491, - 0.14828198657380137, - 0.05238399322938532, - 0.1277124494620755, - 0.2554561817345248, - 0.16250397873402722, - 0.19134732839981441, - 0.2514481247317301, - 0.17386135174486056, - 0.15567836066842214, - 0.14820499160562592, - 0.14308194393738335, - 0.3005349672641853, - 0.09078950483880104, - 0.20664303883342483, - 0.18499172363828065, - 0.1339520378610635, - 0.1927000278627178, - 0.23946837447084032, - 0.2795833186265405, - 0.23784397118284445, - 0.11616349155592745, - 0.1874725512392416, - 0.2310145549407882, - 0.2444824917083357, - 0.11257305063305197, - 0.25755802572387654, - 0.2397776827908704, - 0.18217058176047132, - 0.22868785672337802, - 0.1856878307260963, - 0.2292036642875071, - 0.1283813161457038, - 0.04082766651666613, - 0.26711611049282125, - 0.055269784270910706, - 0.17888682776342035, - 0.16530454707862027, - 0.1425899127710042, - 0.2763064904261103, - 0.293412160367548, - 0.13832558377390955, - 0.1705020511467774, - 0.224702305645966, - 0.2627441741151187, - 0.06531149197824027, - 0.2847136553198675, - 0.2544078937137236, - 0.27534638581084925, - 0.19469232211580526, - 0.21007668567881874, - 0.08623358775519867, - 0.17008301791387495, - 0.12295392847099677, - 0.10301706213983775, - 0.287707205083104, - 0.2621336121494923, - 0.06390911101364603, - 0.16715425557785718, - 0.24962757416083292, - 0.2614845987322003, - 0.24838874249827145, - 0.10795732895899686, - 0.14316288857550022, - 0.12517540777975722, - 0.14177213508899936, - 0.1336418555470747, - 0.25926359668505217, - 0.15280609532045542, - 0.2837219598413001, - 0.2022535771967488, - 0.14073046753938495, - 0.10315536927049739, - 0.08487283626867652, - 0.2287812054129356, - 0.28729174372868094, - 0.2881566720958147, - 0.06736013543181463, - 0.29335074062594635, - 0.29343219615419713, - 0.18100959585825271, - 0.22218082015977159, - 0.13340588071273343, - 0.04920459585669149, - 0.29643324492553347, - 0.13664576361246805, - 0.20316243754604724, - 0.18185658769058288, - 0.18614881409705386, - 0.07913530140431475, - 0.21312447579698998, - 0.1961131028299737, - 0.16648750717299596, - 0.11431917627577129, - 0.2435297533186739, - 0.2622610221759784, - 0.2903478449693954, - 0.14305261167393657, - 0.2953018255507666, - 0.2808168367407713, - 0.2898246301863183, - 0.21070965043905007, - 0.14378223913606555, - 0.09371127147900166, - 0.293910450040184, - 0.18688706577396355, - 0.1767593407801962, - 0.23613599724691467, - 0.22613498407181454, - 0.031183156076459786, - 0.019960119878058877, - 0.080265103050794, - 0.13382228220783843, - 0.2540734407854029, - 0.23347425861275375, - 0.0902884856269588, - 0.2571213162679318, - 0.07606441485902421, - 0.08794090024671052, - 0.23348267648157395, - 0.14509661445421726, - 0.1298564055213083, - 0.10825013052457184, - 0.12023440567038204, - 0.2630864230161384, - 0.22389591214187332, - 0.22569243345746373, - 0.10908934327074375, - 0.29139825811787945, - 0.09445006117231801, - 0.08995008978762548, - 0.1611749345882324, - 0.10516221995861852, - 0.1979243711141986, - 0.10118425436566512, - 0.19759668526382407, - 0.29502874463026274, - 0.20985562797632334, - 0.22252202067974053, - 0.20697812589219106, - 0.25637551642370154, - 0.1591133899981291, - 0.28411395447897114, - 0.1328310577453367, - 0.2821939602697079, - 0.282615442405364, - 0.1418873404430667, - 0.2700559623379181, - 0.23055310905272852, - 0.2606099331187619, - 0.30103853902562866, - 0.1785623275343553, - 0.06507341572373264, - 0.20164668210990505, - 0.13418989170895448, - 0.25907380178986533, - 0.18439588003119045, - 0.18265637270605992, - 0.154906220811531, - 0.22632052457566867, - 0.0455506630798691, - 0.15963099540013836, - 0.19200494249788022, - 0.13044880671092055, - 0.22117429571054184, - 0.21456234159610277, - 0.20745337814180423, - 0.10385092307387461, - 0.18091141527664809, - 0.21762158817219776, - 0.055509229721254154, - 0.2915204631827151, - 0.059888588864284296, - 0.17659909347841604, - 0.273362094314917, - 0.24794715591560818, - 0.29734003986252316, - 0.1717661823253763, - 0.24730832550016113, - 0.25444497694945645, - 0.13563557563164505, - 0.11151950197260675, - 0.2778292657406465, - 0.2812211035709156, - 0.12018232832973687, - 0.0563570057544671, - 0.2381779714170544, - 0.13986062000927832, - 0.1479526666184142, - 0.24627067779368503, - 0.12656283146321787, - 0.08501668333041651, - 0.14722417694805293, - 0.2971110390189072, - 0.0631257052095643, - 0.29431552615401996, - 0.14645906445638082, - 0.2861266153368352, - 0.04609854885530248, - 0.23250440924192436, - 0.232364091389313, - 0.1843605918533857, - 0.20276865934116683, - 0.2794127819774682, - 0.19127039430471135, - 0.28452415652611385, - 0.023596219862323933, - 0.2775271308596862, - 0.14921637109696018, - 0.1542218318332079, - 0.1989611110515247, - 0.252548692484411, - 0.13069489995596847, - 0.2199940105954661, - 0.2633284389192036, - 0.2476724225807944, - 0.24918078325758383, - 0.16218962525748168, - 0.025758172492450465, - 0.2091891826231027, - 0.15031403958552644, - 0.20479750626493318, - 0.1715813266887942, - 0.24791146469118602, - 0.21210684091208637, - 0.29470798232146506, - 0.1282122677700438, - 0.2374978795835429, - 0.29284614805530174, - 0.22964352359384996, - 0.27449187726496066, - 0.1639097843790071, - 0.2511480610000017, - 0.22481194627713705, - 0.1667603261703727, - 0.07318932029888235, - 0.29781764631589086, - 0.05369321023973304, - 0.17590929421313448, - 0.25509030192055054, - 0.24539084117893686, - 0.06584698561389246, - 0.13197143024443064, - 0.10558199970836467, - 0.23899327684726196, - 0.2352576178746611, - 0.2296101833583848, - 0.17103140156231772, - 0.1339105132878214, - 0.10811459598674457, - 0.29092926672277913, - 0.26325556237012554, - 0.2816606172865995, - 0.2705793155007007, - 0.2880764525969483, - 0.24050527776990946, - 0.16233943638295975, - 0.23212910048423835, - 0.24090486591755844, - 0.28668215416686665, - 0.26491401579873164, - 0.2431573582946893, - 0.26250986704892, - 0.2582271005282511, - 0.13878817712136887, - 0.2182458048398721, - 0.132874794634922, - 0.25914232024903533, - 0.1484869804260936, - 0.2603180418951686, - 0.06855331058162868, - 0.16074255955329336, - 0.2751507516468864, - 0.23920510598593894, - 0.1516342652523346, - 0.1777877619577412, - 0.25260389636773534, - 0.12667209810608107, - 0.2596965517177458, - 0.2892794229347164, - 0.2815829566304334, - 0.1698337624049068, - 0.20136098331182378, - 0.18272976599639332, - 0.14298554849897183, - 0.23463861449899898, - 0.2797126745947251, - 0.0778069076231206, - 0.20030562010289835, - 0.2229613366680784, - 0.1901927364305741, - 0.2191582006636226, - 0.13906313198720194, - 0.23212312296787854, - 0.10661142365115153, - 0.07027261581820313, - 0.1034511524656586, - 0.23361019821305898, - 0.15096732713365552, - 0.1711586752938495, - 0.22507603642325275, - 0.23480828354711053, - 0.15107905845055888, - 0.25155666227211665, - 0.2228843197088964, - 0.19524712216961643, - 0.24395942941891732, - 0.27817169952609055, - 0.11929906261604471, - 0.08381607486497886, - 0.18686387308397204, - 0.20999527443255434, - 0.2570698567367582, - 0.058901103615292535, - 0.2769591414548384, - 0.27598310469673965, - 0.2821505565843805, - 0.28988528255097973, - 0.05150051976118358, - 0.15917999577585787, - 0.25845358187973827, - 0.27567299678000473, - 0.22712024034889114, - 0.276056003426197, - 0.08640450269500653, - 0.02646427282611677, - 0.30289304276107915, - 0.14952170278655394, - 0.16084149250573554, - 0.2622273058587041, - 0.09832097707040319, - 0.10535687166608367, - 0.12691995350217322, - 0.2035466847757874, - 0.18202658696236074, - 0.07446019805892079, - 0.2656465484535515, - 0.2711285055626988, - 0.22482925553118643, - 0.25398286523008856, - 0.16646727790097074, - 0.24563383616873244, - 0.2261751857684485, - 0.26640574273520945, - 0.2631150815241893, - 0.2325710311881632, - 0.1681044757631614, - 0.11711730124727035, - 0.07966142075152963, - 0.2191049571217024, - 0.2902400178693884, - 0.10644830712406292, - 0.2734186652020395, - 0.05197372660595629, - 0.2948437546327784, - 0.0950447683957894, - 0.1819747189040945, - 0.29067807629121567, - 0.2738071502300164, - 0.1027402586162576, - 0.22979926786649296, - 0.2581198399241554, - 0.1935230404257859, - 0.26171016927876856, - 0.2857504996355755, - 0.1491065075023348, - 0.13227002287531273, - 0.1406349485702548, - 0.18161239415688687, - 0.2739526363397502, - 0.28852227016697357, - 0.15061969784929008, - 0.08869769612624691, - 0.08920488338294533, - 0.21496296212623742, - 0.1589270944718574, - 0.09429671067632348, - 0.12610326437934152, - 0.18852826820984375, - 0.13896682794340937, - 0.13559429584529026, - 0.17840671626330562, - 0.2118762248199594, - 0.15176296059884758, - 0.17496609910952976, - 0.27723091089520785, - 0.22873123430149936, - 0.23247948518827175, - 0.2954303951287984, - 0.10067455655193522, - 0.10484096443118701, - 0.17388538638057435, - 0.2164255964570831, - 0.11220858341425656, - 0.22913393407062316, - 0.08310746487784026, - 0.29005203751767944, - 0.19648120331757826, - 0.2750156403137095, - 0.13428214213617715, - 0.25915318315472013, - 0.29514821127774976, - 0.2156651370866097, - 0.21571405610106476, - 0.09541439104492301, - 0.14324857911909925, - 0.17862493999369725, - 0.24441387018288055, - 0.13300505548491182, - 0.28652791410040623, - 0.2901024908284707, - 0.26513000154928634, - 0.27032952967988066, - 0.13607242395644384, - 0.27328699895226916, - 0.24476462985024153, - 0.2221337734487119, - 0.19988996539019074, - 0.1375661815416032, - 0.2047169478798668, - 0.16593681461401125, - 0.26036623592703373, - 0.03391959733533532, - 0.15368185608735727, - 0.20555870907446236, - 0.2562585189852513, - 0.26358082353943524, - 0.3053053033175505, - 0.24020758796209857, - 0.119669491821398, - 0.0939473443124866, - 0.22632025528861616, - 0.23864922916008616, - 0.10675002407667013, - 0.26757712390709204, - 0.2888246077255077 + 0.037390354701688756, + 0.1366727257673293, + 0.01896497711355174, + 0.1781084082181187, + 0.16583431190340636, + 0.16933992352720612, + 0.02721398308320946, + 0.05444590031344, + 0.1602076965090202, + 0.028660090870436354, + 0.1431557751074098, + 0.17781852725840952, + 0.03915164588910641, + 0.039346890648079516, + 0.07420562653595361, + 0.2690757579602086, + 0.22420389550455166, + 0.14265936138123578, + 0.1012185970580372, + 0.08046826193309256, + 0.013757350834253623, + 0.26583073666915924, + 0.14896841524152138, + 0.025169403311690135, + 0.29616796169523407, + 0.1161562210830151, + 0.07577931807491205, + 0.1186321934808284, + 0.13097497941091385, + 0.04538348401387904, + 0.12105646828489361, + 0.15825600023159617, + 0.16806005874813063, + 0.11434010703653359, + 0.07562044835890457, + 0.1292573679517499, + 0.0720257151671472, + 0.06685533169077722, + 0.18107277376513067, + 0.08689201478802383, + 0.22711803350352475, + 0.21400770814789916, + 0.09394683587270067, + 0.24699644943865698, + 0.05217024078456527, + 0.008168181581510694, + 0.12458107120475687, + 0.040131074724923166, + 0.09215418951150434, + 0.037076436397982956, + 0.23986591318152484, + 0.24834936397403087, + 0.07112240356146864, + 0.14756377597295253, + 0.13906460325256811, + 0.28183437612563766, + 0.06445770669491747, + 0.07929029014512225, + 0.18691920750910693, + 0.29047566635698585, + 0.06977353425954941, + 0.16985473722980285, + 0.11927894459182405, + 0.27554083471493135, + 0.2638704219191374, + 0.037698611273599074, + 0.08765672469307195, + 0.2551184026579383, + 0.04479248715799298, + 0.18833584946963758, + 0.05365328777366469, + 0.19010394082986073, + 0.17057472327614367, + 0.19413141789467478, + 0.012314385430265253, + 0.08976455885413014, + 0.25802764946762025, + 0.05217105920451346, + 0.10956852203854534, + 0.1829343883492156, + 0.15670689339315882, + 0.22449430898170175, + 0.05516095102663021, + 0.06761287286416509, + 0.09657006525640585, + 0.08201488338606042, + 0.21219708397847553, + 0.17182451111762792, + 0.22730980335481715, + 0.05179461275531549, + 0.06417155122782495, + 0.18632749593189948, + 0.14308697032718945, + 0.24563238948541416, + 0.30632640058443444, + 0.27809744271368386, + 0.09128200782344359, + 0.16947201717043245, + 0.14390543981104117, + 0.2812818281430726, + 0.2269864984466092, + 0.1576547927858872, + 0.1521525777582648, + 0.017345185505449626, + 0.014544298545731355, + 0.10100091554766766, + 0.12494558936862724, + 0.270705463474896, + 0.3114283085351552, + 0.14342124107828644, + 0.10867509021543283, + 0.2505549616315266, + 0.11979220445408388, + 0.1183436601614714, + 0.10597843646702096, + 0.28306519741260566, + 0.2025726666874207, + 0.26778050365271927, + 0.284737364413629, + 0.1848205640835622, + 0.28209034579135284, + 0.24076095811533585, + 0.07404124130587243, + 0.06859982320067719, + 0.05476439818438498, + 0.061984750961177296, + 0.09249907472740998, + 0.1582724038459138, + 0.2802185940450926, + 0.2310934193419602, + 0.0169486819283101, + 0.18889388320254208, + 0.04233677574523349, + 0.16291137991901686, + 0.08991673199695902, + 0.22851017728378395, + 0.03707762426888005, + 0.2477034868157516, + 0.31012170968338243, + 0.057547651381646386, + 0.06910938789937934, + 0.08943576062955265, + 0.10885126797690561, + 0.25989295132635337, + 0.06175157078637069, + 0.14466367160807347, + 0.012001254143065963, + 0.13697017256153382, + 0.1515447564164071, + 0.10354253440595829, + 0.13263016217843196, + 0.08339730322331182, + 0.092876941480302, + 0.0667980644784893, + 0.14922034940866544, + 0.12316702833971015, + 0.18739293749275732, + 0.14592582521223602, + 0.050402774792625026, + 0.2456764208073022, + 0.1464079400011995, + 0.17453892347876118, + 0.12115653843590997, + 0.2944426349386998, + 0.16992961015625008, + 0.06456888508329289, + 0.0889149448277325, + 0.06513967495625926, + 0.15733379676448592, + 0.15727456303035708, + 0.30255454591089376, + 0.022119538076550805, + 0.21024649906352574, + 0.15702855769858656, + 0.2531143263378646, + 0.04639587742158651, + 0.2868116519788101, + 0.28326204623095724, + 0.12050972760432808, + 0.26998529634942914, + 0.07311635191789931, + 0.1389173608322929, + 0.07576590116292836, + 0.2870659743909647, + 0.26439731398829286, + 0.28875167354843684, + 0.3119664191263936, + 0.04119013897407925, + 0.08774845705901865, + 0.13905230299111973, + 0.11585984592554271, + 0.24307520088506723, + 0.09362553170901208, + 0.25813285477762604, + 0.05542728024470627, + 0.1800892950396037, + 0.15718593904707162, + 0.14186427606694121, + 0.06407438043952352, + 0.2850908262332049, + 0.057155910792663064, + 0.22364675306050086, + 0.25620892266442946, + 0.06308374281672613, + 0.12245583695358699, + 0.2880770221527392, + 0.2539065582793193, + 0.23303860678855118, + 0.1860188233589474, + 0.15943830545543375, + 0.005612765836499478, + 0.09179254059500014, + 0.01989433534179809, + 0.21311567805774448, + 0.055084239263074285, + 0.06010704432208926, + 0.02125308128211427, + 0.19793964010282528, + 0.22669921297966836, + 0.16764449049056923, + 0.28636423995182014, + 0.16406179410012134, + 0.014417644866165669, + 0.29602470943556825, + 0.25736284318087577, + 0.2865546940614866, + 0.07241299840703161, + 0.18730160195824005, + 0.0983520098814089, + 0.27978405010478263, + 0.2363057870928036, + 0.028860436684587484, + 0.10893165769270723, + 0.12529520863588933, + 0.14285574814434635, + 0.17001103776622137, + 0.22909293443476303, + 0.16871481395459045, + 0.2844961529074517, + 0.14901140559947154, + 0.23952427287553713, + 0.10871315480648969, + 0.0835895452745341, + 0.1896080684997517, + 0.06289381063305763, + 0.28928643231810863, + 0.2775396024280474, + 0.06164220706332981, + 0.24104581553633497, + 0.040372109076121314, + 0.02338741139462028, + 0.02765464673872183, + 0.20067557682549572, + 0.07203073969847852, + 0.2722556655896279, + 0.2386291200689921, + 0.0869354514994288, + 0.1839993920185191, + 0.09629810136338722, + 0.19172187335675786, + 0.2297839260207359, + 0.1625634979567364, + 0.18363401437436785, + 0.19371720281284166, + 0.0624395655073948, + 0.056753070491058544, + 0.1484064221991734, + 0.3009468043738178, + 0.05472529333407213, + 0.010026456958008705, + 0.0644629073869422, + 0.28046106060444465, + 0.018937056813718593, + 0.15544510176434365, + 0.07217019476015314, + 0.13539142919109118, + 0.21379340440899824, + 0.1702622426575686, + 0.07147903910919663, + 0.12957217886184944, + 0.1666247953919825, + 0.05655184883643386, + 0.1900726483952778, + 0.12080857573162945, + 0.09663097500080756, + 0.1303349496256968, + 0.16424053652652132, + 0.157680780995639, + 0.07515297882560547, + 0.13858133406497183, + 0.26091977465432203, + 0.05801573806927941, + 0.31061437304955086, + 0.25874175785606374, + 0.11362959876821907, + 0.09281011285718187, + 0.3043812325840951, + 0.044370753140443, + 0.08476744239667537, + 0.2284746189179548, + 0.07039873649563973, + 0.16121212205431862, + 0.046546690121115016, + 0.2603353252277492, + 0.19952494711557345, + 0.08233339581767601, + 0.0666618708980124, + 0.04313051508780929, + 0.18315322973049025, + 0.038290413207342236, + 0.048529579826456816, + 0.25748117428559275, + 0.18432789731316926, + 0.1911195336218904, + 0.10312961438658656, + 0.10419684836845533, + 6.878943549733938E-4, + 0.12322319750640644, + 0.2787145269695932, + 0.14229223541554395, + 0.17142058960668216, + 0.28296360109941887, + 0.16028406803518444, + 0.2016589093548264, + 0.2185691404342069, + 0.21084122903730795, + 0.1739201014596444, + 0.30147535753121324, + 0.2361605186520935, + 0.23746404701726562, + 0.08041384029913029, + 0.3024720605394624, + 0.25974926463819875, + 0.13385231688214982, + 0.041807958144447044, + 0.08489833429540121, + 0.013253252947006565, + 0.16875113266839784, + 0.20551383153739847, + 0.3210968478180208, + 0.12248068787012983, + 0.1315956241597149, + 0.2022432087521108, + 0.046903508483207235, + 0.040690274943260614, + 0.11249258812354665, + 0.1613150501833823, + 0.07910211348402024, + 0.21514768591471484, + 0.15063500062137872, + 0.011436482234230261, + 0.1476130941227302, + 0.23208529162531108, + 0.1553150548036827, + 0.0745752152857773, + 0.1966642395982448, + 0.1840122141381398, + 0.04533920537143628, + 0.07389786273648326, + 0.18855889835891676, + 0.19104706530370946, + 0.30498190504825706, + 0.09728517636791645, + 0.15119024987701946, + 0.03309797110313541, + 0.08885910256450315, + 0.06869225504132587, + 0.21435441791967105, + 0.012120884335118482, + 0.20474913318999347, + 0.20787077850251853, + 0.04233837339243749, + 0.2759725958184817, + 0.004456926909421235, + 0.19426428085785785, + 0.04474721682800546, + 0.3110527015779766, + 0.27274458005402247, + 0.23216848617416602, + 0.21520558494996245, + 0.26011048186606023, + 0.26574370051204005, + 0.028700361129410604, + 0.08024350039708135, + 0.2694621611520205, + 0.14105813674628528, + 0.04469650140464048, + 0.21764987725764517, + 0.029436226254445592, + 0.120830017987284, + 0.07931813901190346, + 0.07979118985111497, + 0.21166153870076584, + 0.023075187168515615, + 0.10781665048627216, + 0.22225544936115135, + 0.12136633096687977, + 0.17734799839932436, + 0.1463504281804764, + 0.2618969140332372, + 0.29442152649365305, + 0.03875938207188401, + 0.1676285869951907, + 0.09123905895486757, + 0.31853783156471743, + 0.18198440871574612, + 0.2744447396481863, + 0.2763082265537312, + 0.12127467760006821, + 0.21405774743553818, + 0.26715231853199856, + 0.06473995107214833, + 0.09181133914753972, + 0.0192827321450764, + 0.2647432864726643, + 0.07539691689110647, + 0.2511019957716314, + 0.26420356427854524, + 0.164559178331794, + 0.25936198784519343, + 0.006008251069719346, + 0.09269213139446777, + 0.19363400976746423, + 0.08638592714661604, + 0.06074287201631729, + 0.13462113103004572, + 0.08673910854234358, + 0.009046009485896078, + 0.21172368958668, + 0.057168652829430976, + 0.21962709032565159, + 0.1124677754150115, + 0.08806798087217999, + 0.2418120996898827, + 0.1715148966319566, + 0.25347948992695046, + 0.11766007194844899, + 0.02478503668489332, + 0.29598321675642136, + 0.009777848409478946, + 0.23262637853128162, + 0.3154474305945269, + 0.2937866108722873, + 0.040335761348141264, + 0.0709138453449375, + 0.16320488889905005, + 0.1681089063368948, + 0.014710112394317153, + 0.08124140152056424, + 0.17570488670733933, + 0.2852231701145934, + 0.2520457485344845, + 0.05506251815314024, + 0.2566515252178652, + 0.23849399931058116, + 0.019914527296732147, + 0.089539080460643, + 0.0558520376985593, + 0.030893194148677375, + 0.12924650971932397, + 0.2766188911657455, + 0.22110134259749434, + 0.302340310722322, + 0.051460409931508265, + 0.23491416158881376, + 0.034643266708189915, + 0.28961036156722625, + 0.010734157141604327, + 0.16554292842982024, + 0.08098179581329118, + 0.29083340530123875, + 0.15024859303253238, + 0.2679770199096094, + 0.04754760685291781, + 0.01064231643640605, + 0.10855132648097973, + 0.2533969570348023, + 0.07015424528401548, + 0.09535422381671287, + 0.1855028467264692, + 0.029817915975498967, + 0.09368131935008177, + 0.024384268506193713, + 0.04736271612961317, + 0.019603246402633508, + 0.19811870503501885, + 0.158271003756756, + 0.12478639830441199, + 0.2704305090941256, + 0.11701252991786915, + 0.25686102618225276, + 0.0023586436905214322, + 0.26448799106442866, + 0.016422722459717938, + 0.005609572356114014, + 0.20024024176367375, + 0.11972706099973023, + 0.09106126485347386, + 0.30782351461856594, + 0.2868889734975145, + 0.1269794225807527, + 0.15013655510807894, + 0.058656807757214297, + 0.14032338269660424, + 0.07928016756189524, + 0.21225978011992405, + 0.015484619539704378, + 0.1899487436889696, + 0.2166419774172967, + 0.02262437549578951, + 0.2340424501723673, + 0.21136316163296368, + 0.3129493083802818, + 0.09553566562082266, + 0.026949454135069967, + 0.12030728113784753, + 0.20388895714822544, + 0.2009772071396901, + 0.08010477694465919, + 0.0035200372135009584, + 0.20069179850595123, + 0.14648921525202055, + 0.18137089335779089, + 0.043505817800930845, + 0.26162206966635493, + 0.14537681724240445, + 0.13156605075173358, + 0.2643622304968965, + 0.013033657203694277, + 0.07908781720564384, + 0.19366916164598175, + 0.03684012722714205, + 0.06998980710526537, + 0.10429634591967274, + 0.2354044589857911, + 0.30268837378421404, + 0.09374320595923501, + 0.17140679460120242, + 0.04338670932309578, + 0.13634656661281214, + 0.23600736107491993, + 0.013105374842983476, + 0.24021188739611585, + 0.10651700550941787, + 0.1909502201831947, + 0.15670781168429831, + 0.13962122979951913, + 0.30085441009880165, + 0.005423067916975437, + 0.27231761973768454, + 0.0033823489159892574, + 0.21137642206242935, + 0.23931811828320368, + 0.14741121481615402, + 0.26870982924821224, + 0.24845493229508528, + 0.23476192062562748, + 0.0411347002683363, + 0.11236347702980654, + 0.09744748096826493, + 0.28486876688006324, + 0.3185188875440203, + 0.027663775250103925, + 0.08056095844183303, + 0.2083980329167701, + 0.27747846285374794, + 0.0031100333192370447, + 0.22785963756046101, + 0.10467761623704319, + 0.25209534587629856, + 0.2605766912833886, + 0.1572995759985723, + 0.21748253975764475, + 0.09479836891263184, + 0.22668035725810398, + 0.15060141140223476, + 0.105767916509277, + 0.05629281077575179, + 0.07470796504524699, + 0.03456610436440543, + 0.16513173859484093, + 0.19503647605858754, + 0.26051437806442557, + 0.12679856102028497, + 0.16949203856384631, + 0.03394241160125979, + 0.2676731671495032, + 0.01739830172896302, + 0.18320988089091905, + 0.09764042538192724, + 0.073512739531846, + 0.1725737524133686, + 0.012865675720960935, + 0.07225052258372322, + 0.06286681180325605, + 0.08033670070526552, + 0.13244158567583422, + 0.012252387136824083, + 0.10346032428566239, + 0.043038880564915796, + 0.1361233920771905, + 0.22881023996425015, + 0.26635725702355023, + 0.019347530608091284, + 0.26812454691751186, + 0.13570245918156087, + 0.1133396119701106, + 0.11789619111881314, + 0.06663679489376075, + 0.08440278484694276, + 0.09279429971658641, + 0.16528907053762348, + 0.3231263163534197, + 0.21800434344081593, + 0.22242703652461868, + 0.13525083432630436, + 0.03573839882491076, + 0.08541329358762863, + 0.056326741536113924, + 0.027639223098813774, + 0.26924736931485127, + 0.15026053580192525, + 0.23029486062051002, + 0.29945462985722116, + 0.07981539295001433, + 0.287121812376841, + 0.18202050502159275, + 0.09524061867733055, + 0.01914375639863388, + 0.09407103001237933, + 0.03234485373808768, + 0.2668764815132888, + 0.13747345648321443, + 0.2779085313814282, + 0.12710704530143482, + 0.07906658552485675, + 0.08844285860756744, + 0.10749933394601573, + 0.26689765374270547, + 0.1675608185597545, + 0.18722762074296723, + 0.09198935171929194, + 0.1838821797194548, + 0.04679616027245693, + 0.27680801388721993, + 0.27253498398588555, + 0.019939435241194445, + 0.2723021064255231, + 0.012986314945504784, + 0.03423399993816921, + 0.10507421615825663, + 0.06135476100208841, + 0.2967114691273634, + 0.08406072822411448, + 0.12617259405056966, + 0.26419852850535996, + 0.126856502887811, + 0.2306887647348236, + 0.17731705917555202, + 0.06105191554295843, + 0.2277201263285725, + 0.0561585105693956, + 0.13531575927036743, + 0.12039016434287007, + 0.06869435261078545, + 0.006086044039618263, + 0.06173571550202768, + 0.09610810408484621, + 0.14508766042973284, + 0.17585339003258263, + 0.2782861605489981, + 0.17485411545094068, + 0.04883045539592729, + 0.08205601354734847, + 0.25400873204979013, + 0.2959046236440269, + 0.08196495168675544, + 0.26099319753419614, + 0.08463977524779298, + 0.013871130048640105, + 0.1834092440400771, + 0.12326338342377981, + 0.1829769184645282, + 0.020169800760894117, + 0.15691830436594748, + 0.07886715064024798, + 0.07791058623029719, + 0.12129863664718427, + 0.2004581687863168, + 0.24185176205079909, + 0.09351776159353177, + 0.3229768232659855, + 0.17847667959737284, + 0.08913978384852905, + 0.038040105773807384, + 0.17554403246475386, + 0.11724895594216041, + 0.27849378216611725, + 0.2896415303263999, + 0.0951583828337081, + 0.04748764565268596, + 0.12474206027163941, + 0.06954385310404156, + 0.2469482496152361, + 0.26520010450703524, + 0.24506107772687388, + 0.25945926116209367, + 0.004890414369085221, + 0.032940157910355525, + 0.2874382233206009, + 0.18324318774150383, + 0.016042625037773962, + 0.08522521406045316, + 0.2389796695871749, + 0.1938644654305161, + 0.16106900749549194, + 0.18084468491487313, + 0.2774268577484394, + 0.13080647464167233, + 0.17881350837701568, + 0.32379410489038923, + 0.007237835984648147, + 0.034337520218445876, + 0.04290847111918474, + 0.017110315288516177, + 0.07844883984898211, + 0.24903993298747015, + 0.2594396016059051, + 0.14317215351216594, + 0.07506261911543302, + 0.06025049671527401, + 0.2784286194684102, + 0.1290449883087207, + 0.08324548507718933, + 0.1707445472316085, + 0.1295538593625649, + 0.17264801211067723, + 0.133557766647656, + 0.1415497974360007, + 0.18281612908209155, + 0.04325905071974633, + 0.11448890618186688, + 0.21248169356145985, + 0.05355266064914738, + 0.13030425108449722, + 0.16500348924009037, + 0.26385193274457214, + 0.1739445518548748, + 0.15527203475376214, + 0.012154646021106831, + 0.07750740964988406, + 0.06316209321179309, + 0.15072565883813674, + 0.10411598530923609, + 0.18046183336908056, + 0.267603425060809, + 0.06683535294285128, + 0.019107885962069145, + 0.01601776460257786, + 0.1358544219910166, + 0.04098232269481165, + 0.020464348890613628, + 0.25956823118884215, + 0.16622165787512583, + 0.30063793153589113, + 0.2542268955010146, + 0.3007890934030086, + 0.28509168236947785, + 0.1388197976363875, + 0.19470406778880253, + 0.12132472606262523, + 0.2810737578761821, + 0.1216225308343109, + 0.027793264696759776, + 0.2563160405230134, + 0.2505947060677133, + 0.10048441531045549, + 0.049423313326498894, + 0.0471516363860733, + 0.05268865979734355, + 0.2667214655164066, + 0.20501946679508395, + 0.09594417385671644, + 0.11488599396482022, + 0.13051806886487202, + 0.16795343017691855, + 0.004326883478969674, + 0.16157046203946365, + 0.060056805543070975, + 0.07129861502966714, + 0.14912494552650482, + 0.07421921174179723, + 0.10060223247289947, + 0.034401856368640356, + 0.07406427456211762, + 0.17423470702502078, + 0.010542277752143059, + 0.0035375126511588825, + 0.038762201663979576, + 0.22699679721535912, + 0.23263855020702556, + 0.19036291527276383, + 0.11588941973261233, + 0.03622511552090539, + 0.16120270059219766, + 0.16098524808510414, + 0.021625978037522656, + 0.049848343454194144, + 0.14685978864019691, + 0.04950904556189122, + 0.2919583814543811, + 0.2043669709819495, + 0.13358822401346437, + 0.10026884225662416, + 0.21359739658010457, + 0.23800750056235867, + 0.08272889416443441, + 0.22280693929316528, + 0.2004373877416652, + 0.14544334606701378, + 0.156528115921887, + 0.1166957421861834, + 0.2291258326602174, + 0.007799713678795769, + 0.3084638862527371, + 0.08025049584428681, + 0.14650913568813173, + 0.060727140412687515, + 0.041538466386100745, + 0.10920759680140481, + 0.22933789872141436, + 0.0415273379527035, + 0.01744885381630706, + 0.19625860373643442, + 0.2779260752064068, + 0.19618732296151362, + 0.14584997292374496, + 0.29099705014720634, + 0.2573374242960751, + 0.172057767887375, + 0.12106736617213971, + 0.02950693398610937, + 0.2284182580257074, + 0.029918306393012673, + 0.05986473259650994, + 0.1795664753757983, + 0.05630619119841054, + 0.3010521480289277, + 0.015039133056528582, + 0.15856312637595152, + 0.06612254319126981, + 0.020238492521910074, + 0.19904421080836654, + 0.1252994880635412, + 0.17016207616194545, + 0.28247592937310895, + 0.08054480663904255, + 0.15811085309831913, + 0.052212597841361404, + 0.262153778590849, + 0.24778291010733003, + 0.14600981865512558, + 0.2566534772749161, + 0.0940165765646458, + 0.18984343463836348, + 0.09717602566891502, + 0.15221795928268111, + 0.0662600620022854, + 0.11026013195541869, + 0.09127234344828768, + 0.07992633333106991, + 0.07283550233421454, + 0.10422300391982267, + 0.28601084816390604, + 0.08045256574978886, + 0.07335577278352767, + 0.1919085156439959, + 0.03788400603864854, + 0.21494824108432684, + 0.015743866353177954, + 0.008791717632443418, + 0.2048432009288833, + 0.057971645168096116, + 0.2625079774826456, + 0.25390203293401936, + 0.21600677601543058, + 0.19628823710909335, + 0.07081838823624653, + 0.08920642194014844, + 0.1770145337307182, + 0.2508876229093182, + 0.0681762948469317, + 0.13433707599204547, + 0.3151470792496528, + 0.1623219160711135, + 0.12936503256036738, + 0.11725548595618106, + 0.18523183946160823, + 0.14185941129187218, + 0.23783745177732388, + 0.21352369706325927, + 0.0392600945029365, + 0.2582297016658002, + 0.12294091871724089, + 0.10827543764000323, + 0.2173859177250226, + 0.10726970783137078, + 0.22933708973509798, + 0.1087262562577601, + 0.3184782303183177, + 0.26698644063190613, + 0.10800483158431681, + 0.2159993088883378, + 0.1393302401886606, + 0.1289186187395799, + 0.06509896302083082, + 0.10814289503647917, + 0.2586969802865805, + 0.03346537596142192, + 0.12537238744982832, + 0.10524907260936987, + 0.011083585439828916, + 0.13124828651894482, + 0.2624242238397329, + 0.23439509676925116, + 0.18095193549927358, + 0.14808119542896703, + 0.12937268539495328, + 0.2916558766444828, + 0.23932732954907782, + 0.12494561856156963, + 0.21900016961344146, + 0.09341093963549822, + 0.040638738578767736, + 0.28536324838505, + 0.2520209791179764, + 0.18195446211934815, + 0.12817207641947959, + 0.21453983623362413, + 0.16116778455186168, + 0.17836902642597113, + 0.1974389551763164, + 0.08710079125401782, + 0.1966320421376524, + 0.01522886688801002, + 0.045703972435429605, + 0.21664262793482394, + 0.050295929118717095, + 0.1440920835564822, + 0.10817756649447448, + 0.21970221153666683, + 0.19201659317909225, + 0.03291772362165671, + 0.019267825002806993, + 0.10689858066191024, + 0.1267287832888889, + 0.0759280593840592, + 0.026805557615881583, + 0.07819148122493784, + 0.26893653826647645, + 0.05162611074851631, + 0.17015389584343613, + 0.28402248148912324, + 0.04278870253837794, + 0.3041911982339415, + 0.0388623177896374, + 0.13004006501375712, + 0.08327979322432652, + 0.18430970777046504, + 0.037825594400210036, + 0.039521229218840666, + 0.04082101979539533, + 0.018378206922577904, + 0.1169942201917526, + 0.20214261761502214, + 0.05012272391573885, + 0.04201861860453182, + 0.2851375202926841, + 0.05604793428521345, + 0.2589842824820623, + 0.024327177618824497, + 0.31676941957700777, + 0.2794655024634765, + 0.05038761871411391, + 0.28005770659753476, + 0.2664560455201984, + 0.2602583235829368, + 0.12264129634101152, + 0.04892579114113519, + 0.031254787822172184, + 0.27951694564759205, + 0.148657650534062, + 0.0836690143572187, + 0.16744429337007388, + 0.19873372370421816, + 0.2523132460838398, + 0.2215047113474611, + 0.23124189447140292, + 0.1687229832811503, + 0.2856976041791215, + 0.25940237728539683, + 0.12819946814829888, + 0.04583556939213675, + 0.23974527102844925, + 0.2186249503083089, + 0.049576143144602895, + 0.13657289875725867, + 0.24929882242209517, + 0.09670670145253522, + 0.2479487356718115, + 0.05775315585891035, + 0.12460053204184302, + 0.08685758888684036, + 0.2397362801837297, + 0.19903021135657115, + 0.01747644281352202, + 0.20111221329491413, + 0.14300360221748964, + 0.07428060243009309, + 0.2729794455259552, + 0.1469152276974097, + 0.18584885302312265, + 0.22967093436237768, + 0.21805284944288314, + 0.28292806931490877, + 0.30596481256637575, + 0.08288119891277287, + 0.014774765456531273, + 0.0706859612309871, + 0.2329566330752741, + 0.26207939040798145, + 0.00662190615605111, + 0.11134708770707465, + 0.023598791155653553, + 0.1115195839667207, + 0.03504901543255403, + 0.16407681469276936, + 0.03226181484938101, + 0.23344535223344234, + 0.10208079603196488, + 0.26189276632657726, + 0.11536918670512976, + 0.0200002818972866, + 0.2807433995613068, + 0.1389541934843479, + 0.2641622422440206, + 0.1520810367488046, + 0.27508723492010756, + 0.13187107937915585, + 0.08749828600369122, + 0.11186003502208638, + 0.16661066986630668, + 0.23634389645920112, + 0.14086786265152323, + 0.2083714388274246, + 0.2180017707330216, + 0.04579850969954948, + 0.08364570617793059, + 0.062437356410157734, + 0.13344229746672073, + 0.28728637143877417, + 0.21866126156585003, + 0.2730342695782791, + 0.1643550986852482, + 0.3012025548039374, + 0.13959548549813502, + 0.2462317393218925, + 0.06202812147528391, + 0.00770685105763856, + 0.0506688976198487, + 0.2467621788653706, + 0.08185700829887349, + 0.04030008239576575, + 0.09124855030270203, + 0.14220882671963028, + 0.1503224674188733, + 0.1069994466058465, + 0.06332713226078991, + 0.30392084978862693, + 0.25036512550627354, + 0.030683269721877262, + 0.24579364611252608, + 0.20914904417532296, + 0.022497026131098167, + 0.19353200112017188, + 0.08440594820212621, + 0.003140463124821306, + 0.25436297026482113, + 0.22274007651627412, + 0.2694128260558258, + 0.1743619415747088, + 0.08005243644737252, + 0.3138628665581115, + 0.14319588255777843, + 0.08894098559588758, + 0.10374042801303629, + 0.2454800742128148, + 0.2747945927200944, + 0.07901951971254817, + 0.046306823344341955, + 0.02018528187073139, + 0.2104919487152605, + 0.026986728323210474, + 0.17410678562141005, + 0.18454213560280797, + 0.14837566649175313, + 0.27780278564129807, + 0.047875234506425356, + 0.18441432441084663, + 0.3207033688657823, + 0.18575828488232943, + 0.03839228083927504, + 0.10238868944617271, + 0.011765314755276804, + 0.15660019328391708, + 0.19811483956399087, + 0.25765893902155584, + 0.2739017721127224, + 0.13566082199362672, + 0.2816721936136623, + 0.26783659045182523, + 0.0287143467798471, + 0.1954307361398289, + 0.1958667509459525, + 0.24738422785810926, + 0.05006035596981205, + 0.16034662455161405, + 0.09371554717668053, + 0.14100821274549177, + 0.09575061073001473, + 0.06798411945625837, + 0.13049400046004966, + 0.30862578667860424, + 0.03609402771514361, + 0.2739088144767002, + 0.04608329773353352, + 0.042686818946115486, + 0.05696473284565965, + 0.23540046123671418, + 0.25620089528768925, + 0.1251146583885655, + 0.28138855977057786, + 0.06832906789177152, + 0.15587644531210246, + 0.04420002778647306, + 0.14011005580195157, + 0.11150062415518378, + 0.1853113164827464, + 0.224108817587809, + 0.03643902581205899, + 0.30568952851067305, + 0.22795147245173356, + 0.05202322590303519, + 0.010913756560556244, + 0.056821152852864036, + 0.044096599064469895, + 0.11460831275441637, + 0.20865589262540757, + 0.2441443640592249, + 0.2917184108232406, + 0.10134730427410259, + 0.12294012933672238, + 0.028336363233584416, + 0.11389891087754633, + 0.08903428813930264, + 0.19788962566587623, + 0.13685866733599752, + 0.2836322579223263, + 0.18451422666568176, + 0.019713887961990625, + 0.0492656862155773, + 0.1974989594877588, + 0.1092608751464925, + 0.15633849585428752, + 0.1568875351958891, + 0.06262130810557232, + 0.259277594273429, + 0.31381541337436486, + 0.19921914049234735, + 0.10666797655012344, + 0.28539669388699285, + 0.31339679472890103, + 0.3227180433648511, + 0.19405117585231257, + 0.06433821031385688, + 0.16605644670533973, + 0.20920851765073004, + 0.1449468169402153, + 0.17392400541720945, + 0.32384239988251357, + 0.0956429739175776, + 0.26437579770931924, + 0.05281214970182415, + 0.13228756559424557, + 0.3045909282346713, + 0.015014971501927278, + 0.25238919941820215, + 0.043987964387830814, + 0.13335600993542876, + 0.10008466827397323, + 0.007904739308362944, + 0.10114749307426593, + 0.13195162732898996, + 0.06763855436029587, + 0.07759225247701726, + 0.018020655124385058, + 0.31742864129233594, + 0.05526713822640674, + 0.1510130097786693, + 0.14541969489563475, + 0.1762137783187799, + 0.06532682242724643, + 0.11620699032933128, + 0.19101502455853617, + 0.13608437074797217, + 0.20283034142969342, + 0.13416399243270588, + 0.037377534787980185, + 0.1511198623401761, + 0.2963593037021726, + 0.03142653787748108, + 0.30382684053423886, + 0.1856385015142021, + 0.26646829785685316, + 0.07055603455920727, + 0.24301388929022133, + 0.03528980908347865, + 0.06669309825028118, + 0.07377296086232232, + 0.05709374318815286, + 0.26258633372324464, + 0.0678048710899244, + 0.271148658765319, + 0.16706747972848499, + 0.10643443255943018, + 0.02202957077994246, + 0.0113133885760095, + 0.11522674313699383, + 0.2541742329614886, + 0.11644351714498472, + 0.26033820062379487, + 0.27844581901086757, + 0.21658854129371177, + 0.23476613879239483, + 0.07569674083299462, + 0.2869867299971129, + 0.08911024221206104, + 0.06992850593143003, + 0.22486169824682606, + 0.11002156634190706, + 0.17389914942220036, + 0.1392527169312095, + 0.18056943861981456, + 0.2809572418386304, + 0.14605301342802873, + 0.04548791090307977, + 0.2021732781447896, + 0.0523021515541227, + 0.19941762789191556, + 0.025839779825950066, + 0.02386151092723476, + 0.1501050610345071, + 0.2879576165760482, + 0.07455794052089793, + 0.248006061491653, + 0.061868513406987534, + 0.1092869792257687, + 0.2951190747414865, + 0.008723550723090539, + 0.15439138478670156, + 0.0992835102768211, + 0.20008144322773752, + 0.09089083951116504, + 0.279963295575963, + 0.2963345488002846, + 0.017474794029057494, + 0.23683912839976595, + 0.2710584538981511, + 0.3005735057463336, + 0.2166742082370282, + 0.08096114507004608, + 0.007588023758473338, + 0.3212959741510208, + 0.08859510373624124, + 0.280777678491844, + 0.2741575067406154, + 0.2983781979072928, + 0.010555147834683271, + 0.10811702887468938, + 0.15340761748755935, + 0.12250479248104106, + 0.051255065690903136, + 0.21772762949445246, + 0.15768951062974748, + 0.07956225453042765, + 0.31067929808310346, + 0.21922166773917337, + 0.0695963282251502, + 0.0841455954859209, + 0.27718917153390643, + 0.1693800673456462, + 0.10838554966930584, + 0.0599063911548958, + 0.21783918750461093, + 0.11602125661966613, + 0.1111735990284887, + 0.0687958363279993, + 0.18131278535409798, + 0.0854471697591065, + 0.0988464302712859, + 0.04827567519656401, + 0.01826297516498391, + 0.2878377996553523, + 0.10616558930540826, + 0.18678083542953783, + 0.3055312466400548, + 0.1463449081227671, + 0.05926409815507347, + 0.3034284976780731, + 0.13552928149987695, + 0.22304192849506949, + 0.16221400372960565, + 0.273441427246133, + 0.1357979625566973, + 0.00646267577288305, + 0.012129484959892918, + 0.17675650071680218, + 0.21437005716781274, + 0.2305842228467256, + 0.0663523644055097, + 0.02112321381779374, + 0.2609820699541133, + 0.21060651077049614, + 0.22524858511613594, + 0.08477631406355055, + 0.0965716027079768, + 0.0788654164413753, + 0.30608899681219837, + 0.0777512608528036, + 0.06493706781415459, + 0.08017014839730971, + 0.13131726151597276, + 0.02769776717849074, + 0.23378707147299327, + 0.28456001929053143, + 0.2254227164018312, + 0.18824362900618014, + 0.08414593352644317, + 0.09945465540984919, + 0.29254270888586525, + 0.26692605570841965, + 0.3088045231345376, + 0.09250412528079545, + 0.11231581257334611, + 0.01688287418140138, + 0.10147467842316955, + 0.10715737909053377, + 0.2765319863302336, + 0.18111240421901992, + 0.24951463758615733, + 0.11292260963870117, + 0.15201512900454797, + 0.23737134088688355, + 0.2970638562996334, + 0.24968784375014808, + 0.12410418667406663, + 0.21487280640812362, + 0.25538644957922757, + 0.15409271991135393, + 0.24210436625432633, + 0.3043173778497105, + 0.24165492426401422, + 0.21805570808419797, + 0.27062888910248106, + 0.1540902680073873, + 0.26991601894686895, + 0.12947799875508914, + 0.17195326933814917, + 0.06561877333306596, + 0.059269615686156844, + 0.25303161424138926, + 0.20962178436093082, + 0.14931304244578386, + 0.09821066872027019, + 0.10240629989147755, + 0.014636097446205826, + 0.1211995892572228, + 0.14967658972256082, + 0.005889870871037451, + 0.19242987110924686, + 0.2904426129665113, + 0.11509084526943135, + 0.13706749069642157, + 0.03111079020249485, + 0.09156328154272679, + 0.16415529063676126, + 0.31132294524331156, + 0.1804265875012563, + 0.2582354337649134, + 0.03371324249290835, + 0.15660788271687234, + 0.07992234115888792, + 0.24738464087583542, + 0.20591738681511718, + 0.22582331734652067, + 0.015466442866601038, + 0.19887910294775105, + 0.1753234696784616, + 0.21696948373693736, + 0.20284976960275855, + 0.1851084854272286, + 0.2750796965901694, + 0.11972241838755153, + 0.19050598344412892, + 0.06021696352049316, + 0.024510335110259008, + 0.24632712985603591, + 0.1982319601182395, + 0.03874633810096579, + 0.1137600058031298, + 0.15290282949132605, + 0.0932776261693346, + 0.2924899701652006, + 0.28163782857048236, + 0.18118411168227697, + 0.23932863145060324, + 0.28346416527548346, + 0.015953344732775883, + 0.17374314249137066, + 0.11426239302279419, + 0.054095528031851865, + 0.022716640323681977, + 0.18589243623035387, + 0.09779565221621747, + 0.19544153935354638, + 0.08557997990278364, + 0.1386625671460921, + 0.2500841891442262, + 0.05331359297217607, + 0.009057236929040223, + 0.1520278349867288, + 0.02400846186980959, + 0.08434213044779185, + 0.07674340918929816, + 0.2426367518068753, + 0.1293589303095615, + 0.2075985063239719, + 0.10016094024467055, + 0.03342162067948957, + 0.06145236704854368, + 0.07955283830568986, + 0.1838604873802597, + 0.17420031163609084, + 0.0077898336485594894, + 0.08600720545161422, + 0.22418192269554713, + 0.09655285101041451, + 0.22463071233783488, + 0.30748349879838255, + 0.20825880369501445, + 0.11040858862928488, + 0.13558903614397647, + 0.07787961544660307, + 0.09131169775117551, + 0.1770165071452904, + 0.09376555913309959, + 0.14389888090091796, + 0.09667064098752862, + 0.3032018077069834, + 0.16871869496798098, + 0.3059664068640524, + 0.18099989383793907, + 0.05656870140624004, + 0.01010638755204864, + 0.035177744277187346, + 0.14717959819031343, + 0.10816349795262703, + 0.07385481758196014, + 0.014966021045173741, + 0.16455606111860782, + 0.06583698559782059, + 0.2402366860993762, + 0.21448090954685106, + 0.08861067550622198, + 0.04929806088788683, + 0.19040756149100455, + 0.02785489945373499, + 0.24497428741093089, + 0.23294931460898807, + 0.10061409733993747, + 0.15847009377941346, + 0.2970371186895077, + 0.1994856021779031, + 0.2657552964953019, + 0.16256669313338418, + 0.22315059633690898, + 0.18726515308972522, + 0.23546338379452764, + 0.015711687370783222, + 0.059601107393011304, + 0.23217294659220325, + 0.0366684198115524, + 0.18679325483066672, + 0.25623174789464886, + 0.24941707264308385, + 0.0912236290102279, + 0.28426638729235276, + 0.07371286618607631, + 0.23360876800717506, + 0.11543470448915827, + 0.06956502387572198, + 0.04626202083674618, + 0.2839948609964122, + 0.10493211041836778, + 0.2914691672991703, + 0.2460689578044049, + 0.03102150930308726, + 0.18197579730914049, + 0.05469560169472085, + 0.06701108963342792, + 0.15492325921187095, + 0.0768432666020462, + 0.08279078448572888, + 0.17133247160136514, + 0.0575693157900172, + 0.014844788357957784, + 0.22322215602776202, + 0.27801198863682175, + 0.3026258876078206, + 0.07053793202359517, + 0.14121937337456608, + 0.018131536353108064, + 0.31834070932408776, + 0.050344439791055934, + 0.24361340699392656, + 0.1124074933523163, + 0.21643352041959932, + 0.29094999413077727, + 0.13268140157866387, + 0.2615018310188922, + 0.11897170517543319, + 0.11637076248939736, + 0.0635533822344316, + 0.2343820581266395, + 0.1241247876309141, + 0.2923159973001698, + 0.12468670560585222, + 0.23535607504638464, + 0.12652749410959716, + 0.19639128918510992, + 0.2415576613596178, + 0.09604707058376027, + 0.28750764180437866, + 0.24919591544474512, + 0.274778227098305, + 0.2374325225438439, + 0.04026561403649194, + 0.30851987252199525, + 0.2539326614123119, + 0.22240336708649686, + 0.06308085231933079, + 0.29691304824544335, + 0.012924245331227907, + 0.13357263345599762, + 0.09127224211132522, + 0.1266870065762547, + 0.012317956530270189, + 0.2959606000341796, + 0.10529457211718106, + 0.1633647269018937, + 0.07753950010356818, + 0.04601490267012351, + 0.16832088271177892, + 0.11306601044796183, + 0.035752176180569355, + 0.20018458853477847, + 0.10357599631968964, + 0.059203269755036585, + 0.09755562175052834, + 0.0118669969695027, + 0.20409757576300083, + 0.14146255089478577, + 0.09844307356305221, + 0.27664125197319683, + 0.14629027399203542, + 0.044800849945163077, + 0.10721413687798743, + 0.032917038774235054, + 0.30817117531304794, + 0.02342674750367045, + 0.0778049896806776, + 0.23090805824277394, + 0.27274279162753634, + 0.30725766535893934, + 0.04474933375044851, + 0.0975122217369741, + 0.20114385552779196, + 0.08075410891280169, + 0.1267805230428327, + 0.15253364523496202, + 0.2193612063668295, + 0.185147775583987, + 0.2579746378868788, + 0.17799175066867035, + 0.15924699072104195, + 0.1346365129110876, + 0.2662571154541173, + 0.18360844758799444, + 0.030271387514711895, + 0.09431224010006911, + 0.10629135881078418, + 0.09067163765497888, + 0.2698491886267719, + 0.1074381074175823, + 0.26901654100619005, + 0.13904602997913457, + 0.020635172590878284, + 0.0012030053737768732, + 0.035326718538929415, + 0.157088687295661, + 0.019194151007662474, + 0.15817675241928897, + 0.24161034311240853, + 0.05983804716684733, + 0.307518943991126, + 0.30764784573421106, + 0.12181377779438138, + 0.19499883093156298, + 0.27862342731985723, + 0.24148567228040838, + 0.014385438494390815, + 0.10830123123638587, + 0.25323160030991376, + 0.2578540647809833, + 0.12259439536663229, + 0.19480174425040497, + 0.2586908662186438, + 0.03217724113962828, + 0.06457665020495006, + 0.20197560472470436, + 0.276747976279015, + 0.22861803383411788, + 0.1278025596392696, + 0.10628811836460192, + 0.0596580711389709, + 0.19667168516840516, + 0.14475075567298434, + 0.1780651552662241, + 0.2134776635206307, + 0.06410633060614045, + 0.03126326736444316, + 0.13048188108623396, + 0.05831233204496781, + 0.2162557831608072, + 0.029990481747231006, + 0.061476385390187245, + 0.28184967450631043, + 0.1605458960164334, + 0.042062046758536094, + 0.30807701105561863, + 0.03481683232569585, + 0.1650526596636246, + 0.22194739333525343, + 0.12095212220425061, + 0.30451298816687794, + 0.06351120345796944, + 0.1866371519392235, + 0.027142328810145326, + 0.2121181590866515, + 0.16745697661697004, + 0.2575704756297839, + 0.21602666776410473, + 0.11096922127925404, + 0.16793133143408034, + 0.14861730240975185, + 0.05023850549870651, + 0.05060874074247244, + 0.08720595548273757, + 0.017594139705375447, + 0.3025998625695838, + 0.10520566811590722, + 0.09108578504687391, + 0.06868085902022232, + 0.23122366846244577, + 0.059366778735689775, + 0.26959725980577665, + 0.02889491198603959, + 0.13763521926764447, + 0.3034231478153148, + 0.11869833845630993, + 0.10690830965597924, + 0.2546975936456455, + 0.11520575474812818, + 0.010427260019763478, + 0.12906618264537287, + 0.038462561157925346, + 0.2536188535112179, + 0.02270241191818071, + 0.2852247521638583, + 0.046928088419171114, + 0.055777648966237374, + 0.056573905343925215, + 0.2754356543842008, + 0.06405834058195387, + 0.17540203280651656, + 0.0642460115649518, + 0.10736490430816187, + 0.043233843869353986, + 0.2821368233651277, + 0.23229871299576155, + 0.23737565056402948, + 0.11714186089487479, + 0.2643305101023996, + 0.2563470888275016, + 0.14005609062442637, + 0.22355016098941388, + 0.0403065091330471, + 0.14944468648824388, + 0.22568855898587664, + 0.3126794685647815, + 0.2105186492245128, + 0.08251454534698092, + 0.03263443827633579, + 0.14817827998980812, + 0.002125566377687852, + 0.21284353388929653, + 0.015996169180001532, + 0.1766822617580179, + 0.05900500519080943, + 0.042336416541452045, + 0.017204302750339066, + 0.20121923451011695, + 0.1793412163994307, + 0.2481899365865573, + 0.11345678336058308, + 0.3174987798949667, + 0.2623642550694098, + 0.01835930402370236, + 0.14349860508681933, + 0.1448918024639299, + 0.18439529894665324, + 0.04166884364972409, + 0.17161796484485142, + 0.17309786296333793, + 0.22147533409129258, + 0.1563625464348293, + 0.12980739170248665, + 0.05540608026367823, + 0.006891317072621018, + 0.23571018275978264, + 0.32143709964127837, + 0.21731384880167076, + 0.02024260525840962, + 0.024912778757500833, + 0.20570015264662497, + 0.23217768244711132, + 0.14558384697334134, + 0.2936573700550818, + 0.11010312574112172, + 0.2794041732167157, + 0.09997040582015607, + 0.14146770550069337, + 0.14949017500071468, + 0.25959116315753167, + 0.17017685203916486, + 0.2582180312790977, + 0.2607511504308378, + 0.1940459641802936, + 0.034401506259649266, + 0.17745625633033207, + 0.2103742118347415, + 0.09271008332512337, + 0.23277207353139545, + 0.035406593318874274, + 0.1922682727127224, + 0.00851129908845363, + 0.08326834193552975, + 0.27742042688606655, + 0.03319004108163855, + 0.11457311995357725, + 0.10750274577715777, + 0.09092483521499958, + 0.10687658962394483, + 0.05468273310517307, + 0.021720167161855097, + 0.04725070964449167, + 0.07205162752298291, + 0.09140540276131902, + 0.11361126025668791, + 0.3069313293967986, + 0.19809724117803476, + 0.21009726610712354, + 0.06828009500759896, + 0.2675215142598872, + 0.1705002399274131, + 0.31650288196562415, + 0.08033909376665496, + 0.27234134216613654, + 0.26689158395685403, + 0.15868824357716277, + 0.07322111764843202, + 0.29820826741389206, + 0.04126253876680423, + 0.14400523452028255, + 0.0047972160876476695, + 0.25475805715493294, + 0.31120672156599616, + 0.18226117659501004, + 0.11711566817476596, + 0.22775717516153865, + 0.03757292397809907, + 0.02012320950490989, + 0.19214091609382802, + 0.14029110720932395, + 0.06691957409664359, + 0.2639758814179168, + 0.208147824259082, + 0.02140034867715702, + 0.11039854442651958, + 0.21059596377293238, + 0.02965112501298849, + 0.07979100080083942, + 0.15808295161644859, + 0.2105934945573907, + 0.15698240342802258, + 0.2476094411467324, + 0.13476370037427593, + 0.13125243597265648, + 0.21008156815759127, + 0.02364246515558471, + 0.023917976219436372, + 0.09206620076250302, + 0.15154147526645032, + 0.035362091540294696, + 0.08346407677642166, + 0.2085069997184432, + 0.2687580700965404, + 0.03893853914272468, + 0.06877718337994787, + 0.004317475905587865, + 0.2768870360448832, + 0.15833931576908747, + 0.2749835314336819, + 0.09557135977579682, + 0.16709337121119885, + 0.20661166656638766, + 0.11096402404294416, + 0.028324266273224506, + 0.19990358795998392, + 0.002625163399267099, + 0.20326387844769622, + 0.21629277341319328, + 0.20519533842968196, + 0.30515196698965363, + 0.216750536125592, + 0.055081270772431565, + 0.0919390900848464, + 0.12436830095923553, + 0.10950322459447448, + 0.22087220628904516, + 0.06911193016344762, + 0.05875600813734538, + 0.043405979228010046, + 0.028875939298918588, + 0.20728115620391996, + 0.0664889926066232, + 0.1954130218917373, + 0.04931841837569984, + 0.166985112650432, + 0.19527859980923004, + 0.218016999472748, + 0.09009570346502702, + 0.15065025484271174, + 0.28595766751122453, + 0.272437969259055, + 0.3139397696172959, + 0.03158120946619017, + 0.013723392542419183, + 0.060371107575977176, + 0.04065652165216404, + 0.24662719029456853, + 0.2697790936871906, + 0.2812567512289653, + 0.13935379242120285, + 0.07179330136533568, + 0.2521599343685908, + 0.11694633602728224, + 0.015689289768155968, + 0.23825255765165645, + 0.1400965993405384, + 0.058487193220690334, + 0.19782084941763778, + 0.30514739826859094, + 0.13778516310626054, + 0.06260611196470736, + 0.27587660364541877, + 0.09193822617623665, + 0.1489556435244977, + 0.06550718386266008, + 0.22622531105441707, + 0.29842166152319854, + 0.07674206340979263, + 0.04935678547455577, + 0.18827161373547946, + 0.004726176869760197, + 0.10599999374555992, + 0.24079919993209611, + 0.11877337943731849, + 0.011074860679057351, + 0.1256507342733128, + 0.23745010856366502, + 0.21497570589620296, + 0.1777074486351679, + 0.2778289094936174, + 0.319163151658687, + 0.04671906811841161, + 0.24532406803528015, + 0.009918613350459717, + 0.12705502090412077, + 0.0895670772390444, + 0.27964857207906063, + 0.24951031700613124, + 0.28833047891837715, + 0.08132725984423979, + 0.21861553867456085, + 0.05026015486824147, + 0.0954008128333171, + 0.09988933988390353, + 0.2002740548697938, + 0.07738584614085757, + 0.03694444612827588, + 0.20146199179416463, + 0.0862156283627414, + 0.261590725359016, + 0.08631882051231554, + 0.22390871992967865, + 0.10887489684979171, + 0.0032541425234557646, + 0.19252587204636554, + 0.1332047921987199, + 0.27935258547189196, + 0.29425964681115957, + 0.3223664269930873, + 0.05847227363667512, + 0.07970583532816639, + 0.24254586731851477, + 0.12651951492459781, + 0.2525508002808903, + 0.06944064657529418, + 0.10393722849391958, + 0.17872043677659782, + 0.0174799829257536, + 0.2825469481104415, + 0.10991066383516579, + 0.14148694467301756, + 0.018703623911508763, + 0.03197018296068721, + 0.30532660205194856, + 0.03131187576319525, + 0.21616158105412814, + 0.18769999032462586, + 0.11129237993609466, + 0.21521905516268222, + 0.19827996839402615, + 0.10141338791547412, + 0.2643867104653616, + 0.1094980990839153, + 0.04243724859037626, + 0.11908474709939319, + 0.04891691829051669, + 0.17349408308143835, + 0.16438193927979386, + 0.16516734409990863, + 0.0941750566809898, + 0.15361741057560663, + 0.07283988515734226, + 0.1250241221868541, + 0.056680920051566, + 0.08666264912732262, + 0.15511978958084324, + 0.32325963779949524, + 0.2975333407446941, + 0.03463240656920151, + 0.2195935784535235, + 0.24900494679491422, + 0.1392699240186077, + 0.07159144366069907, + 0.15851595252555398, + 0.2206257205122031, + 0.17353256304156556, + 0.010466896845686609, + 0.08654200604460417, + 0.06707563539770305, + 0.22298217027019052, + 0.06300363724026181, + 0.24994935948933517, + 0.19676793225165268, + 0.1770037999542928, + 0.15618801661063209, + 0.11976318005089398, + 0.15661557950747268, + 0.2733918862871629, + 0.09578796332534645, + 0.05434168447315235, + 0.04134456174545046, + 0.2100305473688497, + 0.07422354129177207, + 0.09024569069877596, + 0.06802562528183602, + 0.20114208254131744, + 0.05396663687478327, + 0.2111185218936651, + 0.2965659022630742, + 0.26592795992934815, + 0.056976809212110624, + 0.10534213045395595, + 0.04554946073272281, + 0.17530782478013615, + 0.22311706069860568, + 0.033106328202969305, + 0.1500022087793055, + 0.1627454693359542, + 0.13027911910055226, + 0.15837835587302335, + 0.16623268688690518, + 0.09296233762215475, + 0.25826878548891674, + 0.07072675438103883, + 0.31467680944667364, + 0.2622532040308649, + 0.059878883402762144, + 0.0694028318249895, + 0.13988692911609743, + 0.23898483019234842, + 0.2968057924795872, + 0.022408290658250913, + 0.10155785743511796, + 0.209097077553315, + 0.053622246990535374, + 0.023098568790740716, + 0.2140901945843001, + 0.11349253648556024, + 0.06990067244716139, + 0.32108799784174236, + 0.07665648735189717, + 0.22207497419406486, + 0.2588596049895245, + 0.16734446924934993, + 0.10036397705228874, + 0.1707684305426654, + 0.1759863169110055, + 0.2164804013408232, + 0.27983298319689376, + 0.2594341836696699, + 0.0033549228933689476, + 0.13071345663369877, + 0.16099115971136171, + 0.23482682447971992, + 0.0701368556619368, + 0.21319788169752757, + 0.13565264243398376, + 0.28085281053128874, + 0.22688446783275135, + 0.1433963065600874, + 0.23869633826775916, + 0.24661733676194303, + 0.06683408198399833, + 0.32212686501511195, + 0.155283278792899, + 0.05418324087558911, + 0.04925360594595951, + 0.31865005252174095, + 0.14330966613494228, + 0.14561863630981775, + 0.27399713554159816, + 0.2615795527939423, + 0.19459655467437068, + 0.2777710146757132, + 0.1151959824446337, + 0.04937104120144556, + 0.017934008861104023, + 0.24680349233878085, + 0.025053410059846386, + 0.12175133021948499, + 0.306816990335239, + 0.09016380459091906, + 0.12872670440855138, + 0.032429876431466914, + 0.24336586309708544, + 0.02487250905305853, + 0.062134291881366134, + 0.29269367879590313, + 0.052543574161261965, + 0.08524011333085756, + 0.1453462966690393, + 0.023916878605452885, + 0.26227240310241834, + 0.14668135271455257, + 0.026370217028023987, + 0.20444384199182014, + 0.09462701613347302, + 0.0766024456284141, + 0.24006725228162906, + 0.040414562824117935, + 0.11251260896357711, + 0.09549650527494685, + 0.19458142755535565, + 0.18990762278748305, + 0.2711606444958198, + 0.254433774073057, + 0.13320224010026788, + 0.15935608197977455, + 0.24784180936940484, + 0.007063940641053073, + 0.18244496610476282, + 0.26005222705007897, + 0.2894705758529006, + 0.19921342117575302, + 0.18662866936077452, + 0.19391358092229843, + 0.02307624603679313, + 0.19472975439082002, + 0.016577620273254004, + 0.10750146374553729, + 0.04536123850946084, + 0.05718052394784842, + 0.24221112060957967, + 0.19970755754395075, + 0.29792503939841214, + 0.0029405471408439857, + 0.184365890341908, + 0.20914915771836942, + 0.29578492123476585, + 0.22368678377561563, + 0.10248339568650283, + 0.17236953324301363, + 0.017325504162680142, + 0.27711237603762034, + 0.0691222001577861, + 0.04353532200155048, + 0.10882767311775406, + 0.08266585544728605, + 0.19693887319488185, + 0.1784809174738944, + 0.09648335039159876, + 0.093455428203795, + 0.29914259688552053, + 0.16442961299593586, + 0.2919343409774493, + 0.0077983513568743645, + 0.05156785112124006, + 0.17938749883416763, + 0.027787701515850655, + 0.12827631144538307, + 0.11221748792926727, + 0.06594506865999868, + 0.1010835011060415, + 0.09326423568949326, + 0.16085064098893526, + 0.23959695906666892, + 0.09358322714594634, + 0.1638126310778908, + 0.21904293259689972, + 0.10404950804217872, + 0.13333352655586392, + 0.24616465759269937, + 0.28294700591468064, + 0.14001996604436467, + 0.029948282387481154, + 0.1704713320130741, + 0.2165465592460891, + 0.3080500693446403, + 0.2405573870248584, + 0.2665854278359214, + 0.2753008550965409, + 0.2235215573369762, + 0.2586234477098668, + 0.23305417343357127, + 0.09101016714551508, + 0.2560083217538093, + 0.20556319868939052, + 0.2212038926178159, + 0.05149599291429548, + 0.2935021831636647, + 0.1947353333802959, + 0.17134305685133516, + 0.045182525988193355, + 0.13125332363079364, + 0.004168359417385088, + 0.012345847002295908, + 0.29563897276578927, + 0.09949244341593967, + 0.06082866044871284, + 0.0020646978655663325, + 0.1465711428197996, + 0.1406437405416253, + 0.2783359280495716, + 0.20197208027356, + 0.3034878447815952, + 0.178838073202521, + 0.030016839956771627, + 0.18488256796104754, + 0.24357259962333486, + 0.18108032470267882, + 0.32003990291144124, + 0.2464236574327885, + 0.07982157763715712, + 0.19278871713089638, + 0.1718802204142227, + 0.03047338254694096, + 0.05690091396223237, + 0.01597370907848816, + 0.010321678675423848, + 0.2767075918434004, + 0.2922496459106174, + 0.2661004206785118, + 0.11618426212404925, + 0.19722844070373113, + 0.20304687594601561, + 0.16971160437714342, + 0.26449179788408855, + 0.19476138426102255, + 0.07837327249692579, + 0.1252137795209896, + 0.2896455103403659, + 0.036006150888931464, + 0.00969718044720563, + 0.05290896546538171, + 0.09733658148519761, + 0.1313549767460562, + 0.09482350492613038, + 0.280996850183214, + 0.14176197520329276, + 0.10357514254647229, + 0.036048275734567405, + 0.18513064551724528, + 0.010197245175223489, + 0.2065779985017766, + 0.047397203401226884, + 0.16681555671617393, + 0.025055949485654268, + 0.1766156627680464, + 0.12612366981290787, + 0.05173998819760383, + 0.193340302808469, + 0.18185060812136716, + 0.12504480193032705, + 0.16878056820520895, + 0.03785336057337525, + 0.016030706172907496, + 0.0447904645858992, + 0.12895903292834168, + 0.07218925637141202, + 0.04417364907187509, + 0.1440391887921619, + 0.08850934007461059, + 0.017011068588304225, + 0.17125115059749207, + 0.21360522753570016, + 0.012392318476747289, + 0.24334431463451275, + 0.30814551451540195, + 0.16844489550101283, + 0.16260466062828105, + 0.24024919401161143, + 0.29120258585277997, + 0.03316882941425265, + 0.1852453132543558, + 0.019778258076019947, + 0.19655581476848258, + 0.178447529209965, + 0.09041280139243363, + 0.15912089365463897, + 0.05048422386343573, + 0.0865279902709634, + 0.04350463729176894, + 0.1406678929902689, + 0.2076560321811661, + 0.1961873938459254, + 0.08083484936692305, + 0.06697009796981507, + 0.037601304797340494, + 0.032205653060328555, + 0.13838451930639206, + 0.17408019943168948, + 0.045253895999163664, + 0.05459820369816108, + 0.069600287202832, + 0.1043255528285284, + 0.18187346768845086, + 0.2922044727753451, + 0.1953946298951597, + 0.1940036550073875, + 0.08651236135758493, + 0.23552349261353187, + 0.051186367392744, + 0.13725218333066758, + 0.3162810819303398, + 0.14214038383364663, + 0.2604850080176812, + 0.2848780921040411, + 0.028384466734436436, + 0.020690995574330538, + 0.019767113820587795, + 0.23990563418084423, + 0.16050085099555034, + 0.21328410513218837, + 0.18798546899905974, + 0.2590651290061526, + 0.22949822133728348, + 0.31317438833029376, + 0.1661070905137651, + 0.24398009899805126, + 0.017592068223328556, + 0.27293204225435475, + 0.08898114358085685, + 0.06826610170693, + 0.20775212125268722, + 0.24996064859413641, + 0.17955957428931102, + 0.26785729610408393, + 0.09029673985316893, + 0.18321529732327388, + 0.2057721078950934, + 0.04536261651276833, + 0.17364458577686684, + 0.1489950232515898, + 0.21384856722973863, + 0.07737341044096782, + 0.023844864406640486, + 0.22683286015745058, + 0.1292211977882412, + 0.04169435755394817, + 0.2916535673298963, + 0.2717399128135376, + 0.003414028015648644, + 0.1849183381830735, + 0.24254406578305676, + 0.13175728498937342, + 0.06021265221794055, + 0.2925713058425434, + 0.09177176935399506, + 0.1272447005344317, + 0.04844747717907579, + 0.23454246983392932, + 0.0401503516781159, + 0.05543146208892015, + 0.1094418814785909, + 0.03802207674814082, + 0.10909943749042425, + 0.022888071243956604, + 0.25050200675464984, + 0.053100363489543737, + 0.12943766981053764, + 0.1409389404843201, + 0.21095615473934404, + 0.2632446181620843, + 0.03934992512413706, + 0.24345192360762816, + 0.3182870046933624, + 0.2595134949773875, + 0.24271985962631695, + 0.047750543063613336, + 0.3031962972162401, + 0.07429613955967852, + 0.10647927739908757, + 0.2538048511913272, + 0.11718144876262086, + 0.21210428942159748, + 0.2547425180889467, + 0.05787330276070248, + 0.19296492505233634, + 0.03561617494639305, + 0.168366155013624, + 0.14947424749832025, + 0.19103561930019686, + 0.04939537206030004, + 0.00207877108206773, + 0.1612270943173625, + 0.06404570861301558, + 0.05834044849162826, + 0.26287006197243107, + 0.04403861344201299, + 0.31233396538101366, + 0.2840076302970903, + 0.18325680534318894, + 0.20330421341341723, + 0.01988107116921178, + 0.05324807793488442, + 0.25299939088151163, + 0.2028515260626711, + 0.18707311031916368, + 0.06002587105424368, + 0.15364888413575462, + 0.16365435582992088, + 0.2406594439892895, + 0.30893151644482003, + 0.17856603095682777, + 0.047065299898151225, + 0.08921698728068687, + 0.14122477895286992, + 0.23052782469436423, + 0.3080802399558309, + 0.21813892800329837, + 0.30134671132681157, + 0.08433206354528441, + 0.03912135059145844, + 0.16762171567815268, + 0.32415117575961067, + 0.23186694316458195, + 0.10203927095145404, + 0.1968238899918459, + 0.1444424259879095, + 0.0350534308733113, + 0.2679026986368898, + 0.21963192782017205, + 0.1775490463330152, + 0.3091785694414404, + 0.24806577579035133, + 0.24171037587646807, + 0.2790047640485742, + 0.08398276869471025, + 0.27111775862714355, + 0.07211145783377503, + 0.23756249338427654, + 0.1254547822418057, + 0.019710467555221076, + 0.08680266105373748, + 0.30375305474282355, + 0.21529044079895324, + 0.13304876427072157, + 0.19444553005317927, + 0.05239562999206824, + 0.09524208135726844, + 0.055330673789913694, + 0.040337445534063515, + 0.059366366395610375, + 0.19763277227420878, + 0.25042775065220074, + 0.25984719057620664, + 0.0011414902487738765, + 0.19363078214612248, + 0.05422246659582356, + 0.25431637880218744, + 0.11667564159703628, + 0.07168391323111109, + 0.15185245121061425, + 0.040017284535356815, + 0.1311709786715032, + 0.029556885463892374, + 0.2931054742142504, + 0.05799979472935344, + 0.10625413268102347, + 0.273035761073767, + 0.1254700790233716, + 0.11659986604328344, + 0.11440245075270977, + 0.036668383207299746, + 0.1013862352180302, + 0.16338301601186533, + 0.10173434728790048, + 0.2635034134915153, + 0.19719237454573185, + 0.07405317639475091, + 0.18505163652044668, + 0.013931732605568035, + 0.01835119002468043, + 0.08839980484914255, + 0.10734657172002783, + 0.2790052782363265, + 0.2969357280807069, + 0.05050981174164169, + 0.16204710497267272, + 0.018474694234647256, + 0.20497909263430092, + 0.15411110550186424, + 0.2696110261967548, + 0.12712433270233994, + 0.17365442283973515, + 0.25373624545461904, + 0.12324604493730355, + 0.09498593157480716, + 0.08488741131230572, + 0.09009663236572261, + 0.20294066174129247, + 0.07592329505602798, + 0.06771657102155672, + 0.16979075413846775, + 0.13207610348090937, + 0.24867440690143625, + 0.05398585111190434, + 0.09080586437881936, + 0.06645881061201651, + 0.13619578097897336, + 0.2511370779866724, + 0.026424747789094892, + 0.3208152821344131, + 0.21702390797970467, + 0.19666836929378373, + 0.08309094063159654, + 0.11422125564296555, + 0.07586741210114697, + 0.21721196046821972, + 0.1488396076970617, + 0.2789652214602697, + 0.08267174765982938, + 0.3161189828472671, + 0.061220803789664914, + 0.25942085119982133, + 0.27636852389973576, + 0.02380553415159517, + 0.23362470851046105, + 0.30249258803717866, + 0.10612282967173138, + 0.059082465186918655, + 0.10057255215603209, + 0.11388162268975692, + 0.01632484900589689, + 0.18812938181013614, + 0.1985754290698123, + 0.07907146290405583, + 0.1044137021871511, + 0.30506363136330766, + 0.16960237897593955, + 0.15207561157102298, + 0.1659353312126974, + 0.1477119732358105, + 0.20972139892999403, + 0.18589661190511528, + 0.0564413293677911, + 0.2509822202311551, + 0.07306140947088874, + 0.16769559130752834, + 0.30184721511538437, + 0.14829291280263243, + 0.13134345567860345, + 0.20647675797616782, + 0.24657885093007412, + 0.0413520204117196, + 0.0599263589576732, + 0.19611215103816493, + 0.047043113067791756, + 0.24276876719917911, + 0.13869579808743085, + 0.009013804858064378, + 0.039802941234309185, + 0.08816366699114912, + 0.04950107913171409, + 0.052107496433270444, + 0.2643789825518892, + 0.09933073431006847, + 0.0806618142855531, + 0.24434549609871364, + 0.16681546005148082, + 0.01642358749738109, + 0.18357916618899675, + 0.3227473367357342, + 0.06239500659822258, + 0.05019984641204454, + 0.20570413829024206, + 0.30748035797873446, + 0.04098039313253422, + 0.15455530743822174, + 0.02709744754498464, + 0.005740925557824203, + 0.22298204299623856, + 0.06927546698059169, + 0.23955098903624458, + 0.029791326426943533, + 0.2386212594015335, + 0.005538770585229066, + 0.19985928456115454, + 0.058772906612582956, + 0.2098115501572896, + 0.23419123276436063, + 0.23330091266784217, + 0.10493045080608962, + 0.09582679945095679, + 0.02340854647775694, + 0.21456116862687352, + 0.29227291221690993, + 0.2761932379595184, + 0.14692293213393895, + 0.12139475239045198, + 0.16221987523546447, + 0.26485929219672855, + 0.19546814511756952, + 0.22616783507068133, + 0.06804178863323382, + 0.18866346444235915, + 0.025808746341856575, + 0.04787332371728277, + 0.14268477262436224, + 0.11707715750661511, + 0.10143400354644408, + 0.266555950410028, + 0.15343716244749842, + 0.07813294351648514, + 0.010430262957327359, + 0.10411916281119044, + 0.033469198001118985, + 0.17302383855957956, + 0.06998426577705107, + 0.06522008099667849, + 0.32224101283632745, + 0.1294972557942411, + 0.3119086175051279, + 0.2747133673164904, + 0.21238900408996728, + 0.12176935588382277, + 0.0738794702526578, + 0.13951985140881465, + 0.034637168513945105, + 0.03146382430932738, + 0.25356824825251906, + 0.05945875075791529, + 0.23423542065262595, + 0.24655225410358314, + 0.24027418280838023, + 0.2096296756666013, + 0.11413268395916158, + 0.07243392135083943, + 0.11227966342062604, + 0.13431411755533967, + 0.07290814675693698, + 0.12070821085201104, + 0.03504621993744241, + 0.06064709977873582, + 0.2356415516196298, + 0.16562147607173977, + 0.014829202385980136, + 0.1779076242812238, + 0.16424854516071988, + 0.15763897539653424, + 0.21814554206486034, + 0.3194264555736467, + 0.2788347146780925, + 0.3223840203663431, + 0.1942047355372466, + 0.2813011475419609, + 0.0936377390581825, + 0.1330297010709277, + 0.28473271715085924, + 0.007399697977409521, + 0.04065068030683999, + 0.01799305033632992, + 0.18373661383470913, + 0.30829273650970673, + 0.04905323467340019, + 0.044505594401712444, + 0.1546950803842874, + 0.20031047993353665, + 0.2598995488764196, + 0.21245998291494925, + 0.046535472046024075, + 0.22943406527409155, + 0.017926510871029477, + 0.31644873601003576, + 0.21584198399633994, + 0.20745114139022597, + 0.14760059053384453, + 0.04002488553680977, + 0.16414451317883177, + 0.1423806252435174, + 0.0994708158897513, + 0.24659122728414398, + 0.2705113212395764, + 0.25621395678167197, + 0.013403938311359793, + 0.050433382493201215, + 0.1710937113885312, + 0.02634742576419027, + 0.15297150817000948, + 0.10897948806969747, + 0.11066951933211161, + 0.2201373569276441, + 0.24502326607368216, + 0.11764478202141265, + 0.24743663143485511, + 0.18171094739568427, + 0.1844487464871674, + 0.18867149117770163, + 0.12517514944401653, + 0.1625562044275287, + 0.007682612849725105, + 0.192776386832435, + 0.2590062506317009, + 0.23825354317950073, + 0.24750283727693118, + 0.20941584835029925, + 0.1479603037639854, + 0.19099024282948482, + 0.13721409175134022, + 0.30350171081605437, + 0.06022923474158729, + 0.039102350460951084, + 0.0357738032500437, + 0.12090406289514277, + 0.17420038748327993, + 0.3226281228958755, + 0.1239712061180854, + 0.13721432948748996, + 0.04085683925250503, + 0.21312821988724015, + 0.06561126728077868, + 0.21808702769101948, + 0.22250771967706032, + 0.2097690054743992, + 0.19476342624097553, + 0.04711882944878688, + 0.1646108930047375, + 0.22927854084826246, + 0.13494942913618393, + 0.061625525861580335, + 0.006788640275316281, + 0.10483364089048237, + 0.15467341099583704, + 0.00874550744512288, + 0.07679977248058471, + 0.07189355894324455, + 0.17086516579705832, + 0.13442479437461244, + 0.11724638858227829, + 0.21641629666069487, + 0.024487380479330238, + 0.24021856394512178, + 0.09360277275415596, + 0.27641452974329805, + 0.038486749376556294, + 0.033961827153138245, + 0.1396566725652269, + 0.12883591788465862, + 0.004303176460485466, + 0.10028045782422723, + 0.2204697596972189, + 0.09296592469485086, + 0.15651824007236795, + 0.20775664318727877, + 0.02322288327729164, + 0.2595895126967374, + 0.30886352315630755, + 0.29874284385796446, + 0.13577041798761716, + 0.19124294067858044, + 0.007128119986339611, + 0.03936636443101732, + 0.1625720039881789, + 0.28886440117259427, + 0.21704132840163562, + 0.10609490706772964, + 0.31361344764709803, + 0.14190697034971858, + 0.06547734491113769, + 0.09282261603255873, + 0.17579120757590483, + 0.11291998279409388, + 0.21747462058794423, + 0.04631350065778329, + 0.25419858595238337, + 0.301022563972158, + 0.2851763957989837, + 0.23780507233542392, + 0.242589469528289, + 0.2469404771781565, + 0.19642638670027082, + 0.03669077712500581, + 0.12739133516109805, + 0.09817876588318923, + 0.14206918715548006, + 0.039020105663792236, + 0.26373563016073964, + 0.26097410063098353, + 0.27574943246393435, + 0.0602524759806687, + 0.030773796303025003, + 0.26332163351910326, + 0.2257778508182674, + 0.15871592994893136, + 0.06785739889197057, + 0.2610128993843403, + 0.24706749721058993, + 0.21798758524355377, + 0.057455368620562546, + 0.2665564613141104, + 0.1190378812086775, + 0.24063830107142675, + 0.06276019803130213, + 0.18522166633294754, + 0.270674370288608, + 0.20310919437270472, + 0.264845310801677, + 0.2732987993580522, + 0.24446635685387005, + 0.2708639158709, + 0.2613603839751038, + 0.07223546810489427, + 0.03574309587773457, + 0.23258029587570317, + 0.0499934464710171, + 0.21910919371854637, + 0.19177225982702503, + 0.10410076654463657, + 0.10433286624548195, + 0.2236397146264101, + 0.25644198996398443, + 0.3169615859558352, + 0.15352806718857334, + 0.1943798139194885, + 0.14678493626491382, + 0.14004807022066654, + 0.18142647686042443, + 0.0888047012262782, + 0.03081752274511015, + 0.022566746129895756, + 0.19116301700757637, + 0.07995924803851849, + 0.07167569420287007, + 0.22564605864207068, + 0.016200715029413275, + 0.12038410516774016, + 0.10386226134448823, + 0.012400498781198158, + 0.24374985484619838, + 0.02805673444786284, + 0.2514157688900636, + 0.17315454573739594, + 0.1626516453347625, + 0.12059877034551499, + 0.10689864311192933, + 0.07557082476419204, + 0.20189471013153837, + 0.29847486155031516, + 0.2844455423756465, + 0.25752953762890696, + 0.18448234751264442, + 0.2722404003664796, + 0.2813621311487776, + 0.03891041167710826, + 0.19384853454427337, + 0.1525011421723293, + 0.19278571205044637, + 0.30006104321841837, + 0.10228918037882152, + 0.1547610423829063, + 0.013235687747120448, + 0.10690371117455383, + 0.27321474703871096, + 0.14251901771624714, + 0.21725127567917968, + 0.20354076305990396, + 0.1049884792200897, + 0.04343792729895125, + 0.12449257774708287, + 0.13173674288184098, + 0.24841291030443854, + 0.1535009500715905, + 0.09956027414500077, + 0.05558894153690475, + 0.1516504249982617, + 0.21916873900780498, + 0.28901718122286196, + 0.045881466552238875, + 0.04207447183610984, + 0.055813598526348034, + 0.14599321110782784, + 0.2837420655174675, + 0.15709054826494454, + 0.16087119794857965, + 0.003500471213984427, + 0.11367962469290645, + 0.11667021797991885, + 0.1199370610197878, + 0.16423610951758472, + 0.21705313065196155, + 0.09964761055064655, + 0.04891521064009924, + 0.19906909616187582, + 0.31038794987343543, + 0.31868998619205025, + 0.2891388870228015, + 0.010888520097307109, + 0.2134927222426513, + 0.25193008196041417, + 0.10046995747590913, + 0.22186354043810547, + 0.07881884943464233, + 0.214868061385039, + 0.1678928380685143, + 0.18940601150670303, + 0.1621539789544772, + 0.24992980769319012, + 0.18289470215339268, + 0.029762084932850066, + 0.18445234704007982, + 0.07921195969975615, + 0.2941384428351301, + 0.03263889864495672, + 0.0094044285128181, + 0.136681702177945, + 0.25083639241928307, + 0.22810808939240632, + 0.0723453868744947, + 0.015733873372316604, + 0.22974991005778467, + 0.1374951223857434, + 0.23461857633094974, + 0.232955286328861, + 0.020920779797960816, + 0.20978331871716324, + 0.21716345696486838, + 0.04460333568448142, + 0.060890063156408346, + 0.16163810400333625, + 0.16774080732416502, + 0.027133399108977416, + 0.11048942040329379, + 0.13104993959938882, + 0.02918245967237712, + 0.2206409369525186, + 0.2762063013007982, + 0.20491958022334855, + 0.058922145616613, + 0.11728473149969186, + 0.05381585970575245, + 0.3071022760251058, + 0.2021716572180271, + 0.13034444269247172, + 0.09898527145523055, + 0.10817817265727411, + 0.30715795705738647, + 0.3188502998692093, + 0.11409916677613287, + 0.30730479701247126, + 0.22850740923135668, + 0.28120641379225314, + 0.09301346391655999, + 0.05577441071045505, + 0.2560167568800074, + 0.06747784052337162, + 0.19159071037405914, + 0.23041226298066864, + 0.03241747021675781, + 0.13619096156742086, + 0.13857358881188003, + 0.23201863876149523, + 0.32048129907542566, + 0.2299213890199135, + 0.02455510639554216, + 0.19343597327672649, + 0.09533053460457337, + 0.18154155462167895, + 0.2774030580156461, + 0.067806112803177, + 0.05555696224563808, + 0.06117661471723505, + 0.21340323893380844, + 0.14398820597022335, + 0.05194027905589254, + 0.0466330482424279, + 0.04233087599882853, + 0.01094260408730457, + 0.10921579047118714, + 0.12446191533822092, + 0.27187737623313063, + 0.25387011221614786, + 0.020295649943600294, + 0.305130018163218, + 0.045706580251537385, + 0.16490478469414693, + 0.02911124976778092, + 0.21667288448822586, + 0.04777104449858289, + 0.19895770812652705, + 0.02005613100594492, + 0.04031883375957403, + 0.03855961722143748, + 0.11396655861186927, + 0.22804344987845437, + 0.10676801147844703, + 0.16563004402098344, + 0.29345214692076177, + 0.012374242423077665, + 0.1816311743711642, + 0.2413003565789571, + 0.29708481835496536, + 0.1926472121027401, + 0.22496636719799867, + 0.1092225571351704, + 0.19377036164472028, + 0.2874209227418949, + 0.31943373991245544, + 0.25641684462618036, + 0.15234537391764127, + 0.14770462449241253, + 0.023681102020294876, + 0.19967467212984372, + 0.025352632380086924, + 0.26092999596392513, + 0.08905210107618676, + 0.16980296657120753, + 0.020653334852424005, + 0.11914405773313883, + 0.05761210830681725, + 0.24658080447275313, + 0.21562173775215018, + 0.29176471980730573, + 0.11625504288795241, + 0.30094411973757546, + 0.05095660732555856, + 0.32051566310572066, + 0.049817092430502204, + 0.28298252941549473, + 0.049109008978362234, + 0.26382943134125736, + 0.12721876154142697, + 0.001961381641537423, + 0.3028034664239406, + 0.1881227178960861, + 0.006712940440500905, + 0.20836223021120026, + 0.05810500165526543, + 0.1975455813971333, + 0.16581380524929235, + 0.20462084372054617, + 0.10143326466638633, + 0.14057258951969276, + 0.18553940701170332, + 0.046320248544513734, + 0.12290258744726792, + 0.011651595596190079, + 0.29184640582894683, + 0.10561139974735943, + 0.2769663070650989, + 0.044008450752481255, + 0.25419792446734046, + 0.02241865167266878, + 0.31686893564647334, + 0.26119737005413, + 0.19698302213038704, + 0.05946524387131893, + 0.0014017103356671044, + 0.19224359730524276, + 0.037482495011483576, + 0.19527877844499647, + 0.016476019164156436, + 0.05235900727477211, + 0.31381421637448215, + 0.0376426818599033, + 0.08770498462531186, + 0.1722188428206219, + 0.0851826453276371, + 0.026539022351707565, + 0.22734560563361497, + 0.07299770522359245, + 0.10968539864946883, + 0.09249903161923292, + 0.11603435539833193, + 0.13256990766760657, + 0.03454732100482982, + 0.16372188453226788, + 0.20293249634182434, + 0.04835546778914684, + 0.187811698880726, + 0.05928892616342396, + 0.031054114876620333, + 0.2613089340105763, + 0.02342288757989806, + 0.16204610859828036, + 0.23577685468455697, + 0.1595278754090812, + 0.059377247402905384, + 0.25212083334613344, + 0.28343274687047154, + 0.2534033098796594, + 0.20621455585298507, + 0.18702451920989077, + 0.1262816617658752, + 0.22835257553724328, + 0.08610531653739571, + 0.03433614529101398, + 0.30024058906101997, + 0.04116026636701693, + 0.19940304531066388, + 0.2574077118959507, + 0.17125729397107825, + 0.1015226589997761, + 0.258366693416869, + 0.12763761934549508, + 0.22227405312358678, + 0.1074235806610516, + 0.018613159301553623, + 0.24910419105776774, + 0.10341496938386956, + 0.049145398156519554, + 0.20964341103415937, + 0.03175974544639368, + 0.0506081600846966, + 0.1529032491681603, + 0.2660992670849838, + 0.07944763897233259, + 0.10009100339640747, + 0.10082182991861438, + 0.1963549247171767, + 0.3175816362740764, + 0.2887420514992646, + 0.26822280604713966, + 0.16106509391200832, + 0.03399779495976913, + 0.02447236168890762, + 0.012988969056481264, + 0.2096958660456746, + 0.06646465083764967, + 0.18664528221024204, + 0.06870754578388234, + 0.14611675888680328, + 0.10032473609499398, + 0.06081032256987722, + 0.15580108251496852, + 0.17730870971713067, + 0.24809300170885296, + 0.13289397938092257, + 0.19236179425103914, + 0.07385482980019588, + 0.27541720322876384, + 0.2703772685485274, + 0.1292644186600001, + 0.30365478706712334, + 0.030083790308197137, + 0.1387348621350419, + 0.11758038858890604, + 0.17549489158454146, + 0.09025009560510656, + 0.24422164210522723, + 0.08788960588455048, + 0.22235583574209605, + 0.08079631957108421, + 0.26532998659675683, + 0.18095670538713698, + 0.05120038649567998, + 0.1227664056745012, + 0.09470235497460627, + 0.09660690257405694, + 0.01724293337432965, + 0.31117732252806835, + 0.013224241641845725, + 0.13505054395086108, + 0.17685727739036247, + 0.08347508000708158, + 0.17152682970764702, + 0.030037448847751235, + 0.08053251919286153, + 0.023137093608918562, + 0.27759459240991896, + 0.04288994128588033, + 0.18489096572780986, + 0.22910730060102755, + 0.1647247456909151, + 0.021284756979470503, + 0.2295222129850152, + 0.23829701908780948, + 0.3030547969761725, + 0.009439115631423156, + 0.2274823589290137, + 0.18994172340160553, + 0.11646952912072435, + 0.0016273244574570398, + 0.10590577764450738, + 0.1419420989695256, + 0.13337670324395287, + 0.09907045549949242, + 0.22043767955527607, + 0.24281641213114852, + 0.06542950198733319, + 0.29365575173883657, + 0.16420431999186788, + 0.3104967077490559, + 0.2606637605486834, + 0.1146454975843521, + 0.18936566086085585, + 0.1564127686753322, + 0.11529362933664396, + 0.03374943899826442, + 0.18862027890477795, + 0.2356287280926576, + 0.16019012183818318, + 0.3144589224100923, + 0.10963091070149032, + 0.0958672422757053, + 0.023935922654621127, + 0.009438511175041306, + 0.29269952177024344, + 0.05219424739137062, + 0.2709885081763418, + 0.2627569849242476, + 0.029946172544679232, + 0.01850069066640692, + 0.16867470968056675, + 0.026837420123532657, + 0.013573757045152787, + 0.2738803964925796, + 0.042712469594539955, + 0.06822417255570151, + 0.2999254832548879, + 0.14949386157875524, + 0.2690557966736404, + 0.3110991102810256, + 0.19017884811027339, + 0.03404201830706232, + 0.09839568942714828, + 0.19699083183743515, + 0.2052122862820023, + 0.15986104095799272, + 0.06098080187242092, + 0.015509478872013715, + 0.049198787652128234, + 0.23729681221774923, + 0.024860993012034212, + 0.10599566564979769, + 0.00840832028347558, + 0.22399879775868264, + 0.037142784768037944, + 0.14545901525798552, + 0.10439589246711727, + 0.21630109526929434, + 0.007863828047541797, + 0.12978582628406748, + 0.08674154349549813, + 0.11261053049773276, + 0.04147314360082913, + 0.08207855239680495, + 0.31360438574183497, + 0.06317795720350455, + 0.2527442886254074, + 0.05643439043383069, + 0.060988445446009266, + 0.005868421683726778, + 0.1038541002784468, + 0.2946054852446167, + 0.1483855808833999, + 0.2026157474587129, + 0.042955078494541415, + 0.2466012265019828, + 0.03513674849877089, + 0.08136288167939931, + 0.15286555269097007, + 0.17586879971280653, + 0.31382466544724724, + 0.1904538243384553, + 0.10961671082055194, + 0.07215177987610916, + 0.1354025763957001, + 0.020001048047249184, + 0.02165444864619052, + 0.15791018027696674, + 0.09654113544583173, + 0.08485653145854162, + 0.2468296697911449, + 0.21395168868212447, + 0.18961946809388508, + 0.064718242977769, + 0.16464884026011356, + 0.045192389968121784, + 0.26146932823560987, + 0.1898314783379402, + 0.004631321823511424, + 0.007571435193369461, + 0.024749739511708408, + 0.29088718162128374, + 0.20964230961924596, + 0.22154684121406584, + 0.10908909734587804, + 0.1459208787400911, + 0.06794264068018724, + 0.3025269815489891, + 0.06763598573727639, + 0.18801587185319968, + 0.24499876056576603, + 0.30062694088487857, + 0.11893056685165566, + 0.2830993339986224, + 0.2812711704994448, + 0.009456913137408566, + 0.06147082562534903, + 0.20614882269864013, + 0.09260811898629619, + 0.02451743298833641, + 0.27802646138662573, + 0.26726418639799804, + 0.20839215287553406, + 0.14674338310898533, + 0.2053079335393592, + 0.14414940827104955, + 0.16656459767672535, + 0.132220412796274, + 0.0808188082469353, + 0.09558969653353533, + 0.09530868313564352, + 0.116865426871101, + 0.04634595224104042, + 0.06645731323221708, + 0.2959620797031816, + 0.1360992773748621, + 0.02622216565472807, + 0.2347470789222352, + 0.04233059067427222, + 0.255753675940993, + 0.050426853880716785, + 0.1511907394680479, + 0.31177062137367617, + 0.2509419042770058, + 0.08918390677531897, + 0.15535718299691345, + 0.1519419540414298, + 0.08281223826690655, + 0.17656767684978705, + 0.15994972322420517, + 0.03165858457747675, + 0.07158449942070752, + 0.02881484981754625, + 0.23863419460896954, + 0.19657028802806922, + 0.04899427994076908, + 0.0930974470622995, + 0.16260766301190122, + 0.20627481875805445, + 0.17581575286761153, + 0.11451523880504075, + 0.007705306067080138, + 0.2471761037139694, + 0.025781843300135544, + 0.08064574234015189, + 0.3022733876341074, + 0.1303787476486188, + 0.29978606044932454, + 0.12387291643169893, + 0.04128984199638534, + 0.16843925351341107, + 0.2869343036837952, + 0.07918543876306226, + 0.06668340680274122, + 0.19396828069581631, + 0.1042349951242317, + 0.03082832927038769, + 0.026135776802276474, + 0.2024045421936392, + 0.29096772697872, + 0.1287237123353115, + 0.24969981881624223, + 0.3165510556058472, + 0.077853790022555, + 0.2722018980682566, + 0.3145544495668701, + 0.07689123214054937, + 0.1706499482982905, + 0.04625026162470714, + 0.2358751408464517, + 0.1280602761010164, + 0.03996301255990084, + 0.21384707009498788, + 0.235054573598938, + 0.06404685697767247, + 0.2763088548534766, + 0.025970223801430048, + 0.01212542844782918, + 0.1588994655778274, + 0.10060252849410721, + 0.08402628026586491, + 0.012944646724654455, + 0.17942564338826078, + 0.07364560685060126, + 0.08707913259162613, + 0.08585741986418095, + 0.07759075259930467, + 0.005036712241434339, + 0.18306497537058758, + 0.189295469949836, + 0.19781755499822704, + 0.29151298729904424, + 0.059894861027526565, + 0.06580535013937959, + 0.14738917498663484, + 0.19629403494003234, + 0.1636712335260618, + 0.14010648351527538, + 0.018077615767830308, + 0.09413355846678187, + 0.279298529272339, + 0.1399029892773882, + 0.09627273751769287, + 0.07277937541350521, + 0.15848717303390153, + 0.14823571072742048, + 0.1317107084418439, + 0.24605086932221806, + 0.15652661552241962, + 0.18250497398867757, + 0.012166115832097837, + 0.13298830644097556, + 0.26694407492896693, + 0.18688108940843903, + 0.3110396801101089, + 0.00808135658604539, + 0.2542411959384788, + 0.14054213427314832, + 0.019647838007868346, + 0.20527556903017652, + 0.12338501670441948, + 0.10852218001499572, + 0.30188661944030265, + 0.14800337585266013, + 0.19344490136894954, + 0.20304155788345016, + 0.19478933371617776, + 0.2689788789452439, + 0.09862755003914045, + 0.01883419499896165, + 0.07949659324533781, + 0.17723147256408497, + 0.1259304916106471, + 0.14502596311396296, + 0.15334807858092725, + 0.15420284287700228, + 0.2608850767418884, + 0.14963657983574769, + 0.3078361098047339, + 0.048169749118183246, + 0.2428580692664161, + 0.09793728022179812, + 0.030031640089999333, + 0.15397068590210888, + 0.2932810154610519, + 0.3053757344454008, + 0.19511179685641122, + 0.2693966180482973, + 0.07148394256994214, + 0.12557233893660605, + 0.010133702267173196, + 0.18421307956939276, + 0.15176832357947054, + 0.04952502784442002, + 0.2642274712549161, + 0.15095580059757394, + 0.2850362831120361, + 0.09529163171563912, + 0.2272961167217938, + 0.2868432066653512, + 0.18599935518014366, + 0.19999203124646728, + 0.12547876840479552, + 0.2945041497141064, + 0.19553464611941232, + 0.234345212724757, + 0.023646286193486132, + 0.2059493634786188, + 0.2722127782088083, + 0.042981780699244, + 0.20947025202288316, + 0.07417294874098632, + 0.2161197338237977, + 0.1170514002335398, + 0.2667728142293874, + 0.04950999679480169, + 0.2930313290889802, + 0.05151972685488714, + 0.3124207085446234, + 0.21240015863285122, + 0.20504079780874757, + 0.09148293945359084, + 0.10223709773159625, + 0.12053476995236855, + 0.28421348778222566, + 0.07713928799227812, + 0.0348072401238958, + 0.1280589299460543, + 0.1682609762326081, + 0.17820152727254132, + 0.03799719141795042, + 0.12534516605711532, + 0.22496953242081966, + 0.16017011151504518, + 0.28421837750296075, + 0.13507360338444813, + 0.10994821823644468, + 0.06553558647070262, + 0.14182093954679645, + 0.20836089645051709, + 0.10604114528667923, + 0.22161394428161385, + 0.17480153013345182, + 0.1253983690254647, + 0.26052468416537666, + 0.16695573049502385, + 0.11005518945043098, + 0.20022553245421235, + 0.1776228564726482, + 0.24244943387303422, + 0.005839437180482993, + 0.19607228595098583, + 0.20954365652299742, + 0.23433783427626922, + 0.11932738451498905, + 0.07750482269056395, + 0.2272412718545153, + 0.110690914240807, + 0.10108366930760887, + 0.06691941006800707, + 0.09164151041380675, + 0.28663259488487175, + 0.15240650150816068, + 0.06373764775546707, + 0.10365286951117661, + 0.04831565311809911, + 0.1127514891437931, + 0.008822440098091407, + 0.17711697669968562, + 0.2066404889175201, + 0.16313016851197817, + 0.0856558050120054, + 0.1649684935210718, + 0.2901316439580305, + 0.2662933818610331, + 0.03477248767914121, + 0.025600578790981213, + 0.16618045457248262, + 0.05533768531850621, + 0.15747562514536043, + 0.11989703056515395, + 0.2911738573609724, + 0.19152852099013953, + 0.20310561292155868, + 0.10800411236074998, + 0.2618863541224218, + 0.05732027157709178, + 0.17323811705407557, + 0.09850975589499425, + 0.24030866807110102, + 0.17606683839537854, + 0.07394735462596419, + 0.3146588465363175, + 0.02175159149687742, + 0.10509349618632903, + 0.2633564373385628, + 0.31184608306091255, + 0.11794720624869352, + 0.18756726212184918, + 0.10855969920507444, + 0.2198558178312724, + 0.06185201504724856, + 0.037280248269146166, + 0.0231444300994037, + 0.12010475993847877, + 0.20080231924139955, + 0.2763814734092602, + 0.1783169347971437, + 0.014259622021787714, + 0.09429395194354459, + 0.02657200237869314, + 0.30158049870962345, + 0.20078437999135593, + 0.11459486224375612, + 0.14878391797544083, + 0.06641235336425297, + 0.1576596804613952, + 0.22607969815757686, + 0.1042170678207666, + 0.27950660442316383, + 0.2538316760499933, + 0.13155365962510285, + 0.29934038624637777, + 0.029437188857142655, + 0.10336324685141131, + 0.02338965779869065, + 0.12018940628111775, + 0.2651221393973472, + 0.030574695478787068, + 0.14800233117696932, + 0.022529217460263186, + 0.20631007302919732, + 0.11203003793321303, + 0.2009236247399982, + 0.023770594823861554, + 0.24403144534678045, + 0.15029179798755515, + 0.16432122139243577, + 0.10624768136218066, + 0.020576741041496094, + 0.17069588737081257, + 0.03564301194505822, + 0.010460709053018068, + 0.05582172750859659, + 0.018158096025382812, + 0.20633967021891, + 0.15842023192675023, + 0.14352724082559873, + 0.17101975452858464, + 0.24894297556482767, + 0.2834544888708678, + 0.29321860667781935, + 0.08062401740754203, + 0.31456363143571675, + 0.3205956853710712, + 0.26384578195762837, + 0.03056620837109748, + 0.01681427959104208, + 0.05298372728897094, + 0.061123630073679054, + 0.26202087347649194, + 0.20298432400749084, + 0.08077348339256203, + 0.13786695475905075, + 0.14217017820969247, + 0.08339501963655269, + 0.05745450837042729, + 0.2923549413565086, + 0.27777494079062276, + 0.2852129235795315, + 0.26414350708667994, + 0.13846877309960512, + 0.12372175321502993, + 0.32011389895616954, + 0.19413175474205005, + 0.05558184732243175, + 0.04098417706414764, + 0.19741819680265774, + 0.04659322697197481, + 0.056166188303199395, + 0.20503907377003472, + 0.16727216922631347, + 0.14274596879210075, + 0.2614179445253419, + 0.18548100726503777, + 0.032968345350135604, + 0.13159427244970084, + 0.17192878796564698, + 0.061357135627495576, + 0.28227302418906614, + 0.05336352577353864, + 0.09643801683563227, + 0.2684506135532059, + 0.02751751445296895, + 0.1761834537279669, + 0.049718077764583896, + 0.09236629009438245, + 0.049002388986036656, + 0.12495155196246925, + 0.17263412794509336, + 0.05327272844051029, + 0.07775329870820173, + 0.018269128123835764, + 0.09807475064782047, + 0.03130399876122359, + 0.23349925098818228, + 0.1816402314331302, + 0.19699504705664989, + 0.16880436097871965, + 0.1246191154745916, + 0.21112247676902787, + 0.25998572573099143, + 0.2577574507459949, + 0.21989152815357824, + 0.11862255599484255, + 0.036732332068967415, + 0.044484228577011516, + 0.2293430178193605, + 0.07336217726368595, + 0.06134843127063915, + 0.19516663666912643, + 0.08827436833901833, + 0.11810562183804588, + 0.2665472140725538, + 0.014421191367073186, + 0.08902119860119959, + 0.12162514507161803, + 0.1961884988606215, + 0.11912349342814016, + 0.11406916050657076, + 0.20699075159935426, + 0.2686723498023687, + 0.020570020578206873, + 0.15970019411594752, + 0.2111766687132786, + 0.035646911339701146, + 0.08847365768221757, + 0.13634416625177398, + 0.13805045658526116, + 0.27897996838363887, + 0.14658944669934731, + 0.16830785968074666, + 0.12112430593736727, + 0.08607891573592154, + 0.30124260433889194, + 0.26084493146666893, + 0.13539365316690002, + 0.20232948864846637, + 0.06625935994899344, + 0.21904780149214215, + 0.15485146199314406, + 0.1882702761147007, + 0.21875745405814534, + 0.03483901893900281, + 0.29695684628189223, + 0.002975317906479649, + 0.008947075483630093, + 0.08589684783935747, + 0.11010522996680333, + 0.2955549885952869, + 0.22254458308157316, + 0.18229200762539427, + 0.049064416424688104, + 0.19443143595046666, + 0.05583426157141649, + 0.2436214360807213, + 0.1375905024161023, + 0.00939477884049595, + 0.12674687318356262, + 0.11927740420192733, + 0.008459987055328825, + 0.1365443008078542, + 0.1635434446804173, + 0.2503220053936474, + 0.2296530995773307, + 0.2189839199324456, + 0.2264891057955213, + 0.1389607036394293, + 0.056866322604281365, + 0.14539082119264063, + 0.18551001575157883, + 0.10747087896454516, + 0.003893430730755824, + 0.21638835943573823, + 0.0964467736783709, + 0.2815157280046125, + 0.21479812498358947, + 0.30733932911627926, + 0.009330200444309296, + 0.02798299802616283, + 0.229748380724042, + 0.290920207675114, + 0.2702923242452836, + 0.06828411351021686, + 0.20965065809485353, + 0.08134821278255563, + 0.015059862885723113, + 0.0380043238712491, + 0.1768767904944647, + 0.2254731444652414, + 0.1804815188030676, + 0.05217100161626248, + 0.052593223034338, + 0.1456930194407218, + 0.23097460844909123, + 0.2951899020403849, + 0.08537332722860239, + 0.08248798244353846, + 0.23118238441705408, + 0.24583883150348596, + 0.13328611001897356, + 0.2281142988091233, + 0.29342263039592387, + 0.18484313268247834, + 0.2812621493122542, + 0.0726623189097477, + 0.27602217411302915, + 0.07734232585311807, + 0.09911434487457696, + 0.06218419487600908, + 0.24508078694916627, + 0.2842110004016432, + 0.011117279993152606, + 0.2691930304479535, + 0.09676267115051994, + 0.30875931938143214, + 0.19901640695110864, + 0.23214068949932526, + 0.1354218852471806, + 0.06186038601149213, + 0.23496431834087153, + 0.18243854155302772, + 0.20800627512570455, + 0.28314950662892385, + 0.23203064743623217, + 0.11170000844417308, + 0.2141261299795361, + 0.2135038401708433, + 0.2194197502753209, + 0.10549186782384197, + 0.08154473480812284, + 0.06158686081063912, + 0.03642314556408889, + 0.03163764601839897, + 0.18893237428888995, + 0.0041766657603539165, + 0.04190445128112531, + 0.053074861528861955, + 0.044585209830287235, + 0.1502359588840134, + 0.09612916654623048, + 0.005987609276310971, + 0.1627698883919916, + 0.1872397918860358, + 0.25132908979288704, + 0.22739724862090704, + 0.17877902687064398, + 0.27733546131942655, + 0.2602413738254304, + 0.14880086316286997, + 0.23205906134997617, + 0.006562673056467419, + 0.17809339996836054, + 0.24684976134773717, + 0.012057332235054487, + 0.266175656894589, + 0.14355511469130655, + 0.29744537578210617, + 0.09050287394756482, + 0.0612383091674608, + 0.1694845232627809, + 0.07198244199828079, + 0.16632580800964886, + 0.22631744983257546, + 0.04003099371566918, + 0.01902453803493442, + 0.010243281988680977, + 0.011006873909398146, + 0.11813940741246202, + 0.10336277304532301, + 0.009355251950191462, + 0.11131824583357215, + 0.25062514400384656, + 0.05873744075483578, + 0.03634208343935192, + 0.043938182547500045, + 0.280447640006844, + 0.16887932146153117, + 0.24268508778315925, + 0.13801717926771181, + 0.045815278011045374, + 0.17205876010994609, + 0.29437935114617886, + 0.15102642284265114, + 0.09390047361916616, + 0.26040578568136896, + 0.17015825653138814, + 0.18575895698146122, + 0.14294935035782105, + 0.0013082884811308484, + 0.04366674584302609, + 0.20222220546904135, + 0.17933486967183532, + 0.3053200280398667, + 0.2782980760649211, + 0.1423517184210256, + 0.07593985548763359, + 0.2032476031251692, + 0.22730188283214234, + 0.1925932331383876, + 0.1618259442128243, + 0.16013869594818755, + 0.07848494779856119, + 0.13395300859296014, + 0.1372125688576478, + 0.005463393753968767, + 0.020321537593914512, + 0.11748420487129442, + 0.10701267519318497, + 0.2426453189335966, + 0.12418779807983983, + 0.20134825330532605, + 0.29498136869613895, + 0.21031381004354804, + 0.19893857819284083, + 0.022197913367741507, + 0.14433564051012837, + 0.06374737025087995, + 0.23448600025246943, + 0.0655487354560128, + 0.03725675569219435, + 0.24570381165914237, + 0.009209651089734306, + 0.019921481157271326, + 0.25210513192929707, + 0.15705618905794147, + 0.022843243458563964, + 0.2465708165243503, + 0.10354673216063906, + 0.21841787341286764, + 0.21367147798954736, + 0.09699778259607508, + 0.2323579624049327, + 0.0702153350942018, + 0.14420369929268212, + 0.08571826549904768, + 0.23164840660133532, + 0.059430628408160616, + 0.15488558601686064, + 0.07919844232157189, + 0.004910254536827379, + 0.22145944773556178, + 0.2660762226884348, + 0.08655916934206624, + 0.15012445178061617, + 0.30119412686716757, + 0.10201175474191854, + 0.2288480424429852, + 0.211622373455718, + 0.2823770835076777, + 0.21540059523972666, + 0.1907283484737892, + 0.23970890342148987, + 0.29094046605599644, + 0.1202735783944546, + 0.2731639787538731, + 0.027599789112629922, + 0.10454433592426439, + 0.2203821439084967, + 0.18441098806489908, + 0.1888484667586659, + 0.3039876331480313, + 0.24343110206861587, + 0.14393415993468353, + 0.15726462420866852, + 0.08461384243122931, + 0.1582313104292861, + 0.2661271526121148, + 0.1409648808790466, + 0.18412307205623074, + 0.11831433385340404, + 0.00636522896289137, + 0.03987980109168228, + 0.12943450805089918, + 0.15915870978584734, + 0.10413805943392605, + 0.3004553972862299, + 0.09577415402628435, + 0.2923061136691342, + 0.1648137387094411, + 0.020712362376625205, + 0.12227577508844925, + 0.13993646398516285, + 0.0987671191751548, + 0.01763764319904014, + 0.19736004689356593, + 0.20422745382972418, + 0.19983505512243677, + 0.1682746607573137, + 0.30337601824902305, + 0.18918442794342805, + 0.3033242400270611, + 0.06355932951427352, + 0.06244055096279047, + 0.22779955420261241, + 0.1139178837874982, + 0.056117815228826286, + 0.04578647269058828, + 0.1969616712228184, + 0.2050854246349959, + 0.026302439103343223, + 0.10693405904571335, + 0.19898658076577141, + 0.07929417574541256, + 0.10115216732892773, + 0.22540900648061263, + 0.17481322523268786, + 0.04542558059751553, + 0.12951836984323467, + 0.15605994119542194, + 0.06546544238114438, + 0.19087657737520727, + 0.1941375400901104, + 0.2677237667760549, + 0.019456177700121983, + 0.0885556764718562, + 0.21741655916403843, + 0.1333230893971366, + 0.25096255909684145, + 0.005797686130872302, + 0.1657084516424722, + 0.17137456215124025, + 0.01661528169833462, + 0.0290437633128777, + 0.14605013038704734, + 0.20374069044659981, + 0.023969604108965308, + 0.2574533966109796, + 0.23121283994402453, + 0.12338536636219898, + 0.2712927641844408, + 0.0022210115661760984, + 0.13115481216914074, + 0.03870640390152394, + 0.08144826608983768, + 0.27304369548299573, + 0.1887428408536021, + 0.10705923307767322, + 0.20533705163981855, + 0.15306967349984074, + 0.3004201949504646, + 0.306357116693404, + 0.0739463074321585, + 0.13697367129675111, + 0.04120229584848031, + 0.23263452531503986, + 0.17569588216414112, + 0.08287532975667135, + 0.10849016285229268, + 0.26044872999101193, + 0.2607348424652687, + 0.21426255497571634, + 0.30853869843589327, + 0.20379818780448952, + 0.25810782940992477, + 0.09146471468288526, + 0.00928555901113324, + 0.257483659338504, + 0.0971974208561149, + 0.19496472326507822, + 0.020399907419248083, + 0.212509765888328, + 0.1464893147075384, + 0.08923247427016319, + 0.16140726847597478, + 0.15140549600546022, + 0.1370722647302931, + 0.2538518333162618, + 0.258337554194617, + 0.15340860457349792, + 0.2914402586097388, + 0.015150184013781175, + 0.18518018466190136, + 0.036838725712993375, + 0.06572762174428214, + 0.13816379844982882, + 0.20430738947201207, + 0.02319838907825957, + 0.11126247123648038, + 0.01417038680772304, + 0.24538388123621863, + 0.19882219433714715, + 0.03841166739806583, + 0.22717436695045187, + 0.21299622188190284, + 0.1355113005955408, + 0.13226712702212684, + 0.22314864406547982, + 0.19840054080770445, + 0.014341412790025846, + 0.28168969938319605, + 0.08754337764940512, + 0.02402327103692299, + 0.03382616026214944, + 0.12142258886677226, + 0.2629667857431377, + 0.08747837322121108, + 0.16783453398271658, + 0.07435739453565912, + 0.05568726124206783, + 0.03416803760745859, + 0.020027639898719512, + 0.2622799324706445, + 0.28736215891540484, + 0.0320065563112554, + 0.09042756349543311, + 0.03808894679297944, + 0.05615172101837627, + 0.19331832880059843, + 0.2043266074527171, + 0.018437795586444355, + 0.3048808236127398, + 0.15852299903924938, + 0.12796646611952164, + 0.046998292575561734, + 0.1494929895029537, + 0.046553749625438304, + 0.005269976538080795, + 0.29186363441659896, + 0.307041288050445, + 0.20469251861941584, + 0.05686713829477231, + 0.043270353976056455, + 0.0343278394434463, + 0.10268311151941699, + 0.031028104926615625, + 0.29452944426103606, + 0.008783849254838522, + 0.18681127245540882, + 0.06396690709100429, + 0.08149080593050333, + 0.19104790136280042, + 0.21641001646657484, + 0.251999434877965, + 0.25114908787522, + 0.059042982668606483, + 0.15918610806508976, + 0.029545883856686245, + 0.06010106093948204, + 0.0649621354906516, + 0.19313187193597708, + 0.11295218253682987, + 0.2093331535295614, + 0.05645774154550585, + 0.02525636101429283, + 0.24724363165580812, + 0.27898115444966287, + 0.0632701939150581, + 0.0839519825395797, + 0.0654688896310595, + 0.21060997183712646, + 0.3114027943839424, + 0.3064298906331288, + 0.2740760067030924, + 0.3195559935481534, + 0.07749792761958893, + 0.3003872213265561, + 0.23047689848276973, + 0.2136589906250219, + 0.03309972201717694, + 0.22492823720241598, + 0.201868727357108, + 0.3027758805373924, + 0.2835539502902321, + 0.24059695219903215, + 0.11138396895765877, + 0.11268856935562377, + 0.3162593442741605, + 0.2944227907665575, + 0.1351321416586221, + 0.285729484682759, + 0.24352018781937174, + 0.2376007392900046, + 0.24259154757323373, + 0.02534531865795615, + 0.13854400665960098, + 0.17557084961134292, + 0.2468942194295475, + 0.1375161616299761, + 0.16010258287757406, + 0.30656347503939546, + 0.2955559578258399, + 0.19458882208430603, + 0.21623496092029246, + 0.2904983668299791, + 0.17750765978921657, + 0.1347843526576717, + 0.24249553690851755, + 0.31402388355055744, + 0.10474312588153875, + 0.2916086024870162, + 0.14009695131171268, + 0.09709478410132788, + 0.3146843806352462, + 0.31251924582559015, + 0.3217543788821077, + 0.05362009038497432, + 0.17779542623543446, + 0.22059272635494095, + 0.11047797603414694, + 0.11840155883987699, + 0.09596107805474487, + 0.31714559826351435, + 0.11414573256640369, + 0.05870957822666993, + 0.10100868113721856, + 0.0468565233610647, + 0.29459523761616, + 0.22820683435152722, + 0.16791159156872884, + 0.32100092996109064, + 0.06416324650440482, + 0.2524845945962122, + 0.2708271697273168, + 0.3183442348728953, + 0.23944136647304426, + 0.21444311300552618, + 0.2664533606367243, + 0.15326962400640973, + 0.11183797833077792, + 0.27167414854922095, + 0.31226900466721774, + 0.11494507409750725, + 0.2468173381493523, + 0.01940562007911429, + 0.25833930103051456, + 0.1296741010061383, + 0.29261125113620406, + 0.2833732865170331, + 0.2779528744144469, + 0.06551727114476413, + 0.3120694196436214, + 0.012733616000406955, + 0.30977697863354814, + 0.1177642627579804, + 0.1368945463262895, + 0.1971052054161182, + 0.268716646283398, + 0.3166531201075028, + 0.1521523877093263, + 0.30999975419262504, + 0.23250402059549646, + 0.2983538499869923, + 0.27513773851709916, + 0.21696359231209075, + 0.022989584516771553, + 0.28778016999518197, + 0.24700827772804415, + 0.3014015918279045, + 0.16154810056900765, + 0.25670334071623085, + 0.1387915873315839, + 0.3123111779481489, + 0.2867409797560852, + 0.2921229519221381, + 0.2648812280905177, + 0.21388746537446798, + 0.2543454996050511, + 0.184015709501408, + 0.14511810952688503, + 0.07431560240849584, + 0.25793575102659727, + 0.23755417244781407, + 0.29670696545724257, + 0.2616854931899381, + 0.24825926499296788, + 0.3154672318836072, + 0.29674442141148905, + 0.19994480877630136, + 0.29606033130327686, + 0.0949134556429366, + 0.1193625965617501, + 0.3192975812854978, + 0.0697267729263259, + 0.2714865853585937, + 0.1513134068933203, + 0.2304505800903032, + 0.07900390561216737, + 0.10405214617243005, + 0.3013363549187382, + 0.3058847535883011, + 0.19383270612232129, + 0.3152064448349728, + 0.14608807721941242, + 0.190163292437463, + 0.1030171492864831, + 0.290927154202821, + 0.25085345290534805, + 0.26265971544536465, + 0.25581139696821364, + 0.19412731678336834, + 0.017818461952671727, + 0.12018998904324883, + 0.3207535276925807, + 0.04027008759771978, + 0.22607724890779604, + 0.20239078280085301, + 0.12813992081954728, + 0.2807993980062725, + 0.2172712882214551, + 0.20848987507892822, + 0.06460169595457133, + 0.11470022369523465, + 0.3113818784535631, + 0.00835575283530031, + 0.28977196947973066, + 0.2933559732104484, + 0.04233191950124811, + 0.09332430427480404, + 0.2999398953681784, + 0.11912031105275858, + 0.011574700021703492, + 0.23676271576543714, + 0.2093603432002219, + 0.009738105638666963, + 0.23155314773298952, + 0.19567810240598413, + 0.09433506694172879, + 0.2831139755765848, + 0.26030326270446624, + 0.20447322888448033, + 0.251242188393036, + 0.2543888181723918, + 0.13129495709841213, + 0.25910601954831775, + 0.09455818285529197, + 0.02179829188462674, + 0.30506565059764235, + 0.32373382923421695, + 0.2843834993444984, + 0.14885216736439083, + 0.26707348749784754, + 0.27821359836156884, + 0.14622016560562484, + 0.30137635318303774, + 0.26603360912273366, + 0.3121448234480715, + 0.08648275362212184, + 0.29957436156672684, + 0.16518615548155366, + 0.29955119365214133, + 0.1885029646084964, + 0.26746998487357065, + 0.09407521598613873, + 0.19840448697320467, + 0.28825358153625724, + 0.3172319146753494, + 0.18489760763083024, + 0.025413273413400383, + 0.02440409552295456, + 0.3123787110660724, + 0.1242578121527304, + 0.20525529317416819, + 0.2369274585590322, + 0.21593915507791864, + 0.07468696681813908, + 0.24381409597726172, + 0.16965383482185514, + 0.2369071742705042, + 0.2517307070872527, + 0.00890480977486671, + 0.22337975509669525, + 0.30883030599652256, + 0.32079831787610685, + 0.30203464841912364, + 0.30480923695126905, + 0.30018642192215617, + 0.1558120504172084, + 0.06715382248790026, + 0.2297693245468581, + 0.03864092479083949, + 0.07564206956404504, + 0.021474502822671007, + 0.16831075777137774, + 0.28929592277299837, + 0.20843981998737462, + 0.25072549238611075, + 0.30437406457004884, + 0.11168205336943582, + 0.10449991970679179, + 0.25124823274969116, + 0.12864045915306638, + 0.2892559083260384, + 0.2864302413069665, + 0.1869412964660205, + 0.153434753072612, + 0.29161682442872666, + 0.3177492150351406, + 0.0841753698500695, + 0.15342924569276467, + 0.27849502658684383, + 0.19097316382840598, + 0.09131011638938347, + 0.3030381795598993, + 0.0737192020582533, + 0.32080504139670507, + 0.3119492248129041, + 0.009945996446357824, + 0.2880727456390805, + 0.2132417917775103, + 0.31292503352710843, + 0.1370699007227856, + 0.19362965035235188, + 0.302507739684522, + 0.3040388024465033, + 0.23726920744975538, + 0.235822731071721, + 0.1268632636857003, + 0.22003886339236237, + 0.24437261862859494, + 0.2952148153177575, + 0.2131884601480523, + 0.2509013452545873, + 0.05921137287039414, + 0.1816081551653537, + 0.23692103628837188, + 0.14867168501697467, + 0.300229328066917, + 0.04942615864183684, + 0.19037973957045845, + 0.2178558635254142, + 0.2689493682540116, + 0.20319134141461337, + 0.28418605868524394, + 0.28649938922199814, + 0.32222492984703477, + 0.2784428416038638, + 0.17130551714956965, + 0.07832312206010741, + 0.2957977836672897, + 0.26489010505949195, + 0.2794233502146301, + 0.2901108403910513, + 0.22345230379434589, + 0.016528198249320124, + 0.2505246442675582, + 0.1581930690875049, + 0.272369876101389, + 0.2418219401996724, + 0.21146053444293547, + 0.1600967305756099, + 0.21431943196869144, + 0.11291814840762648, + 0.2923894893421205, + 0.19382472584270613, + 0.14350115062518126, + 0.1339013320758157, + 0.24215196756591398, + 0.32079520637755105, + 0.08593730838550301, + 0.0915671679082846, + 0.17713325891950965, + 0.1484190318951595, + 0.1742373809288826, + 0.30868613244880005, + 0.1418649873365736, + 0.20751495358259658, + 0.06974209672276267, + 0.15995283615469022, + 0.279215243952012, + 0.23066862378370262, + 0.3179232768861153, + 0.2888646828412087, + 0.01229031683083869, + 0.27089847747344253, + 0.13979191910665173, + 0.0977750248423647, + 0.07704649018727258, + 0.2099579387027825, + 0.12943339532380152, + 0.2673765385148939, + 0.2951420413229434, + 0.3229405397021885, + 0.2780049058867088, + 0.05840432065000765, + 0.3081218321599393, + 0.2266998238853881, + 0.10300699143272309, + 0.25224125990451673, + 0.22233500793699928, + 0.14646761445541256, + 0.3187669100805705, + 0.18868972208906118, + 0.2296567945774517, + 0.321199824268598, + 0.07313645094318105, + 0.29066796491633795, + 0.3222652618319796, + 0.16818706875726352, + 0.04670084583101125, + 0.12921206842572905, + 0.29040313052728156, + 0.2768763100977773, + 0.23741507852009636, + 0.132692290716283, + 0.10199110938707606, + 0.2697352970882652, + 0.11488695247890897, + 0.18827512453890075, + 0.2369804330456866, + 0.2697613592763056, + 0.2916460229377242, + 0.27322577692018585, + 0.3127526800403761, + 0.11074174805832011, + 0.15109424293374588, + 0.19833057164092943, + 0.11703933645997922, + 0.24117442550508958, + 0.05400207875676287, + 0.24527061328619354, + 0.11709469689441065, + 0.2887461464647274, + 0.11695520169397988, + 0.3144004859874502, + 0.1494560346440628, + 0.20321381576650072, + 0.24057638881870513, + 0.3121510426064254, + 0.15407552911843364, + 0.2919501990444823, + 0.2823073259795071, + 0.3119091757121985, + 0.2775292365358909, + 0.18085342670251076, + 0.2991815266019529, + 0.2238268793290549, + 0.252165557843131, + 0.16897756031987632, + 0.20907812148515437, + 0.30825539028074483, + 0.14784640636204244, + 0.1233581093577829, + 0.2737917571458233, + 0.24952016660717574, + 0.2649857813977896, + 0.2015682791675279, + 0.3143724176597207, + 0.15261381206650848, + 0.3192149778192818, + 0.13553386086914998, + 0.23019825669960434, + 0.2812262403762425, + 0.21363903422793157, + 0.2619369559437767, + 0.2481928752032798, + 0.21349802588007435, + 0.15764843707150314, + 0.3158610637176008, + 0.11246087963136285, + 0.27806004541427926, + 0.2777183131206609, + 0.025997437864934206, + 0.21241303843978185, + 0.28691888411770033, + 0.22537699392863622, + 0.3187986076206924, + 0.2808772476208797, + 0.1337180225829296, + 0.18789512812384554, + 0.11229407576833209, + 0.053428955661142946, + 0.17938781920312655, + 0.25411518282484075, + 0.08547337365259035, + 0.03736533024768326, + 0.26765662977790483, + 0.05865321226555143, + 0.12152560968592631, + 0.20998531718428676, + 0.29711819031352493, + 0.065270759439233, + 0.14561450602861853, + 0.303409161866672, + 0.29888302160993957, + 0.2471842089194829, + 0.2850433165407496, + 0.2692854590134723, + 0.2938153653873281, + 0.12896096648048722, + 0.3051883273138236, + 0.17285048483584642, + 0.050855170869212145, + 0.1598159096036641, + 0.24767228880743195, + 0.07444348000075629, + 0.19607726806369966, + 0.31095868821520417, + 0.2362380382943879, + 0.23856284623022347, + 0.13542329802944242, + 0.20232764020885616, + 0.13594623823717836, + 0.2524947974468419, + 0.2980016838805341, + 0.3132260369732514, + 0.08514678966056363, + 0.2916776537077139, + 0.18314301331961216, + 0.19984650883660093, + 0.19288157921151078, + 0.28347461969188026, + 0.2647998621487242, + 0.28626921357044866, + 0.2902710392234402, + 0.05990310586513515, + 0.2322836109233143, + 0.3172300035815807, + 0.04964135533413868, + 0.19972547785578665, + 0.221588609748743, + 0.006682076131537961, + 0.30713660614845206, + 0.04079929872262811, + 0.1929006202193605, + 0.17847781459946346, + 0.3032124136876006, + 0.1364595637317656, + 0.27456268167926545, + 0.11715466433691674, + 0.18991648498916255, + 0.09933238269008132, + 0.3070974066506395, + 0.15236574993101715, + 0.1657764142323044, + 0.28199519154548697, + 0.29476635550840047, + 0.009806743766167284, + 0.0699177276822157, + 0.24271846944118064, + 0.2586752565593006, + 0.13770929963671355, + 0.09720972105130364, + 0.21013973409328848, + 0.3007824562935286, + 0.2837992058271253, + 0.19892128634852774, + 0.3175573393435412, + 0.07670819177244362, + 0.31478592450481785, + 0.29252767184744927, + 0.13005041639342566, + 0.30546189128335066, + 0.07080382055421754, + 0.1526771104746443, + 0.32069618839221864, + 0.29340468710061807, + 0.29046932781342716, + 0.13149067854934482, + 0.2777297281982996, + 0.14002734507392323, + 0.303851634477221, + 0.1573123023071375, + 0.23850694909890466, + 0.11018484961992023, + 0.2360453692251804, + 0.09954429213804353, + 0.28476450960640604, + 0.06442719664679732, + 0.1649354157510925, + 0.2035677355172259, + 0.07459083212370156, + 0.08905134983520335, + 0.30285633788345945, + 0.1830736859682409, + 0.13243311356128304, + 0.30857932721303916, + 0.24137037218279095, + 0.1910334387630669, + 0.30714628854556786, + 0.2954137489009469, + 0.11524007618949124, + 0.14329940680481185, + 0.1892581434284247, + 0.24692784341587445, + 0.2948514748380821, + 0.29478033088496164, + 0.018531072878121932, + 0.009624495362920994, + 0.21460528809022214, + 0.30889295721640025, + 0.306135894962206, + 0.18323591176335627, + 0.2497520037352582, + 0.25020123784756415, + 0.2361565996298872, + 0.27476802132126854, + 0.14058584417475636, + 0.2975470813613464, + 0.03860271234066933, + 0.17982055933695792, + 0.09902576322449642, + 0.10942098652099287, + 0.3145123769149998, + 0.17761184527785995, + 0.024524190707169918, + 0.12874491775984306, + 0.3039619465111921, + 0.24371603148984433, + 0.20341817780913476, + 0.27045590956657684, + 0.2583691935378612, + 0.1512108557101298, + 0.07570542874787539, + 0.2334943551543351, + 0.08497129682203314, + 0.034196094406950546, + 0.2858801742901744, + 0.3154387567980009, + 0.3115853513679572, + 0.24255693704509554, + 0.28093262223739385, + 0.29188978281617195, + 0.25587648118657014, + 0.3069758410262109, + 0.1664677186718195, + 0.09188173717226439, + 0.27844903579096925, + 0.16405199740658188, + 0.15415632649495786, + 0.2778720521261735, + 0.27209581267678495, + 0.31857872662069947, + 0.2855523471513844, + 0.3121948009334693, + 0.015060280890499786, + 0.2678466674291499, + 0.025038634458768895, + 0.20377433490007987, + 0.23268579734907455, + 0.14789629147215974, + 0.20886860000755547, + 0.2565655366042359, + 0.23526015499142164, + 0.3034516067014563, + 0.3245989548431352, + 0.1979477710485385, + 0.269726266616032, + 0.25294469040819106, + 0.3114783566489416, + 0.04708332570015489, + 0.24516137230688534, + 0.22301981341581967, + 0.11608647364234514, + 0.26496468711036214, + 0.26126057793572666, + 0.13926285112139938, + 0.2863369739153583, + 0.27351261961295237, + 0.29840795594432257, + 0.11106524347924181, + 0.31270198361264917, + 0.025158125833099242, + 0.3142253548152456, + 0.2538738962422758, + 0.23630102735528755, + 0.07108252095539574, + 0.2980084890767245, + 0.3102346995249678, + 0.19138753165019612, + 0.28102208573583054, + 0.24488736306117878, + 0.05106808416666272, + 0.3031165044549647, + 0.2849445127852772, + 0.25823967181106666, + 0.2594048878081343, + 0.07753723110439574, + 0.29434250559452185, + 0.15582593574845044, + 0.24982264994006317, + 0.2922399366625663, + 0.2326403793858854, + 0.259446116703626, + 0.2527457787514931, + 0.11429486838945137, + 0.24249192018165205, + 0.0864467249803181, + 0.2585860808161118, + 0.3164024473945526, + 0.0160762332774737, + 0.2743288920821871, + 0.28969908553787976, + 0.14938661099202644, + 0.30547310497230734, + 0.24144965095637533, + 0.2680688231054674, + 0.312348352701991, + 0.21720101738092668, + 0.23053250818796744, + 0.24095937070647144, + 0.18077338744499866, + 0.25155155786547484, + 0.31015421082663003, + 0.14973846354076736, + 0.23947757570795306, + 0.23811649691390838, + 0.04038318147186157, + 0.2206460931228841, + 0.28925665474497153, + 0.058408739937004746, + 0.2546135768560508, + 0.30774493676480863, + 0.25916949143630125, + 0.30508252689216575, + 0.1047537522264308, + 0.19464211356865618, + 0.07621666713863534, + 0.2999504085775197, + 0.2868726434373773, + 0.06807100088870564, + 0.2844135214551305, + 0.18335956674063428, + 0.1420820859520656, + 0.1756953769199706, + 0.305819845748924, + 0.06946395903515035, + 0.2499064302058957, + 0.08402487189660332, + 0.030482407444550986, + 0.27053798180480554, + 0.29949000680003723, + 0.15804875866709336, + 0.18847308754085362, + 0.3089256286370262, + 0.22917219871866915, + 0.17382110673812526, + 0.13669765694745376, + 0.1092198969871246, + 0.01249490831857202, + 0.022737581688326063, + 0.17290124063686482, + 0.21220440137712576, + 0.2969628010685857, + 0.2530400890338978, + 0.22415980927817114, + 0.316428844231056, + 0.22911000960155717, + 0.28922904843579794, + 0.21658858501866124, + 0.10356507632792833, + 0.31801355333926984, + 0.2830674705601002, + 0.10771764688189356, + 0.1642012242045967, + 0.019891584371996514, + 0.14221131081443336, + 0.22942893482019705, + 0.1069109081023749, + 0.26502599235860996, + 0.19704288536443107, + 0.12509086388412416, + 0.2721472401877011, + 0.2993007155134703, + 0.19378610222740594, + 0.3077275101688099, + 0.021889859662693235, + 0.028791219386701497, + 0.31065408101678443, + 0.19876124642878834, + 0.23153106299021592, + 0.21934341666988041, + 0.04473388155761919, + 0.22913292917351893, + 0.020819662430281192, + 0.30993019007803246, + 0.29089536473871386, + 0.09599195323281659, + 0.2921349262467775, + 0.2697988971858578, + 0.1790152162395465, + 0.06770988069503539, + 0.15435792801485013, + 0.315438207242484, + 0.3159383493953981, + 0.22344415928915423, + 0.17769406337452232, + 0.10116279404093263, + 0.15427058814122746, + 0.2065538649287449, + 0.10896928330262844, + 0.24581591167287264, + 0.25807387674743126, + 0.12103117577507673, + 0.24981105034381507, + 0.20267206428133663, + 0.2337386327725435, + 0.17707869279946617, + 0.2796439097143129, + 0.2047361431370857, + 0.15957193186907448, + 0.16956834716959407, + 0.15095204588921446, + 0.2967104153117351, + 0.2892250944591763, + 0.264635525141574, + 0.20268899659876266, + 0.31303143392003546, + 0.28902704125884904, + 0.1892897692661756, + 0.2024130917124336, + 0.3018609122407584, + 0.3112649463027553, + 0.29278556106630793, + 0.25195797924624325, + 0.18644247095229358, + 0.22635451094410636, + 0.1405889996369455, + 0.26032439932237994, + 0.3204082070093995, + 0.07660203871853624, + 0.18262724725784707, + 0.1303618017722617, + 0.10331250208905977, + 0.20709531538212966, + 0.2950384494884472, + 0.12693500868646437, + 0.28623013744774556, + 0.3040325899418004, + 0.26922111539239346, + 0.04004261688100314, + 0.3095102115000658, + 0.31133999921422445, + 0.314771302126099, + 0.3118838275817921, + 0.25370515175666764, + 0.30239470683446773, + 0.20239589084531032, + 0.15143085485340402, + 0.25204538839740465, + 0.1778414284637215, + 0.2234088942772311, + 0.23268092273016633, + 0.27018099070506346, + 0.30933117098671326, + 0.21389712231602606, + 0.3019409866758076, + 0.14013328819713344, + 0.32431090941131097, + 0.30030343175333074, + 0.19604502005541602, + 0.31674605210327433, + 0.25235855524794104, + 0.2205609132037727, + 0.04011603255038648, + 0.12851894524550297, + 0.18709876599988717, + 0.10784573721126278, + 0.233170236480709, + 0.23799683051240142, + 0.039753756967053536, + 0.26605559438356513, + 0.21238230915884826, + 0.2404909272249862, + 0.07531166746797366, + 0.030514550369428167, + 0.23822803584430313, + 0.30147906556074666, + 0.22134134946944586, + 0.2721493869625097, + 0.1798286689641257, + 0.3179264607557186, + 0.26456368406206976, + 0.2670820912672862, + 0.08676767693508167, + 0.31125446049809363, + 0.3147726430088926, + 0.21810116392801382, + 0.10427194954562505, + 0.1831353902209953, + 0.06634013657718664, + 0.2238642105838814, + 0.15001268911698878, + 0.30684038661123514, + 0.32152768371164575, + 0.05986288835788833, + 0.12355756370857002, + 0.23772230351400966, + 0.12278944548669378, + 0.30647015083451884, + 0.15308429652070532, + 0.3157217358324464, + 0.17705341040598446, + 0.22160505068806213, + 0.12106646582395264, + 0.19915264020720044, + 0.3074247628734754, + 0.19856381781268526, + 0.10298184825870454, + 0.311461009671775, + 0.053364898552517956, + 0.30882387201574824, + 0.25028979945445884, + 0.16386007184903842, + 0.16361767342616934, + 0.237662929981435, + 0.07771368079307028, + 0.17644077599040148, + 0.20823096909252775, + 0.3074782951556923, + 0.045969395465592484, + 0.3145684085672134, + 0.2864543388821565, + 0.26754755068157643, + 0.2766593937022405, + 0.31958915422870005, + 0.17201170408023117, + 0.09693942498586818, + 0.2914035050905627, + 0.3054377828314576, + 0.22843184480415807, + 0.30968785496394574, + 0.2518942143828556, + 0.2099758254722195, + 0.08027188697949308, + 0.16643801189697596, + 0.30332625726552703, + 0.16031058066872148, + 0.3187605569295695, + 0.21354544437543116, + 0.31706666575711945, + 0.323781599027803, + 0.1484407270550038, + 0.10608753046226499, + 0.03855563374009703, + 0.1518729683035541, + 0.22827554024803098, + 0.17999838547538877, + 0.008128150553071919, + 0.2460488268541951, + 0.23082914304070204, + 0.3138608586008805, + 0.27575074672597183, + 0.29573465998862364, + 0.17703038107941904, + 0.16968354164896837, + 0.27624056381079165, + 0.2973891691386823, + 0.008181299109368429, + 0.05854377107648863, + 0.21221186891120428, + 0.29906227026768634, + 0.02823532962733171, + 0.14175160593691222 ] }, "mode": "markers", "name": "Samples", "x": [ - -0.08247967293966789, - -0.020482515338927153, - 0.08263861098317427, - -0.012271932886478567, - -0.1604410826051478, - -0.07538214892635428, - -0.0369448830245077, - -0.13900442403288354, - 0.12974572292740394, - -0.04160095997600712, - -0.12237320194847867, - 0.12326733343138567, - 0.09062262050774288, - -0.17552054256446753, - -0.011500744368538322, - 0.020407525795306476, - -0.14975963944587287, - -0.08863690392225253, - 0.15765888944307996, - -0.13464596042317353, - -0.03696288738855911, - 0.15239157675232093, - -0.19120429419741308, - 0.04711294988827954, - 0.08343801101206301, - -0.03622119064825279, - 0.1539325599225718, - -0.08804819939790035, - -0.06905766038571123, - 0.14465183957834432, - -0.04953268111884667, - 0.1995151407896522, - -0.16014245090938323, - -0.1270147260017257, - -0.06999878351096536, - -0.13097467065404797, - -0.18450132702197805, - -0.016102850208278844, - 0.16734182616323917, - 0.18155060951856652, - 0.11881115424483901, - -0.06050814276625586, - 0.07106789496146336, - -0.05776658855723866, - -0.04984681896171204, - -0.18090752795479872, - -0.021822514546699895, - 0.03201987702655999, - -0.14976169436196696, - 0.17830323734523432, - 0.1659979380940867, - -0.19141718925165727, - -0.05357334081143997, - 0.18312366322147527, - 0.14227815171254204, - -0.09265835612077486, - 0.15441879847802306, - 0.12192247820446894, - 0.16813576926242238, - 0.16914953763121257, - -0.16917952123884517, - -0.020806259480260603, - 0.19359462963639648, - 0.013225199167845285, - -0.13411032137547085, - -0.18987225867780774, - 0.051688722290228514, - 0.147192832712173, - 0.06641500846624561, - -0.08865328415097543, - -0.15872207464149232, - -0.15994677568375398, - 0.18565406336709042, - 0.13576836621595773, - -0.15878765529090574, - 0.1841326461719077, - -0.042592379441739825, - -0.13094024020137476, - -0.0072135801729801595, - 0.07270181823975685, - 0.013644578157872355, - -0.011681429412319866, - 0.05155899381091644, - -0.05195133637401685, - 0.12513928801293345, - -0.07300129071812621, - -0.056514470253654796, - 0.02899399476038594, - 0.04836254497051035, - 0.09195361445250859, - 0.043356300147012757, - 0.1559832910849375, - -0.15911419795847326, - 0.0838813744669662, - 0.19499439778121558, - -0.08570019139523134, - 0.04055054033779206, - -0.18934501466013612, - 0.13348930237330528, - 0.1741317489528771, - -6.213650520203563E-4, - -0.1689508208441957, - 0.10381284578236626, - 0.009764955610356578, - 0.13232554739449648, - 0.08635572674812227, - -0.017940171176781733, - -0.11310339881765488, - -0.01784687720997811, - 0.09100634891718204, - 0.05217535648529545, - 0.1648086952143453, - -0.12963612037237363, - -0.0245484846310287, - -0.010528847384495364, - 0.05142974509542286, - -0.1461297668245388, - -0.02358959798700288, - -0.017238232242101525, - 0.08874598946755752, - 0.03323436528696378, - -0.07157467498094698, - 0.05402913766614506, - 0.0676203840899956, - -0.1626338007845792, - -0.07769976384898157, - 0.11204090817261705, - 0.04073648185910997, - -0.16784324122588512, - 0.151168591588126, - 0.08830527624739688, - 0.10397534260354277, - -0.12708379088539412, - 0.19039883420377435, - 0.10083094485292693, - -8.33134731849217E-5, - 0.10527200247109075, - 0.17976139040306968, - 0.09286536947808677, - -0.024167742361664815, - 0.029821232687362368, - 0.07659991031863005, - -0.1853536089574719, - -0.13288306624834836, - -0.14085709199197347, - 0.16528042136036963, - -0.0837732425711853, - 0.19144727973619416, - -0.15316798511485855, - 0.07250141543704733, - -0.15592769847107957, - 0.05617971343675717, - -0.0637117731840065, - 0.19000691913941495, - 0.1277114413164542, - -0.10948813684755769, - -0.13983103305891137, - 0.14037698331133341, - 0.019728076621550725, - -0.19545281101668838, - -0.18812052339242216, - -0.11366134730826834, - 0.03309392205112188, - 0.08480584830281158, - 0.15376268993052372, - -0.001989802107416922, - 0.09130948526612286, - 0.09642164473826305, - 0.11282509271758413, - 0.04996329588114586, - -0.1293281330899712, - 0.1845498983085093, - 0.053232823609822094, - -0.04299431328991128, - -0.07466631963067039, - 0.01771806868661318, - 0.04134698117451263, - 0.1798614110838952, - 0.16883044012119736, - 0.14923277605189036, - 0.07540040579410716, - 0.11224043766228109, - 0.1552400776302462, - -0.1786476664452218, - -0.040944412707144884, - -0.17302265791971697, - 0.042719278820204015, - -8.408624624062229E-4, - -0.04482689770889706, - -0.12294413194269456, - -0.17103149036504983, - -0.05119357455959683, - 0.15679679751277195, - 0.08462003643108158, - -0.13217258945510502, - -0.049685567038359295, - 0.14386895193337848, - -0.14365203755206973, - -0.0998926848538002, - -0.03775707521396544, - -0.007746183316240363, - -0.14060044430767218, - 0.17075028770050343, - -0.18265563847670377, - -0.16360164399290877, - 0.023151232565943904, - 0.1000876931503308, - -0.11814816695282301, - 0.05419939355452994, - 0.020684129426403432, - -0.14687899584216305, - 0.05705124465793933, - 0.09018088702204338, - 0.038735198736703134, - -0.04044662179092342, - -0.023249089412464674, - 0.135593296917398, - -0.06448623533146122, - 0.008724986905956899, - 0.15153005342739345, - -0.13866391652311155, - -0.05811264177548403, - 0.14348962657360873, - 0.04209131518978373, - 0.0401410306887657, - -0.011330187099025942, - 0.13734241862880567, - 0.1730908903202146, - 0.12244133248337388, - -0.07651931537291184, - -0.10780230942559428, - -0.032270909860187554, - -0.01548021782511882, - -0.14428017984411368, - -0.04894935204285431, - 0.015587074264770706, - -0.13623776987821778, - -0.011784044676619755, - 0.08100112258117191, - -0.1549744075548645, - 0.12949123297034926, - 0.14714974358136337, - -0.16841610759673056, - 0.04310139924192985, - 0.08987808635555164, - 0.0613833001363185, - 0.1228472081816226, - -0.043979685127031036, - 0.0908279592480026, - -0.047355558406514627, - 0.06414878607600516, - -0.012196639958698631, - 0.04183162881579321, - 0.057008564126324456, - -0.19233816419910324, - 0.09471862080816709, - -0.13417639208492524, - 0.14286899853634397, - -0.17213622369329196, - 0.07556270786006015, - -0.16359115033801358, - -0.14118965980290918, - -0.06999755514190258, - -0.033934003255054974, - -0.1973127970561205, - 0.08168693767159266, - 0.16005818040978873, - -0.0947632802177206, - 0.18043686292873293, - -0.19163003024264194, - -0.11366050035601755, - 0.03163853838862641, - -0.18025804145371513, - -0.00794938486910252, - -0.10968048004359862, - 0.05035709492269809, - -0.09147172376832932, - 0.07866312656260523, - 0.08808704234847094, - 0.13316604115179753, - 0.1020606631270158, - -0.07472841224565747, - 0.029886331503618854, - -0.11419532471759544, - -0.10730734724713671, - 0.15470977375767395, - -0.010447678069231319, - -0.01043719927200836, - -0.17192863876843006, - 0.03099449198426246, - 0.1620403808263102, - -0.019978777549936384, - 0.11323747915794387, - -0.0015116344622499748, - -0.01674088729481691, - -0.042751418862097094, - -0.08725030737131138, - -0.09801470381240136, - -0.014866968697846216, - -0.08274159497559447, - 0.11715078502103586, - -0.08776352076117874, - -0.09268861508241605, - 0.031089333748908966, - -0.08639005204855586, - -0.020945704448508608, - -0.06621819724259809, - -0.026827710704022227, - 0.19999243350542992, - -0.11144249654762217, - 0.08074530762606784, - -0.10185204329891549, - 0.05678589605462371, - -0.05034876876972379, - -0.11460151126169525, - -0.026187041936385075, - 0.13057088006146503, - 0.15580248564318516, - 0.08665071081016536, - -0.1692572137829027, - -0.09789150171696433, - -0.10567007416764734, - 0.1642261518599231, - -0.0625719351355464, - -0.08393482847991754, - 0.0016122147576177865, - 0.13450544466396658, - 0.16288348234479708, - -0.037489873982872894, - -0.12177754891655451, - 0.18517984138452592, - -0.08509252679053853, - 0.16542928515776756, - 0.14181234215991498, - 0.0252705388429028, - 0.008058334368933946, - 0.04884298685230296, - -0.060498509549475464, - 0.09324501609080288, - -0.1351997792197603, - -0.023321725003997935, - -0.03251384438767251, - 0.028173415057550635, - 0.0018638347938056566, - 0.001001130643087002, - -0.17802845435497272, - -0.05345765409301218, - -0.09600555591366597, - -0.17403353994027343, - -0.022264751247238927, - -0.13716834173906162, - -0.06532657175570993, - 0.0310093588643874, - 0.1924655441371463, - 0.16362805869107475, - 0.07946318864189895, - -0.02471796580242556, - 0.16653473774086844, - -0.15994922670880474, - -0.06284136348115776, - 0.14388044797297575, - 0.18764268135853926, - -0.16116333203450084, - 0.10678477248357436, - -0.05698271973548434, - -0.18567496653605434, - -0.1571005707295824, - 0.11899610024026559, - 0.10594925872755086, - -0.09628850779088748, - 0.06637053837469645, - -0.03258865098894268, - -0.053521678199235444, - -0.10909245675402265, - 0.09764238106987233, - -0.18765605147013836, - 0.058719767462738943, - 0.05049514082560656, - -0.15621174702950238, - -0.07529468035356915, - 0.05990790965919528, - -0.11901874019740238, - -0.16143251402515615, - -0.07594168036966992, - 0.13194332812035206, - -0.12373276579298687, - 0.10462770731940077, - -0.0779063378507099, - -0.12768277262972436, - 0.06654308073097677, - 0.02050386287282074, - 0.06890019629240617, - 0.10162331718496838, - 0.08253897058088952, - -0.011416468637552602, - -0.07074842103339592, - -0.18063748033635935, - 0.11351159471858503, - 0.0732739352565312, - -0.0565080306675556, - -0.135483787355607, - -0.18502559847038266, - -0.004936004086700432, - 0.08838338525554164, - 0.0867085210689171, - -0.05179665780727696, - -0.1400931414526188, - -0.07147463494740325, - 0.18183112587973477, - 0.10546351351666135, - 0.12316694711057802, - 0.18380288719877302, - 0.1690323791415063, - 0.17507368696666997, - 0.19317234672167027, - -0.046764481770940565, - -0.020391346802234377, - 0.0194633394009903, - -0.15454368207146413, - 0.011240184471969172, - 0.16484952714514936, - 0.15026269246319288, - -0.14295416912496908, - -0.014829482991228257, - -0.09496558491232585, - -0.09048952641092588, - -0.08224732141966187, - -0.02179131541029612, - 0.14288273494262077, - -0.0664889733802153, - 0.13174025610890192, - 0.07168878879641338, - 0.0404314899595577, - -0.11528797335249062, - 0.009255840678819018, - -0.14729218943293912, - 0.06163752490384972, - 0.16960922984010787, - 0.10990586332395685, - 0.19085811923623033, - 0.0033737906228528272, - 0.010325830484722144, - 0.012835209121186806, - 0.13378284649574101, - 0.08884895137878865, - 0.060478329871293576, - -0.006436908449881049, - 0.11642631920394401, - -0.16669766376664455, - 0.14247704871747233, - -0.17744265180770533, - 0.1750641256933707, - 0.04020092299816948, - 0.08510746988454887, - 0.09814959308256659, - -0.08677381732482925, - -0.08629170719791603, - 0.11841533747166956, - -0.0676242831227503, - -0.13028341674086044, - 0.06046539307574083, - -0.14337065264648247, - -0.11480361903588632, - -0.006496163703240677, - -0.0590698681763249, - 0.17741675452733, - 0.1625000547949627, - -0.1737498394870637, - 0.16783692721870494, - -0.039824588582416026, - -0.09661931155000708, - 0.06838184839119978, - -0.19712462444534146, - 0.08691649926144711, - 0.17035018236516355, - -0.13065181806944062, - -0.05652251139721316, - 0.06812786470031763, - -0.13548718782715571, - -0.19695161037017817, - 0.07694839314510893, - -0.08384289028253356, - 0.13556901849201716, - 0.04225716211196891, - -0.09238103055302857, - -0.05378784339123119, - -0.13754442010529383, - 0.019488139304688852, - -0.09326555337485197, - -0.15375184283183946, - 0.1192582495772757, - -0.15662607660112612, - 0.1006510127835199, - 0.040767335960341974, - 0.0036083044662028716, - 0.14347074196218867, - -0.02057203669728321, - 0.09923723150160851, - 0.13311236804834836, - -0.09299286981084284, - -0.07330833093384673, - -0.053356788548588344, - -0.12430428661057431, - 0.0922128255026261, - 0.07047296916676858, - -0.18809968216864115, - 0.06315679358491312, - -0.17668115263788303, - -0.04415801713578429, - 0.05287477853063145, - -0.03798558244476306, - -0.1284159457207915, - -0.11984421153013225, - 0.14362223139120614, - -0.0133030062567584, - -0.18854532473263455, - 0.17531490923604198, - -0.00578045127625306, - -0.14024635953557116, - 0.1423077582590644, - -0.05087438160130591, - -0.1444654534733894, - 0.1947898832314585, - -0.01040692805732434, - -0.08156921763203753, - 0.1152818663451604, - 0.1630073109787415, - 0.13149297207563146, - -0.15101162770768597, - 0.178989919683526, - -0.17072203072973172, - -0.1337195403669755, - 0.009448164663071284, - 0.10188670207555038, - -0.029480253239550485, - 0.15739128893797108, - 0.06530136568074058, - -0.15000621703459455, - -0.059197947843801196, - -0.16127197584768552, - 0.06993501972896103, - 0.04451922907999498, - -0.060968022376539394, - -0.18661095291231972, - 0.09956465503099966, - 0.0455233370662757, - -0.02017697659037224, - 0.18756812287290817, - 0.1925498334761825, - -0.08875180757820658, - -0.033830502665748094, - 0.12450259101793153, - -0.079542189408715, - -0.048748885497290305, - 0.10522930753147325, - 0.047669082123908836, - 0.14686212868339082, - 0.010199744541534418, - 0.15568977482953378, - 0.16675394912918998, - -0.08986169893352343, - 0.1435815272482359, - 0.11837882111423796, - -0.015054191634059064, - 0.06728344459982266, - 0.007049297001724756, - -0.12566780276179526, - 0.01579867149209477, - -0.17953868442131068, - 0.06870725964968472, - -0.009704119076485229, - 0.15843404840168784, - 0.11636635082123245, - 0.18904590784981296, - 0.13616845470547584, - 0.179699649178315, - -0.18549716702249203, - 0.0664021052438538, - 0.057771861325238184, - -0.12606917536019913, - 0.0025067095443709977, - 0.03844500890468045, - -0.07176334283762652, - -0.06429821024630213, - -0.06723637857093645, - 0.0704321634644978, - -0.15621452774655598, - -0.1980266448965082, - 0.15069844237475674, - -0.09826880238469779, - 0.0067135475976204916, - 0.13239296183911364, - 0.1794932967950687, - 0.15561256238661622, - 0.12092040823701264, - 0.07709587181479437, - -0.15771870267906585, - 0.16773499000980452, - 0.07587269449699481, - 0.1523029163938575, - 0.1566677363870666, - 0.021550746597374316, - 0.10134451954729502, - 0.018680350379780136, - -0.1918957560621528, - 0.08830634966362973, - 0.19253733564168937, - 0.1846260857640066, - 0.11607839868646375, - -0.031016466626596767, - 0.09417540475825294, - 0.05597627109956147, - -0.012989756343689512, - 0.1465410217547528, - 0.11096477134722668, - 0.02011440139003047, - 0.19498396997705456, - -0.04843448746087087, - 0.1870030910399529, - 0.008434900570060288, - 0.004849070983542495, - -0.010593000340866418, - -0.04886039072520804, - 0.05965236306184635, - -0.17634038678529992, - -0.09806820616158445, - 0.17408166057724483, - 0.1509722937682142, - -0.15362054420964544, - 0.03022124052941407, - -0.13226319016287238, - 0.05483325596019265, - 0.10305576029384306, - 0.019879262290754224, - 0.14304363340993007, - 0.07669451203226095, - 0.123093019521603, - 0.054868638275223314, - 0.12536671742800348, - 0.08591240687288419, - -0.10255826665464637, - 0.0580892959516307, - 0.14032786993853366, - -0.06995779465432124, - -0.0533509663137654, - -0.1515835604952167, - 0.06424238589172374, - -0.08351743833802515, - 0.16272712647291135, - 0.16476060059191366, - 0.04086889323280181, - 0.08697117117631156, - 0.19855388762469112, - 0.04537638764841674, - 0.14725657471621037, - -0.0665147672074357, - -0.11299908261031753, - -0.06437848850369715, - -0.07945243202899656, - -0.14906425909910992, - 0.15664144303394617, - -0.06849703609595403, - 0.05940185005087416, - 0.1398234880058684, - -0.08680047123672373, - -0.06603107813801423, - -0.1617793205392097, - 0.10394409866574254, - 0.09925076643568484, - -0.08175956768107591, - 0.14186284174112807, - -0.18670760093915406, - -0.08498369690579659, - -0.10029662301588992, - 0.11685243769086652, - -0.1493117184059267, - -0.051882210722013586, - -0.14815321724176397, - -0.1859600081047603, - 0.09665994685245441, - 0.06573302492261794, - -0.09647034209671307, - 0.12172580008560029, - 0.16603982538922396, - 0.00627698287835078, - -0.17622949438515204, - -0.19226557978070064, - -0.19856455926292021, - -0.0775670732712829, - -0.042179840941162804, - -0.036587813158834574, - 0.1145606956611005, - -0.04996335582680426, - 0.17177487845363468, - -0.06811394127315333, - -0.14218543438133838, - -0.07932352793739056, - 0.03133140103278357, - -0.06046433670526125, - -0.15256974827082048, - -0.19709318566769826, - 0.13107310805308914, - 0.024710062431671356, - -0.053090086126688855, - -0.05168382421311581, - 0.1499268843415179, - -0.19247069495267433, - 0.029878561301274732, - 0.1351151481499252, - -0.043913997874173404, - -0.16012125768041557, - -0.1945603764197395, - 0.007047695241501859, - 0.018652945254781214, - -0.061821232524991616, - 0.043778054693361095, - 0.14446693807407293, - -0.011038651406865607, - -0.14940478432582255, - 0.13906427306785202, - -0.009205344480552373, - 0.04822532084009741, - 0.12909893800698127, - 0.09456489084958823, - -0.0926623957424954, - -0.13564071532423652, - 0.0756264431688782, - -0.07289555468448, - -0.1541123246057699, - 0.1566325701862063, - -0.05794723013907008, - 0.05154105151447255, - -0.03632025685089146, - 0.19476845506053247, - -0.06037745792496845, - -0.07629829212660316, - 0.03685812597504827, - 0.19444209699544115, - 0.14944166418715685, - -0.03151702694320722, - 0.0036828376652428777, - -0.055621163266258086, - 0.0031458000838905705, - 0.10450046592601579, - 0.004411623086038517, - -0.16613275687637602, - -0.052807382584436624, - 0.05390482040910262, - -0.14002041932222747, - 0.18226536941477825, - 0.15298031922046668, - -0.04816663756687417, - 0.16333615427843517, - -0.004443751787389555, - -0.17133435671774067, - 0.06822675152661002, - 0.15423411467762868, - 0.040773457562653284, - -0.061754695851119805, - -0.0677546351016938, - 0.035615083271475265, - 0.08424472564924668, - -0.0018678076302806972, - 0.11490924205204736, - -0.09426652717380699, - -0.17079762087522396, - 0.11277454313627074, - 0.1690170073258182, - -0.08171534208852346, - 0.011184388688490917, - 0.11138965574962507, - -0.07639165646283894, - -0.04409028903901944, - 0.1447990248585141, - -0.10668024698704437, - -0.16997755287336197, - -0.14642228681477315, - 0.03229761681645124, - -0.1145272121839721, - -0.059734573635081785, - 0.043404495108105796, - -0.043344914484614826, - -0.08944556648479791, - -0.12791155079320393, - 0.047420748516810586, - 0.1771780778928975, - -0.037957941599739815, - -0.02688130067591212, - -0.019279157750869056, - 0.002002022114857312, - 0.020170449794033866, - -0.0057147517391234965, - 0.16936366689443552, - -0.09297726098727041, - 0.14779837555666658, - 0.17439923925132622, - 0.013800808855300752, - -0.17935909036782913, - -0.03575068324399088, - 0.1298509867157445, - 0.11399181782720325, - 0.008049825955940258, - 0.16467164632407671, - 0.14788053463882334, - -0.059142999625392746, - 0.020820128910396793, - 0.15350444046713976, - 0.07543519913045535, - 0.05962082139999774, - -0.024907920707967827, - -0.012908877665177974, - 0.08775586090615571, - 0.07243109269227174, - 0.05186998281821354, - -0.12144892524322878, - 0.13355015400363277, - -0.13962643152461657, - -0.0021912105588980423, - 0.06721956963152309, - 0.1150417502141627, - 0.13765682427540935, - 0.023297695985928013, - -0.1431423227374085, - 0.09171576028048041, - -0.022999160927345403, - 0.036865509155320005, - 0.10249011974989192, - 0.07804063040097721, - -0.18253083780512575, - -0.03883965561803229, - -0.11989570295941962, - -0.029830669928917048, - 0.08292847302697605, - -0.10528753577648123, - 0.062320574655773495, - -0.1548653864468851, - 0.021651538020387422, - 0.09152167227979914, - 0.052253340293318566, - 0.17285103450889316, - 0.12416276231723594, - -0.0019527062857964872, - 0.13276497104645707, - 0.03160184160824676, - -0.07433079241013368, - 0.035492870303201966, - -0.13437716626630264, - -0.026352472038074948, - 0.1894004147281888, - -0.07039604620913562, - -0.18594838008282885, - -0.03135192088843926, - -0.12205254402893567, - -0.14741119895351376, - -0.04270272360671232, - -0.1444732017467244, - 0.16742049084123792, - -0.013587013900117588, - 0.14672364188849085, - -0.1919575857131047, - 0.1844213825904442, - 0.02949091078494092, - 0.16067323473632458, - 0.06539055786181909, - -0.06870455821798349, - -0.07773780352146299, - 0.0698745216257695, - 0.003057092002144598, - -0.1330850699760688, - -0.1802735314287382, - -0.06601671880099365, - 0.043667593597985936, - 0.1415800855306049, - 0.13567855385565153, - -0.050829311113283974, - -0.011696466554001838, - -0.08906628240587072, - 0.022928653910479845, - -0.10062067575554358, - -0.09264612361082303, - -0.1920010200119742, - 0.1297094185345251, - -0.0476097044241243, - -0.07414079584647859, - 0.05784942430715212, - 0.1904573464268375, - -0.08958197586803157, - 0.05722180537712204, - -0.17814768584981566, - -0.1326677288406763, - 0.1913861478591581, - 0.04410987757240072, - 0.12960020868304598, - -0.13361299140171504, - -0.10482491455277403, - -0.16723442878874462, - 0.18611595732794134, - 0.09777781978436702, - -0.047977165734023546, - 0.12245436975736568, - -0.15571453939077623, - -0.04739028567389503, - 0.13074923249393353, - -0.13417413894775074, - 0.04500002312738295, - 0.04916362089789503, - 0.11371300592310035, - 0.04496041225736392, - 0.007936283635131458, - 0.634256009464736, - 0.736769297494647, - 0.39972332402693, - 0.2202596736677956, - 0.5014222104108335, - 1.419997538266117, - 0.4664007516088313, - 1.400574242314705, - 0.9915932735567312, - 0.2763673358769762, - 0.7177865001631408, - 0.20461589145950113, - 0.595554858737168, - 0.4842766229162955, - 0.5215307207264069, - 0.5272633264665253, - 0.480689349191689, - 0.3186459548789576, - 0.6924580501709519, - 0.7733965710399601, - 0.5614828738933838, - 0.9257991550108425, - 0.4305056299219265, - 0.6918203270047119, - 0.4799385274032942, - 0.7630024218071374, - 0.26318563673328854, - 0.21073360493412782, - 0.7256301797044409, - 0.3731639668402714, - 0.28262795860110934, - 0.24404385754796123, - 0.4769383705936377, - 0.42974709501913166, - 0.9411471263742903, - 0.8230824446388507, - 0.4514452795199267, - 0.26888192242992903, - 0.35266064002712305, - 0.5399297764032079, - 0.8998122598713819, - 1.0372807393445578, - 0.4421255332259029, - 0.6111526079306036, - 1.2429370193843887, - 0.4606730378253188, - 0.8314031259004974, - 0.466309623245995, - 0.7210681442471921, - 1.074324254556125, - 0.31994479841973045, - 0.8152990692742894, - 0.45044521055501663, - 0.7974421557052923, - 0.4697901446974986, - 0.3134154900785992, - 0.3907462401013725, - 0.3580289300117948, - 0.45275070271869344, - 0.8951720066482213, - 0.2003982851969111, - 0.5839107587148833, - 0.28191972166323304, - 0.6190520224681723, - 1.1336874237248014, - 1.3406200613729418, - 0.21915958257151683, - 0.6846241021708291, - 0.7291341531416331, - 0.5416281055251689, - 0.7434472988792892, - 0.3249891827091247, - 0.3455061654207278, - 0.6081322722869719, - 0.48051542340024356, - 0.3763971684956674, - 0.7399128751571712, - 0.3208090601994198, - 0.6562572171493704, - 0.38766400819524827, - 0.29808884719301254, - 0.5333932694265564, - 0.6563348513934647, - 0.6410571218571501, - 0.26696022780503204, - 0.8083027680824931, - 0.9499772274290701, - 0.20254847061138434, - 0.5545363912714816, - 0.24886112879358005, - 0.2126159372129759, - 0.9187840104624566, - 0.5777620497563973, - 0.7929054200675741, - 0.44773124200792835, - 0.933727303324389, - 0.2322441147721302, - 0.21635959157461931, - 0.47879552156291144, - 0.8688657392957164, - 0.2863562064860622, - 0.2494144212608869, - 0.46930569888834256, - 0.5279314961463252, - 0.8319033399405131, - 0.20149359860547023, - 0.32254358454824905, - 0.3831585576437976, - 0.6810087791217984, - 0.3612168401809209, - 0.33398030186183825, - 0.4247314011449587, - 0.9233206830600351, - 0.7589360265006363, - 0.5930413874308283, - 0.8541317115154969, - 0.48629232102245257, - 0.30679209797340307, - 0.3329623451037095, - 0.3045454092599363, - 0.44712716098489064, - 0.511184724233385, - 0.84185906535748, - 0.521931591123258, - 0.3056732134485201, - 0.6436350137782337, - 0.6993487351503116, - 0.7025168441783055, - 0.5898591195717126, - 0.46290326436591495, - 0.6427675433515221, - 0.37562965640993723, - 0.5926955652483495, - 0.49390037263811293, - 0.23006017689414213, - 0.6691972847947409, - 1.1139987116426133, - 0.7427335413112843, - 0.20987599884969718, - 0.44828400358427417, - 0.49237825758941917, - 0.7047281439909464, - 0.8378213745376444, - 0.37956834634479647, - 0.4740282960266631, - 0.6584781933938578, - 0.2252339645135759, - 0.7073231547702948, - 0.6482536171072482, - 0.33140552416336316, - 0.4529552866186449, - 0.5732438436546764, - 0.2260541406868626, - 0.42823082956651776, - 0.3690907553873188, - 0.5678005159953958, - 1.0376076544532171, - 0.21683003569407636, - 0.41064506828167924, - 0.2102190553878134, - 0.6293390247024151, - 0.5317522066421627, - 0.34481660928837715, - 0.33161642120839113, - 0.32357206227446694, - 1.070620960324434, - 0.3461047002722959, - 0.2675000511235706, - 0.34565954096522933, - 0.9002706840169078, - 1.4116479663027264, - 0.6920058975702595, - 0.385717970596439, - 0.24772589912179308, - 0.3445069567709196, - 0.38150193191228177, - 0.43930089255897664, - 1.1207936578455375, - 0.4762549759689785, - 0.37590732204347105, - 0.5776652786237652, - 0.6553873790165112, - 0.3046709802716182, - 0.4147357342526921, - 0.47768248519968887, - 0.2744330608012301, - 0.8363495213881982, - 0.6223979556902343, - 0.3962313803710227, - 0.6158628139959157, - 0.37975360911040207, - 0.6542157005233821, - 0.5635080857858316, - 0.5142740965176485, - 0.947896868978972, - 0.25124017968131857, - 0.6350249399002579, - 0.4348000494537825, - 0.5055199463785988, - 0.998844856541317, - 1.4021140436905237, - 0.39440718009600284, - 0.5369364322864422, - 0.36473915932139234, - 1.0799034125769236, - 0.503305666968446, - 0.6911994548153466, - 0.6082374816961457, - 0.8899476617311071, - 0.20094205217834354, - 0.24112416271269735, - 0.7855673385130142, - 0.7861395977716654, - 0.7214210886309756, - 0.806523813789324, - 0.2599631245155391, - 0.22137602893723896, - 0.37704368386903603, - 1.6062234108689482, - 0.45154100651294693, - 0.2661997706501123, - 0.8358935220286057, - 0.39098633125284027, - 0.7727785592028728, - 0.5617750538106723, - 0.21394105635377786, - 0.7583422587790445, - 0.5978194301942626, - 0.45396930132195773, - 0.5262750019672782, - 0.23117358607644836, - 0.6880824343673113, - 0.23722151170859979, - 1.0328041956364733, - 0.34561687112132733, - 0.6855048638101005, - 0.2916592436764588, - 0.5821370331288173, - 0.20923676874931577, - 0.31374999697980654, - 0.7288619387050672, - 0.5291098866750868, - 0.763183892618063, - 0.37506104699526877, - 0.3176634080215647, - 0.8229502109622159, - 0.32521704276526264, - 0.6358186078469741, - 0.22210356484267327, - 0.4432254533151105, - 0.84523761189082, - 0.857188294112302, - 1.0818851596827872, - 0.32459145344735346, - 0.4135025905722868, - 0.6405565205053048, - 0.22762370814132443, - 0.3240992178112207, - 0.38586093644405883, - 0.31239004350896044, - 0.7248675371894163, - 0.23657862289076198, - 0.5957022748692821, - 1.012533031025015, - 0.8282995593512681, - 0.2154277632120922, - 0.6606107424809893, - 0.5201347450621558, - 0.6425772850677394, - 0.449098638450262, - 0.7330918924459819, - 0.42933533779990096, - 1.0173777392841887, - 0.21451332753439512, - 0.21048552873389773, - 0.44846882422507695, - 1.4262622112728918, - 0.2296276414554153, - 0.2444023816344618, - 0.5719082312298379, - 0.3436042862495808, - 0.24593616206704658, - 0.34444200267818775, - 0.5631854079784208, - 0.6760355034989408, - 0.37849020027558433, - 0.275755383744943, - 0.24162180628202948, - 0.6395758401940418, - 0.39305010270708096, - 0.29863770442664145, - 0.27055871391874514, - 1.3398716181198862, - 0.6800760033273014, - 1.1284966449434974, - 0.24020668783846255, - 0.8284125793518783, - 0.4232226188916261, - 0.5368594927318557, - 0.5184796709182897, - 0.6496171134530287, - 0.44571211034747044, - 0.37021639370877385, - 0.5506387670783621, - 0.4821849620155024, - 0.7490506572454038, - 0.7429352271479697, - 0.6581210930773547, - 0.6107272397609824, - 0.518376275184519, - 0.9804480817343506, - 0.39571079393721764, - 0.3524688207580026, - 0.39949598807898035, - 0.5616892980553098, - 0.9313453825732377, - 0.4810778533901489, - 0.2996877844305985, - 0.6268230770056443, - 0.20260509571041146, - 0.8828867211143421, - 0.3761232751126954, - 0.2040296598918269, - 0.7925941760289024, - 0.7459914940892686, - 0.41694922026834874, - 0.476675961618671, - 0.46330847132909225, - 0.7543678825217437, - 0.6797290094229408, - 0.25241824663887236, - 0.30285805236351826, - 0.8347834685626516, - 0.37473011500535164, - 0.43159961810836234, - 0.8296923525950415, - 0.2471104607440809, - 0.22734778762175445, - 0.2722691158135733, - 0.3837090743919713, - 1.3847839543232883, - 0.9613674370298912, - 0.32620024391220587, - 0.551863596881256, - 0.24763069309651403, - 0.4222358753993424, - 0.4076282620269936, - 0.7547299357994931, - 0.5340629978238842, - 0.7867420099508058, - 0.8019049324985525, - 1.3932951451395728, - 0.6485173692154461, - 0.7522378183430231, - 0.3540924605672005, - 0.3598955373155058, - 0.23692549529320323, - 0.9043224674829536, - 1.2084777640115265, - 0.33911874451848045, - 0.9242229983070934, - 0.5981387783535395, - 0.8633422504636756, - 0.5317034278267212, - 0.375892314457528, - 0.5005761411391029, - 0.22125118918006698, - 0.3874046193102501, - 0.9047813470950474, - 0.3715720676936528, - 0.42381513728108045, - 1.031680590023362, - 0.41226101273603005, - 0.22583008034911536, - 0.34782143407560157, - 0.3369391792981257, - 0.21688220872318079, - 0.4995469129591281, - 0.42103892472573357, - 0.49140393469063504, - 0.6359836157805729, - 0.5760593704541431, - 0.34592121245973023, - 0.2503068435572268, - 0.21054576886823456, - 0.7396768886016951, - 0.8725088136120321, - 0.987372478904763, - 0.39525300649076006, - 0.31041090187545706, - 0.47606252458781134, - 0.9318991357324738, - 0.3760644729917732, - 0.8398180043989046, - 0.8372331964820118, - 1.054476113880961, - 0.38765005810038233, - 0.3894560978865284, - 0.7487995023374058, - 0.8578317238950135, - 1.224420624504845, - 0.5104197269822726, - 0.7832211961932684, - 0.6070710895780518, - 0.5009213313798011, - 0.4854501018310396, - 0.526345708934175, - 0.32623356376664625, - 0.20018904823758446, - 0.46253766671146385, - 0.7784336939387895, - 0.26934191751587394, - 0.42291278878529914, - 0.34735283962026836, - 0.3116300972361871, - 0.6374925161462459, - 0.21831998781712608, - 0.20231366176004015, - 0.5165441859268617, - 0.5554515421406321, - 0.5208165080991551, - 0.8637448521180895, - 0.3326351259680587, - 0.4373320183767071, - 0.28673928298532964, - 0.754398289524024, - 0.7870334304687068, - 0.25102638959232026, - 0.24348191243358278, - 0.6884808546793747, - 0.5820355152962473, - 0.3068699396830244, - 0.3196568311939234, - 0.4093692405840534, - 0.2866372591996242, - 0.3938628981656929, - 0.21822007517421937, - 0.5583454617599964, - 0.6841828961708137, - 0.48967118916027164, - 0.45578945597139514, - 0.3942367125872493, - 0.4572299273966072, - 0.2931648087176154, - 0.8069774461469637, - 0.23966760147158153, - 0.28003124305762334, - 0.3362400509042878, - 0.7595065531090445, - 0.2305669118174929, - 0.3904343344543396, - 0.7992685126524786, - 0.23118433505274386, - 0.5851903680529191, - 0.2946253677037036, - 0.2243906020253013, - 1.2885960183518785, - 0.2058608163278584, - 0.5157754138022863, - 0.6371122751467463, - 0.20936623955462025, - 0.2388314474387968, - 0.8085430548375921, - 0.4770017411464131, - 0.5033494070735582, - 0.2841106956119234, - 0.6531402953793822, - 0.31151521175185953, - 0.5681598305575295, - 0.5009231702282039, - 0.8152033024669362, - 0.3311528155441492, - 0.26236568491586587, - 1.173086600446832, - 0.27578846599547857, - 0.5329438189471373, - 0.39463025902591065, - 0.4268105798406184, - 0.7487186905806756, - 1.3474873396249654, - 0.27141181298513445, - 0.31540129063836503, - 0.38764828782105926, - 0.30581962862116097, - 0.5680858481000634, - 0.5079358682689147, - 0.35345818827447106, - 0.5621584051325494, - 0.6209713236241372, - 0.9836322649793464, - 0.5397253795349227, - 0.5982650366907528, - 1.2510997919686424, - 0.9094903784138292, - 0.6853506018068416, - 0.8029743737405757, - 1.1242754238607207, - 0.9247324629484314, - 0.6032924483207096, - 0.5637037316275196, - 0.33135861970924885, - 0.5217705386514522, - 0.5374401183201967, - 0.22744888511476152, - 0.6728056429802979, - 0.44115171943888537, - 0.6230226003102581, - 0.39162792233856464, - 0.3842364318228443, - 0.2563726384872395, - 0.888007377786039, - 0.7402975609140281, - 0.534216123952576, - 0.9582888973340794, - 0.7381080940191246, - 0.24264223232012397, - 0.28484451288181384, - 0.2588305882507817, - 0.2393671624825806, - 1.2205882439905007, - 0.5612066097215936, - 0.25130278287087265, - 0.6982118906680883, - 0.2763291386174774, - 0.6623833138769977, - 0.4630146075683296, - 1.2735043966647646, - 0.3815801452352516, - 0.3684240185026086, - 0.5471585939733067, - 0.25059813640841555, - 0.6898235039106502, - 0.6729181318887946, - 0.5976559501044378, - 0.3273426863907327, - 0.3245324937723628, - 0.7143836966291579, - 0.5695752982354785, - 0.2333293896316046, - 0.3609719055678925, - 0.27665138288906854, - 0.6099599916630724, - 0.4440063524192072, - 0.33333387852338037, - 0.2568073371741031, - 0.6769525202824105, - 0.4178873126323742, - 0.33124728509380325, - 0.7961041586818602, - 0.4745278435151123, - 0.7606256086943418, - 0.2514306031998429, - 0.5483722032151825, - 0.8010836072425834, - 0.46145429346134004, - 0.2965534258065352, - 0.3789124294987536, - 0.7995226546247434, - 0.7339931087778598, - 0.5853090281596784, - 0.8992396264003039, - 0.4399938201639524, - 0.6559315089232508, - 0.6563984631291699, - 0.3092352842510641, - 0.5695346773826799, - 0.40636268497454553, - 0.7251583143892132, - 0.9326569149800392, - 0.3882888503638098, - 0.30706051351218955, - 0.7637709281229245, - 0.4168001847176278, - 0.30312152477182425, - 0.6625763191878041, - 0.5813125892663706, - 0.4068361065129343, - 0.9240285295116516, - 0.2540432504403188, - 0.5006487349193429, - 0.8357492451985011, - 0.6114522685279914, - 0.5803267930636863, - 0.41436505140849295, - 0.6304851826941116, - 0.5788238211852843, - 0.8713957914032563, - 0.3584815602975139, - 0.6128077862500066, - 0.9049783550285448, - 0.6909354456958375, - 0.2980938148066902, - 0.2143666984651162, - 0.5798436049316485, - 0.7731582031327372, - 0.6455963025069962, - 0.66691752752091, - 0.339593074094132, - 0.33268494199573445, - 0.27943937081099257, - 0.4283217907213458, - 0.4441034288221615, - 0.42253364394365367, - 0.8336768415252623, - 1.0898075107675187, - 0.8100305415186373, - 0.2928935895363843, - 0.23494822285442749, - 0.7089714743781416, - 0.5775655234880605, - 0.264961593678971, - 0.4255684164622174, - 0.314932324095991, - 0.557391075550699, - 0.6237880689907225, - 0.29783404611523395, - 0.6170250312949758, - 0.3304716274939081, - 0.23090030803575826, - 0.9618732486093187, - 0.3726853216404911, - 0.653186861503025, - 0.5104372710972195, - 0.4589912945213816, - 0.9544673902503745, - 0.6187659698997405, - 0.27763450654771243, - 0.7579663819037437, - 0.7361076546617333, - 0.3212860112183528, - 0.5148467280973842, - 0.4094271032289277, - 0.6515188386555952, - 0.9404498241033918, - 0.6419453914846117, - 0.6109429231601814, - 0.6173274569612465, - 0.5045400905240494, - 0.46869989277152174, - 0.5290147699648651, - 0.8530756002174575, - 0.20494279303311216, - 0.4454928390283479, - 0.39045394937082173, - 0.423205478748963, - 0.46416809033333345, - 0.5589322861491016, - 0.8465899377006573, - 0.49913458859444454, - 0.2169230517434646, - 0.9003268807793652, - 0.5122093566478548, - 0.4499964545462343, - 0.407135370886647, - 0.5611669093853374, - 0.22286343335938194, - 0.6717075030791791, - 0.20251932185386673, - 0.8581713496757928, - 0.7753510199294384, - 0.9894394571905226, - 0.2675197914726363, - 0.765449886208478, - 0.609989139196308, - 1.0189500563683274, - 0.21934882750095477, - 0.5746627226023732, - 0.25990448866956417, - 0.3956435605580122, - 0.4001093351213786, - 0.6842615948656433, - 0.6449426442186793, - 0.3300394759938137, - 0.38339554841891943, - 0.5708109342311176, - 0.515720528287805, - 0.6619089080679674, - 0.31762614973596637, - 0.4784096706628216, - 0.37638509403882653, - 0.2232286276141411, - 0.703617800161686, - 0.691126465574492, - 0.4448084316340139, - 0.2758745362445847, - 0.5236570240132802, - 0.4649726100891944, - 0.3215470044981429, - 0.2946983577624051, - 0.665264708897942, - 0.292817412319122, - 0.21256319577980748, - 0.344134493103508, - 0.7717010451998335, - 0.39266641369466926, - 1.0533244695230635, - 0.4004900946259121, - 0.6890115161263765, - 0.5658274430913549, - 0.3335313683037575, - 0.6736297335784447, - 0.7417108572975801, - 0.6461211277721175, - 0.2270366908604925, - 1.0029007006947817, - 0.6761558725932689, - 0.27420488211893723, - 1.1220200215938718, - 0.8258368595850032, - 0.43745136292917647, - 0.47862221605578575, - 0.9360849082109401, - 0.5854022128730432, - 0.37058176101647955, - 0.6102394176070718, - 0.32589709991082616, - 0.9324939816831531, - 0.3704850985814619, - 0.28336182105338986, - 0.2374409097875485, - 0.4612996609362457, - 0.7439349235738071, - 0.3500436448528084, - 0.3026138119715174, - 0.8491718574476186, - 0.5699683886578358, - 0.22775603371103414, - 0.37050677540195986, - 0.20575010159816096, - 0.9379783176207629, - 0.8669948753263261, - 0.37935860413182165, - 0.42361400502976715, - 0.31631246362246157, - 0.8658848580559388, - 0.42242611393032226, - 1.1013702003437622, - 0.3191562789746356, - 0.7062554761143212, - 1.282552570161006, - 0.21952664865982388, - 0.35273469867400803, - 0.23571606739920825, - 0.3637383882453607, - 0.5109884861716116, - 0.9867112679640834, - 0.2476103564043496, - 0.43735097358394187, - 0.3548718009341618, - 0.4043959592982137, - 0.8926888919592307, - 0.9967786127375851, - 0.28800232673554327, - 0.48979565821208093, - 0.5523236667188721, - 0.5799965616049054, - 0.2582721179078014, - 0.4027657792415097, - 0.5122175215951512, - 0.2460055817693416, - 0.31587992771556467, - 0.7543864805071527, - 0.439649707752877, - 0.40187808722804097, - 0.29532647302374265, - 0.42515093902476425, - 0.33970028008313735, - 0.6033964980935979, - 0.31690839097122026, - 0.33290575543333717, - 0.37412178588427464, - 0.39330747528892257, - 0.4853201683109622, - 0.8695190205851738, - 0.4787857325806995, - 0.2492373500275203, - 0.43050049943640617, - 0.2946659042575125, - 0.8428568924096137, - 0.8507689549786529, - 1.1057395981625266, - 0.2199425406635274, - 0.49655457168084577, - 0.643694957595014, - 0.2763334679157249, - 0.6188064559157895, - 0.5836589925409408, - 0.3353762580807183, - 0.908609263385983, - 0.2761078980192169, - 1.2429403187798274, - 0.24832822802981114, - 0.25802831708176355, - 0.6274147654122172, - 0.23132919459065004, - 0.302682051430395, - 0.3194128868551814, - 0.3843252664680756, - 0.5886905270061022, - 0.45414111132280566, - 0.23724891142287216, - 0.37974688466044326, - 0.46046714203564815, - 1.6130314951576832, - 0.6462157207057807, - 0.5958265357624346, - 0.5168363489243817, - 0.32878978367015405, - 0.3765975882974893, - 0.4408476357251095, - 0.48815806650205246, - 0.5520305206871241, - 0.5402482329330549, - 0.30972350962789486, - 0.5208668756884507, - 0.7687124678372449, - 0.2568202642536032, - 0.26470022665102144, - 1.0000138046307827, - 0.5702259605137092, - 0.6997540402975931, - 0.6717998627940173, - 0.6275855054914751, - 1.3395953861139909, - 0.3131755523105054, - 0.25502255517651, - 0.4783922745463344, - 0.3476555292169019, - 0.4181209214869909, - 0.7565544751252636, - 0.6127567747291667, - 0.7466815797485429, - 0.591547364520142, - 0.20205961217353216, - 0.4652302822934863, - 0.23453978172785794, - 0.5154531413324699, - 0.2656096423035519, - 0.6670800280928332, - 0.4029225167221599, - 0.3710678536932373, - 0.43982109833213145, - 0.38676651856292416, - 0.6978363175349477, - 0.2594159546770344, - 0.7485363173982265, - 0.556887343869877, - 0.45538033111293696, - 0.6840085742875884, - 0.8735015397431746, - 0.5753925741791134, - 0.6937803979048226, - 0.23253211794580564, - 0.7204780411484871, - 0.5256235394531966, - 0.31568111137329885, - 0.5789480814743941, - 1.1463954549153565, - 0.6717928840994248, - 0.22203711022876554, - 0.4020922481517024, - 0.33255161286468365, - 0.42580316580505423, - 1.1191030080347717, - 0.2948985386885136, - 0.309193635919495, - 0.6139568263588312, - 0.33472732176306785, - 0.2966851479309438, - 0.4655479073899203, - 0.5455649078760236, - 0.6019031722261328, - 0.6809062356249275, - 0.33435525478538997, - 0.593690492121696, - 1.0176878187660998, - 0.2971519520832842, - 0.8106589816704636, - 0.28833294576045276, - 0.35168756716732763, - 0.9590106183774619, - 0.5395592527342759, - 0.44681570798979914, - 0.45045727582491135, - 0.7231864625178303, - 1.146184456515412, - 0.4007431053781894, - 0.22062834484716212, - 0.758427632043504, - 0.36359330502669657, - 0.6732914759418408, - 0.21098898573873243, - 0.37891967226233353, - 0.6630255037663279, - 0.5365168716116363, - 0.32714989255566035, - 0.9115258684939088, - 0.5956306422935136, - 0.21400194913331666, - 0.6032106721737673, - 0.3741322217158704, - 0.22267652829931928, - 0.371084021853645, - 0.8527709803443005, - 0.27010016357751354, - 0.34096713630047387, - 0.8872555362031043, - 0.39368457494865766, - 0.3480452905520136, - 0.5459963062113197, - 0.4209365017197753, - 0.5674466547227011, - 0.5239470215107488, - 0.2978960274226041, - 0.5887819982731205, - 0.2685420834862011, - 0.521369157820792, - 0.49285582215670737, - 0.31199620310957404, - 0.22937294422816296, - 0.8277945199202261, - 0.48875432922874656, - 0.21358420168369083, - 1.1866604367301359, - 0.7979733864874137, - 0.3159036009953701, - 0.23301623960456472, - 0.6465483259306577, - 0.8830511344733778, - 0.4405558122754855, - 0.7799370896551044, - 0.4551118989990317, - 0.7922373535742645, - 0.22493827804605776, - 0.4683701654478829, - 0.4958816027912315, - 0.3512582365627345, - 0.45394031693976744, - 0.6926349631334944, - 0.2076095968274677, - 0.5119766907096587, - 1.0066146210320506, - 0.421398574557307, - 0.45581559859364995, - 0.7096670012083918, - 0.37392265733712116, - 0.3809407085082209, - 0.2054484427394068, - 0.4128346506345432, - 0.368685839339786, - 0.9769034517258816, - 0.7508281227162906, - 0.7101912234263209, - 0.32283490176033464, - 0.21656227712454273, - 0.4270218735996759, - 0.21339894361749076, - 1.085527763698224, - 0.47287136051485973, - 0.4955588633037599, - 0.32637634451599007, - 0.31424334641783996, - 0.924676031771503, - 0.9914810728185511, - 0.2403510423222428, - 0.3253261265555911, - 0.4963752159905608, - 0.5866155124581109, - 0.8078338803167114, - 0.6994082553490429, - 0.9736424514793082, - 0.5475110963397407, - 0.3085154145819838, - 0.6369102454761296, - 1.3511544980014663, - 0.8164804548956579, - 0.915318523549312, - 0.38718698285091835, - 0.3343430259422821, - 0.4081948429534073, - 0.8495152938165748, - 0.4102494456018234, - 0.4198955817226142, - 0.2667996260314239, - 0.2683192474850844, - 0.5057189072820082, - 0.562552864267602, - 0.7456335235933137, - 0.33183498602199907, - 1.9326343841924167, - 0.7045865787776053, - 0.3670207427633647, - 0.29696263385049537, - 0.25831983569994477, - 0.5533515511812428, - 0.3000472303171149, - 0.5965817543296055, - 0.49113924400265774, - 0.30726529668511005, - 0.25173444451439086, - 0.5112757242767652, - 0.2734183663103912, - 0.5093465554830099, - 0.47058659970442185, - 1.1151143990616836, - 0.912873257683388, - 0.498030001691574, - 0.7566722487224559, - 0.30385725757166754, - 0.4219859150788975, - 0.5191340067613105, - 0.5395805648208936, - 0.7860230434825595, - 0.8836409207887023, - 0.6101466184426669, - 0.9421901459636197, - 0.8253925629719625, - 0.20846310261883633, - 0.60287929276841, - 0.8411123168610838, - 0.23073543881358782, - 0.39081715680025575, - 0.7837670264184768, - 0.4046510867123998, - 0.332539872756823, - 0.4278140980738739, - 0.5890609570062159, - 0.4323668359259129, - 0.5602265300171625, - 0.2967135547210504, - 0.7021265910400895, - 0.4670813965863367, - 0.37611361786715086, - 0.9225391602261578, - 0.3991624071303601, - 0.5013757881173047, - 0.6285084598682045, - 0.3739502696409027, - 0.516455220770696, - 1.0657363360858039, - 0.6488562463459153, - 0.6064830082698189, - 0.28209711325582854, - 0.31823808865400305, - 0.32358512258925787, - 0.41725723331187947, - 0.6271294917790421, - 0.39687316560475366, - 0.49745501080752613, - 0.3221433505781183, - 0.2389601312024824, - 0.3080935938273269, - 0.7956235012974484, - 0.2144201789438125, - 0.852237166683627, - 0.3280087016631628, - 0.737541620471629, - 0.8113993808886489, - 0.5112229248973481, - 0.3502439732121183, - 0.21109046885959165, - 0.7045557075927076, - 0.4721448087245748, - 0.476251481268672, - 0.9139518273570636, - 0.2831273665932976, - 0.8324961885826925, - 0.2871974099385633, - 0.8862824677763708, - 0.46337477859793946, - 0.23640866632597832, - 0.7462856280464687, - 0.4130203461734826, - 0.39359574003824455, - 0.35746957929903417, - 0.44391878574019666, - 0.6574249187230875, - 0.45055241556205167, - 0.22354478258680305, - 0.7998339011144805, - 0.29813159496251734, - 0.3490800822904099, - 0.7454910053769035, - 0.543424985155833, - 0.26829443890439597, - 0.20005921795508508, - 0.3488316806563525, - 0.7996002288349501, - 0.5941479162150175, - 0.86632414716925, - 0.23321965322736438, - 0.4146454958234439, - 0.24937902786750316, - 0.6448186971961011, - 0.32338042108948223, - 0.2810973022301184, - 0.3672233069643398, - 0.3855626891519961, - 0.44454010108418374, - 0.2584898814768478, - 0.2722966540974105, - 0.5153528482452712, - 1.0909087388880394, - 0.7896176667586198, - 0.7064846082769228, - 0.43929206040689966, - 0.40980347079773327, - 0.7869985625439901, - 0.4497156869787894, - 0.3074946438647294, - 0.39890578771413837, - 0.32095982322422617, - 0.6838682892997728, - 1.0295131668514523, - 0.3415095333531835, - 1.3606055833954342, - 0.20152583968873852, - 0.8462288096616676, - 0.23970959591848298, - 0.660563810703126, - 0.2385021105550419, - 0.26416110731105025, - 0.9270461914431496, - 0.46606206233742775, - 0.24435059023676423, - 1.2084021075574507, - 0.3230113746143578, - 0.6159729131629045, - 0.5640950304368804, - 0.6433406690252352, - 0.5926377585152508, - 0.42070876930174006, - 0.6366696693885627, - 0.28469889340545584, - 0.5433877013063614, - 0.21711212828139748, - 0.3982282322633136, - 0.6436774171600853, - 0.5330096517982429, - 0.5287458631382362, - 0.8005469986675434, - 0.5327339521810115, - 0.4137999824499718, - 0.40850198124614895, - 0.2144655697137868, - 0.34193783157166613, - 0.5458218339776969, - 0.3157965376363219, - 0.6194185363200326, - 0.45448961136781235, - 0.6631770077372104, - 0.7125741901166848, - 0.32139174799525777, - 0.4843972284486092, - 0.3876033978540672, - 0.40715153291424594, - 0.9673497389319385, - 0.40557330243422607, - 0.2706571886108266, - 0.2582753202952868, - 0.443364400596857, - 0.8529371866826458, - 0.3440306063293391, - 0.40270147019461405, - 0.25971731148199967, - 1.0932268739171866, - 0.7202987008401873, - 0.25033885519667504, - 0.6432972163341232, - 0.32269255132568436, - 0.4847487454271818, - 0.4575097135863969, - 0.2621388573782456, - 0.6625590548711509, - 0.20823771573184327, - 0.6406848036256539, - 1.542452642275036, - 0.6747690580631556, - 0.3898722316519599, - 0.3048115378083791, - 0.311640309053868, - 0.7763283576328424, - 0.5469522604817891, - 0.6322616495867921, - 0.20818549400180755, - 0.22998824171355378, - 0.697849889795687, - 0.5672525416734849, - 0.39966383669077904, - 0.26576570655259146, - 0.49463867177164894, - 0.31079600708493316, - 0.4092933538265688, - 0.7717451590840378, - 0.8558726116732959, - 0.5216070965727782, - 0.48898955073511563, - 0.6301846933339937, - 0.30653128631470833, - 0.4981741529761056, - 0.8896264470350707, - 0.8026625103446822, - 0.391124396355734, - 0.9487136350139395, - 0.9210195666960477, - 0.31051004546337246, - 0.7211002646964131, - 1.232950041295091, - 0.43594211579757214, - 0.6839324928468186, - 1.0374343250505553, - 0.4308706205640193, - 0.24448067492899478, - 0.6137691621007505, - 0.37748795543809305, - 1.186646983537946, - 0.8260751851524004, - 0.47040615252472157, - 0.21550800037223086, - 0.42637328498560867, - 0.7692394668096698, - 0.40150852983943036, - 0.36413044011117135, - 0.33666936900098415, - 0.44273863478944814, - 0.475707920934428, - 1.217272569504754, - 0.5425680676907301, - 0.22040496756424713, - 0.8496679346401526, - 0.6656126557607783, - 0.38339200810568314, - 0.43932058590120526, - 0.41406180567568646, - 0.3719403723997528, - 0.5160088178770439, - 0.5424131760004139, - 0.5330509327397354, - 0.343612425828402, - 0.2669820953425506, - 0.9725121647777388, - 0.6842812625445138, - 0.49277257323431856, - 0.5327219820018553, - 0.48841708702131964, - 0.28878385501748827, - 0.5142809667438357, - 0.5703978314567691, - 0.5838375004744798, - 0.809417678746357, - 0.33675945105430016, - 0.21827175157063697, - 0.21872575322994656, - 0.5345431511226179, - 0.7895131006149619, - 0.5440378271560188, - 0.4807493426998431, - 0.641195625909665, - 0.4383836877395006, - 0.528129337048504, - 0.3018009976720885, - 0.431319308499429, - 0.2490647865061565, - 0.2730551251496292, - 0.2791897469236062, - 0.7689915460341112, - 0.2541549317775488, - 0.35631846358882, - 0.3859045006564223, - 0.7348673435389337, - 0.3767284195442876, - 0.3176519499058942, - 0.21323072946922636, - 0.3533004178008109, - 0.3827611743504773, - 0.5361808972360366, - 0.4249585195244363, - 0.39588335128235536, - 0.3854165119013985, - 0.8304688904158617, - 0.39554129366617236, - 0.23474667495818893, - 0.34829855904614265, - 0.4398341064965148, - 0.6589665838196519, - 0.7179027974703968, - 0.3389948241222625, - 0.8354347708305702, - 0.20634100260450125, - 0.3522345633767039, - 0.3155316690573014, - 0.5620018267302004, - 0.23100120240956068, - 0.3437633872173385, - 0.4216130667989316, - 0.37276991911893476, - 0.26188305282683894, - 0.7673998034654237, - 0.2898500940122211, - 0.8386228459685754, - 0.2892127746127409, - 0.8277900390858604, - 0.4563413271983039, - 0.6248088909623994, - 0.5655332535696124, - 1.5311518891748268, - 1.0568436821035023, - 0.9980876599371312, - 1.1601249338700539, - 0.4754944744154258, - 0.5191637676652999, - 0.886706828471024, - 0.6222568741215776, - 0.6802023870174141, - 0.46582880684302175, - 0.33287439767327626, - 0.3518700433556299, - 0.442268864391896, - 0.8873652837743262, - 0.24650884528580033, - 0.28190297903739453, - 0.46336462661786204, - 0.9769775963552166, - 1.1517376876722074, - 0.21888845283091982, - 0.20324180205791623, - 0.4235625761799345, - 0.4003628353394427, - 0.25303733084790986, - 0.7821303081029188, - 0.793449407617427, - 0.6025015737395907, - 1.2707239537623027, - 0.6365930531810845, - 0.21465436121278705, - 0.21508409682017993, - 0.34944681507318603, - 0.48947356534205466, - 0.5900018665513523, - 0.27999894376897966, - 0.3697765142322858, - 0.4250072196673887, - 0.454009671559356, - 0.7137496603799813, - 0.24746482261290229, - 0.5813268386859857, - 0.5055919869442345, - 1.159728358444747, - 0.4239178876193359, - 0.9645505384033414, - 0.6032326645647335, - 0.5379667528676555, - 0.2347837700944238, - 0.28529884500135205, - 0.7159036765803753, - 0.3857243497108799, - 0.7416617813136894, - 0.25745577041928847, - 0.27461118119991323, - 1.25091703412876, - 0.2503044141483123, - 0.7225963622069538, - 0.7530989585414773, - 0.26952142823103126, - 0.608232296186614, - 1.2254386391246088, - 0.2141112902479274, - 0.4387403978319135, - 0.42918181575619524, - 0.3196036504255477, - 0.39554059571913575, - 0.8239395573924753, - 0.9380618801989483, - 0.3571553019735848, - 0.3006521988065344, - 0.588047004008537, - 0.45920427533960345, - 0.422654299143835, - 0.4156553366811123, - 0.4496058482289219, - 0.24653707455950583, - 0.6097601114755526, - 0.6266997120104154, - 0.441878580755456, - 0.32421306095530145, - 0.981288661752014, - 0.43357662867205754, - 1.389998698996555, - 0.22154607986640112, - 0.29867455391095504, - 0.38530695794444536, - 0.9564004312858353, - 0.35827195205764156, - 0.2480478391703901, - 0.4646996252868883, - 0.44137473945067157, - 0.2865027676987247, - 0.5266536626473639, - 0.7123295533349436, - 0.7983217549485107, - 0.7857385035937837, - 0.35297596363116246, - 0.9975489072645283, - 0.5144191328178644, - 0.2602420673408002, - 0.8119804740333891, - 0.2187269784742886, - 0.8881488019732043, - 0.6624356908251214, - 0.6678566083158528, - 0.9265888247252942, - 0.6202389292170186, - 0.7119305659664735, - 0.5487904827598721, - 0.46933628182055653, - 0.4546701303997741, - 0.5318062945592736, - 0.28843554598466187, - 0.5701907551358346, - 0.9938455936068413, - 0.6141789708118814, - 0.6511784152577909, - 0.5367114087278048, - 0.5846065988468295, - 0.308131818447472, - 0.9666153110044603, - 0.4234063471307004, - 1.5731151472670424, - 0.5677063453808345, - 1.2571725537793392, - 0.5719615771592781, - 0.25788478650717134, - 0.39556835019658976, - 0.5155799676861003, - 1.1315948011946717, - 0.5327756051406664, - 0.20824434136364187, - 0.4584023020915869, - 0.366068457206358, - 0.2193181440007031, - 0.3285931688881559, - 1.0334215935305833, - 0.4127031702368957, - 0.42070433263918655, - 0.9640074474352126, - 0.23403693671017434, - 0.4623614114861595, - 0.33032242801322576, - 0.20952998684221066, - 0.9410846030067626, - 0.6199743060813667, - 0.7251364383014878, - 0.5665520240127276, - 0.4161179609748429, - 0.47551946052775707, - 0.28559316876696034, - 0.7237862255903882, - 0.41234710209150166, - 0.40325270030416166, - 0.2845735437925023, - 1.0022956126307678, - 0.2780092980729082, - 0.7722672483998361, - 1.3652890144382, - 0.24309292261351736, - 0.4530717286198796, - 0.31117153696391825, - 0.7925569182176185, - 0.6287213617965065, - 0.2724405845524767, - 0.3429250194820951, - 0.7941100666619215, - 0.23464642732514765, - 0.2583334458553492, - 0.3158497356851066, - 0.8680994216530096, - 0.20819579755856665, - 0.5789025628147765, - 0.2282085468889608, - 0.45791582268089487, - 0.3958748428112027, - 0.37077125153255486, - 1.0021637979531293, - 0.6710848648009132, - 0.5199981115409242, - 0.3502535126421063, - 0.5459027176631036, - 0.2972207365910501, - 0.6156398623265195, - 0.24362134120124626, - 0.4229840357974088, - 0.5696081665915664, - 0.23036776639470963, - 0.3468050971026117, - 0.32910731906193835, - 1.0616460796627536, - 0.35401518774538415, - 0.3365730553153735, - 0.8602579756026618, - 0.41780200662450495, - 0.832894090663412, - 0.3598110000232188, - 0.47427877158609627, - 0.39174965488715063, - 1.2352170680413916, - 0.3486354571306103, - 0.4841342867891264, - 0.8531864323516855, - 0.5041037344804666, - 0.6215297622102275, - 0.35967640970204184, - 0.45450273310226985, - 0.4967197566459553, - 0.36224977004554476, - 0.3542541261103493, - 0.8588205987044661, - 0.6929247666511645, - 0.4279723200826812, - 0.28685077195481984, - 0.28988486330253127, - 0.48825708711104665, - 0.9906295096127594, - 0.38532139371597424, - 0.5228045099774055, - 0.8184440304668028, - 0.9381274847696969, - 0.8004405342496884, - 0.21587464609752816, - 0.5104226032859106, - 0.9415342765824498, - 0.6095342507153533, - 0.7373543285200502, - 0.34715095034277577, - 0.4775255096839846, - 0.33390860993683774, - 0.6566869916162393, - 0.278072757789342, - 0.2524994844815365, - 0.3674556222219868, - 0.4633575306547109, - 0.3260232244745574, - 0.21619928249366746, - 0.31864887695399685, - 0.3353907495581269, - 0.2797420488511346, - 0.38680126094974826, - 0.4046735527168806, - 0.2878880926485723, - 0.7619666939552305, - 0.5077847007862664, - 0.3055484797146355, - 0.28124103179622545, - 0.677711722221705, - 0.5031278903735312, - 0.29693537555814686, - 0.6900594303415992, - 0.6549117830333581, - 0.42011692768869885, - 0.32695382816604923, - 0.5947401710989746, - 1.318370670342502, - 0.7138214907262944, - 0.21367058471917155, - 0.7077239430847527, - 0.3921028791115815, - 0.6310255692555407, - 0.4376009493226289, - 0.3784573241306279, - 0.4572612991741418, - 0.6361816460860675, - 0.6211359206329334, - 0.38092190925494146, - 0.3863861856489024, - 0.5546315927931325, - 1.056159953191928, - 0.6998182927395226, - 0.614318545719052, - 0.40092993952220646, - 0.2433629489214721, - 0.4214782713230565, - 0.8127111946763973, - 1.0504546851032488, - 0.7404829979982965, - 0.49154450348893886, - 0.4410575475402533, - 0.261246924902277, - 0.5184496672323358, - 0.6132825574768233, - 0.7666150747928019, - 1.5634113831131906, - 0.3273072525589181, - 0.272863474455125, - 0.3683908886558816, - 0.24558111980737715, - 1.102587859121308, - 0.2615152437864808, - 0.2379242229970415, - 0.5076006865452214, - 0.5745510830121504, - 0.41651162742500675, - 0.9887192142616699, - 0.5335524567242236, - 1.1068533092447181, - 0.42636790725322327, - 0.20663928859126957, - 0.42727822905833013, - 0.2809207570830092, - 0.20504634844980132, - 0.5200397342462371, - 0.3915385589274065, - 0.44326219486609675, - 0.492291149483411, - 0.5584109761624866, - 0.2163707922233531, - 0.36642208387271225, - 0.28581508732864747, - 0.3020461636675236, - 0.5084678308093555, - 0.5312672269718729, - 0.43418812677775265, - 0.5399264692832456, - 0.45374566921551385, - 0.7647478916572296, - 0.7516212074076143, - 1.0917751981902741, - 0.2994951862177394, - 0.2645125476715687, - 0.4887866888103633, - 1.2809821637511603, - 0.8019006355282391, - 0.5155687577916991, - 0.3075323034212928, - 1.1330455110906128, - 0.24725117845347286, - 0.29600677461058206, - 1.3629364115919227, - 0.36162214002532883, - 1.0707864878062503, - 0.6298423640622353, - 1.1418891439409844, - 0.5621138104846483, - 0.21319326085463244, - 0.8361254617270059, - 0.21114562854855287, - 0.44617631108503386, - 0.27358520764474, - 0.5967240334220124, - 0.5792605164316632, - 0.6774876047997469, - 0.775100546007478, - 0.8140046824229862, - 0.3226653139324229, - 0.366721294774324, - 0.8158473754008242, - 1.0040564402586376, - 0.3665750858476938, - 0.4988012161155826, - 0.42998954977473786, - 0.38431722049731937, - 0.265802080251316, - 0.34083714668286536, - 0.28562150535067726, - 0.34149066387371196, - 0.3119771667114332, - 0.40041809855938, - 0.36804168193030506, - 0.6204842911009618, - 0.6869771426313105, - 0.2642294551448181, - 0.2570445782431856, - 0.4155178011917707, - 0.5569175636330889, - 1.1478375051059824, - 0.8043238887657718, - 0.3290462575547996, - 0.6174263511434858, - 0.4683391768160026, - 0.36171352453280237, - 0.37091120393077776, - 0.4890435484309872, - 0.8063469507080895, - 0.8098762827344284, - 0.3219953275741448, - 0.5128111712452645, - 0.2161758019967608, - 0.4218461788377638, - 0.2912740573854287, - 0.6541164666933138, - 1.3574685007044487, - 0.29357234576587743, - 0.628219919121244, - 0.34706752242256067, - 0.5082828589592729, - 0.22852108830978343, - 0.22627838459512395, - 0.20349749449212878, - 0.27753075496700347, - 0.521596692445356, - 0.4142657812415504, - 0.7098232707194896, - 0.7662720099943384, - 0.4596265150526996, - 0.4700475229852638, - 0.5361786648850525, - 0.48609628541342736, - 0.6740404163041381, - 0.4708998223334748, - 0.6538933477782155, - 1.355459784815044, - 0.9567141986422893, - 1.0760716362966651, - 0.4676347955942431, - 0.3334245479200941, - 0.6867242513003893, - 0.6454119457436521, - 0.3632550361832189, - 0.5242066727615137, - 0.3465044485205715, - 0.4895304095020748, - 0.8036876926757034, - 0.9109320356201083, - 0.816116004555086, - 0.9033058485563785, - 0.3504648068111399, - 0.4267981736045033, - 0.6646440671464353, - 0.4406602264902842, - 0.48958340430098946, - 0.6946358585751841, - 0.45472936213013226, - 0.6708493963946236, - 0.30077006024209246, - 0.3406905612928384, - 1.1629545465015518, - 0.23955495128595675, - 0.43465479017617187, - 0.3441764014756209, - 0.4010465199100413, - 0.8077084875685201, - 0.8585919475952353, - 0.4059404351144484, - 0.3290100668975519, - 0.37454534578350435, - 0.4723773144669252, - 0.5196375643017745, - 0.2577278772407103, - 0.4301170182959781, - 0.9714506335344368, - 0.4279149108328006, - 0.6020330401621576, - 0.25915060586200783, - 0.34195765843230547, - 0.35710970540532083, - 0.21352873151411325, - 1.198737723549631, - 0.23523481923622988, - 0.924670999610799, - 0.32371401110790154, - 0.2993665198208874, - 0.3471407541563305, - 1.0837399655766637, - 0.24638473430864982, - 0.3997215210385717, - 0.7243870230829357, - 0.38792256948056314, - 0.3773970214212203, - 0.5404765341555235, - 0.2551013613452603, - 0.4772190233028889, - 0.45709814503771934, - 0.4635441309277484, - 0.6587734161128745, - 0.20708646405813158, - 0.6449641319665774, - 0.4403818120521681, - 0.5042102528204301, - 0.3050928692400495, - 0.6860000337936388, - 0.8122184251081701, - 0.28622166003999183, - 0.8790898894828084, - 1.0117106735938937, - 0.5477977219808814, - 0.6463590297204266, - 0.45610008248664186, - 0.4962337760670061, - 0.6290288789992936, - 0.3318266588031324, - 0.6016800521552581, - 0.4928701442116488, - 0.8117739567441992, - 0.46786106067451727, - 0.4528557659802638, - 0.7685618667780917, - 1.180359566638386, - 0.20690846708654909, - 0.45025442012646505, - 0.7611438001863063, - 0.3445747879569845, - 0.4938977662809444, - 0.20361663838784638, - 0.4572471548966123, - 1.2923362873591235, - 0.93010006029316, - 0.3854013363830971, - 0.31109448459096417, - 0.45425070040929766, - 0.35710570609798153, - 0.9704387847972678, - 0.41741461791568574, - 0.4290228141244861, - 0.2909512871305305, - 0.44048074595755304, - 0.7069609974212264, - 0.6908146293234129, - 0.41944280137344064, - 0.20029241881009402, - 0.3851922453715318, - 0.9867446720807251, - 0.8055988885940257, - 0.6101982457994092, - 0.5213058841541204, - 0.26060261245433475, - 0.6465945927615713, - 1.337211745820047, - 0.8663096109837931, - 0.42721539301382494, - 0.2920136593128999, - 0.9233947080630983, - 0.5835336862285834, - 0.2940759036202974, - 0.8392749959964247, - 0.41620228732359427, - 0.9100416215662762, - 0.23792286894549308, - 0.9160591416624626, - 0.8569208889601762, - 0.5298845097669425, - 0.7916199030630086, - 0.3806758591144111, - 0.39585893223923646, - 0.8409854940056037, - 0.3715690084478417, - 0.6938389085773768, - 1.081432847003764, - 0.3094870267196231, - 0.4838478294193267, - 0.2057067870921361, - 0.261827990567009, - 0.6615130178629541, - 0.641307383361592, - 0.7172746137610571, - 0.839961409686234, - 0.22337974635681068, - 0.3371276397457916, - 0.25169923207729245, - 0.6946821046316829, - 0.41599536066270554, - 0.5480005004297158, - 0.23851529790271112, - 0.35025758019078224, - 0.9576308326067912, - 0.67984577990435, - 0.5409112989408941, - 0.7358217620869775, - 0.98069996690115, - 0.4170406937058612, - 0.6013720902740279, - 0.9792677271402638, - 0.24706973713559338, - 0.5299089072545621, - 1.2749339602985752, - 0.2768519087255026, - 0.6983752631239615, - 0.46362848272950435, - 0.32555030708247723, - 0.4918891744741071, - 0.2918577925752536, - 0.2108498957674299, - 0.5957010953418325, - 0.24305239226944966, - 0.6183656389423394, - 0.29572915095418734, - 0.20673124571294008, - 0.4444854142317941, - 0.341445506391699, - 0.23994141042848924, - 0.8052630594950884, - 0.22883185064452566, - 0.31437785247545663, - 1.364759743008039, - 0.2469504570549121, - 0.28656578439927194, - 0.2911760193060382, - 0.8341328654141106, - 0.3938311040767956, - 0.44443764550976383, - 0.3829325193132089, - 0.426457907172333, - 0.447097704183272, - 0.2140671167942713, - 0.8909346931781054, - 0.2760551807536085, - 0.7500655542792838, - 0.25606849620782846, - 0.24352389237494765, - 0.5087402357383187, - 0.24007220101797486, - 0.21561483191727338, - 0.4645787323471821, - 0.37150681702825666, - 0.8142305996566189, - 0.5937258987885541, - 0.41470428027917505, - 0.2979252111813333, - 0.615949079067528, - 0.3419897922842979, - 0.4538380722438626, - 0.7573476891473683, - 0.2713028629258324, - 0.2753181271614307, - 0.29712500064188946, - 0.27121978973346333, - 0.628079336772762, - 0.558835527929247, - 0.2379850657255233, - 0.40120535942901436, - 0.42477707255193026, - 0.3279256901568511, - 0.46632291425509526, - 0.5369580027451535, - 0.23005636961020753, - 0.3864392008171015, - 0.3448690553783713, - 0.3308898901199754, - 0.8073628383000528, - 0.5574830590117407, - 0.2468855245451831, - 0.23381885135824804, - 0.2174168752232335, - 0.3891193495081538, - 0.21090779207942456, - 0.9036552631915507, - 0.8864539306098399, - 0.27593294021517983, - 0.327520599023999, - 0.28888030306584517, - 0.33352761696416455, - 0.9309288065580441, - 0.3163705381406443, - 0.407416644228343, - 0.7258487903064454, - 0.2097598072398323, - 0.2304699241747695, - 0.3161280440555315, - 0.7058856166580776, - 0.5375807888885228, - 1.038398515492051, - 0.8376249912829573, - 0.43370152981209814, - 0.44482817052483997, - 0.7471829055830198, - 0.3709638564514044, - 0.8636148913908025, - 0.47544254918292883, - 0.49349084825134015, - 0.24358626206417322, - 0.362284506814929, - 0.45487728385936765, - 0.2943746539396582, - 0.5940149494655868, - 0.28259208696831534, - 0.3693756235066174, - 0.5728506972624893, - 0.36361843757595425, - 0.8857636102873335, - 0.21857770113581995, - 0.5917762726550753, - 1.22629055346173, - 0.20367995535883648, - 0.8929493798382079, - 0.7449947158100819, - 0.21700783626348974, - 0.34877298868298884, - 0.4950290959930134, - 0.21525206469589256, - 0.4371803691043, - 0.5418325457365677, - 0.6149355846231266, - 0.4588192304343236, - 0.2008535407473945, - 0.29260484907576123, - 0.5682123933953619, - 0.3486193288408875, - 0.7123670686894785, - 0.7267176316969339, - 1.608720528724775, - 0.46437299013618166, - 0.5605040890973021, - 0.6585591942156903, - 0.3296335785642202, - 0.5045619679791905, - 0.2073583267730887, - 0.6674516642391665, - 0.4702499817339804, - 0.6436970684739993, - 1.096254916211768, - 0.4102096164304576, - 0.32993868267930504, - 0.44131468318164946, - 0.31521331138720415, - 0.38794522163006967, - 0.9043851226347326, - 0.4903397731191666, - 1.458283552461314, - 0.2066259890807642, - 0.4200165552959336, - 0.4795759876607658, - 1.5898591654824625, - 0.6319378967911048, - 0.4759657321676252, - 0.6664928899277005, - 0.27067248892530954, - 0.5777450111452739, - 0.47107927011475054, - 0.29574988969536126, - 0.49800094696024927, - 0.724351686664709, - 0.27839291627032725, - 0.3536245527637275, - 0.5413757713999879, - 0.308499991695178, - 0.2583630686864033, - 0.5507407236885759, - 0.39462085532927643, - 0.34656742994312595, - 0.9021081401333229, - 0.4312165188291233, - 0.33436933612270947, - 0.9111383898355285, - 0.7828225415886778, - 0.5751416220535371, - 0.33886111704628163, - 1.0715041036448392, - 0.7509815477460703, - 0.7146968596648332, - 0.8609944276790934, - 0.43168561733620353, - 0.591120955612138, - 0.41369404657955655, - 0.6537987318599716, - 0.6243272914752622, - 0.5694047116808394, - 0.23043225481115828, - 0.27159834176770203, - 0.5364180277011185, - 0.7816170156535668, - 0.5433166056921731, - 0.5027232873223926, - 0.38470507185159286, - 0.5303303661412361, - 0.36280902194871517, - 0.42237651999728104, - 0.23782159499962263, - -0.31896215822052043, - -0.5236620474894426, - -0.3896414379799704, - -0.45039167222773757, - -0.41634305229513474, - -0.42361814634638106, - -0.4821955135723619, - -0.7246740733286118, - -0.4214845014607367, - -0.36461166915716214, - -0.46078414865674433, - -0.49546785276125327, - -0.7468092168061615, - -0.5051580937680689, - -0.2575677094684532, - -0.2278300423345721, - -0.6168541818631872, - -0.2851153181369716, - -0.3893170481608978, - -0.296661020141626, - -0.8303581548271539, - -0.4860875641272654, - -0.21376403584899004, - -0.6092625661114356, - -0.7954852498680162, - -0.32785734316500104, - -0.5319029720931819, - -0.33794843466693425, - -0.4676409113148918, - -0.7386252197712556, - -0.32545984895309654, - -0.27457138215368626, - -1.1059773278151461, - -0.5512033205535263, - -0.734920277398723, - -1.202916062962965, - -0.5074958882070241, - -0.4935960334052404, - -0.31552569289918714, - -0.5603261028306277, - -0.8445531644531284, - -0.4942687255065058, - -0.29842945762950246, - -0.7326404776053925, - -0.5067299931129984, - -0.8264675446656674, - -0.3453865360567154, - -0.5272589466365002, - -0.4956642226393148, - -1.0336819491143712, - -0.5132709455407152, - -0.6566658215283988, - -0.7984510071640202, - -0.27640324581563963, - -0.30554940886443377, - -0.7538908314753394, - -0.35918629165572047, - -0.34748437259516574, - -0.2947780605290259, - -0.7894937011133114, - -1.1537565688259677, - -0.34157267840812977, - -0.7857411035752326, - -0.460018039709802, - -0.6768765024072714, - -0.23620131037703881, - -0.26671480371138007, - -0.7279879812843146, - -1.019791959832794, - -0.9214045505936266, - -0.39191159264889247, - -0.689518512488122, - -0.435648097954425, - -0.3068586082119385, - -0.3574336884635522, - -0.42404363099821446, - -0.2811995604682429, - -0.2625425642554949, - -0.2596325477878913, - -0.7526741978065147, - -0.9020342439970527, - -0.4801835504052997, - -0.49259076757166487, - -0.40652368073614725, - -0.21060269706651558, - -0.21544543415159795, - -0.3527758001579485, - -0.9669194229487411, - -0.8049414762127229, - -0.2345055370744051, - -1.1262931658495314, - -0.545411749093133, - -0.3793324979423999, - -0.6960677995139884, - -0.641143041387857, - -0.5473719688618226, - -0.5606980783405847, - -0.3495225393868231, - -0.21924884203853187, - -0.4238973742877946, - -0.2689440520582348, - -0.3677635552567955, - -0.6754914487291553, - -0.5064811027113285, - -0.23816021593856396, - -0.21890588678453746, - -1.0225376820873602, - -0.27131541657662644, - -0.38445402397081346, - -0.6420364007203716, - -0.8998329097643436, - -0.44430088289420894, - -0.5211907111577084, - -0.3978966048598495, - -0.38870791870720867, - -0.35869183138447347, - -0.3678021023465517, - -0.49151672323765155, - -0.7267120063808751, - -0.7196990636801439, - -0.3266947854644869, - -0.3194876801119011, - -0.8434777905404515, - -0.20819878782333276, - -0.37088785645058664, - -0.6136436232082548, - -0.23534672791101865, - -0.47808860021105165, - -0.3086985300882537, - -0.5015671992044852, - -0.5801670072445081, - -0.4994627371762248, - -1.1663008245903188, - -0.7568940721885455, - -0.9961351025656578, - -0.4523509940182846, - -0.6550562868725117, - -0.4373655211897698, - -0.5691107281136564, - -0.5180339505012608, - -0.5708665392842122, - -0.3047664227947919, - -0.343512262034025, - -0.510468727631129, - -0.5066551969549292, - -0.9390610743607345, - -0.5745767563490087, - -0.5927915553226081, - -0.44631746727934113, - -0.772996584778933, - -0.7684184561757411, - -0.7699873167052684, - -0.2870150099482663, - -0.4801247933284675, - -0.5387177815827908, - -0.8752126450480417, - -0.3177225067207099, - -0.5542254341930222, - -0.6208351900518043, - -0.21608260883682187, - -0.47250724192121685, - -0.5893019017743365, - -0.2004377682277549, - -0.31734023596269884, - -0.24611970415839093, - -0.20922514385188679, - -0.6398780043899136, - -0.5881102432006363, - -0.4869146265643144, - -0.4693129809978366, - -0.21025949364402982, - -0.2140048451102338, - -0.40170706336648293, - -0.28963131566123246, - -0.3638477880945072, - -0.4856858144541047, - -0.7467031000209658, - -0.3988813475289643, - -0.45497193316512563, - -0.6274895471593561, - -0.4900665943849213, - -0.4153903260084803, - -0.499567186800186, - -0.3686848692751818, - -0.4935185059121863, - -0.5717222975357578, - -0.26236772859280366, - -0.9091374647168621, - -0.3820531310084635, - -0.39146094496080514, - -0.4329534644915828, - -0.5525311221922358, - -0.3359610127834387, - -0.4786445790807405, - -1.0922976526888812, - -0.5130301930808152, - -0.8034055978093814, - -0.2941846178685949, - -0.7784781014849375, - -0.30122842392655874, - -0.6701957095568795, - -0.4899586518133471, - -0.30803589640698514, - -0.45607443741053505, - -0.46019541555801924, - -0.3001854818560978, - -0.7801756472965882, - -0.40704065790971655, - -0.30498509195530943, - -0.39381568520444166, - -0.2810437511130957, - -0.5283010796222928, - -1.1158014693152676, - -0.23156768397737743, - -0.2535989108032096, - -0.41548485245863936, - -0.6440537637759836, - -0.22870923390916456, - -0.6604117559593862, - -0.43304525541276345, - -0.4458550681742964, - -0.2509350894494243, - -0.23084459822735307, - -0.8723484900842793, - -0.5209307776611029, - -0.641031898750043, - -0.2814122054444878, - -0.45717472292545264, - -0.7510372229772938, - -0.30879627531856463, - -1.0910975888266514, - -0.6218859962313275, - -0.4540772699622766, - -0.3970573381374873, - -0.47861778629267004, - -0.22100381642917277, - -0.2217931604895443, - -0.36786650547611793, - -0.4829793085753312, - -0.4417671775604101, - -0.7050377011727942, - -0.7851949882419065, - -0.23034733175799027, - -1.2504112271429157, - -0.5023609561445812, - -0.7995089008809171, - -0.46622676040459016, - -0.3895508840874695, - -0.3981480772112944, - -0.6954886643549405, - -1.0671949231621791, - -0.40992964289050304, - -0.3672673726578353, - -0.5271612948914937, - -0.9184883217326324, - -0.8668300260283562, - -0.23377242604857373, - -1.0249335248467442, - -0.4971803810776663, - -0.31505267913259155, - -0.21990092652649654, - -1.008348016684959, - -0.22172014978847374, - -0.4288330041127715, - -0.3024956416733951, - -0.22450393786422282, - -0.9279702115921752, - -0.9462808227489433, - -1.1129335546421635, - -0.5080109860276885, - -0.732067676379609, - -1.3787429522503802, - -1.3596843611331169, - -0.4340020102264367, - -0.27580612557975404, - -0.7485184186992663, - -0.5881489463463662, - -0.5074669383909886, - -0.40694864527461455, - -0.2543169771660149, - -0.2969533734335029, - -0.6401721543300697, - -0.6043990578135578, - -0.5350404611781248, - -0.47482314998567404, - -0.2991571992351589, - -0.3203463627806008, - -0.6080448520623976, - -0.5430781820568069, - -0.3103305763369781, - -0.3042922107596466, - -0.45679826724197764, - -0.5367199891942415, - -0.27653486460911, - -0.41087799425656407, - -1.0077174410846657, - -0.6115971409430923, - -0.23984827502666656, - -1.2433248490041653, - -0.6570171263976804, - -0.4657196216056528, - -0.20042723574933216, - -1.2437663533632908, - -0.4924440090882785, - -0.38144289241626306, - -0.8840514850664836, - -0.48850895357544244, - -0.24753619549347983, - -0.8040961147089887, - -0.37436033794143136, - -0.8318380529687226, - -0.5568254881792375, - -0.35665243818125475, - -0.5774524994940988, - -0.47280990131777173, - -0.5227657810482808, - -0.3758638691289771, - -0.8159750286664207, - -0.21613032007807584, - -0.4218590177867722, - -0.7243082314613539, - -0.3183954977620505, - -0.3512130244165788, - -0.2086107232326269, - -0.24879963724149579, - -0.9099025656771604, - -0.40148254961936386, - -0.9532925666456429, - -0.5075194119425764, - -0.31640359229375964, - -0.464983895800806, - -0.7955522307977663, - -0.4710917239576929, - -0.7877309071500761, - -0.26601003790023053, - -0.6898137224707137, - -0.8364493689140376, - -0.43751753920020103, - -0.5553560293017914, - -0.29140684809028916, - -0.4266566325318225, - -0.9023040431364686, - -0.527080223207618, - -0.3406154896160301, - -0.3711484675061061, - -0.5517374629032805, - -0.6917428593964098, - -0.4792148161676471, - -0.2703997933304773, - -0.7369183207160048, - -0.5718799433000823, - -0.8888571816961027, - -0.5347889199237182, - -0.8390734575486689, - -0.4705435406769791, - -0.27686714115038885, - -0.4805595512540137, - -0.682115649560928, - -0.47498010664759954, - -0.5420079676095052, - -0.4959265370915044, - -1.0103283764364213, - -0.38091914581953756, - -0.56012124755439, - -0.3269968926154696, - -0.5519649812043088, - -0.9211218058889054, - -0.82533274083334, - -0.23335172360855905, - -0.4768185829398573, - -0.40332480926715847, - -0.4598427170538565, - -0.598402238161229, - -0.5606135166414393, - -0.45439180030378196, - -0.266580627689751, - -1.1141033126287818, - -0.5600369765669249, - -0.6442290064739444, - -0.7520429120301941, - -0.8037309406158053, - -0.33878083166609274, - -0.4350649583798784, - -1.2700888526434158, - -0.4632904036100773, - -0.7224563898601228, - -0.4769263638089596, - -0.5236661371970537, - -0.32133782141636097, - -0.6690216089549689, - -0.43460937786201553, - -0.47129963510947065, - -1.1734038432716822, - -0.3362945531039296, - -0.38656105630921495, - -0.4276310032027737, - -0.3428624659985514, - -0.5638912845670631, - -0.2885703525994347, - -0.5261107806184839, - -0.24672028508313956, - -0.45917772423061526, - -0.4727305515880137, - -0.4337650378386534, - -0.5649501175207908, - -0.5604869291778655, - -0.26363238023615504, - -0.201016872400754, - -0.2838764310695542, - -0.5846759476984501, - -0.7935337164783474, - -0.3164734456223358, - -0.5979865224851403, - -0.21822955197269034, - -0.6875988221238025, - -0.690563663968816, - -0.874752902092441, - -0.4162318882365932, - -0.47609952566882385, - -0.5207835763410988, - -0.27372190214636244, - -0.3629130265571734, - -0.6917844129176225, - -0.637743652583975, - -0.6035309542780182, - -0.28225831634878973, - -0.34649527790569695, - -1.1894335533838214, - -0.709724710663096, - -0.2961705407787406, - -0.6792096571731999, - -0.229805360442136, - -0.6589715134318322, - -0.47632859160017577, - -0.4818996076503558, - -0.8728086022889002, - -0.24020342873912698, - -1.4128729771723803, - -0.38251827302426256, - -0.9088778769698106, - -0.559721393989996, - -0.49606350146761763, - -0.34049496909020754, - -0.5896757063819388, - -0.5979105782028576, - -0.2789030102732501, - -0.35169906839097353, - -0.8634328065815233, - -0.4001907976833466, - -0.2451450303664641, - -0.7065468887278651, - -0.7161808785391995, - -0.7018821023562456, - -0.5644207347318733, - -0.6809352992858241, - -0.2784465503994342, - -0.6062282010498585, - -0.8036733899794796, - -0.5315678377488043, - -0.3431154840971545, - -0.9138338856413543, - -0.7691970502882279, - -0.4016321325316282, - -0.3386156179544442, - -1.4344808393168655, - -0.296847645861244, - -0.21451998041340717, - -0.5634007726478478, - -0.3519499006381757, - -0.4646178042291448, - -1.447004642973889, - -1.1043921627344966, - -0.6142246134873973, - -0.2771490662951397, - -0.23849437001044102, - -0.2914110951698226, - -0.6038443894704008, - -0.5059045528421611, - -0.3147481912602289, - -0.3053234000930572, - -0.25376035372067923, - -0.26393544789817536, - -0.49412546740710267, - -0.40096970801860576, - -0.8177524381797187, - -0.8225301708152023, - -0.35190059807273827, - -0.31805479335284126, - -0.3527492534232427, - -0.27965628095753853, - -0.919409384734053, - -0.24702830198465464, - -1.032076162218058, - -0.799904280865447, - -0.45472468717108216, - -0.6392002599370531, - -0.4717456697777077, - -0.6746228380886036, - -1.528768223721796, - -0.3204134232530995, - -0.8027462517754671, - -0.9061574941970025, - -0.38284936004340153, - -0.8947948023016512, - -0.4265848386736463, - -0.5705570421138931, - -0.6788346398309514, - -0.268490971132057, - -0.6312221778881832, - -0.5999279119073412, - -0.9663439651501, - -0.48575451606179265, - -0.5476046717445098, - -0.32714240145575346, - -0.21320089930721361, - -0.6960140608982651, - -0.386629415508979, - -1.196164910071613, - -0.22031019436985821, - -0.22597545893276536, - -0.24209650633402216, - -0.28644205450422183, - -0.2127519090983975, - -0.28234610645265024, - -0.2679360018628934, - -1.2986563589857536, - -0.38963366514585945, - -0.3630592989256443, - -0.5577738765888834, - -0.36333581209075555, - -0.45440086794965107, - -0.29108221634922554, - -0.21356442061333666, - -0.4598821713172262, - -1.0167321806046103, - -0.6014300748714022, - -0.983802817879174, - -0.5349692011058349, - -0.7000708131757348, - -0.5308492113036245, - -0.3571276027776653, - -0.30843724322668575, - -0.32881196335415425, - -0.20498699760274036, - -0.2767910826640779, - -0.8104615529221697, - -0.5816412495777382, - -0.23449027894887425, - -0.4874019362167441, - -0.2686542291573754, - -0.365086867628505, - -0.42143807389963234, - -0.3622727898734915, - -1.2011768300748282, - -0.2433002838601791, - -0.5957157018661999, - -0.6367049464150555, - -1.094528284165422, - -0.3260116768285115, - -0.4213681003472974, - -0.4835452953977995, - -0.3920980620479929, - -0.35060562663542805, - -0.5558072596281732, - -0.8821645987919317, - -0.5329659488374647, - -0.3847781505601839, - -0.7326250582709645, - -0.45587791873509886, - -0.7097280550417666, - -0.6952780631336714, - -0.3993883739503427, - -0.9682527158481892, - -0.7116820104500375, - -0.7033846900827562, - -0.6941117784885104, - -0.6818807409296266, - -0.2747275850852779, - -0.6213790652313946, - -0.25576882759106806, - -1.3115466075093478, - -0.5431115053645248, - -0.6137838587642851, - -0.6854941031630545, - -0.4935600242692694, - -0.6319305081577565, - -0.5770666243509162, - -0.5962197477697575, - -1.175187042180329, - -0.5965049736404708, - -0.28014210905263515, - -0.381406926375387, - -0.5885444310858089, - -0.5320688182708857, - -0.43748564578607485, - -0.4777573666136466, - -1.0246489444235718, - -0.39731008331007034, - -0.44337713567164333, - -0.20806352133990005, - -0.7808138100544607, - -0.7791015864138748, - -1.0902237432427568, - -0.7780925740746715, - -0.35636402813987034, - -0.3521720154472801, - -1.3899556159137048, - -0.34040920041328093, - -0.3049362591251628, - -0.21773498580493444, - -0.28571668826686497, - -0.7114254455036876, - -0.2362460455587702, - -0.8600504219958965, - -0.5647003003330194, - -0.26635165586577514, - -0.29703085958079645, - -1.1401792766451175, - -0.5180642096797967, - -0.24744325067138073, - -0.22672031294724188, - -0.566085695686477, - -0.543729425551446, - -0.7497605533303064, - -0.23602796206416718, - -0.23661871767624193, - -0.3320826046767371, - -0.6669725626921909, - -0.23590359167294805, - -0.7889789554500084, - -0.3345325976171325, - -0.5674195743649686, - -0.3157792362350475, - -0.9524594606883879, - -0.21635077509375358, - -0.30254631407063004, - -1.0715433941054402, - -0.4514686219245211, - -1.1376403847156742, - -0.5631760200544165, - -0.45818245061665813, - -0.22605270152903273, - -0.3497468290270079, - -0.47456394823773157, - -0.2210520423766908, - -0.25502021405163183, - -0.44088292248107647, - -1.0547048846323805, - -0.5186756852116475, - -0.26887618614300124, - -0.48981967642829927, - -1.0280615032565645, - -0.3391198781946689, - -0.786113523127361, - -1.0714522588609543, - -0.46167138402345365, - -0.26442987765822157, - -0.5304139653220794, - -0.22782308010054586, - -0.8242342944591589, - -0.33275487310962015, - -0.568460952797132, - -0.42978286197876764, - -0.5134018810392219, - -0.3263660126333606, - -0.4947740063126535, - -0.6986994948779465, - -0.2786512824386312, - -0.5608170933886691, - -0.5432712791357007, - -0.2009756232469317, - -0.879906395889597, - -0.33757881819136926, - -0.9885232082807841, - -0.5228312902257594, - -1.006903292511183, - -0.4768612886560489, - -0.2586780112095752, - -0.2809434320477059, - -0.365384857630239, - -0.3428718376839171, - -0.3672770312044818, - -0.2447231881440068, - -0.23503239429433395, - -0.25012221069501156, - -0.5997350233303849, - -0.48739489655327883, - -0.6039021958448779, - -0.6486220369334521, - -0.6089501753084233, - -0.679108803322235, - -1.1486747433733404, - -0.4239525565035107, - -1.3782535557102904, - -0.27872477126273587, - -0.5669395386500043, - -0.3121925740763091, - -0.4358687051690725, - -0.3888686874720807, - -0.7993735692104779, - -0.7749976462020749, - -0.7544347488260398, - -0.3604244577803868, - -0.32903102021490105, - -0.3477925165044513, - -0.3334145360283965, - -0.261775587026347, - -0.8223780129041031, - -0.699017450740615, - -0.25558049631076774, - -0.7360969861687213, - -0.9836623015385736, - -0.733126822309535, - -0.5080869320908509, - -1.1061537320777257, - -0.21734591385268978, - -0.5588348344398381, - -0.553140756010269, - -0.32751273985012924, - -0.8647793815312548, - -0.34424457808647135, - -1.215431010674527, - -1.082348139552649, - -0.3311327373604127, - -0.6048396331754526, - -0.807884661765368, - -0.2733186414184853, - -0.6596081643311361, - -0.3787255085768114, - -0.42119896115535116, - -0.2564020986665886, - -0.2667547489867846, - -0.6551158431614675, - -0.9860159926819382, - -0.39182785977725243, - -0.6851105170226275, - -0.63466616760341, - -0.4286724066795782, - -0.48546252246769306, - -0.23948527590891866, - -0.3704230602937467, - -0.23496581235737563, - -0.7189338729662446, - -0.31673128508006265, - -0.3407338861318912, - -0.29138518298265714, - -0.3296301593197961, - -0.7188040878776725, - -0.2947103748834594, - -0.5306878842691956, - -0.8458246269658898, - -0.5823550721595921, - -0.34399359831496673, - -0.22124714161770528, - -0.5768199593339227, - -0.2775009056370589, - -0.7366075927504199, - -1.4429445649854604, - -0.7878759338416224, - -0.42948965978332126, - -0.8234550796116756, - -0.7595296784406826, - -0.3238989896986822, - -0.7343461500116212, - -0.3231618319920192, - -0.6919268327810371, - -0.6759338346019886, - -0.34183526810031734, - -0.3837052828980484, - -0.20603223818772223, - -1.0473678034123783, - -0.4671769682312599, - -0.2899390030599478, - -0.6370118452905156, - -0.5499394568260686, - -0.5292275488080108, - -0.8764529595284697, - -0.2395066050301308, - -0.32876028706074506, - -0.28199800548518483, - -0.6224514851121719, - -0.39557537794170544, - -0.22531875990091815, - -0.2044941447102851, - -0.8499722479980878, - -0.3136249176750271, - -0.2840058867144231, - -0.2821837854125717, - -0.6262852765209185, - -0.9075309228320857, - -0.5913109165058449, - -0.24236556778362636, - -0.3710819581345215, - -0.6979807993788075, - -0.5118517736822648, - -1.0890290334689852, - -0.22014694044787522, - -0.9474125396705624, - -0.37395731297186613, - -0.2574518046273968, - -0.3409124972126996, - -1.1426201133935208, - -0.6007826489773588, - -0.41873425763641237, - -0.37555692559943954, - -0.9056163724908655, - -0.7967682269505455, - -0.24110341590806803, - -0.3450034595667536, - -0.22543528599056237, - -0.24258356695227787, - -0.34019055003169196, - -0.26030744795759886, - -0.32321142751250015, - -0.3385766792477059, - -0.4710346858017122, - -0.6680867698965045, - -0.4230846302217875, - -0.23037415123702118, - -0.6678780660604927, - -0.7966341135262075, - -0.7163902315880931, - -0.24703635448822933, - -0.5138262999683854, - -1.3300199114974454, - -0.44786546227342144, - -0.2568304278983386, - -0.2406373580531449, - -0.41224453013915313, - -0.41252655229488566, - -0.28530327823635027, - -0.24070736885160993, - -0.3317890065975621, - -0.950352483269346, - -0.2394826435075468, - -0.28230426326089053, - -0.30101577289883186, - -1.0020294831398204, - -0.36375122807612825, - -0.44843472364684206, - -0.6589487654537403, - -0.5406190419232646, - -0.8811326183499898, - -0.48623879162965944, - -0.5960388310253991, - -0.2090746237727661, - -0.4417040937446206, - -0.5482381412067485, - -0.4249298927513262, - -0.530366244226892, - -1.12264130669631, - -0.2683023443398746, - -0.425652064163704, - -0.3459294850354695, - -1.0034302845680234, - -0.787967480819308, - -0.6131583545869838, - -0.5597748563304895, - -0.9747857559924223, - -0.49258259417962325, - -0.2734524386856207, - -0.5663018464674896, - -1.3325355694993146, - -0.6888395361412684, - -0.29116049108476594, - -0.36189992903759455, - -0.2652935138020254, - -0.35672440769563546, - -0.5169239561952585, - -0.8694425366686566, - -0.31386369160611977, - -0.7138024282079463, - -0.32286678528240176, - -1.0648467950346252, - -0.24578830860281753, - -0.31318689140657846, - -0.2559573542231657, - -0.6924459033420665, - -0.2466920387033481, - -0.6193810346033137, - -0.4250632246591117, - -0.47554779068373904, - -0.33915517132218137, - -0.37041769446899864, - -0.3602403903123957, - -0.833798484298457, - -0.6529048515467004, - -0.32526819904768833, - -0.6369873654989748, - -1.3165894861879401, - -0.6508343929339371, - -0.22794400696293526, - -0.6223345007027941, - -0.664965586371474, - -0.4850266118114967, - -0.9371273674138949, - -0.5141725909345705, - -0.7153075438364133, - -0.4069852083299992, - -0.6688709782299261, - -0.2263227370454303, - -0.5285146215197296, - -0.8281304750394983, - -0.24309602968211508, - -0.3378385627325749, - -0.3598894809971674, - -0.6092495025521266, - -0.570467393659621, - -1.0149655376405562, - -0.7913438742835153, - -0.46828278409928104, - -0.2703725012803709, - -0.30557098861311566, - -0.2649743574519531, - -0.2789288357295327, - -1.0811267293046487, - -0.5350970336688782, - -0.399826458398692, - -0.6200402053523821, - -0.28861461243418884, - -0.2474435324089007, - -0.7624944597640554, - -0.5909535572965009, - -0.6116276882901156, - -0.24305383616450876, - -1.0820000710590847, - -0.2095555371733027, - -0.9453690983351931, - -0.32088769415997587, - -1.105451873315325, - -0.3956438092496356, - -0.5330837757980833, - -0.6819189718558746, - -0.515327964314068, - -0.28882185095654145, - -0.5855581801332147, - -0.5199774546959852, - -0.5545989930926998, - -0.5636235511383887, - -0.20499404468987056, - -0.6601346911143, - -0.38919063795284414, - -0.2894567946981245, - -0.8460806774412765, - -0.3219433597621221, - -0.7819101261544951, - -0.5650634732062811, - -0.2516083925188537, - -0.44160756293579423, - -0.45368610035642826, - -0.27074188206084443, - -0.4293106730300385, - -0.28952331163755374, - -0.44092845319334933, - -0.4491708309300995, - -0.7070547394210366, - -0.2481482163612548, - -0.3336539356151169, - -0.6222431949466465, - -0.37501171700253505, - -0.593078098203688, - -0.6986618603194567, - -1.2750743499993447, - -0.20299881517679025, - -0.6714078768598645, - -0.557817834085729, - -0.9206504931592444, - -0.3631985341066186, - -1.031951237921605, - -0.4888695165193139, - -0.6792633091985532, - -0.8412133423825168, - -0.23645755035429908, - -0.4135979612802872, - -0.22186079957094412, - -0.2115704273480654, - -0.3502091711118047, - -0.6810232917647007, - -0.38825512484050934, - -0.6253071065924715, - -0.4213874153118567, - -0.5421332656733986, - -1.020708785475365, - -0.5017230078711675, - -0.27980434685924616, - -0.5147100425006869, - -0.5924436272610786, - -0.4635959963133829, - -0.3654622709330161, - -0.7938650110015156, - -0.54679111656424, - -0.7798840633299803, - -0.48947899608660816, - -0.34876576522751146, - -0.30719006155897743, - -0.3540880728886739, - -0.27206907534113073, - -0.24550157429194316, - -0.3155291554326138, - -0.5958574569793511, - -0.7907806405305843, - -0.4564951824214881, - -0.24857765586832048, - -1.0324035888186152, - -0.2867923606711518, - -0.2568410129784672, - -0.8793038888805321, - -0.200964976459465, - -0.6311857122658493, - -0.21768898375212212, - -0.7551486308552543, - -0.534978033778334, - -0.372790569978432, - -0.5534236990768651, - -0.5017683944819268, - -0.5651178330859373, - -0.2978725256534117, - -0.7942804534116666, - -0.4524980070474153, - -0.43788570427634665, - -0.6132630492980572, - -0.8480112585441765, - -0.3192844934311957, - -1.0346101468552764, - -0.3088359942476457, - -0.4045177417471724, - -0.4258300709133457, - -0.24508849027768242, - -0.2377330102225484, - -0.6798045821017699, - -0.47288002201127444, - -0.3589809603956475, - -0.572485723236846, - -0.4666415533015513, - -0.7042070150810877, - -0.37995212788396104, - -1.1008003554970867, - -0.7176894196530692, - -0.24269079949828487, - -0.7709574986958313, - -0.45559842328471484, - -0.4043222482526793, - -1.3012792792594075, - -0.33096825128776847, - -0.7892403082044874, - -0.639891631937658, - -0.41126642255665985, - -0.9279658668471887, - -1.040113408156513, - -1.2474509735208712, - -0.22757577766632076, - -0.49970895930205417, - -1.128003053339357, - -0.21334777881071876, - -0.7325939341541933, - -0.5189444099563808, - -0.23468974813573032, - -0.9239450031796526, - -0.68156781965899, - -0.2698612466032871, - -0.7490416433560727, - -0.2291115023950133, - -0.9939682125647988, - -0.4789127978984902, - -0.41480298637366286, - -0.6492361663363087, - -0.2407332438706414, - -0.5073819852671397, - -0.5942350552164388, - -0.3579244238057858, - -0.35051054995983927, - -0.558764654508106, - -0.7905567062643185, - -0.8827950942231031, - -0.45497742943744385, - -0.6588837605562278, - -0.5692450763667654, - -0.20264513169903625, - -0.6975067044146431, - -0.2749444676125436, - -0.24204249708726208, - -0.21783845743417987, - -0.912705401949494, - -0.3158263729105111, - -0.6887877401213361, - -0.339496624670264, - -0.38621821786191685, - -0.5802391563806095, - -0.667673139910029, - -0.7359092762770135, - -0.34842995644943775, - -0.3795110680154059, - -0.5483812906451536, - -0.551905542117823, - -0.7366311683725357, - -0.2441567734740329, - -0.6561331543203323, - -0.6339388790173556, - -0.29357098439956125, - -0.9659105681407707, - -0.4078377972291669, - -0.3609311585327224, - -0.4330764948046885, - -0.6155418784192085, - -1.3690416193551251, - -0.22847847239099803, - -0.876213431044179, - -0.2758764863279137, - -0.8002927005221453, - -0.2252259856312852, - -0.29087589750931064, - -0.21579329032592623, - -0.3624223862077548, - -0.20588968659575202, - -0.7657973540399451, - -0.8077390093018678, - -1.3718451832632312, - -1.0392461144090892, - -0.21035176761066762, - -0.4390469263281676, - -0.625515710595065, - -0.27049105118142797, - -0.24938664205961647, - -0.5740738561101106, - -0.4939786270429984, - -0.4915388848915729, - -0.2201427622306957, - -0.5382568531960327, - -0.3096492809247235, - -0.9771494100708545, - -0.9525717237647952, - -0.4016939730929059, - -0.26277161392649817, - -0.42771000938781334, - -0.8863950949085446, - -0.6927666349725856, - -0.2375678893733476, - -0.3422550699528662, - -0.37466196381882266, - -0.2922877545581645, - -0.3299411113847288, - -0.900700278035102, - -0.3646201186707885, - -0.4845267203856494, - -0.8096446731980999, - -0.9207515632422736, - -0.6269870736560835, - -0.6940751680979659, - -0.5685375497961778, - -0.2882738389017398, - -0.3971022060295663, - -0.2576380954405629, - -0.23945608835381366, - -0.4748657820310804, - -0.885040967892259, - -0.834747940660293, - -0.9392041678989459, - -0.6367915575115496, - -0.729924523493075, - -0.31832928659086124, - -0.4188012325643881, - -0.6400609035635891, - -0.6004106735715405, - -0.4749385169664477, - -0.9726714712141062, - -0.611744927830492, - -0.31531203780938916, - -0.4924103672992368, - -0.9395807204246889, - -0.26087888550404237, - -0.6568565035351174, - -0.7495211819881206, - -0.5917670297632068, - -0.4944491217885118, - -1.2669140496508513, - -0.6413166293181395, - -0.3338162122603313, - -0.9873627625547491, - -0.26196549621864296, - -0.7490777129642013, - -0.42322301718425537, - -0.3537143122115365, - -0.6395424155467431, - -0.3638443844966331, - -0.6868594950213119, - -0.7648780630314558, - -0.35615507289664944, - -1.1532093255311764, - -0.30181094833004185, - -1.008013068850146, - -0.6472220098951099, - -0.7139114300573226, - -0.5324680198932926, - -0.6564441692332497, - -1.0283045201716905, - -0.7146745688561107, - -0.9429943519256903, - -0.3977273814132763, - -0.5395478715491843, - -1.4664544996081055, - -0.4080790222000125, - -0.8350175601448343, - -0.32753350517289426, - -0.47264194993656733, - -0.21187672059815016, - -0.42279145012090497, - -0.22591968360152231, - -0.5798108901546922, - -0.24083862517328386, - -0.4259204698775717, - -1.04107185596345, - -0.5263952133678154, - -0.9042851635275335, - -0.28521103138650783, - -0.30295460025931237, - -0.2411560273091878, - -0.4309391152379237, - -0.9832288648011042, - -1.0671016582222212, - -0.5725947848052741, - -0.6042744312555297, - -0.4498282620564126, - -0.7842628011124564, - -0.8855963828962293, - -1.2378339380750107, - -0.555489301429725, - -0.2266877084852669, - -0.47472494484702105, - -0.649403224531825, - -0.5089481015254292, - -0.2083525246947031, - -0.4790731051506366, - -0.41509466313669713, - -0.41563785328736913, - -0.3703133699512076, - -0.7903244661609706, - -0.21635026331898807, - -0.6433490190090755, - -0.2714240447028625, - -0.7159522859645786, - -0.5710696417761519, - -0.862201866362018, - -0.40057285053695313, - -0.22003119817452996, - -0.20681785043395928, - -0.23091546581726996, - -0.9395709337870167, - -0.34959519604076883, - -1.138167586007974, - -0.22877743807574552, - -0.536940407941914, - -0.9125533613910036, - -0.2518366031338841, - -0.5329423640473991, - -0.371202322096452, - -0.4142505825292631, - -0.22243270009061583, - -0.24794913910630445, - -0.6019083849503568, - -0.6807124318354577, - -0.2124102548484724, - -0.24096122460863043, - -0.49713159857754335, - -0.6100822745287233, - -0.6501733636306539, - -0.8451032147997908, - -0.527093034540414, - -0.3723085679591465, - -0.27102305519575176, - -0.3105493347721526, - -0.33180372550269066, - -0.4975586091593466, - -0.4706376096208092, - -0.2843584101234266, - -0.75875916419964, - -0.6381476568052171, - -0.37054365297384456, - -0.20445335338332957, - -0.6726737037681418, - -0.6619852604450529, - -0.4442746549878953, - -0.44455726508609233, - -0.48195184040964806, - -0.2599885871632246, - -0.2660273310801916, - -0.6154180198735287, - -0.22889202953063226, - -0.2761997116571713, - -1.0091067054777674, - -0.6430221374541407, - -0.5406773734394938, - -1.1103846335975671, - -0.5086979126302358, - -0.3909684221114096, - -0.6229216412497078, - -0.7937345045908285, - -0.2702651317147354, - -0.29682831309579877, - -0.6481723742015246, - -0.2489432382122446, - -0.26833634331334855, - -0.21619925405520923, - -0.29245702648138533, - -0.36305946759544416, - -0.8918909656940774, - -0.37374977560642125, - -0.6658407607933291, - -0.8772084314292373, - -0.2214195985011924, - -0.4276116958627044, - -0.23006731512055792, - -0.5382922489537395, - -0.37177788844131326, - -0.4289418640394444, - -0.8736242411090426, - -0.9347089693012147, - -0.5100167960941783, - -1.0585367154019298, - -0.762797482998745, - -0.7575418441796995, - -0.2729295260197698, - -0.2894558682236132, - -0.5572288306966182, - -0.59371262700416, - -0.4860998593065757, - -0.469945670985779, - -0.4983785366044725, - -0.2176115666591866, - -0.5714685636273014, - -0.2076372256395952, - -0.4354604950551471, - -0.9531111871563518, - -0.6426231019726724, - -0.745009242942143, - -0.4249028858129759, - -0.9449646816370242, - -0.7101240458449263, - -0.2331517209196125, - -0.4032220619497044, - -0.35263786393852353, - -0.6418481591032668, - -0.38104738856626696, - -0.5405341760218134, - -1.5888201208644577, - -0.9962722981360261, - -0.48248984885341517, - -0.38563319875469104, - -0.9290921555898207, - -0.46129727076721005, - -0.5190671452459712, - -0.9881439126718233, - -0.4781228721278084, - -0.6777000574958109, - -0.6119520753834038, - -0.951146595358123, - -0.5850529269625603, - -0.6712152377937771, - -0.6115338170980361, - -0.8209723975445172, - -1.4597653985567167, - -0.34800312177579956, - -0.4725452722862529, - -0.22345560719556645, - -0.31495027349928123, - -0.20725714697949935, - -0.5910639300429193, - -0.21994138374124028, - -0.2953126425221434, - -1.381397891875939, - -0.7863135161052848, - -0.5365205787050861, - -0.5629715324672397, - -0.2438458961800992, - -0.5066028498371113, - -0.29174957942248286, - -0.8252312178882925, - -0.5273408061179654, - -0.6571204774576417, - -0.36602378915065314, - -0.2438695990414906, - -0.6160736253552854, - -0.44587889932572256, - -0.34189855900048777, - -0.6342291981551974, - -0.5069482482143237, - -0.38893993350239814, - -0.6396474628771761, - -1.1996792118728103, - -0.808989335573745, - -0.8159113044784352, - -0.46665053784719407, - -0.5141624588874824, - -0.4391067291081229, - -0.3464583784972732, - -0.4899601721584026, - -0.5654588153877259, - -0.7777367294320628, - -0.49935171509733467, - -1.0603369561983618, - -0.3168427737299619, - -0.4884575910407855, - -0.5439220677461376, - -0.9996454721384402, - -0.28317340709846006, - -0.4754930760845437, - -0.4159794339248636, - -0.27525148796099147, - -0.3636587538394191, - -0.5620524359527662, - -0.5058483223243165, - -0.9814450187949134, - -0.23679519528354795, - -0.2398854504485542, - -0.7435504996461788, - -0.408305030495808, - -0.39053277030357003, - -0.5112024964178121, - -0.5704629252793534, - -0.8095677143230635, - -0.8438646631303568, - -1.6791498970454934, - -1.1251293796043689, - -0.31779676704084636, - -0.33775635033963664, - -0.2415743752861371, - -0.5126415342648916, - -0.23574983982619604, - -1.0288721057134254, - -0.5049687459785567, - -0.49017536175386395, - -0.402136285028753, - -0.943095784185542, - -0.47998576499655293, - -0.34262116057088315, - -0.34187137573068, - -0.2113547799297597, - -0.367004624322692, - -0.7330200243920175, - -0.3856955180102711, - -0.2945856734694025, - -0.2509955194688236, - -0.5448080797753225, - -0.205916943610366, - -0.2827104245742802, - -0.33789129778308374, - -0.6637933173315528, - -0.5265119625963849, - -0.23421745234579044, - -0.27948294228965, - -0.3680247426247771, - -0.6691771889150829, - -0.45183963201161553, - -0.24969854383513237, - -0.6122374275785177, - -0.3299072770034941, - -0.40533415092826414, - -0.21801141254050108, - -0.7980265033678268, - -0.42008187184009493, - -0.3162272499783327, - -0.4528422589237676, - -0.8434881855090222, - -0.3698610740485996, - -0.5113723069708143, - -0.9301912624563575, - -0.7570343599452567, - -0.2033962020975262, - -0.8676756358407048, - -0.36402903699759287, - -0.38345760852245164, - -0.3150164610071589, - -0.3347533832205656, - -0.24122974891696458, - -0.24163391139447743, - -0.9399309068076452, - -0.2080679601723296, - -1.0263777500700368, - -0.2249709449028674, - -0.23487154007277045, - -0.323809430435108, - -0.38444919856094234, - -1.6191701287088207, - -0.32496126852591206, - -0.2382357225642652, - -0.48756584996244473, - -0.3536521271651189, - -0.42712357074778723, - -0.6605915821261367, - -0.5302016115953763, - -0.6567379707039319, - -0.2194763210543431, - -0.21092104248599244, - -0.7597083249358031, - -0.4311950312550527, - -0.37441865493103554, - -0.7542063301321144, - -0.21930106956891954, - -0.8367892739034521, - -0.6165142937360537, - -0.2768680982489971, - -0.2565646866454474, - -0.9538496511038722, - -0.3245551712789529, - -0.38272504792671413, - -0.25606040207371816, - -0.2527957328896528, - -0.40792474636338155, - -0.7450188721884308, - -0.2060733012419099, - -1.8085852317013655, - -0.25624685603456265, - -0.5437153566378592, - -0.8100772853874866, - -0.20396233866798166, - -0.9600760045469027, - -0.3591002687028685, - -1.186461965643482, - -0.7075794406285888, - -0.42823248996598523, - -0.44248473857526716, - -0.20418073837156073, - -0.24853167915231378, - -0.5571004653593575, - -0.5879102361108475, - -0.23569918404062307, - -0.30979858190532494, - -0.4335098477422352, - -0.366357145010893, - -0.2280096736826415, - -0.37533860575147643, - -0.6070178646474369, - -0.2922093778969652, - -0.2579668564370182, - -0.6400088619716555, - -0.8055518910514291, - -0.6497691337641968, - -0.420296190883824, - -0.45354670010976633, - -0.6660523373051717, - -0.5816455253163098, - -1.0989719842449521, - -0.219490026794913, - -0.771894667965466, - -0.5460385194355034, - -0.48518412362510766, - -0.36349992341061477, - -1.06836341044085, - -0.5594476951711965, - -0.7378548068885165, - -0.4811584507070232, - -0.30955730181435026, - -0.598386817900103, - -0.3604221016612581, - -0.31369543684048207, - -0.21548374294897335, - -0.8134665504104757, - -0.27027230635387545, - -0.9731169256632439, - -0.6786213079535354, - -0.2156359738184742, - -0.2349404525849751, - -0.4204572973536123, - -0.6744693576727465, - -0.45769481146210533, - -0.7781707299008493, - -0.6252492643995178, - -0.6633075907657299, - -0.8978195812352777, - -0.5881609747146312, - -0.5225950996102494, - -0.39170658420041243, - -0.8315389332812131, - -0.5676218690721875, - -0.49968590103872684, - -0.39523171153559344, - -0.27053235210668425, - -0.20470457212186588, - -0.2975543807978394, - -0.24110398176023495, - -0.37154561071568415, - -0.8956257128234352, - -0.4197559289009459, - -0.634746514401001, - -0.7289837085038223, - -0.34407823336362053, - -0.26299668842488355, - -0.9178042495293768, - -0.2727280042146579, - -0.7990838948690474, - -0.5613879132941998, - -0.6591191499450472, - -0.22197468160923592, - -0.5821666417327183, - -1.3429533232791284, - -0.9380537397288679, - -0.4668440989472912, - -0.7583833649263122, - -0.2821711969677566, - -0.4625872743743004, - -0.5338109170385094, - -0.8450709667647983, - -0.23090513257014564, - -0.8892924544080849, - -0.2272844615303203, - -0.726903577482699, - -0.4401372552261676, - -0.7259954646376868, - -0.5721985560512197, - -0.6686563704107502, - -0.2158571602733609, - -0.35271014484181673, - -0.5358365345692082, - -0.42273184062521113, - -0.23203579192456947, - -0.4911666677853067, - -0.34793323727507197, - -1.0114494590022827, - -0.22111026583960544, - -0.42295055798500686, - -0.7439041511508949, - -0.2509248008787742, - -0.41068494711663683, - -0.262469991804008, - -0.9499463273551092, - -0.21155726773355304, - -0.41853131098125385, - -0.34727924188183934, - -0.752474067350829, - -0.7678067927635248, - -0.8908054607306998, - -0.3739819712399651, - -0.27699085497743453, - -0.9127697871652686, - -0.2955114868014864, - -0.420902530526401, - -0.24232383564903906, - -0.6569639458357046, - -0.30591234460390276, - -0.3904547584492363, - -0.35235197301996596, - -0.43964677153549064, - -0.4855499556432413, - -0.998972731005372, - -0.7449715094047011, - -0.9232533677115989, - -0.5219027286916391, - -0.30567036170679984, - -0.4131976583416657, - -1.1088228213012552, - -0.5071682965670713, - -0.24710851252133353, - -0.4416476169513818, - -0.3900951351636086, - -0.8538023936782931, - -0.891419902701978, - -0.8532732522013017, - -0.4437635104416198, - -0.43250706846547216, - -0.43621930594670316, - -0.6102238185649577, - -0.25464057156644115, - -0.48987927135951004, - -0.3020227655652665, - -0.9989486745486467, - -0.8793755202094218, - -0.5406207403671637, - -0.3136984573650755, - -0.3147776163917925, - -0.5786957849334998, - -0.2763407541859462, - -0.2374652764696286, - -0.22688565874995317, - -0.44381463586294095, - -0.9008315826616169, - -0.9706965234834929, - -0.2554680691244456, - -0.8843395819957929, - -0.2927457821353059, - -0.41008144129794977, - -0.6135531887194693, - -0.40162358794293324, - -0.6070441072629101, - -0.6934599078872028, - -0.6107457882395264, - -0.2878207670503938, - -0.3687054799239241, - -0.2927011016512284, - -0.25668132315094616, - -0.633543759615117, - -0.2361159278571737, - -0.24333468681470355, - -0.26663547218561184, - -0.26709301493230503, - -0.7402292340850677, - -0.8707819454449304, - -0.2807144072580345, - -0.41057132384707046, - -0.6256617183187458, - -0.46510438152165, - -0.28402907385666876, - -1.4715053178740625, - -0.5367599196985126, - -1.1548974956337685, - -0.9303735038373285, - -0.46657974027294175, - -0.27213884493236695, - -0.36345444734980303, - -0.45978004268929806, - -1.0061173420674119, - -0.8841644802738581, - -0.24183150309143325, - -0.3036639204921354, - -0.7757723832626721, - -0.47399821374657636, - -0.5522704441875281, - -0.43401690316675157, - -0.5852617574303774, - -0.5712307193290094, - -0.931350384156989, - -0.24415178406426713, - -0.7045056461704827, - -0.8098071680939591, - -0.5244918575011116, - -0.8052238608947528, - -0.5843227798797791, - -0.43125417210350814, - -0.5169773014865218, - -0.226752203030785, - -0.6434675063760812, - -0.48583579409053235, - -0.6332680261978687, - -0.4470040343499757, - -0.8133437045371674, - -0.235982549493029, - -0.8915437353661104, - -0.34294673066822423, - -0.29072461766081714, - -0.20374537409565063, - -0.3871787418710719, - -0.20751231735311199, - -0.2238090145845397, - -0.2347124521275664, - -0.4085328522334308, - -1.1501729826880696, - -0.615005297020405, - -0.6000229560909378, - -0.3479508386759734, - -0.6017606367837482, - -0.6458546466673745, - -0.6305211231429835, - -0.5344344467241452, - -1.1660739198057557, - -0.8230699158775926, - -0.7100291393200355, - -0.24801427870251636, - -0.2764465113107261, - -0.6272473798596185, - -0.4856053951752283, - -1.0570066163278313, - -0.5951895520041017, - -0.6075943149500723, - -1.2676133451469216, - -0.2231376177266142, - -1.261157714211524, - -0.4337878443811667, - -0.22669892368447292, - -0.44463308508772187, - -0.21636101236207406, - -0.33673519697104604, - -0.29964915372672285, - -0.36263807508941326, - -0.8272460705847953, - -0.8001063370317171, - -0.31819581784546014, - -0.2808865647012272, - -0.9425884170363157, - -1.2215544179559303, - -0.5002727688302466, - -0.830524649609551, - -0.23826137945916884, - -0.2043624239251822, - -0.8281373367262003, - -0.5042064905386624, - -0.8104286094831149, - -0.2576311857710717, - -1.0623390763555733, - -0.25107670480657207, - -0.33986200442732567, - -0.228772599495233, - -1.1926798128238743, - -0.5096041201538882, - -0.5466173915887039, - -0.6386836348148418, - -0.32949580141129636, - -0.3153918587972526, - -0.7096389269884841, - -0.3293924965686415, - -1.5375546695916666, - -0.22537099063347793, - -0.34782998155491723, - -0.2993834557403305, - -0.6680586992509188, - -0.44520039530888045, - -0.9426996893174711, - -0.5104212508625222, - -0.39777903429183664, - -0.2665700984443428, - -0.48711375762082265, - -0.4658764879157437, - -0.6395189107221753, - -0.6435830004497787, - -0.7061485650056902, - -0.29196458711779727, - -0.49370747870566956, - -0.22064945966807914, - -0.6079799536332644, - -0.2673266321916141, - -0.9116384959119789, - -0.42143009954908384, - -0.27930461647029425, - -0.28054335309263606, - -0.23726485587544222, - -0.7260773051842033, - -0.4680322781475941, - -0.23095190478344133, - -0.6205918244222843, - -0.28935661718161065, - -0.21191432911512917, - -0.6113300429549642, - -0.33462124063969356, - -0.2404283689144671, - -0.27943320821863704, - -1.0136516891505127, - -0.701167311225485, - -0.952105456181688, - -0.5312079518551326, - -0.5455365222984727, - -0.244002833408233, - -0.5893610989043836, - -0.9115028941249746, - -1.0332626360603918, - -0.2998910141259873, - -0.31837681733855633, - -0.21064648058475713, - -0.34715208926591784, - -0.2771586299526436, - -0.21441635556370534, - -0.23969666316704694, - -0.5618585884608555, - -0.5161189718375334, - -0.3220540417295827, - -0.42627255907096523, - -0.3947411273600767, - -0.4165872754711484, - -0.45347260451448523, - -0.4858901402827695, - -0.5272622039135073, - -0.8865372681247069, - -0.45291331259943574, - -0.3760120023174674, - -0.3706746487726517, - -0.40744617450534415, - -0.8158328494973264, - -0.35484658905668237, - -0.5170688489630975, - -0.7486497948096514, - -0.2575121155161291, - -0.40879652790914717, - -0.3849228133566335, - -0.4166585104033113, - -0.29277159256342505, - -0.35010871641110997, - -0.7849810746413484, - -0.6250274165166373, - -0.5306670136538957, - -0.6422646603923619, - -0.5249377499798337, - -0.33662422104651507, - -1.1337659484153022, - -0.4375160196667062, - -0.3988626357460644, - -0.43319774899724794, - -0.3117370308632423, - -0.6737714048172558, - -0.4119754148018966, - -1.0438094565082323, - -1.1947577670658245, - -0.968314958405781, - -0.5494309125851542, - -0.5769797646695339, - -0.5833000137570834, - -0.39772858397541466, - -0.5076456692027892, - -0.8599177710665058, - -0.22128029817863545, - -0.5550109740411255, - -0.6613213847067201, - -0.48993487790762036, - -0.3668989270044954, - -0.32563633440252077, - -1.0432459233115157, - -0.5208476637936371, - -0.4027459148017001, - -0.4397401895941201, - -0.9715214685571527, - -0.2296345041720817, - -0.3776568970154085, - -0.23623457864501232, - -0.2371743440515029, - -1.1914114152051334, - -0.6501854553336425, - -0.456043652352862, - -0.3455191458584609, - -0.3760676243900464, - -0.2528599162123094, - -0.9082615357711028, - -0.6615468190460717, - -0.22191166150495442, - -0.8512097558126079, - -0.8231488376322412, - -0.3112692216841705, - -0.7909415934895698, - -0.8650940876407338, - -0.5050426986746545, - -0.6262712759035921, - -0.4407736956766857, - -1.034376174944662, - -0.3675086770046684, - -0.3556292004690765, - -0.4732792623429743, - -0.4523821479899143, - -0.5628520789133412, - -0.3113244212262602, - -0.49291404599810057, - -0.3047519077199362, - -0.3874944751902527, - -0.28742054950845114, - -0.24964195588661955, - -0.29839084037357094, - -0.4056249730123957, - -0.4284578813876631, - -0.2916753616654342, - -0.9607611292946623, - -0.27697384406113773, - -0.2614730226391541, - -0.2423954445263222, - -0.8679444314758585, - -0.6255673338965102, - -0.2687367846068112, - -0.3250779651738379, - -0.44031625343301345, - -0.28964544128376934, - -0.21090516649733718, - -0.671469697976029, - -0.4084359884684402, - -0.30622560787917696, - -0.7447357789887912, - -0.5479324966193846, - -0.2815364169453482, - -0.6676578683535793, - -0.30362300531432346, - -0.24983525314434205, - -0.6217865480250353, - -0.33242037073572817, - -0.5950096942963115, - -0.25035493897755023, - -0.3582787281617694, - -0.9445596116223431, - -0.962177568197086, - -0.7179133454723361, - -0.5229014445105209, - -0.9050915253111644, - -0.732497204370986, - -0.5359545735990593, - -0.8467002640381769, - -0.6796178637392687, - -0.36413098103531694, - -0.4945190358366176, - -0.3205568263368299, - -0.2727245067567413, - -0.3303864614722747, - -0.3901623334621691, - -0.7520691061168323, - -0.4153708325032037, - -0.972556109729559, - -0.5178932691878444, - -1.0187813127699528, - -0.29086938587607997, - -0.6944791635696663, - -0.3169213318766927, - -0.8033208004887968, - -0.39719153717171807, - -0.2674474477082522, - -0.5423038513717501, - -0.613373371569122, - -1.0837772686291258, - -0.25770046483083103, - -0.6690814435938734, - -0.5139638207978283, - -0.3602116579820135, - -0.2676560005728889, - -0.2534464356283099, - -0.40138610574893313, - -0.29377069212363643, - -0.8432827181337917, - -0.37763410506647993, - -0.3234935080512723, - -0.5396774413313524, - -0.3040111153200116, - -0.8978380225412432, - -0.5958697541079362, - -0.789025454910136, - -0.3063744229099775, - -1.4960783226559085, - -0.5373933213575024, - -0.6591529887370451, - -0.2440596587994043, - -0.41243504127673275, - -0.20347340879933515, - -0.5305028033218329, - -0.36099592989825807, - -0.2229516017500209, - -0.5158800839510705, - -0.5188726043303871, - -0.4141231990318807, - -0.41191987723461226, - -0.30826090622489993 + -1.4667515089896195, + -0.5790633384243934, + -1.5435398824037605, + -0.7880737146142803, + -0.6809902292870229, + -0.6661581010694717, + -1.4176920767436187, + -0.7809403344828725, + -0.22215599415247367, + -1.0443541316885225, + -0.7752149162475835, + -0.726993692535098, + -1.255491029792055, + -0.5495727643310321, + -1.1629487154968356, + -0.3310590060410756, + -0.25886713353314195, + -0.38484465956454333, + -0.8271660797424499, + -0.45869894548750884, + -1.0409562049356937, + -0.29767660196878676, + -0.23129773666249698, + -0.6146739745728058, + -0.23928409279309723, + -0.7871413894466872, + -1.2204671996915444, + -0.9541667162378777, + -0.9351539614118634, + -1.2424884473985938, + -0.7495237849902293, + -0.6312836968170541, + -0.7061038597425341, + -0.88824313557038, + -0.6963319169043274, + -0.9095892838595439, + -1.027367437476644, + -0.45287588646971627, + -0.39706328932997564, + -0.9585722197089535, + -0.5098947533685516, + -0.38523349937695667, + -0.881523293413903, + -0.2569020466063843, + -0.8019182604977485, + -0.4057790560745802, + -0.40035101120165045, + -1.2456943137886842, + -0.9673319442244634, + -0.7684898380567852, + -0.4513927487760398, + -0.5490694778638632, + -0.7320595620675265, + -0.4703235923926819, + -0.6266420482785372, + -0.4181916304450253, + -1.1705425920757526, + -1.1351384177264299, + -0.7683722333473658, + -0.3842743319905672, + -0.24778853457871422, + -0.7336207543875285, + -0.6152768289861482, + -0.2912589303902388, + -0.27916535336134113, + -1.0867928951843482, + -0.4586694237610463, + -0.3199509624232216, + -1.3422073460446713, + -0.7536599261005174, + -0.601082809551367, + -0.5224044079544212, + -0.4156987642132697, + -0.5384628686880422, + -1.1753542629162863, + -0.8726933805429867, + -0.5138281899704763, + -0.6975649197240055, + -0.37812697427703884, + -0.27654582132566596, + -0.35735615014650174, + -0.5316314895738521, + -1.145081368090527, + -1.0399785427841106, + -1.009974119358116, + -0.6314185355840964, + -0.2331468575477539, + -0.8228345560687372, + -0.2935700391381559, + -0.3105518767412249, + -0.2839135363390448, + -0.6477645715254493, + -0.4391714539712093, + -0.5205408700629842, + -0.25367692773361467, + -0.39998320182827746, + -0.7567966922250715, + -0.38218866921568634, + -0.9234393327276432, + -0.4252459253260543, + -0.349391465149318, + -0.8719944946390298, + -0.3686615795776081, + -1.2585468019503523, + -0.46065884771652776, + -0.9580616649583921, + -0.5327853269786734, + -0.36749873179066234, + -0.287215037791013, + -0.4686987233187426, + -1.0276697934212433, + -0.544497281124754, + -0.9984376297675638, + -0.4304822902278828, + -0.434992461887345, + -0.421682014121349, + -0.6771354541485628, + -0.42882300251475125, + -0.3952583397162227, + -0.7020734607001652, + -0.3229175677359276, + -0.5561500000949224, + -0.8807610972862912, + -0.9460198576875761, + -1.2447776672773982, + -1.1479810873941838, + -1.0574455806613074, + -0.2935961830619391, + -0.3989290287810421, + -0.5534515206616327, + -1.4517279109737906, + -0.29504886134373404, + -0.8716891954942397, + -0.7256366262765611, + -0.6625871597780724, + -0.5390189238908434, + -0.4495545843679283, + -0.5144231357967869, + -0.2925439046041846, + -1.3254655024983708, + -0.5098814208905753, + -0.7455083845603095, + -0.7166081330606084, + -0.4411894830041861, + -1.2097098766043952, + -0.40377351347340384, + -1.737186218777263, + -0.6299552543145079, + -0.7806323587067713, + -1.0517536663909246, + -0.27056228761465917, + -0.9225134304124896, + -1.1088238215181772, + -0.8150799445740189, + -0.42988929964760103, + -0.9791945394017437, + -0.7177084687011921, + -0.5378194223462949, + -0.8984541463064291, + -0.34314001846877035, + -0.22647044994126406, + -0.8020702913783198, + -1.0131170484880738, + -0.28860222548608977, + -0.761528087205973, + -0.4021374079193053, + -1.0206363508695455, + -1.2770450699331575, + -0.8748655418063721, + -0.6361437348064232, + -0.29095868522694535, + -0.4793015783081467, + -0.6256554921957405, + -0.8662581882804561, + -0.5126570174366148, + -1.3761806470552833, + -0.2753375505214452, + -0.37315200422896133, + -0.9929716545031225, + -0.40354704742842856, + -0.49160696722540903, + -0.7119997663953727, + -1.1776044184794863, + -0.3240183474314143, + -0.3323696741942943, + -0.2893150210574461, + -0.2833105969000716, + -0.38973959872465447, + -1.1474515695626903, + -0.35903966033183676, + -0.8183353060389434, + -0.3611077163675936, + -0.6802109285577989, + -0.3912986588603686, + -0.25365779469350613, + -0.44325326108255503, + -0.7330641258828908, + -0.35690046762140004, + -1.114886937308783, + -0.4095549129208012, + -0.35256152232604415, + -0.5523493627631615, + -0.26514089262410057, + -0.9997408637057746, + -0.8921123983371109, + -0.3488855192268438, + -0.5214388261617969, + -0.5848637141548317, + -0.3164149366226771, + -0.8574547198645814, + -0.48792526879882825, + -0.6480726713663053, + -1.5541939436370382, + -0.39833595760500684, + -1.2217799744468485, + -0.7400880437122817, + -1.3840444643068337, + -0.7319123604317591, + -0.3899308575933119, + -0.5412301134748964, + -0.3115317938627566, + -0.2595378588203591, + -1.411034868222459, + -0.3472201905948351, + -0.370180076869879, + -0.3896512037211502, + -0.9929309725709711, + -0.49102662321939283, + -0.45868853651695674, + -0.4288885909417323, + -0.22255762861234946, + -0.7334087748412731, + -0.33297271870362904, + -0.4237426544008057, + -0.6517233025982048, + -0.8109587222494623, + -0.305401232127859, + -0.4767446312032811, + -0.34476136644428973, + -0.8861335957349988, + -0.5813493438008485, + -0.2916984494107494, + -0.8667347405067114, + -0.6662032132428166, + -1.183718508782624, + -0.3467550731427867, + -0.26426982346790706, + -0.27379176636951613, + -0.5640006387780291, + -0.6692803395286483, + -0.6739448837914234, + -1.4791880870286396, + -0.6652782091235644, + -0.33406190048146456, + -0.4309552249337072, + -0.2999873524908851, + -1.0483058854351452, + -0.4558208281743951, + -0.5566118750516482, + -0.3469056276314206, + -0.6071619482398745, + -0.5277639918172548, + -0.7726542207673796, + -0.47618212608834, + -0.8376965467871182, + -1.3321122699704628, + -0.8715121789797805, + -0.33093189437555676, + -1.2734574845287334, + -0.7377564816664928, + -1.2806348818018, + -0.43001022508361125, + -1.3811724546842385, + -0.5418060194401757, + -0.7030215574649756, + -0.36466051253930537, + -0.5539177648351991, + -0.711388532466459, + -0.8217904167300983, + -0.6780767807934619, + -0.6874160575382979, + -1.0425295356694197, + -0.6316677875265279, + -0.7057876003842705, + -0.4648917740553694, + -0.612528240105111, + -0.3049370268313365, + -0.20258225883973294, + -0.5005705881849407, + -0.2759711947490402, + -0.5057690770818718, + -0.8120668677012762, + -0.2830095996159061, + -0.5070570612815087, + -0.7362918602767035, + -0.31493887768294115, + -0.29229495294569646, + -1.4233106283263537, + -1.1708244072062015, + -0.6258494955860517, + -1.2486519224098682, + -0.8571607935366056, + -0.656544555357858, + -0.42018840019452064, + -0.7119347385123891, + -1.1388352463648581, + -1.2721675943386286, + -1.1940420876223046, + -0.7828828525297681, + -1.2571902584193488, + -0.25268870812061506, + -0.4830317060223369, + -0.395227325885267, + -0.6211744150619781, + -0.9283543507467081, + -0.9371572430162715, + -1.8692102366548102, + -0.33875112111097316, + -0.2584094606592847, + -0.405315911318289, + -0.36282237707261045, + -0.2294848852258725, + -0.7475350985460163, + -0.7025603088285018, + -0.6482455287460178, + -0.687500820132255, + -0.6696057613490176, + -0.23861915552155763, + -0.4819848422916155, + -0.5914903486936832, + -0.37606583635189716, + -0.24813646321047475, + -0.34323093631618234, + -0.23694308431499908, + -1.440406340877105, + -0.6515875665633059, + -1.794901552997255, + -0.6425784789441203, + -0.31157104976687533, + -0.21940340070301126, + -0.5128793151906124, + -0.4307940896318981, + -0.6783219730811806, + -0.9679562984696509, + -0.3296754464461936, + -0.9066534498236859, + -0.8470022412841115, + -1.1442156583829028, + -0.6049030762786517, + -0.8872482151353781, + -0.21775480716976928, + -0.4113488979196679, + -0.25834650983652446, + -0.8820449819307155, + -1.039507598482556, + -0.731544537608164, + -0.7450145999391584, + -0.6867843478521848, + -0.9183339395143681, + -0.5466324511707067, + -0.45718189966677014, + -0.31985812250375784, + -0.6470951238912639, + -0.8968934026646704, + -0.5699808578431923, + -0.7332296145920328, + -0.964586946507631, + -0.6338039278856022, + -1.3081752070122847, + -0.6688291926834856, + -0.6194440092013205, + -1.371069744545857, + -0.4439352665547536, + -1.6799337208443172, + -0.5149422313554987, + -1.3307813288150168, + -0.2543587946074502, + -0.46055094389882023, + -0.4646268244566624, + -0.6308434438868186, + -0.4824854377636459, + -0.4872933883924047, + -0.4327954446107907, + -0.3720106987571837, + -0.439776146638002, + -0.7357180149036969, + -0.25248649890622143, + -0.592086939738244, + -1.538649895515943, + -0.32344865570598713, + -0.36046006803508096, + -0.7728727809280946, + -0.6772769479664695, + -0.7883763079206464, + -0.37533513635105537, + -0.2135567553594619, + -0.7531605802248135, + -0.6815523633391891, + -0.7677731426902993, + -0.4247026849223633, + -0.368275507390876, + -0.6956908161343915, + -0.7157023928497405, + -1.1359250562378957, + -0.23763009245671554, + -0.2775206497211944, + -0.2649043943011158, + -0.4483275119247894, + -0.7407002721308581, + -0.5928904447698712, + -0.41177911668248907, + -0.4715296692823231, + -0.43110103081529233, + -1.2180924650109444, + -0.3583465137161367, + -0.8070964296084777, + -0.446023521170633, + -0.2102891223843266, + -0.2097175938843591, + -0.48338482035250535, + -0.4762731973999992, + -0.4165889270681212, + -0.6587976110836249, + -0.8900305208594583, + -0.974443629051636, + -0.9023255031065993, + -1.1580924416171816, + -1.1361383088420773, + -0.6599131903311872, + -0.9274438552534084, + -0.6058511763675909, + -0.8206020199108702, + -1.0942025350347362, + -0.5720272388239412, + -0.5647705242792688, + -0.23765337904230502, + -0.3398505299877096, + -1.523959830216154, + -0.22242619997453658, + -1.7841883592649166, + -0.6081452388659376, + -0.26320455290730455, + -0.2743914658223848, + -1.1189776789682808, + -0.8048184490798836, + -0.42198619774201473, + -0.8313599170540501, + -1.7302037836316353, + -1.120576886486916, + -0.20083358801994303, + -0.2090831892891727, + -0.2940948879883434, + -1.0688095721591755, + -0.3265820204241754, + -0.25796535729220615, + -1.0659385378386097, + -0.374650158508675, + -1.1944098512322252, + -1.5156284870543761, + -0.6944366429661167, + -0.23150056369652505, + -0.5653158943646235, + -0.3087396049432832, + -1.3671205620874567, + -0.5906244721789992, + -0.7914421887452622, + -0.3496911808015845, + -1.8445480909992795, + -0.6804605458966007, + -0.6566310938972416, + -0.2083972500415083, + -0.9007857215382672, + -0.41261370506724054, + -1.275273221743306, + -1.7543927630320715, + -0.9267738737918223, + -0.327324755462774, + -0.6797021886213299, + -0.797452424176946, + -0.6830486964411149, + -1.488575247849262, + -0.44019813965300675, + -1.4895948568291044, + -1.2517599125680743, + -1.2079497630056024, + -0.6351708519086158, + -0.5980390129074433, + -0.7781811674789311, + -0.4685164323219777, + -0.4517619475298156, + -0.39116982505619774, + -1.9072724725102421, + -0.2781105511866482, + -1.7373101703101255, + -1.998449376075458, + -0.4607280675546788, + -0.5694057404195791, + -0.6836865153997328, + -0.30591209122592433, + -0.30502323323572295, + -0.8817419593328046, + -0.4661970188964971, + -1.19750373059071, + -0.47365463120367657, + -0.8668122586103925, + -0.3638355876146821, + -1.7179543924779237, + -0.4360303045466097, + -0.3736980832676535, + -0.6827941015536856, + -0.606151733678104, + -0.22333995310238458, + -0.20470259550261208, + -0.6541096221726104, + -0.9887929123092992, + -0.9308715988608588, + -0.2557205404441554, + -0.3139373914970066, + -0.8215971280664988, + -1.220369237541909, + -0.6451277552807293, + -0.8271984833340307, + -0.7190397949185756, + -0.3168446973814252, + -0.42358963420035955, + -0.3956586314727917, + -0.3869796277023778, + -0.4044895142597208, + -1.5639364605812778, + -0.8828353934961193, + -0.3182472781783348, + -0.9185723904345228, + -0.36845278567267525, + -0.3934270876444073, + -0.5040741405029854, + -0.3287961337507045, + -0.6875314411791053, + -0.8243142947235532, + -1.4100240663372294, + -0.7780560871491846, + -0.5107372989384538, + -0.7104616083391393, + -0.48989831018229696, + -0.39283130363582586, + -0.4827813816664917, + -0.6572226455064698, + -0.4182797555881974, + -0.32926613313596353, + -1.1568684326689267, + -0.3227530833826153, + -1.8519031708500444, + -0.6739825312268726, + -0.3634077234984936, + -0.69630345078505, + -0.4057216937896617, + -0.21351870845390022, + -0.515467035640527, + -1.0835016039725864, + -0.4631196899310904, + -0.7471321106710326, + -0.4088183699459141, + -0.20654471614203518, + -1.3292640919782914, + -0.8723473774988265, + -0.41199522721898185, + -0.44428026470612686, + -1.9386766260066943, + -0.5465417256829804, + -0.918467585843905, + -0.300889431312205, + -0.3523967267298571, + -0.8671149441986202, + -0.6345953020322229, + -0.7804511939610308, + -0.6100370533066982, + -0.8674141277221272, + -0.20202416770120457, + -0.41102764721050755, + -1.004508062339198, + -1.4139809904410237, + -0.8446040091736344, + -0.7380145274623713, + -0.35418247372145245, + -0.6037818705225177, + -0.5347736021411841, + -0.6209297000415278, + -0.3867144810104474, + -0.8059926734735796, + -0.4518164938676446, + -1.0600650392035955, + -0.20134059404050267, + -0.2771835140245081, + -1.4887162819207342, + -1.2097196546499969, + -1.1597006523383007, + -0.7913253161049635, + -0.4435116508809034, + -1.4333252855071668, + -0.7473152264508669, + -0.27323665827026844, + -0.9536145416728306, + -0.5601145484970839, + -0.4421542507755204, + -0.20688579214856606, + -0.22923928533360693, + -0.38405837633790935, + -1.038430459533264, + -0.7732790838737102, + -1.165264508183141, + -0.5207565889250441, + -1.0866878393364316, + -0.8057838011644455, + -0.21312266089724982, + -0.6621479943023486, + -0.24033669719537953, + -0.22996065942137314, + -1.3041758771470022, + -0.7597458625094142, + -0.959224324552792, + -0.39151016233799696, + -0.22338379181103823, + -0.8218170924675052, + -0.5730364728114619, + -0.3301354757137461, + -1.1500992117197564, + -0.32957251566351087, + -0.7131310038612009, + -0.6987574943004461, + -1.5558092535500125, + -1.129741408260928, + -1.5161176969719827, + -0.24468079175231405, + -0.9482500138984797, + -0.3614605874811405, + -0.9862389133788655, + -1.0719584539857365, + -1.05796232333806, + -0.5475849381357648, + -0.42727396207910107, + -0.6785691463855915, + -0.6156113491658274, + -0.39618216825894337, + -0.46564239284583375, + -1.0074335057040347, + -0.4268076722791955, + -0.38039392211081524, + -1.6487089208051657, + -0.3995693162229643, + -0.27077023235183867, + -0.9596438608249784, + -0.7584514269937306, + -0.5253148882376868, + -0.26447244977947665, + -1.138059542144247, + -0.4011675916512855, + -0.4747838336291965, + -0.9341037547642225, + -0.6126771922041079, + -0.3564209700350011, + -1.2942250587415611, + -0.6267219649618757, + -1.2722795862605072, + -0.9212698109729562, + -0.49189903400778645, + -1.1061944827889791, + -1.9304567887037503, + -1.011021805618249, + -0.5178772011642349, + -0.2154620556287784, + -0.6435234361192386, + -0.2724740574351633, + -0.2145331812787856, + -1.1198749883372332, + -1.1575797964853156, + -0.5345015411584766, + -0.3521719594216333, + -0.4127488299694216, + -0.48088286650707474, + -0.806543845611556, + -1.6821555327458546, + -0.7155280422369289, + -0.48101130036742584, + -0.2813352536575611, + -1.5907489505068868, + -0.34012885009748306, + -1.0806001397087341, + -0.7823081530769892, + -0.26549796753777827, + -0.7162998623528744, + -0.43554938845640856, + -1.0906472074745133, + -0.21370742107246302, + -0.6779037955345744, + -0.5432481212132517, + -0.7252638988337274, + -0.7801436022078739, + -0.4907347943575986, + -0.42388022539774733, + -0.3918889208045065, + -1.1248979727851818, + -1.3850561175891452, + -0.7746789372138172, + -1.1062294986015964, + -0.5507052784335154, + -0.46935666333926634, + -0.26214267061871227, + -0.46406968299746637, + -1.9999376330351428, + -0.5035909780785772, + -0.3115108021722356, + -0.7825227612126084, + -0.9612503379609182, + -1.0109435545721812, + -0.319161041164713, + -0.49647265319727407, + -0.8364372069270214, + -0.6549050829327184, + -0.44428312840392675, + -0.9190077411155071, + -0.6730064873322712, + -0.20863105116594155, + -1.152964656616306, + -0.9496305221642822, + -1.139471010828018, + -0.2940068200571684, + -0.6971630096824071, + -0.36738569085252837, + -0.42132595757944113, + -0.6570931250466215, + -1.2197496485861736, + -1.124195456442725, + -0.43520423652324447, + -0.9622114489839496, + -0.5967489828276259, + -0.30417485293268937, + -0.8811876008175503, + -0.3046273060281897, + -0.9639506421860431, + -0.5031690035595647, + -0.4305522911298151, + -1.30265132830295, + -0.974434139301884, + -0.5919693658610833, + -1.1811141531688227, + -0.7453778620083029, + -0.375593090223646, + -0.39247050531235944, + -0.8096698405649558, + -0.7208234891544728, + -0.4489748669222336, + -1.2009266225029862, + -0.6408668011821871, + -0.755267318200301, + -0.6840580628171089, + -0.5091827916125221, + -0.3629303817243719, + -1.1994267084896038, + -0.2400026661400186, + -1.0447120775207774, + -0.7974608981436466, + -1.414360473304135, + -1.6404922621010658, + -0.5058096275401923, + -0.697402752215401, + -0.20999399722591558, + -0.392641665876604, + -0.3416856993040956, + -0.3383952349061352, + -0.6012496305687505, + -0.6653653540297084, + -0.2248425995625818, + -0.30662765990225893, + -0.5602494677617743, + -1.5807983746183876, + -0.3067867700086469, + -0.4835821449886224, + -0.8271580405996515, + -1.286455555643974, + -1.3197823149005132, + -0.5349344540738674, + -0.45769164481102836, + -0.6072669187880991, + -1.0379595079374921, + -0.7306899851764169, + -0.8941792738663797, + -0.7823270984654109, + -1.2070476093245617, + -0.31860003878994075, + -0.6956087600141532, + -1.2389458329591796, + -0.6814809979715937, + -0.7491131253198249, + -0.6286241270020342, + -1.1035851121287832, + -0.8005588359372553, + -0.5813634807592303, + -1.8232116496802895, + -1.9771806292250786, + -1.4716943486757217, + -0.5115444834784842, + -0.41869729038319703, + -0.3413307410228098, + -0.8375647470354444, + -0.47528511760717873, + -0.8540712625584109, + -0.8615933861526459, + -1.3174402366561024, + -1.299986952089124, + -0.736819527006218, + -0.7456394500708909, + -0.27352154032711073, + -0.7017215750026625, + -0.33202657516643236, + -0.24785869732105525, + -0.5160269252241094, + -0.2635256253999394, + -0.6008515934114059, + -0.6445169046462731, + -0.6698922291197438, + -0.2713889372938922, + -0.5581973346398473, + -0.780690999720683, + -0.22036951301375873, + -1.5607967131348914, + -0.2850621193546593, + -0.43604760515733687, + -0.7289682956331016, + -1.01007578953657, + -1.4472676622304028, + -0.9915084424074133, + -0.5137592718561693, + -1.105955010931569, + -1.3451000243879678, + -0.2547480842636876, + -0.37295724923266654, + -0.5943798801130616, + -0.2927776253296611, + -0.3867992812980984, + -0.3278195291204005, + -0.33801751995048596, + -0.7627132145972209, + -1.4370631660793447, + -0.532331442885718, + -1.4121192974899774, + -1.3049106388523304, + -0.45180964339698626, + -0.32762445658202727, + -0.30139568692805396, + -1.375215137368138, + -0.47472630927986514, + -0.9902267276254432, + -0.6316080073350071, + -0.49985849513576064, + -0.5564338485574627, + -0.23785670570341003, + -0.37445245964968193, + -1.1647032246489748, + -0.3992361768382778, + -0.852422778858215, + -0.5021688067473857, + -0.3739009280709113, + -0.8428775708042917, + -0.32012949769999494, + -1.0593567436744147, + -0.5384924631824289, + -0.5925464845153774, + -0.3528650846491671, + -1.2767684282930991, + -0.5577153553950581, + -0.27630011439177016, + -0.9670935722910218, + -1.015716290556304, + -1.0747359733456106, + -0.39440243906810435, + -1.0097265954156769, + -0.45940620353700956, + -0.2161059780938429, + -0.6285723441491734, + -0.5594796507539387, + -1.105570742189663, + -0.972138888727773, + -0.3491329501409191, + -0.6771064601505468, + -0.5020659196125178, + -0.3526964885355658, + -0.5365665595408048, + -0.20619964240957125, + -1.2396169998325544, + -1.0580846959566916, + -0.8044674222621593, + -0.5148174357046986, + -1.2547727747528237, + -0.9482073557798447, + -0.25875126366828005, + -0.7838948563767549, + -0.9631308345010947, + -0.7051628945756213, + -0.5922659475620846, + -0.7497689573902135, + -0.5503334465755391, + -0.46114825379246305, + -0.2661421468015469, + -0.4560993385549935, + -0.9453631114563084, + -0.671526316567795, + -0.6422324818566791, + -1.0499533048676954, + -0.5363850826026986, + -1.065324699097405, + -0.24382931524452317, + -0.45996616122960426, + -1.006262498948445, + -0.6530233223140962, + -0.8344328627105227, + -0.4901680536699724, + -0.8595176945570743, + -0.4210345789393033, + -0.34699862327062464, + -1.1925303482661422, + -0.6672375020016433, + -0.8916238597031877, + -0.23824373062357942, + -0.8544250182874419, + -0.3940449930307898, + -0.268946899099666, + -0.6503998398154687, + -0.6926759326510963, + -0.9768051931995342, + -0.28561825042346617, + -0.527131786713126, + -0.5316147567303705, + -0.5894496534781918, + -0.2912490070031772, + -1.3676196371768488, + -0.30372128863244896, + -0.3652344437727391, + -0.6409883449734605, + -0.7125576705876969, + -0.32692172263808034, + -0.2729010108762933, + -0.26669508346203774, + -0.6123926199756916, + -1.0204627401231399, + -0.2540387330528254, + -1.2674014545822287, + -0.474967404435733, + -0.4717079326498636, + -1.0008547763665678, + -0.8872552158401803, + -0.96602317321276, + -0.615254498831308, + -0.667256580742035, + -0.8077822533458096, + -1.64085452836896, + -0.8982887695263438, + -0.9353096533555187, + -1.2214862851027126, + -1.5651175202831784, + -1.1280450923736678, + -0.43238004404410624, + -1.0436150049531487, + -0.6323104113394121, + -0.4003280583451471, + -0.31220377601652216, + -0.26337114034602055, + -0.9097178994554956, + -0.7145363449671348, + -1.0158681504615432, + -0.7632943672612644, + -1.0777211194520182, + -0.22005806413114082, + -0.7103593932010838, + -1.674380451935477, + -0.6025941445971728, + -0.6126178632572196, + -0.629762199213212, + -0.9633212943431922, + -0.41271419892462985, + -0.8258180537938068, + -0.5154075100174412, + -1.6000438458279453, + -0.21316404139327233, + -0.21646030531458613, + -1.2819341371023656, + -0.2598025028000277, + -0.32485863108001495, + -0.4275694207211337, + -0.8928015023151897, + -1.2571435284026553, + -1.317759542076624, + -0.24080489651812131, + -0.842199501261407, + -1.0632639359948908, + -0.6249129815309603, + -0.7198926541794977, + -0.49075991743791336, + -0.5842862810507873, + -0.2600214997481182, + -0.7231084702843313, + -0.41039943558876807, + -0.5034881680589892, + -0.5807009010351555, + -0.8950151521257396, + -0.3941043468154464, + -0.6146424521661501, + -1.30735206758542, + -0.5120281694294346, + -0.31521322668954593, + -0.7167725327787358, + -0.3031761357248694, + -0.9745228961288832, + -0.24995484786013158, + -0.5781132448827632, + -0.5811606011625213, + -0.7199295403931943, + -1.316511537158417, + -0.23886090715026995, + -0.8694799647964034, + -0.7066141080974625, + -0.45315814478759436, + -0.8550206355635366, + -0.25549994302478496, + -0.4650972878089482, + -0.657651710744546, + -0.29088336755349525, + -0.22620928814947813, + -0.8747123412332145, + -1.7662626463995694, + -0.5712981168043859, + -0.5954294675184568, + -0.41898821165396466, + -1.8285311171141365, + -0.8963689246721045, + -1.3561677139334638, + -0.9138129316805456, + -1.3878041634486802, + -0.3298731297678409, + -1.309402765530986, + -0.4263982038271273, + -0.22729783880969667, + -0.5044412610275527, + -0.4565063151548069, + -1.6426692877091789, + -0.4224126376871095, + -0.7361945596546966, + -0.3715272608134339, + -0.8909794918348141, + -0.370890907017237, + -0.5426057190144139, + -0.2889077414959937, + -0.6217924485554215, + -0.8360766800588112, + -0.5389125191779918, + -0.23880086377154222, + -0.473076342396492, + -0.66123815617749, + -1.118230595902223, + -0.6243712823669599, + -0.7648722934303819, + -0.8156079742309419, + -0.28526814903978154, + -0.5113728356819389, + -0.4529148144189225, + -0.6914248154915988, + -0.3361068233232818, + -0.3578922074888835, + -0.4731267194718952, + -1.0544444214880921, + -1.0275840965197975, + -1.3755800931094917, + -0.44907571583058004, + -0.2831893897439799, + -1.4515179441072195, + -1.0988827722259717, + -0.7389542554112613, + -0.6559259101339717, + -0.41947244819041263, + -1.2942249337945781, + -0.29404131292730723, + -0.5484897819761491, + -1.4025918214058548, + -0.40505716219700255, + -0.6930443655493597, + -0.9813976085704573, + -0.7360819620284457, + -1.1529959644663224, + -0.8656009915075784, + -0.2427612915469738, + -0.6392172121445462, + -0.42633105995642157, + -0.7609253007715661, + -0.9950006896735405, + -0.27350319074846213, + -0.3160268665538146, + -0.7489774486375609, + -1.0809977645051227, + -0.5653446939848666, + -0.26615168421736757, + -0.5127200952012048, + -1.3666314180426133, + -1.2475545777598533, + -0.616464054712365, + -0.7185466755700274, + -0.2474961489402844, + -0.5358871740886032, + -0.8717067942363463, + -0.2836155927628996, + -1.19853343813622, + -0.5400603256264879, + -0.2288631814733291, + -0.7501076423873415, + -1.4699719811423335, + -0.7890913826175263, + -0.9701521527574587, + -0.3257063215515126, + -0.45336254863354086, + -0.48421400571150397, + -0.2405690543926533, + -0.6344562261528894, + -0.24839649536653374, + -0.4810725106690545, + -1.4935384331449242, + -0.7157446385771873, + -0.6397920175860973, + -0.30505657711529705, + -1.16198357702746, + -0.23933999252405433, + -0.24482093973862015, + -0.7081110866282545, + -0.7002867464769068, + -1.223038550987686, + -0.2605396617456338, + -0.30063591423409575, + -0.8187150269740093, + -0.3848993305646889, + -1.2183325350285166, + -1.0093227837495151, + -0.3275555165934239, + -0.399507382449355, + -0.21645334797841265, + -0.7247070175287982, + -0.41981192700042025, + -0.9565142985802385, + -0.3422452326217323, + -1.1556713720323517, + -0.45634941656183037, + -0.844709551206592, + -0.7538950601174578, + -0.6296978797542964, + -1.4347381130372006, + -0.30311306498033225, + -0.5266982738487129, + -0.5386502943447096, + -0.362922476544323, + -1.3329556168218089, + -0.35804997957841145, + -0.4013673040789533, + -0.6688298498949486, + -0.5697720970908888, + -0.3191866347195116, + -0.43885660957641376, + -0.3959627909774653, + -1.5645948276333896, + -1.0188494296741362, + -0.29722748010751043, + -0.633640657401843, + -0.8535651253069352, + -0.3552579086637678, + -0.6225598268285639, + -0.9614207408321954, + -1.3800710566312524, + -0.7330925982753927, + -0.7121897818982857, + -0.3991308627593, + -0.735425611401646, + -0.8408843579490463, + -0.3926027186388414, + -0.25218992765844866, + -0.47371448611874317, + -0.9008630664995827, + -0.3633164604254356, + -0.22906073089593176, + -0.21437676382549353, + -0.5044718788362506, + -0.8983591454084577, + -0.8429615928495171, + -0.26017280537312437, + -0.859719771122052, + -0.7752778040021799, + -0.20842130434274422, + -0.9198536833907975, + -0.22702805225241687, + -1.355631291358894, + -0.6835466657510968, + -0.25777138676575473, + -0.2774423211457491, + -0.25023998111143236, + -1.3906570814463357, + -0.9647416286982134, + -0.97768694687359, + -0.9283500058930366, + -1.0484091143024443, + -0.7614355423910678, + -0.762392947655599, + -0.8316715135881666, + -0.7142389103811334, + -0.25099092108682364, + -1.2745757687315757, + -0.7955371669863781, + -0.6781427702742234, + -0.3419059732386623, + -0.28312119327546675, + -1.0192963324609785, + -0.6614072842733179, + -0.9536783211291908, + -0.6723994882645923, + -0.2414247278716896, + -1.0180765583586793, + -0.7750281672680829, + -0.3318187683612985, + -0.7919240305492374, + -0.2886641597403637, + -0.5712178942870727, + -0.48114746773224765, + -1.0987484186306216, + -0.3475855433294879, + -0.4895625380407753, + -0.4702510630769326, + -1.1390628876683635, + -0.959014384131905, + -0.31381061774921226, + -0.8731902063941802, + -0.45815301045936935, + -0.28436046277714094, + -0.2719960623287275, + -1.396680322004361, + -1.7797871089713855, + -0.5876517184342425, + -0.21004172865691015, + -1.0280958045117057, + -0.38889784848897996, + -0.3543558217924965, + -0.2935031071269092, + -0.5642009300411616, + -1.1437673912426898, + -0.29634129102624246, + -0.9028428256599297, + -0.20923983497843343, + -0.5383044929624082, + -0.4010359094529906, + -0.660227227823839, + -0.7247269285033968, + -0.580336304512255, + -0.28746239554394126, + -0.6782389584152566, + -0.6991780060317895, + -0.6627858339175023, + -1.10913437662674, + -0.5385693461244758, + -0.46301824427490657, + -1.618884882245863, + -0.40110933041274155, + -0.307216625459662, + -0.9844940353827212, + -0.2986464881075322, + -0.4555085605264448, + -0.9680469036323235, + -0.3519991419310562, + -0.3141552675853244, + -0.8115390060435268, + -0.7759140518229922, + -0.5488091043234544, + -0.3681198532978529, + -0.4177551441848786, + -0.28446326726468, + -0.8924284935244797, + -0.292286619277757, + -0.46717295954451526, + -0.33961842016633337, + -0.6366397217494167, + -1.011850759239143, + -0.5926806664020942, + -0.21009434213918782, + -1.010133459007068, + -0.29686321911205993, + -0.35106068281647, + -0.3538518866321901, + -1.102910121720883, + -0.8953829248715487, + -0.8257197115475815, + -0.5007900831675295, + -0.7738231913152935, + -0.45309226552351994, + -0.43476985985556627, + -1.0360705291651258, + -0.2644449993575766, + -0.2831091160605731, + -0.26117979855887297, + -0.652365447358954, + -0.3812829336453554, + -0.5688687555289416, + -0.2369926331330552, + -1.0285053274856817, + -0.2874540872316199, + -0.40664361517982833, + -0.8293879589623984, + -0.5285847615497441, + -0.5724241976160207, + -0.7180336318535944, + -0.7316982227123767, + -1.3912819113721366, + -0.5111169298603642, + -0.39078206316940767, + -0.5383030463765337, + -0.3980047684138023, + -0.2144152703038702, + -0.7928883237622594, + -0.8056781857595667, + -0.3153667641197603, + -0.3078714212999093, + -0.26611552975830527, + -0.2037381840099488, + -0.23829288675150448, + -0.7577141891841254, + -1.4622238591418093, + -1.5616117466214836, + -0.5297344973167117, + -0.4223136716242548, + -0.6140896693527097, + -1.2618822906517275, + -0.8033409612741729, + -0.4751850336687551, + -0.4080747837318927, + -0.4069472776984263, + -1.1737908954963931, + -1.1065812426685524, + -0.8829646748791891, + -0.3136651767386116, + -0.7083097140805309, + -0.802179733860103, + -0.9422102135477, + -0.8611188550123218, + -0.27340871377371284, + -0.28825893175685313, + -0.28406622979729057, + -0.4380194223799718, + -0.7174862355758551, + -1.1704702039969488, + -1.1060054750513624, + -0.3576579104996863, + -0.3431997774229173, + -0.29324615777612384, + -0.6612130858677999, + -0.452068114130395, + -0.30291058418637307, + -0.2875025453869681, + -0.6584439303961513, + -0.30040284801460604, + -0.7831751207850745, + -0.5191545137548422, + -0.9657476272075103, + -0.8807594006480393, + -0.3070686695420407, + -0.27213661412121926, + -0.5401292997923068, + -0.2343166291816065, + -0.6666276394048173, + -0.2840827951890793, + -0.828676860190139, + -0.5309076615308819, + -0.23278698192932215, + -0.4310044421177131, + -0.23933144054308345, + -0.3112649998861224, + -0.2695282204114072, + -0.32284222131534285, + -0.9697264880423273, + -0.7081462620155281, + -1.2073663610957703, + -1.1900491148104562, + -0.5380975844298249, + -0.27592317675272193, + -0.6248568037208801, + -0.8753152996794129, + -1.0919040010963246, + -0.5855496271326724, + -0.9847409141910316, + -0.807274296761202, + -1.9897808526950271, + -0.6430345781126389, + -0.2787272455756592, + -0.6076692733222444, + -0.9498631138494014, + -0.2751929571495053, + -1.1296701314892048, + -0.755383493753338, + -0.24812942053172157, + -0.7553839710452334, + -0.5157997845659593, + -1.499315597178554, + -0.8768799935162778, + -0.9361822126243905, + -0.38238733163059024, + -0.6799045224036253, + -0.5643071989904925, + -0.3499374427427243, + -0.7236453170793025, + -0.7453740388266317, + -0.6149674870791754, + -0.5494401734773358, + -0.543671099559476, + -0.2967737776317401, + -0.7770155606022329, + -0.7554391982959938, + -1.283338702124485, + -1.5831917464142178, + -0.513589036405897, + -0.6509969142278373, + -0.6953229978584593, + -0.9179784041667389, + -0.2919434286577134, + -1.0529435953481032, + -0.34094015737446276, + -0.4084250972530872, + -0.5268779553786909, + -0.5869123825424558, + -0.3567109001678568, + -1.2106542667193558, + -0.6118258698937321, + -0.7665473934057613, + -0.8626614415344487, + -1.3229691455027872, + -0.474376839539152, + -0.6980773647493171, + -0.30391096478021445, + -0.42406039897785064, + -0.8122816191988927, + -0.5341968372446337, + -1.0872212846482272, + -0.2028634733192358, + -0.8322261620963708, + -0.3065597982301173, + -1.165948188401523, + -0.9585437080061692, + -0.25208767861409104, + -0.5357298918797769, + -0.24510811158270265, + -1.0198253051807575, + -1.4425672774667315, + -1.2302625507344114, + -0.4476918631773311, + -0.6143968763078463, + -0.8040049294747902, + -1.0010127054933387, + -0.5765924592183638, + -0.5958051335666705, + -1.1156867142074676, + -0.4359921079745948, + -0.30876411917508184, + -0.4262291092830039, + -0.7976979547773426, + -0.5011534864890641, + -0.5743915269508875, + -0.6471547525674538, + -0.7982267311289519, + -1.0354383251538968, + -0.8652273608327459, + -0.33435030150571116, + -0.2584177946703914, + -0.5822512881123472, + -0.31668258666906307, + -0.5901506579448658, + -0.9179904108965622, + -1.8152681058702538, + -1.4654522688997245, + -0.2633970548603119, + -0.5121404591612568, + -0.2565077334863895, + -1.662460015595612, + -0.6037600675626725, + -0.7415217718602056, + -0.5269810814096529, + -0.6737430540950307, + -0.8700232161432133, + -0.7176941256404127, + -0.38925462102905967, + -1.3021818133581036, + -0.5075819325015128, + -0.3297962363865379, + -0.5295362218821814, + -0.8696374320223866, + -0.29644823307087337, + -0.7222190791158442, + -0.307577292989515, + -0.8283302488474011, + -0.2569709692319827, + -0.43202868705145486, + -0.365010638456876, + -0.7344287195104522, + -0.6256958659836668, + -0.6132923590118926, + -1.184069872703831, + -0.6268808305819744, + -0.46265079026379125, + -0.2541813651067214, + -0.9871810421531187, + -0.35571642168124495, + -0.5337388868004607, + -0.5743820342053494, + -0.6684327963961626, + -0.38687192861715, + -0.29701102816577335, + -0.38468513736942334, + -1.0780258045328956, + -0.2795780467766756, + -0.5359243740762325, + -1.5431140623975035, + -0.5873463065163991, + -0.26825591012937705, + -0.8723597720812579, + -0.8050935590257212, + -0.7742133548493425, + -1.1030968287508789, + -0.6594084683792054, + -1.0836332397505144, + -1.7001441257372314, + -0.6423174084879655, + -0.4426103798807826, + -0.2959380083616301, + -0.8859408064918136, + -0.8963816021234561, + -0.7568016694913964, + -0.22441064774417505, + -1.316278192373074, + -0.5716826024744996, + -0.8793391859571835, + -0.6124078802135883, + -0.34879214143230186, + -0.748068810968766, + -0.478487008923571, + -0.9412379935093154, + -0.754996753692553, + -0.6245235940981557, + -0.6034885839958377, + -0.787536970996749, + -0.2638942902324184, + -0.46627108529051353, + -0.5307016845200373, + -0.8176373688791968, + -0.2735809040607612, + -0.3286197047583672, + -1.1219659443144023, + -0.39607358703506707, + -0.5164948520291891, + -0.45207852881645105, + -0.3188030246135507, + -1.40375967318222, + -0.2943613709156877, + -0.532611975349375, + -0.6104050793949715, + -1.2907183453545905, + -0.3005064318074718, + -0.6356235124611312, + -0.846871982558408, + -0.9728990691703213, + -0.8578234692413135, + -1.4639280420697833, + -0.24865543680737465, + -0.5968919167373324, + -0.43102682612226734, + -1.0929932985693305, + -0.9686981495077007, + -0.8353794206680378, + -0.7539078241075398, + -1.0489708890100196, + -0.6112447571258744, + -1.0353653816168489, + -1.2373938392852593, + -1.0367267209357323, + -1.7929265648830335, + -0.2388894836896256, + -0.6532274437524809, + -0.5903577764340018, + -0.42909493543950256, + -0.48607974124883324, + -0.9275189409635825, + -0.8388693908656114, + -0.4335678382967624, + -0.2745240661762615, + -1.0256509880953628, + -0.8567076396766459, + -0.6046556556684818, + -0.36863844783590827, + -0.207490771234569, + -1.1900692876867445, + -0.6670581484427758, + -0.6868430930271275, + -1.0267725462169444, + -0.6316851690608368, + -0.5563527391610054, + -0.5429638418387579, + -0.7368946355623791, + -0.27910032525355066, + -0.7362206812393024, + -0.482938645755997, + -0.9099466225241657, + -0.28070173811054216, + -0.770812930936476, + -0.9119891069424325, + -0.8389380347818873, + -0.8624283436124289, + -1.09152904614718, + -0.2688368224088475, + -0.569514145208965, + -0.46777858245349263, + -0.8413002437093431, + -0.9286831733987633, + -1.9958811976634554, + -0.7161886367054467, + -0.731708185612233, + -0.7637756224964625, + -0.5077034863307942, + -0.5688142742376682, + -0.24749595268460203, + -0.23929845457483165, + -0.27032644378675125, + -0.20393061294582177, + -0.2599918724334544, + -0.43165680577737775, + -0.5049593162755421, + -1.610732638871708, + -0.6496516340227911, + -0.4884516674887133, + -0.4042594532572308, + -0.9941547040910255, + -0.7049749165745606, + -0.3966344218601759, + -1.111765933866438, + -1.0655133942348929, + -0.7055979522199559, + -0.4168572378595521, + -0.3735464310995553, + -0.3085639643711014, + -0.9206242191119051, + -1.1642715402971646, + -0.23128267250407197, + -0.49533016191672896, + -0.5177085501752459, + -0.5609806255838585, + -1.1428129264669347, + -1.5105168852126813, + -0.969916749914127, + -0.3581913872323853, + -0.5632332834613265, + -1.4990063855235443, + -0.6988880428919695, + -0.28370415369897256, + -0.7974434492411461, + -1.288420856811707, + -0.21861580045707657, + -0.34932347042822065, + -0.21669049695263018, + -0.6169262716393957, + -0.6534093444602013, + -0.30841416424532886, + -1.2929845309453183, + -0.6607463887318752, + -1.562482247436171, + -0.38368327106279976, + -0.7736142824011665, + -0.24260983916720788, + -0.48105240270088895, + -0.9387118548836461, + -0.836675172748161, + -0.8065711494315726, + -1.344893888364483, + -0.36300011795192777, + -0.2601788869855492, + -1.2416811744081233, + -0.3189560900812117, + -0.9859509545628956, + -1.102764087243575, + -1.1260870611343654, + -0.5943557172631652, + -0.6605170822545112, + -0.46960233861809186, + -1.5590486364056548, + -0.932576555651072, + -0.3055174695380078, + -0.6640516018175259, + -0.8410592922105967, + -0.4170336792707307, + -0.6408958974822886, + -1.4932135730672282, + -0.4391866315109704, + -1.454994107395412, + -0.4763013617777959, + -1.5419415698959453, + -0.2770917404107333, + -0.6197623855125372, + -0.9428929872622183, + -1.1596732067927158, + -0.3478082568749419, + -0.47548414325528177, + -0.6448866151743431, + -0.2387592055706935, + -0.580711439450632, + -1.4323410954024338, + -0.3201776548490762, + -0.5205118226933363, + -0.5022307607496819, + -0.7945493357526139, + -0.49023238802133046, + -0.5245119605647542, + -0.5557900349736439, + -0.6386343962466674, + -1.4535252164026125, + -0.6267729363604151, + -0.267470039788324, + -0.2799741568017144, + -0.5842307502872264, + -1.17872760583225, + -1.4081787692921874, + -0.8689311106764386, + -1.8595960820127948, + -0.4217220870068451, + -1.0003476477670055, + -0.38968916859502384, + -0.5375231275621313, + -0.7947767187832846, + -0.5101096230550086, + -0.4751748425129518, + -0.7652697165948847, + -0.41486371661586424, + -0.6838886770040754, + -0.2292322698043449, + -0.4934384236100036, + -1.6552801556309025, + -0.8282593460958005, + -0.4999195082217399, + -0.5480212462286768, + -1.2984045959801669, + -0.4411694963065816, + -0.8173507473292577, + -0.4065728025761615, + -0.6265613470289627, + -0.9761615745140632, + -0.3721435062399031, + -1.9725965923125868, + -0.26810093581585404, + -0.20635607835900877, + -0.4494854902367124, + -0.5579385791001307, + -1.606498602866946, + -0.6102311613986993, + -0.35407206418847637, + -0.6751733997045777, + -0.37596199664421526, + -0.7900158106553843, + -0.301196642543707, + -0.6925387614190583, + -0.4444543132015372, + -0.5371576425257282, + -0.22656520744742112, + -0.6102273277369515, + -0.5178653861883055, + -0.5096601587849471, + -0.5675795794442279, + -0.22159936355882642, + -0.7050228782602587, + -0.591164704346639, + -1.0489998483928467, + -0.37840603864333866, + -1.4849363551136896, + -0.3318541292020208, + -0.30812132483552984, + -0.9594916400114207, + -0.3779769725951538, + -1.4393058564849268, + -0.7883289075650298, + -0.9230661425538238, + -0.999847681338952, + -1.0682331707134043, + -0.9461651806562631, + -0.34739239919906223, + -0.6321677219417102, + -0.6313811557601273, + -1.1002036757994993, + -0.9500882933157937, + -0.2821349527090568, + -0.5626205440298733, + -0.670924812522318, + -1.2357539434925202, + -0.2552384426662976, + -0.6911109605424093, + -0.257212523323354, + -0.5295297709029414, + -0.2224338001722556, + -0.29665556402449844, + -0.2546103331433394, + -0.9613603199984625, + -0.2186847234748608, + -1.1733316417590223, + -0.4401121640035059, + -1.7506696399532433, + -0.4090259727657417, + -0.2877660354465133, + -0.6741138844300896, + -0.3240833337803402, + -0.3222659474152339, + -1.4814457745785397, + -1.6796881519630116, + -0.7520149686190924, + -0.9380979973754041, + -0.5588520398421948, + -0.201182943575911, + -0.5193025269039411, + -0.493028279461428, + -0.9172003056739767, + -0.441936686968745, + -1.420200439729663, + -0.776958473771793, + -0.8716207123707725, + -0.3397442847102387, + -0.4481601199883171, + -0.3020430101045461, + -0.9036509340823214, + -0.8280531110572412, + -0.5558980131457829, + -0.9259831478511037, + -1.586664096197673, + -0.21490746167992208, + -0.886163271430133, + -1.4560620746888013, + -1.1599990459518044, + -0.5862145217044972, + -0.47146970370280555, + -1.379220573781482, + -1.0555633584736612, + -1.2297595589314603, + -0.2671992945021185, + -0.8700986155502011, + -0.43444085542688043, + -0.4469321890989135, + -0.33389348713363715, + -0.7020818201296098, + -0.6085442773148801, + -0.6098520140650299, + -0.7247538596760932, + -1.635544179628393, + -0.5282545740143545, + -0.6503245660600983, + -0.28956134575784936, + -0.22447852112363323, + -0.2533306871476994, + -0.6125867929932611, + -0.9266845702417668, + -0.6508378074269082, + -1.058024330425836, + -0.3742317457782138, + -0.8819947541593699, + -0.7487106593865985, + -0.7341755302728157, + -0.8921654328792021, + -0.6835939686824664, + -0.5293401219034343, + -0.2667268644607097, + -0.41131142182289804, + -0.357674223606479, + -0.48394940809416737, + -0.5507322622642082, + -0.741806710383485, + -0.2761987982037311, + -0.4084373233625869, + -0.45181272841807923, + -0.21305702511015623, + -0.8929024429455792, + -0.6281750146103076, + -0.3150671247513855, + -1.2987176231019195, + -0.44768600783205814, + -0.3679067522557664, + -0.4078572546039115, + -0.8143034211961564, + -0.30563536944389724, + -0.419481004536434, + -0.8817139356859641, + -1.0994418192967574, + -0.4629312837821379, + -0.6716382910251605, + -1.1729604160659024, + -0.7319736279489256, + -0.21470209645396854, + -0.7199317046590474, + -0.3759959868104351, + -0.3047310675129512, + -1.088477916986753, + -0.6812172759738525, + -1.2761815060739532, + -0.3131780084970901, + -0.2812940665288161, + -0.9845054280368345, + -0.8479874703433321, + -0.5948303291677797, + -1.4533214154490963, + -0.8786188711444478, + -0.3846599762461576, + -0.5135940855524138, + -1.8267139769903806, + -0.2080621778074839, + -0.5156425451788279, + -0.5773333229671358, + -0.6887318114047258, + -0.43244381907067014, + -0.23672161876447, + -1.0486981670384354, + -0.44836243066855047, + -0.39428450718434116, + -0.7842418774427746, + -1.14362006983189, + -0.4270319592746681, + -0.38586052998241166, + -0.39950393351188124, + -1.1663219174965205, + -0.24218658957004094, + -1.3462560109332171, + -0.23535196977575573, + -0.3429804965638273, + -0.3306426791857928, + -0.8265524822779132, + -1.2571102418600568, + -0.5337119513063805, + -1.1584991533456188, + -0.29068899728910974, + -1.1652735606475306, + -0.26843793846659103, + -0.25117512341407916, + -1.6424589198802286, + -0.702470506316104, + -0.9652970702557697, + -0.40224353877525293, + -0.36692647513461596, + -0.21897113724151382, + -0.998535780657996, + -1.1962022969587598, + -0.5563355503521904, + -0.8959541881714914, + -0.5373798138995106, + -1.2507939284064582, + -0.8331500405224929, + -0.7591545197946451, + -0.2658269013713754, + -0.35812790174211173, + -0.5836485029807081, + -0.8256034971161229, + -1.498641347533367, + -0.46499462415257425, + -0.3166643697970235, + -1.2834719460066282, + -0.3004513862398344, + -0.5750381478414563, + -0.7265423627180173, + -0.6516545961124778, + -0.24462704581560943, + -1.066012590908274, + -0.3386088871743873, + -1.032326762502952, + -1.0578942231636537, + -1.0153329628542591, + -1.23740396413123, + -0.5153050142591572, + -0.7856825945620584, + -0.49368849260885483, + -1.1218959509939146, + -0.4968329105797578, + -1.1436799402434321, + -0.49976772041129425, + -0.650698267990671, + -0.9942429801415577, + -0.5548558211418075, + -0.203127979369022, + -0.32959468264461966, + -0.6003947858491261, + -0.26042100243361066, + -0.30004465312617373, + -0.908207919323979, + -1.205214463189734, + -0.29834737953763824, + -0.629413466165527, + -0.8151812439736981, + -1.8074809542419066, + -0.5374849533087332, + -0.8429608906831211, + -0.41319442473628276, + -1.1847345723859337, + -0.5354308444765592, + -0.6704352871073086, + -0.43396286119415306, + -0.6941815257172306, + -0.7507713457377471, + -0.4269354939707412, + -0.448535237590818, + -1.0979743736105028, + -1.3494667430681797, + -1.3312816465582038, + -0.5264348450454477, + -1.1715491881607094, + -1.1487786501272503, + -0.22792969911915936, + -0.4873520487482539, + -0.47057393102476364, + -0.2812146743973157, + -0.35858524948130266, + -0.34386613231560337, + -0.6222455866411243, + -1.0675868482721986, + -1.3315057428797163, + -0.7239152473168079, + -0.644751626360296, + -1.3187722697100905, + -0.9006980603029969, + -0.2766060143899891, + -0.9123847144074991, + -0.8231534870900515, + -0.7706075934735822, + -0.9121015969286436, + -0.425342249770658, + -1.22240797612222, + -0.2630426615517287, + -0.38746330506424737, + -0.7604220331602157, + -0.7489715448813649, + -0.9383190095223215, + -0.2008392755496483, + -0.3181806244726484, + -0.262682780340517, + -0.24433435454013536, + -0.2883576130198052, + -1.3554328071500097, + -1.5788273549738896, + -0.5414368192753883, + -0.21928768886599773, + -0.9460431380175108, + -0.22620053584497157, + -0.580082419641814, + -0.3344022158290913, + -0.5171751733837753, + -0.6110236171821302, + -1.0982984373578086, + -0.8192459984422091, + -0.507943421117049, + -0.2622099040443325, + -0.4231684748899264, + -0.42493337856689284, + -1.7963522962800196, + 0.9574566286662496, + 0.8452006093525763, + 0.5381869910569269, + 1.0908371057629391, + 0.6790794817441974, + 0.5651151138455784, + 0.35454590617822496, + 0.5466948480212497, + 0.6218349416883081, + 0.3115133516999475, + 0.5425184428395773, + 0.7442684791257564, + 0.21993476312292834, + 0.7260605882590383, + 0.9053118056094364, + 1.0609085263276188, + 0.23513999602928365, + 0.4006005948756904, + 0.2604588315848138, + 0.20260214017438796, + 0.24685332213569072, + 0.6508624322024467, + 0.42201461324824896, + 0.4198741845662263, + 1.3029314737138313, + 0.29055243089268484, + 0.42152498144938577, + 1.5464953864088424, + 0.8513514282915554, + 0.3121066981864419, + 1.1232705035603128, + 0.7915034864136219, + 0.6154432954740279, + 0.5576726416515835, + 1.5234880358698861, + 0.7879524995569577, + 0.28082433767146153, + 0.3538364683545442, + 0.5283913797118495, + 0.5933731700961553, + 0.22643865349509118, + 0.4828430233943823, + 0.22388517795251095, + 0.9690547149315686, + 0.5752769988918115, + 1.0913876150230986, + 1.0892193802768084, + 0.44777009525791034, + 0.7715762202929868, + 0.9936748193871465, + 1.0758017948311758, + 0.25263094699899447, + 0.7009412318065368, + 0.4698893086143426, + 0.5195608930995894, + 0.45428634889416514, + 0.7880721499922141, + 0.34786401796750877, + 0.6532018364612721, + 0.7854829005414233, + 0.48048580700219884, + 0.23813521558432763, + 0.48909638433752445, + 0.6192776568160028, + 0.7391312085806514, + 0.6622958625104529, + 0.6969813464137515, + 1.7117270185256614, + 0.8283996723027968, + 0.839059146959328, + 0.8777243842844908, + 0.3826864433275716, + 0.322916125791419, + 0.3161834910440166, + 1.3485738342330102, + 0.7789692008870123, + 0.6468764900824704, + 0.2815925431319182, + 0.6410875451951364, + 0.43765108872838915, + 0.7029992812570973, + 0.2570613856472874, + 0.43618816931899457, + 0.5335699992174628, + 1.2993100530697281, + 1.0230767468501865, + 1.1015684396623806, + 0.29464353218682215, + 0.6560230636025929, + 0.8404053024136257, + 0.34348965585744995, + 0.278458508579929, + 0.6448471167097874, + 0.2617147175657952, + 0.3355228140462228, + 1.2072886992105643, + 0.36444724599635214, + 1.412030457363343, + 0.9400898755750868, + 0.4037347709834607, + 0.7549820066897852, + 1.0963580958947505, + 0.8858613416146282, + 0.7070685344858586, + 0.5467258272662279, + 1.1256865208832245, + 0.8338835985177124, + 0.37824131324718246, + 0.56069609748268, + 0.574660433573703, + 0.2944841167685757, + 0.39789473517316426, + 0.8346370846409534, + 0.5176385495505529, + 0.203716187983909, + 0.21019599703084274, + 0.22862542006067832, + 0.40360200930625606, + 0.4660638417941213, + 0.39934112358188173, + 0.6382148826012658, + 0.4787518496815889, + 0.2712153204282209, + 0.8868437855638998, + 0.5214051825097152, + 0.2051632776254155, + 0.6001772116758128, + 0.7576104488153601, + 0.3334769648034673, + 0.5837173447705857, + 0.5039571565892099, + 1.414289037222642, + 0.7552596388029804, + 0.7967894503579123, + 0.7655283749181111, + 0.27666833073043434, + 1.000635657598225, + 1.2796923551345631, + 1.2504400556452653, + 0.7661439522476414, + 0.9225960503810428, + 0.2965091323830521, + 0.5631401417102043, + 0.26969374081711245, + 0.44364127633774875, + 1.4312745497983717, + 0.7179400526036637, + 0.5713385164330006, + 0.30918501618996486, + 0.2114352305958326, + 0.49878668015699273, + 0.21490690031594514, + 0.6532083717334932, + 0.8148505692908088, + 1.264571158158868, + 0.5764929253081038, + 1.4508655763789022, + 0.9649103611248816, + 0.4135835113901947, + 0.3009580582692032, + 0.35782800731633896, + 1.0224925763737003, + 0.37946309951188056, + 0.6560535969094392, + 0.7254228201703601, + 0.3490267328022806, + 0.35463015297197975, + 1.0903125611982558, + 0.8692323013798404, + 0.2651975560673788, + 1.4656570615967752, + 1.6730433943660614, + 0.21036291884223482, + 0.9021022446387799, + 0.6209558270641999, + 1.1071878993543476, + 0.3677190653383894, + 0.8498189417643197, + 1.0311529853234347, + 1.409722882489602, + 0.2546404303136566, + 1.0554062578784038, + 0.3198891373276655, + 1.2224420571901917, + 0.6701953692678642, + 1.229123223141898, + 0.7477184387669606, + 0.820864099116711, + 1.3699896348511267, + 0.5113525826652402, + 0.20528735700177222, + 0.926211737782468, + 0.7200551581091819, + 1.3990374493720916, + 0.7817645773552057, + 1.2344853621430394, + 0.9809936857257535, + 0.22032478083878332, + 1.3072427774745725, + 0.3883035761723866, + 0.4041603773604231, + 0.4950573882457931, + 0.7891107256768725, + 0.4879849305613825, + 0.6762011441254779, + 0.5066216683422085, + 0.3029807660366283, + 0.6259278309087696, + 0.8005565651344673, + 0.49179205270167775, + 0.386917375588718, + 0.43856873644674976, + 0.7569245793444163, + 1.2509864127661456, + 0.64839351496744, + 0.45372886127963274, + 0.21884375711922308, + 0.8470153711751681, + 0.804284364905372, + 0.37754064595919684, + 0.9975284797642118, + 0.46733686454720025, + 0.6885954231935355, + 0.6471174453194675, + 1.184869487267471, + 1.2522572229763866, + 1.3892522115700534, + 0.39968426834572446, + 0.8621892162607182, + 0.6085867192959183, + 1.2549287316881088, + 1.3399074829311493, + 0.8899365608150395, + 0.824966125963163, + 0.4837617699584297, + 0.348885563351981, + 0.7339314288144785, + 0.6118335820318119, + 0.9346170849348651, + 0.586547864252241, + 1.005551011249285, + 0.9341137372839733, + 0.25644166406112817, + 0.5882506155412772, + 0.4826038650271428, + 0.32408333979845116, + 0.8792329233654419, + 0.7853108180466295, + 1.5952393114369576, + 0.5704230952842605, + 0.2647647032612503, + 0.6519305841454981, + 0.686861567877312, + 0.3789221752821911, + 0.6132546161462723, + 0.2584881244269224, + 0.8381829655088612, + 0.5424023977982627, + 1.5795470519468604, + 0.3275123357337015, + 0.5304314785882482, + 1.2622506504490736, + 0.3627633280194873, + 0.24092526319262303, + 0.6606187195380192, + 0.45403459382476014, + 0.38397506954553157, + 0.7472963199469107, + 0.47726341597163224, + 1.1033444565064954, + 0.7204347301757275, + 0.40472082646861873, + 0.20317934742709134, + 1.2140775037484786, + 1.615311641448989, + 0.41172602772324124, + 0.6664053356726795, + 0.2909591767119319, + 0.38333325830448844, + 0.2023014353089582, + 1.84855301762629, + 0.47498528325529354, + 0.5157455256030349, + 0.5541804897514477, + 1.3052285160148664, + 0.3616385490187431, + 0.7260943995236316, + 0.957511370076901, + 0.8742688186137921, + 0.42699419040599446, + 1.4595224120376145, + 0.7703320718866764, + 0.9652592186007292, + 0.5819303289421425, + 0.4145312883621509, + 1.3059854779410622, + 0.5065134398644039, + 1.30691980010619, + 0.7743456734072737, + 0.9253198107959261, + 0.5281256793834148, + 0.28466129300496035, + 1.456178353399288, + 0.4990188300179854, + 0.2362977293259614, + 0.43983212761640245, + 0.5606833580571268, + 0.989393047743935, + 0.32840635356742826, + 1.172005027908928, + 0.37851791195705853, + 0.23281401988542547, + 0.6001717870906326, + 0.21024124978558695, + 0.31179724942954024, + 1.243915917284963, + 0.3711495441593481, + 0.5944184507269621, + 0.8067991011872107, + 0.473847643811217, + 0.4874382478872303, + 0.6025517429245429, + 1.0780856217106396, + 0.7390998162079477, + 0.28310229715602026, + 0.3577790100763111, + 0.3728837012434968, + 0.7007498454311625, + 0.2811605561051045, + 0.40099405884109984, + 0.5898582817073846, + 0.2313552354194825, + 1.1919395258218959, + 0.5176433707344448, + 0.5338258709314166, + 0.624087364088595, + 0.6173991589962241, + 1.294029188820565, + 0.7173283929981592, + 0.8322451365535483, + 0.47503876741649287, + 0.23772719618893487, + 0.3539435763213408, + 1.4000779884951273, + 0.7732992553006718, + 0.8342927445253526, + 0.46768617898219617, + 0.23456122645740163, + 0.6407046782122071, + 0.33562196121643506, + 0.5159099607935026, + 0.597841195172127, + 0.46513493105215015, + 0.20611274678492397, + 0.6088002539123291, + 0.4737131839584327, + 0.4319659276100964, + 0.8098613243975006, + 1.1925663157442883, + 0.22940566964619552, + 0.5165795278122439, + 0.5669022050464676, + 0.28849241703361284, + 0.5286574860279524, + 0.4180936131938474, + 0.2836391551480662, + 0.21134197537472554, + 0.22282071687315885, + 1.0004026242554909, + 0.42350230864533284, + 0.20450564187177026, + 0.972275890044683, + 0.7461244781633901, + 0.3250266455550464, + 0.4176090096260401, + 0.9451574297409183, + 0.5135989003909712, + 0.3602867220780169, + 0.20480252737958168, + 0.7902760376150025, + 0.9000234980128027, + 1.3113880785927463, + 0.7275469927630226, + 0.3993734238014008, + 0.35778351898877025, + 1.4158903358632204, + 0.5172276062304884, + 1.3113957572317845, + 0.5160812090966342, + 0.7941081557393654, + 1.0373430695221066, + 0.3890784971860782, + 1.246899608409073, + 0.8503706153538606, + 0.6042486332089417, + 0.3435235590076014, + 0.2900916059756735, + 1.0636608010656947, + 0.36801132984675666, + 0.35534890370094685, + 0.5665904043289018, + 0.5791313473915215, + 1.4159678457424025, + 0.28884280921947175, + 0.24966673179295626, + 0.7262791641182215, + 0.20614235421732435, + 0.7271769354406236, + 1.1481632060005469, + 0.6957152491109738, + 0.2086332022103553, + 1.697928855493378, + 1.1440960767294506, + 0.34116178470218855, + 0.42405879701331584, + 0.2217798708984228, + 1.3059930262318333, + 0.5290341853331506, + 1.269519322757612, + 0.2705601941497805, + 0.8614685314297387, + 0.43758739337482866, + 0.3014343073347495, + 0.6088279094516951, + 0.528108432969738, + 0.4705588863604607, + 1.0210524037239876, + 0.5445686834365939, + 1.027033640702382, + 0.2628912193617715, + 1.2026733769231976, + 0.40851019053983184, + 0.7912714445686881, + 0.8955915916169779, + 0.4039613800605166, + 1.3150543732643323, + 0.7500998085500262, + 0.2303319019720767, + 0.7035473918331037, + 0.5228325080489442, + 1.5836350163993762, + 0.21945968298445498, + 0.5179707472301679, + 0.4944175223716443, + 0.9251376372732607, + 0.7727510183969444, + 1.1335525066595933, + 0.6595898754506855, + 0.3122703473705428, + 0.3444241055611415, + 0.909550242086398, + 0.23543556929441273, + 1.1501691109264751, + 0.47791619693623394, + 0.2922098753778981, + 0.726629773740369, + 0.32911060142106585, + 0.2960246825754587, + 0.7003777162027437, + 1.1959713967130627, + 0.7471884161171929, + 1.0431700295497481, + 1.3097345240832052, + 0.7654266215269551, + 0.7119784976482181, + 0.579916658673169, + 1.0755268044770794, + 0.3193229669950994, + 0.7955561860515897, + 0.39705023298982306, + 0.5928470740551763, + 0.7920716221355942, + 0.5671521419525674, + 0.7386338117216724, + 1.196293311536803, + 0.5453385844547564, + 0.8962567950539333, + 0.5445462907057793, + 0.31375000499196865, + 0.7766149560131683, + 0.5238973443202292, + 0.38454857881836446, + 0.21923927911480684, + 0.5627060534251433, + 1.1544745529223215, + 0.3790603053223351, + 0.5992635725382975, + 0.5748319976939346, + 0.24094746122490637, + 1.6716782436782727, + 0.28675221432483905, + 0.5458010670365312, + 0.871176025098844, + 1.1193963480392053, + 0.4100482994552548, + 0.5518252569612714, + 0.5097018619724024, + 0.5627908798263588, + 0.7976593552902981, + 1.3396562620643613, + 0.3442492162902713, + 0.20531417114769307, + 1.2118394642412438, + 0.8016574849456434, + 0.45056765666197246, + 0.2706071729435616, + 1.0411483507454287, + 0.3886727191086522, + 0.3087527341453821, + 1.3952242504131547, + 0.3733256141766607, + 1.2520014052619566, + 0.32834047086159857, + 0.315692570824261, + 0.21532204651472034, + 1.9516659762727115, + 0.5761733587400643, + 0.9332755884251912, + 0.6221687450469235, + 0.5917991474575786, + 0.35878410553787093, + 0.9879370613747579, + 0.9701003174868047, + 1.6341196745551518, + 0.6350845779977535, + 0.2499257163288318, + 0.36766439446669835, + 0.878491131360003, + 0.9118127761249339, + 0.7002750808645333, + 0.371920539241359, + 0.45135927545625326, + 0.5201290206766541, + 0.8902009998740784, + 0.3626328343051131, + 1.3409566250319613, + 1.2797143799292812, + 0.7982793105570495, + 1.0091685350842403, + 0.7775009672234319, + 0.2632343645151207, + 0.8545888147531404, + 1.119554264480485, + 1.4404303303636667, + 1.0363822140514782, + 0.973717690938325, + 0.48684517017957807, + 1.2352696556658376, + 1.2698181074875674, + 0.20291866941805534, + 0.22420980157360365, + 0.22692888246136753, + 0.4135056023979652, + 0.59393488941513, + 1.006592796764644, + 1.0159948225648485, + 0.7896563392614534, + 1.4954035083249189, + 1.526362458179763, + 0.31166363262058466, + 0.7375895767706929, + 0.30563839904385176, + 0.3343060319987976, + 0.2775593965038207, + 0.4594775218787838, + 0.24177283697141985, + 1.2243257273705201, + 0.96237395726785, + 0.2290762955016808, + 1.082674470844413, + 0.9991236782835821, + 1.2532241680411975, + 1.0286048260537586, + 0.23633102832962724, + 0.7095582124319062, + 1.7675797094603882, + 0.23368960725240603, + 0.8048395964198543, + 0.35910957979019487, + 0.6000903514785368, + 0.23819172572204608, + 0.29736829293040873, + 0.20832399817263714, + 0.21874825943807294, + 0.31612482060882524, + 0.44075557140301497, + 0.8590801598409095, + 0.295574234532831, + 1.5032675299341767, + 1.3852703819354009, + 1.705559717177896, + 0.23134126272120228, + 0.30183831167922354, + 0.2635628752157854, + 1.092509387668705, + 0.8747172522541206, + 0.45796723763430264, + 0.49358293026711, + 0.4678149383940908, + 1.0211030472609126, + 0.6054625575788924, + 1.1882743370653301, + 0.22708829587256465, + 0.46325250295097853, + 0.26122641811761993, + 0.6038481661913055, + 1.4442601646182147, + 0.8244496946634154, + 0.8013260001292307, + 1.026956362664576, + 0.5539869558010504, + 0.40178211815053433, + 0.26567374936723503, + 0.9831368746304032, + 1.3002607586956298, + 0.35061244608247066, + 0.49334228697351185, + 0.8759645702775107, + 0.7932426379219194, + 0.7033019932183031, + 0.5847099219174675, + 0.39995263242887047, + 0.5330072835639627, + 0.5509692946718121, + 0.32612521190091, + 0.36330455385038407, + 0.37524862893057304, + 0.5710238215732425, + 0.5550635116098916, + 1.5130346965063923, + 0.40072895706582506, + 0.22342975612850163, + 0.5872052018877083, + 0.2954280471212256, + 0.3140590221649693, + 0.8452350939866705, + 0.7223423178618025, + 0.5810117788190293, + 0.32510482639101523, + 0.8707261550513209, + 0.7858539944878898, + 0.5086886817344548, + 0.7259365053614426, + 0.7491530218028426, + 0.21585718952989874, + 0.6565578411599791, + 0.5203389615562455, + 1.450910251667492, + 0.5744805122051686, + 1.0204315285397332, + 0.5590631444317324, + 0.4253768348687382, + 0.6806585113989716, + 0.7051820698530837, + 1.3423268701620215, + 0.5045370857914087, + 0.46800253987644574, + 0.6005469093925546, + 1.271433723321464, + 0.3389619210158223, + 1.065602533215407, + 0.5558917121688575, + 1.7597621715878258, + 0.6682606676737181, + 1.2064680700527817, + 0.7627270163597215, + 0.8720929339421755, + 0.6258018604073541, + 0.6447802843961272, + 1.5335875836798303, + 0.43391917710213906, + 0.5644756919134531, + 0.4467522631582906, + 0.29327791069396103, + 0.24895691611962015, + 0.46328044090128245, + 0.979235425536783, + 1.81272169886208, + 1.100259111334818, + 0.29393678152668745, + 0.7599736489100056, + 0.633242238792645, + 0.6951910227995021, + 1.3272587927780841, + 0.48432163133500483, + 0.26034995143763456, + 0.2983891752571571, + 0.7847468110776195, + 0.7502064015293173, + 1.7788950633061467, + 1.2111462822996888, + 0.6711541952440424, + 0.3651937497774154, + 0.4743986786552055, + 0.8107566235795505, + 0.20936651294691735, + 0.669440502819163, + 0.6774497183601299, + 1.1366579483706303, + 0.6642354509226619, + 0.2918987162438312, + 0.4633085147002086, + 1.2309177467192836, + 0.44606281126852027, + 0.3073198456980928, + 0.25004613619793425, + 0.5869146536655406, + 0.5764916308702127, + 0.33281855126688237, + 0.38934628830606927, + 1.4843018999333173, + 0.47854654899276733, + 0.9131758749498516, + 0.47537143439899265, + 1.3992096801444227, + 0.290585711915039, + 0.49805235024403627, + 0.4137084740374465, + 1.313162486792877, + 0.3735379180241846, + 0.20868736565120488, + 0.577810824021978, + 0.40434303404114613, + 1.020212764447325, + 0.5057704235149058, + 0.5364045757541845, + 0.2326628395095914, + 1.2715730555347113, + 0.4857992784112809, + 0.711504067774769, + 0.38957675980591816, + 1.2949760537303538, + 0.44781281029036196, + 0.45509055371471496, + 0.24855509310356622, + 0.4157311352486839, + 0.35788738533554565, + 0.38020100439381516, + 0.2892235425354156, + 0.5070133893323865, + 1.2383430472749593, + 0.9437768700831429, + 0.4624298679475328, + 0.2737816601389798, + 0.6387806329524005, + 0.3250529789855941, + 0.7366866125807473, + 0.9986654009088966, + 0.6373615593163735, + 0.5076290976548747, + 0.21518358050328779, + 0.7620298032399668, + 0.5734140939515348, + 0.6489086845971223, + 0.9352813405268431, + 0.22447747686168662, + 0.36965044518165907, + 1.5177772006012886, + 0.6872346843267376, + 0.5419042579087296, + 1.0958955336020066, + 0.4458119837912585, + 0.2107323816419524, + 0.7340220790468132, + 0.6990389739417066, + 1.0782921720481375, + 0.361084586879682, + 0.46796891341791863, + 1.5722203834420831, + 0.5265558911097354, + 0.2645587297374444, + 0.38708620139554945, + 0.8314212135249325, + 0.7756967995131574, + 1.2046853589842803, + 0.6706509592405848, + 0.3536426615169036, + 0.3806884841787056, + 0.5178218160923329, + 0.6513185705602266, + 0.3553068757203762, + 0.378664304614536, + 1.440307958612511, + 0.3750323597162434, + 0.7415707992802925, + 0.7172043678039197, + 0.2914804818710285, + 0.8933033886766218, + 0.49592046512422217, + 1.025948940377737, + 1.0019960639385428, + 0.44655962204601507, + 0.2660976260221547, + 0.6586777564327124, + 0.7119218368773236, + 1.0308939675039306, + 0.24527640456837885, + 0.45976157650587235, + 0.8751011531211884, + 0.2083462443456029, + 0.7674802686158455, + 0.6866265231328932, + 1.2481390897697064, + 0.48924856276139556, + 0.6586305781031929, + 0.207080936128153, + 1.4061215557817341, + 0.9432397638743181, + 0.42018467496853706, + 0.2637564684792768, + 0.35203068416216093, + 0.5787117042283616, + 0.6801751806479929, + 1.2603420581515123, + 1.0303020572227184, + 0.20273025472221803, + 0.8839963427063044, + 0.8483304156847314, + 0.389617241067535, + 0.2602353563842738, + 1.384886514078825, + 0.6993005783570335, + 0.2511645607798125, + 0.20765048948881284, + 0.22883381884611836, + 0.634107367534222, + 0.5860493896702492, + 0.29486670208775356, + 1.0902412767315657, + 0.6273045974991331, + 1.161781453106763, + 0.3143026185888674, + 0.5794499923261057, + 0.47897906557721476, + 0.6580197953000037, + 0.38298298737969916, + 0.4762643438101567, + 1.3104745231806398, + 0.5424266950629147, + 0.4927663156701303, + 0.2784194126926202, + 0.28843314558204924, + 1.8852015696359423, + 0.7660990053460904, + 0.5397920839874201, + 0.44566271165036386, + 1.1627380098761648, + 1.592488937567565, + 0.4087586856898832, + 0.924938629947583, + 0.34983204859923167, + 0.3893675151164049, + 1.6583058817363978, + 0.629588187583269, + 0.6650988326920615, + 1.3768711316204871, + 0.626065309514586, + 0.8163207745290841, + 0.799609367512955, + 0.3387796722744442, + 0.8069506245053368, + 0.4377716442189288, + 1.0371174246475765, + 0.27298730999355114, + 0.2787648445190082, + 0.31941665402933644, + 1.1811413243743805, + 0.5189381021166993, + 1.3518935355687622, + 0.22090692479600046, + 0.4380013877298683, + 0.784257004359925, + 0.3405555178959765, + 0.8479628509914472, + 0.21136291822323117, + 0.24288951681927556, + 0.7444312812912665, + 0.27444034961374725, + 0.6222203294839865, + 0.3676641024231905, + 1.0744655523817392, + 0.5895820432256041, + 0.4719685428803768, + 1.1426377913449075, + 0.6732884635547844, + 0.2794220815990219, + 1.362557589168319, + 0.9479535435531543, + 0.9410710774170153, + 0.3776505171014156, + 0.23193420713197496, + 0.598296258666808, + 1.0685904163629358, + 0.7116199100970657, + 0.3927253201831486, + 0.7101748325086363, + 0.36372481794051176, + 0.5291048016401386, + 0.917592478877433, + 0.690213055057936, + 0.41878942872922637, + 0.4184534736152045, + 0.6696086782789128, + 0.942798835743784, + 1.4415591805747652, + 0.47271665137846025, + 1.023469215133509, + 0.901197800753228, + 0.25887708837972756, + 0.5128150883372361, + 0.2526154819336506, + 0.28065008408849457, + 0.4874901659757395, + 0.8465523884482168, + 0.8226488738081086, + 0.6166181016222554, + 1.3631429140502773, + 0.6993464904701152, + 0.9597754451425733, + 0.3808277617199091, + 1.297844758175944, + 0.7082825498026382, + 0.3617155265839857, + 1.0051211171732573, + 0.4598970298164315, + 0.3440103371818209, + 1.6660593775128, + 0.22035559326704476, + 0.5064224492177815, + 0.3329198599188626, + 0.5160263418319516, + 0.5986631894526262, + 0.6281252724560316, + 0.27116549085228164, + 0.2337481504235625, + 0.2216077768553763, + 0.388137822203219, + 0.42306879697733474, + 0.43710181215514027, + 1.6145276477954429, + 0.3705731210486874, + 1.1609102534539393, + 0.4709766683224439, + 1.121093561285424, + 0.7660154114124668, + 1.1273553957738323, + 0.7680216023662017, + 1.2332946882156983, + 0.29245908561265116, + 0.6034638229444547, + 0.3755648357767191, + 0.5413423715186092, + 0.22382851574559567, + 0.20277733618773866, + 0.20209393914304727, + 1.3683195932110424, + 0.3867614155442177, + 0.5222560949048191, + 0.2547576076031742, + 0.9831936460595448, + 1.847369624937548, + 0.3092307309923556, + 0.7475072556101324, + 0.7463477020982873, + 0.29864367047815615, + 0.8039366419429383, + 0.3909270488526444, + 0.6871393543715878, + 0.466778368709141, + 1.0839173913889717, + 0.3051488857800391, + 0.7515750668312281, + 0.7249612226484374, + 0.9263328522784414, + 1.4235746139014631, + 0.33334627072942596, + 0.6408023125901149, + 0.34631698866865185, + 1.3063055295324322, + 0.5278995036944464, + 1.3359851049382465, + 0.2357813286846903, + 0.26053244209686244, + 0.6991747138234481, + 0.7003805904670518, + 1.8679511800128865, + 0.43844981586823917, + 0.7522939301156418, + 0.2712425375260034, + 1.3656482614522167, + 1.3069863672725415, + 0.26015207878820257, + 1.2539063960887682, + 0.9430208036253872, + 0.29689799778077375, + 0.9302702934429266, + 0.4287531153003575, + 0.33247105845872776, + 1.0914193988781369, + 0.522754576006384, + 1.13864448977131, + 0.9281530571396164, + 0.9472226610416467, + 0.846177103812876, + 0.8320122145567557, + 0.5945393721946411, + 1.3162678906239291, + 0.3853849015327223, + 0.25732236833961925, + 0.24033198685761328, + 0.3453857009981429, + 1.507198353421937, + 0.3652074656679909, + 0.6001832103660677, + 0.6759882355559346, + 0.775590515560467, + 0.45599724137395103, + 0.41909289675909644, + 0.4587023422814468, + 0.6965808737255995, + 0.4263181990167673, + 0.6199645866052891, + 0.5557810782817714, + 1.1462712516497897, + 1.0542532310130772, + 0.32161411808197654, + 1.0750600350447475, + 0.600470027841967, + 0.20415485123649932, + 0.23878813534769958, + 0.46580708308261315, + 0.3797877196335298, + 0.22144099174771073, + 0.6479457771481184, + 0.8829347076643407, + 1.5731693677462382, + 0.4750770744038077, + 0.36765424332343244, + 0.34015017928565844, + 0.6343922787330993, + 0.8589837242791709, + 1.0736104591197215, + 0.5720814750766112, + 0.4722330943206698, + 1.1454688306750105, + 0.7072926256471358, + 0.8113825495513299, + 0.5924002043519131, + 0.24379249879334614, + 0.3856435323093498, + 0.43841331397191596, + 0.30421427664230655, + 1.4144912343399267, + 1.5837560747502217, + 0.47106212822948584, + 0.46484461932805854, + 0.7264409463050243, + 0.7293454070996456, + 1.0320858067726435, + 0.6068973574789682, + 0.5385079178157504, + 1.2822649906810903, + 0.3908314264136574, + 0.7293956364976466, + 0.3720027822752651, + 0.5768827767872188, + 0.24529621589892836, + 0.5176421537571428, + 0.3952448109188864, + 0.32664693064132555, + 0.6836085240662108, + 0.31275994832833837, + 1.4974643799723755, + 0.5291520399493036, + 0.6794797933351283, + 0.7856153344945321, + 0.7326937261774378, + 0.39154467690754524, + 0.22321714328927827, + 0.571050834184361, + 1.117429713921427, + 0.4437038079782921, + 0.7710050998761313, + 1.1731580372756913, + 0.6358010228688712, + 0.48926705351645905, + 0.5093312928034287, + 0.442701148276436, + 0.2622321217635517, + 1.0892820922238786, + 0.9398371879449424, + 0.42926813016728493, + 0.465305637994184, + 0.3765893925616218, + 1.1374755331260127, + 0.38914489670779395, + 0.6585528138222286, + 0.3986142136635121, + 1.304529409514628, + 0.525144969879339, + 0.3427173513092023, + 0.8267528689511519, + 1.2957065895358466, + 0.4353229280759216, + 0.23368348733548464, + 0.23685488536963606, + 1.7868066555049678, + 0.310455494438397, + 0.3102941469208824, + 0.9479112865432229, + 1.510561409634195, + 1.022445516788766, + 0.6721594413302301, + 0.9478816638761589, + 0.9997329901233004, + 0.4387958790820938, + 0.5307243793405015, + 0.5435962390942345, + 0.29022407037660014, + 0.8450650413776603, + 0.20082469292735952, + 0.2860209539936157, + 0.8592479615298084, + 0.7129662115501373, + 0.8627669736155797, + 0.9836279332043676, + 0.8762386968499853, + 0.671489101166526, + 0.4157309431652308, + 0.37308085772443045, + 0.23259631886883428, + 0.494248879382329, + 0.8887368105235426, + 1.532280745271797, + 0.8229457866534945, + 0.22868349671639127, + 1.268558194971087, + 0.4579209667810065, + 0.3559060182699817, + 0.6871231974509717, + 1.7039339259185187, + 0.5417270857287754, + 1.3930432169526539, + 0.7552936009410385, + 0.4521153839379714, + 0.7880221955921513, + 1.2560939305537902, + 0.2505687174954608, + 0.9017028600297786, + 0.2963173735234371, + 0.21207245132570918, + 0.23261033983464185, + 0.5431004784383439, + 1.045610978237557, + 0.2648364583147131, + 0.5867621248369631, + 0.8619780903439732, + 1.306762890935773, + 1.7125476691886334, + 1.3212510534488826, + 0.5935882472286872, + 1.4856665637770694, + 1.0687197343546773, + 0.5717440142873537, + 0.3112053517611186, + 1.4862411836884533, + 0.5669884612204593, + 0.61111472188908, + 0.6212063613538047, + 1.4519789894654933, + 0.8720060379973456, + 1.1565509335107018, + 0.48893030634181267, + 1.281453911540386, + 0.5091217483135198, + 0.2383750544255271, + 0.38847955223641994, + 0.3188606078317726, + 1.0753470256087643, + 0.8769188019641626, + 1.9198722494104712, + 1.028473990224032, + 0.21877540155350195, + 0.8067374805174201, + 0.6973288738631805, + 0.8916467674277592, + 0.5504105684593572, + 1.1474549096081326, + 1.1888019795340268, + 0.7823083236339933, + 0.7364205729590353, + 0.23686768038553485, + 0.49316237055003453, + 0.5144508717749086, + 1.08321752577533, + 0.3764380357063751, + 1.316716913715138, + 0.5197642532545517, + 0.27920547607061785, + 0.4804738675381003, + 1.1504729617263374, + 0.5587177633455257, + 0.49142177247474983, + 0.50487223542522, + 0.6823643948173735, + 0.7403623160737212, + 0.6903706120531115, + 0.4735833461723689, + 0.7585070567030625, + 1.7887247886329791, + 1.646654643159243, + 1.5744837518099606, + 0.3306664508810466, + 0.6891790324913107, + 0.6472403264958936, + 0.46226499434981183, + 0.7615766075259472, + 1.1732885545154599, + 0.3222413679980293, + 1.1752179304096135, + 0.647219918783226, + 0.5589339015081195, + 0.29559383283812085, + 0.3233906984494994, + 0.3744678828343991, + 0.4208931217541559, + 1.7929330290017538, + 1.1931034889049652, + 0.4892173193894577, + 0.8686171160648939, + 0.5750257645211981, + 0.28393247280973927, + 0.30400927200959954, + 0.35812910705847145, + 0.7450409632018568, + 0.6508974371206929, + 0.4050155494060652, + 0.8377829387890592, + 0.7733119139222635, + 0.4764024283851042, + 0.3746370052964283, + 0.6994607412355932, + 0.5894551460553645, + 1.3232327704010216, + 0.9374747148144145, + 0.34328913842837205, + 0.9399295210009242, + 1.4583602553826656, + 0.2035990108414691, + 1.4132510530339597, + 0.5283340425068669, + 0.7746488257786387, + 0.6375781378404236, + 0.2788225693870961, + 0.5449103801202114, + 1.0320924744897122, + 0.8407662782847038, + 0.8754819937479624, + 1.115606715871356, + 0.2773747354206301, + 0.38224116124383994, + 0.3198919781747101, + 1.182140402316902, + 0.46933012347130065, + 0.22414220471988436, + 0.5742376381398698, + 0.7458798623900336, + 0.7127572757311457, + 0.6365392762189971, + 0.24269176899506037, + 0.7872048653505157, + 0.883691272817887, + 0.20680627110853125, + 0.40577871276499855, + 1.44298826760434, + 1.1244434919504405, + 0.2111852843960081, + 0.9383285119903334, + 0.21880064534093396, + 0.8075518896670769, + 0.977869334270888, + 0.4622512449082555, + 0.4022411337309681, + 1.053408659746042, + 1.2737677470357462, + 0.7392379483118741, + 0.9095428464916966, + 1.1264153954000755, + 1.0386964103597771, + 0.6942177839667472, + 0.21536822664015542, + 0.7616780545592856, + 0.4619271073479646, + 0.25740320631447444, + 1.130496254766949, + 0.4653310577231617, + 0.2645778955113717, + 0.9590663446527917, + 0.7581234874559184, + 1.402524110717239, + 0.29092926289234466, + 0.9741394235103327, + 0.8049052872341967, + 0.6113701813002821, + 0.5742731691563678, + 0.2764199539587866, + 0.21258767636515943, + 1.0395240191040367, + 1.0928469383634647, + 0.8691765362037019, + 0.9065361905509162, + 0.777708118665655, + 0.7091275773947698, + 0.6452485600257325, + 0.7221782887641215, + 1.1415141528337966, + 0.5410446875380743, + 1.1936778057943487, + 1.7100935457254716, + 0.6756342080720215, + 0.5946504744132638, + 0.7314067507099357, + 0.27111354727190345, + 1.1581396663674735, + 1.018969422613995, + 0.7703600186131497, + 0.5301754685209452, + 0.21863217496886317, + 0.7257214833336774, + 0.7664722974795743, + 1.125541731757371, + 0.24677169249704697, + 0.9369474453564074, + 0.9367591075282264, + 0.39804206610763804, + 0.3724430595302512, + 0.8408180341431748, + 0.9357308955612946, + 0.26397474584133096, + 0.4400664652566027, + 0.3723070093686382, + 1.2207528960911238, + 0.2679556867904459, + 0.479181259281857, + 0.5867078067219349, + 0.25583078541957605, + 0.5152769133987505, + 0.45026453855023624, + 0.5438417056071625, + 1.6648267205018907, + 0.2550961883477201, + 0.9995218403742558, + 0.2983630370437568, + 0.21878322817115314, + 0.5965679852236098, + 0.6706627155635798, + 0.6129710028792592, + 0.5807003991279913, + 0.46291871155222875, + 1.0325686575222748, + 1.6706234144097172, + 1.191976905875223, + 0.7436046392181731, + 0.9386495836625548, + 0.26055678365464985, + 0.5758085913901431, + 0.7649829496032555, + 0.3342474162075061, + 0.30752955767646484, + 0.21801026858852351, + 1.3521793599237868, + 0.4267654919494645, + 0.5467736949440921, + 0.24912974273562893, + 0.3814528912627551, + 0.34824519557864325, + 0.31971655959802026, + 0.6742003929069559, + 0.46957408998079503, + 0.9413061231478038, + 0.3784354034799188, + 1.2220566868582476, + 0.6629420608728338, + 0.7429506852616433, + 0.23843249444006828, + 0.34812790394499105, + 0.8966818354079298, + 0.3752553998841637, + 0.4193860463773045, + 0.6058542694538375, + 0.34835528077204814, + 0.7177853913778096, + 0.6085093179519234, + 0.5203464977949586, + 0.32004461793751005, + 0.6311844051461045, + 0.5658051493777354, + 0.9755538075507281, + 0.7012376097777814, + 0.3344960827145493, + 0.4725256887941935, + 0.2910183105594795, + 0.6354621784311014, + 0.5311170494490506, + 0.5979280824158967, + 0.4802966549001872, + 1.0250583350927638, + 0.24600408534110743, + 0.28075232105938613, + 0.2410974730513036, + 0.4916823630848384, + 0.6778881523223286, + 1.077585234243138, + 1.0548044111323494, + 0.21635434060273526, + 0.3746312567320024, + 0.3820940164095063, + 1.45508653215323, + 0.8513175147326982, + 0.28779012131816134, + 0.776667898845706, + 1.4249914097598528, + 0.9654503831038652, + 0.4742459929713892, + 0.3351256915101319, + 0.27512379951472016, + 0.9194161273747532, + 0.7140478969863062, + 1.1179270077299253, + 0.4703232730314774, + 0.6947467224297166, + 0.5420643465496885, + 0.6111825342703616, + 0.20252602739563175, + 0.35594394466733, + 0.49414873569729845, + 0.8284896849674416, + 1.0289077127531037, + 0.6818801765248156, + 0.4350885885999024, + 0.5766389838913273, + 1.7861795511720406, + 0.510483393163094, + 0.6654956489543511, + 0.2562556552031042, + 0.4372682109804732, + 1.1849662496626672, + 0.3274569657962339, + 0.8839193500263409, + 0.6250202867365124, + 0.5822962207515607, + 0.9896596186900712, + 0.3930429137975687, + 0.8920416028307733, + 0.437631947318513, + 0.5540652170446746, + 1.2817970500640552, + 0.34209710759580897, + 1.8174407553715348, + 0.7431174407580008, + 0.3014684144131035, + 0.42207600884865865, + 1.170969717892198, + 0.7044090546128812, + 0.37545613509518166, + 0.22852720405275856, + 0.523113284093169, + 1.4517064786338392, + 0.4470478865365124, + 1.0890774071926725, + 0.39757146096593937, + 0.2031504981837589, + 0.3756538067939272, + 0.2886714661173359, + 0.7063403582997937, + 0.5277628282480639, + 0.5056242877875627, + 1.3282363419597103, + 0.7879017462355947, + 0.9827864823342156, + 0.553807087140857, + 0.8061534021365729, + 1.1360285490810462, + 0.21628840776623656, + 0.6922217302541592, + 1.0790736020518612, + 0.47806137658625947, + 0.2850485915673919, + 0.912943466349746, + 0.5523020083716607, + 0.6648217435673237, + 0.3605474823293011, + 1.274297028331612, + 1.3850863510145717, + 1.3430186085644817, + 0.9722095950061237, + 0.7219749084343003, + 0.43859635558709176, + 0.777055939483151, + 0.8576183007259892, + 1.0431404324670768, + 0.536440555509049, + 0.22311664954326335, + 0.413061039833793, + 0.9404240342966583, + 0.34974106402009103, + 1.158093438901444, + 0.6357704003108412, + 0.5112693365682919, + 0.9226614628410444, + 0.4340825143526111, + 0.27525689460805186, + 0.8746560999775318, + 0.3221520057423647, + 1.5480358492940651, + 1.0387198262782278, + 0.9395196060086141, + 0.2544044950657379, + 0.48585163187712777, + 1.487037349968302, + 0.7538399447053445, + 0.4346475984665274, + 0.6644308764287244, + 0.487951290614074, + 0.6553712252611408, + 1.1613894733429442, + 0.3089264461987062, + 0.4218582481534298, + 0.7362661358575195, + 0.881411760512442, + 0.3707169819670935, + 0.7560141624750726, + 0.6798389615847567, + 1.7725936319879436, + 1.1815309396268692, + 1.5037906357855184, + 0.3089958451644818, + 0.30874578417913046, + 0.449569404432038, + 0.24537652796480522, + 0.5466343889978892, + 0.37803216595347905, + 0.26343163170461614, + 1.1967026490955888, + 0.26875618953167235, + 0.20909614751989514, + 0.30115065944182895, + 1.4256898175759696, + 0.9422682296705276, + 1.3588341210748973, + 0.9784184525975074, + 0.22165331756988174, + 0.6137259988480652, + 1.0328603708746273, + 0.564847426999836, + 0.9188702296043033, + 1.0830944855832993, + 0.5185146036289187, + 0.3577509581962268, + 0.32544928582067784, + 0.21843083712629074, + 0.49494927152416096, + 0.7143397758805735, + 0.5441226434130935, + 0.23253059708413323, + 0.47744376910543335, + 0.7778685232187569, + 1.009774723598002, + 0.702852947338147, + 0.9079725775939187, + 0.37584189827276404, + 0.37284410567053794, + 0.24985873419430907, + 0.87495911543708, + 0.31832444836246915, + 0.21238994834703295, + 1.3916797195531614, + 0.4584025997616278, + 0.8121870261808435, + 0.8714888110355337, + 0.2433273677609208, + 1.1056696965829942, + 0.3612310041953306, + 0.30976882412832674, + 0.9090785076073968, + 0.7980627931387453, + 0.34569696852561155, + 0.7852817774124957, + 1.318438412791645, + 0.6766940305399588, + 0.6578569801669899, + 0.7024816956738479, + 1.1526481543358178, + 0.5725383526652887, + 0.9287023964589999, + 0.7869084875586475, + 0.4519323626261267, + 0.7361393883533741, + 0.274433260714049, + 0.7841251687188222, + 0.5380781323483255, + 0.5386943508036875, + 0.36676535805730653, + 0.493020037846821, + 0.35187766182130414, + 0.4151709736383288, + 0.8453854828549715, + 1.240027588794207, + 0.44202517298651695, + 1.2341016523703892, + 1.2482708280736445, + 0.33975202501027413, + 0.7081610456617217, + 1.0152286090158016, + 0.30422131375054945, + 1.180729279211945, + 0.9701052071375234, + 0.8005051812872894, + 0.5276505713745935, + 0.7090758557137459, + 1.0392791591638, + 0.5438170523091239, + 0.4193733033166323, + 0.3603290451359052, + 0.8635809065108638, + 0.25034151076312244, + 0.7635841036424756, + 1.1483677208411887, + 0.20095381741354973, + 0.9413776609924894, + 0.38940941533452444, + 0.8342813208580936, + 0.782153646859892, + 0.5616455291344695, + 0.9672888099453196, + 0.3113764300533366, + 0.4795049747984217, + 0.7106862488010441, + 0.5806408331701024, + 1.1856625605205056, + 0.3841654259398584, + 0.8483673635497224, + 0.509386601150324, + 0.42669832292405663, + 1.1889651571490936, + 0.3596160033107672, + 0.9933652364118964, + 1.349723112278372, + 0.6804557926305644, + 1.0248685144388356, + 0.3585744942237343, + 0.6392274233057779, + 0.22354253998879264, + 0.8052744709276962, + 0.740306758926977, + 1.1353494361334762, + 0.5319400117196105, + 0.764363256029262, + 1.562080745763567, + 0.985172046882486, + 0.8815559219909388, + 1.2241515186921088, + 0.9513501365875617, + 0.2109725334925351, + 0.28229989162402186, + 0.6156603838954143, + 0.4013415226277368, + 0.6212945665947713, + 0.44025525245965536, + 1.0090386943410232, + 0.7366004919047625, + 0.7340480671261731, + 0.9721624920600892, + 1.553854748968381, + 0.5194202194780939, + 0.6010424422118635, + 0.4112360242287186, + 0.6738137631460479, + 0.27433309455693783, + 1.1132777916968166, + 1.4534490687662622, + 0.29401081318260003, + 0.38764561944667825, + 0.4512560635765957, + 1.2016535955864438, + 0.6458910480825498, + 0.53730768527181, + 1.6423905168241748, + 1.0502733725988216, + 0.68298608954762, + 0.37925550004130687, + 0.7899178833204673, + 1.366761810102724, + 0.664165230583886, + 0.8188210782163576, + 0.2425273870977573, + 0.3544579878088075, + 1.0849619223118188, + 1.1878540346812512, + 0.59491218151874, + 0.4034578994912067, + 0.9493891179571001, + 0.42620997173999325, + 0.34408606596793484, + 0.5264296928309377, + 0.4038066602998806, + 1.2249494314082914, + 0.4149134960413727, + 0.600246556374382, + 0.8087169356976269, + 1.2428020160924689, + 0.5642624990954582, + 0.31627223425095136, + 1.6381248220264588, + 0.2891200094530918, + 1.0510566646610127, + 0.21944314602967982, + 0.22719941029982044, + 0.3403819834823418, + 0.5873483296695955, + 1.286533724952033, + 0.5071545403931502, + 0.23634100178061995, + 0.5094324733341661, + 0.421532231949375, + 0.34311673950316685, + 0.6287222776179425, + 0.44439345908950295, + 0.6481958787503179, + 0.6405445281456162, + 0.8761374573797452, + 0.6283855287400151, + 0.9035836740612609, + 1.0777028822471337, + 0.43519657356767566, + 0.47498078087506546, + 0.7682352646750041, + 0.3876367850005176, + 1.3603816298748113, + 1.170725671286635, + 0.8849294086850603, + 0.8297313296559188, + 1.493269102246557, + 0.7925267991718773, + 0.7194423924721614, + 0.5426973079055772, + 0.49623376149694354, + 0.5861728392772726, + 0.4440844676991062, + 0.23464541567888805, + 0.6082562680901307, + 0.613050024776693, + 1.186901672125372, + 0.7644423819511939, + 0.5612229508390043, + 1.8056162771952338, + 0.29855579645011804, + 0.7507380555873406, + 0.3302009680767842, + 0.7265913601267835, + 1.0034401714960053, + 0.3219979208473936, + 1.0209724413583472, + 0.37148577093099716, + 0.582698018304615, + 0.6208884050755868, + 0.4543455027347484, + 1.8497236459518498, + 1.5800026655006816, + 0.681890242373913, + 1.0851806830424293, + 1.5198066162595194, + 0.29740366375354294, + 0.5203148772355439, + 0.3733880951954359, + 0.930572113060377, + 1.3924500312743282, + 0.4280349751210091, + 0.5482760031788203, + 0.5761807655588929, + 0.8347557455448847, + 0.9096340252618478, + 0.8218881667539224, + 0.29509283867713565, + 0.4275984100095655, + 1.11202079956951, + 0.3219921085610368, + 0.7541759902817088, + 0.7238310594309755, + 0.8473287062629437, + 1.4302888362131785, + 1.42682321131696, + 0.472727159013086, + 0.796060640428696, + 0.21168413945202352, + 0.43279495827450204, + 0.8955232526087524, + 0.8005046057785126, + 0.35219265103003394, + 0.6226614956136539, + 0.696513864662477, + 0.252615923602091, + 0.8634540090214751, + 0.6005400055093923, + 0.6648587644488902, + 0.6922286475687316, + 1.9406755752790992, + 1.0292338385720208, + 0.38898305917361625, + 0.9403834137522875, + 0.49029098415735667, + 0.5816349151737614, + 0.6388474261169825, + 0.3242356369863005, + 0.6356319614454822, + 0.5396937632416179, + 0.21264474920885706, + 0.7332054954954342, + 0.4044350844035631, + 0.5707795936982678, + 0.9389838280520847, + 0.5136677579124962, + 0.2309106992304848, + 1.6714452474307937, + 0.4818379831160414, + 0.3980667913597842, + 0.5972518553695372, + 1.1435237964740204, + 0.4957984871595613, + 1.0879621910129482, + 0.41813612563656993, + 0.43263662921500295, + 0.8548030947657217, + 0.5953929284525209, + 0.8093282571542441, + 0.3807459926155442, + 0.9496450679585353, + 0.6104622944848525, + 0.991943057514315, + 0.832253130677476, + 0.7652404117436108, + 1.8334254673462427, + 0.4560174628853207, + 0.48480391411109997, + 1.0034305254911096, + 0.5575500250628959, + 0.3090581084251799, + 0.30896153917974767, + 0.49861947149081254, + 0.6848018137495787, + 0.29466869899264464, + 0.6468220701068128, + 0.7276016599152374, + 0.5611512245587524, + 0.3401422431136459, + 1.0163097976272542, + 0.40615261319548945, + 1.008875552281219, + 1.0285209849165382, + 0.392598171743798, + 0.7087810713160857, + 0.4137401285330284, + 0.23684135182303725, + 0.5471013370199981, + 0.283139342992627, + 0.2572929202216627, + 0.43203986189692645, + 0.865582648827199, + 0.4858649248849787, + 0.26509897133275323, + 0.7392786876856247, + 0.8369003107392569, + 0.4584265538802776, + 1.3586739373461738, + 0.7956149189277621, + 0.5927174452476446, + 1.0343520798744512, + 0.22512180295942485, + 0.8742915009339929, + 0.2382563256890214, + 0.7810976765487354, + 1.3719706277280157, + 0.5134694954787957, + 0.9274062788225822, + 0.35603399833035176, + 0.40746093404437644, + 0.6698736477417188, + 0.20211088271249975, + 0.3007037358437478, + 0.8338975674070265, + 0.32960094410887764, + 0.6812565311017467, + 0.3233980909004858, + 0.8226900605440972, + 0.6908703072092143, + 0.5739229341367496, + 0.6872152084298059, + 1.338627865917522, + 0.5963025315410185, + 0.4130286511168684, + 0.26344204049220055, + 1.467853190952312, + 0.8068008884175382, + 0.6171526243474874, + 0.49834685811287527, + 1.0776807429564552, + 0.5580267908733578, + 0.5151653859149128, + 0.8275553239667169, + 0.921921914675004, + 0.45279725567508716, + 0.3041053289775494, + 0.5556204193940837, + 0.5095179600838328, + 0.47633280695712427, + 1.5984715671840446, + 0.8685938919893028, + 0.39508173787268214, + 0.2011147929925971, + 0.2882535936196497, + 1.0950589595863007, + 0.279623546799857, + 0.6874069704326653, + 1.44115542685703, + 0.8113368944808848, + 0.5823924913559583, + 0.3174253868175073, + 1.6129179087355554, + 0.5188906642404159, + 0.4225610895574515, + 1.0039293044695534, + 0.4063111829539311, + 1.977787123453701, + 0.9300553608409432, + 0.759606333343923, + 0.482696621582762, + 0.2805528882817407, + 0.5091826206009512, + 0.510231801721021, + 0.5734726263598935, + 0.47939827363069176, + 0.34428377389557957, + 0.25642738432665185, + 1.146717645841962, + 0.4309223155093243, + 1.274641904748993, + 0.21389179844182035, + 0.7488389956080868, + 0.4949526168428978, + 0.883350590546694, + 0.4929704516489867, + 0.3134942871789514, + 0.555258617661422, + 0.30306997868945224, + 0.3480171409471319, + 0.464968876743405, + 0.2545742322644409, + 1.8092922803427811, + 0.32123114392067226, + 0.25646012897230663, + 0.28461448179884963, + 0.7286264113045815, + 0.2756961168263371, + 0.6545899805414703, + 0.900765766303191, + 0.37202969646824097, + 0.8927597192421145, + 0.6392118142421591, + 0.41425702276741133, + 0.23523970428512828, + 0.8093042994335949, + 0.380920064764937, + 0.4379997885300407, + 0.6572926270888775, + 0.6353060913226843, + 0.6770905817536776, + 0.8922724965100054, + 0.6050220680526518, + 0.9129540573220202, + 0.30518819439861966, + 1.2757441365711086, + 0.42732805915614763, + 0.26881024452133173, + 1.2007808678603404, + 0.43085728327224165, + 0.676170166713255, + 0.9225460190131378, + 0.4705396489593335, + 0.42543820535217, + 0.4407502618163805, + 0.3884704444728399, + 0.2176651458758484, + 1.0588406203986718, + 1.577588582017136, + 1.2997117499651862, + 0.8867222501799016, + 0.24930459429219035, + 1.1346166933059818, + 0.3154377861501778, + 0.8012333925796744, + 1.0175467367602447, + 1.3789013870397693, + 1.0933650298455242, + 0.2641415694812749, + 0.36605557713960424, + 0.7020572507564393, + 1.053649382565234, + 1.3035681150607232, + 1.3235481761520238, + 0.3897895257564901, + 0.625939213924046, + 0.8041131772738596, + 0.3069746062527396, + 0.42056731818881726, + 0.8827126647893729, + 1.2776964667515829, + 0.8450117515025971, + 0.31124213784498095, + 1.7910921389315397, + 0.33201578606148785, + 0.31093487220948657, + 0.7081205850391088, + 1.267770546436818, + 1.350343317168772, + 1.2114653907781192, + 1.0814797423337341, + 1.0996581464789439, + 0.254528174451954, + 1.8237288116235992, + 0.7580550228730143, + 0.8070517824274644, + 1.0330212950208648, + 0.6470965591927219, + 0.2303064477111786, + 0.5118425898559466, + 0.38894988323708274, + 1.3098436902976078, + 0.2705426652507024, + 1.0908255804463338, + 0.9035708013631948, + 1.1969795538113448, + 0.29740396389463675, + 1.0472507383946852, + 0.3895931991245903, + 0.30743371885295734, + 1.5519225328164434, + 0.5233142585503443, + 0.2176838493199833, + 1.2292643428840184, + 0.906465372092145, + 0.7441974269028335, + -0.1572715713329357, + -0.07727977834819799, + -0.02730220301108312, + -0.0012149493630591892, + 0.11252170295355864, + -0.05918938739969493, + -0.11090002393019202, + 0.1258781254474544, + 0.09903361484792093, + 0.054953441650541966, + -0.13205093505567744, + -0.16232804372689197, + -0.14538677001439165, + -0.12041898443145188, + 0.06711325985035198, + 0.10120782038243484, + 0.09002169027339128, + 0.14035589775675072, + -0.1977979117639404, + -0.18823157959490355, + 0.12614500799707343, + -0.06821592102577125, + -0.04828826981683116, + 0.01688131876305062, + 0.049996134120990715, + 0.11699895447429559, + 0.08886026488398688, + -0.08925627502617002, + -0.16026745058601036, + -0.17048479919013296, + 3.0424043223283476E-4, + -0.02311110451977011, + -0.18093694764760163, + -0.15733187596842776, + 0.08212088793373683, + -0.011848750736675412, + 0.038691858145878756, + 0.11163952387174722, + 0.07146590469405058, + 0.1317781419404948, + 0.10669609270780915, + -0.16877142708736967, + 0.0741230390631484, + -0.11395865290345936, + -0.115622563702415, + 0.040593977534260195, + -0.037685189869406166, + 0.021592876982860672, + 0.07936839002835987, + -0.18426116591286495, + -0.11822284450308543, + -0.1727178492017082, + 0.10689926467115748, + -0.17587794362165232, + -0.030570470808904068, + 0.10525664125180248, + -0.07579496993627531, + 0.006561360491090976, + -0.02741503873221105, + 0.09048151782113828, + -0.08671596893857454, + -0.015730206431098136, + -0.0222596624466244, + -0.09998419453503651, + -0.14303266553406888, + 0.14381537578883935, + -0.18700207702399596, + 0.09157332596674313, + -0.040215100985371906, + -0.13393806101571232, + -0.0361419492953031, + -0.1799143606874988, + 0.024183331897171895, + 0.08281030197611124, + -0.046267889509368526, + 0.19476553216465445, + -0.15433883509394586, + -0.17056763425421245, + 0.18337912295736017, + 0.17242680952533396, + 0.04637882214321797, + 0.10729944478440565, + -0.02031114562475267, + -0.1494679159530772, + -0.18431592237958375, + 0.11555023768642474, + -0.1894834149635889, + 0.024888386835516654, + -0.1560398588172149, + 0.11943458341018777, + -0.10508916063845626, + -0.06755373630825146, + 0.08651521439900962, + 0.10131742125774103, + -0.026580240544499343, + 0.0910522839639666, + -0.1567560469803093, + 0.12663814089639244, + -0.1850235663589953, + -0.08332028445276145, + 0.026919167743515465, + -0.14646749433541023, + -0.01764382081586127, + -0.10085108833209487, + 0.16157059874863294, + -0.18149619858257723, + -0.17294818017720842, + 0.1307854598373273, + 0.09465801683180451, + -0.15755383740244794, + 0.19219599317485261, + 0.1216055520891942, + -0.17847701155656742, + -0.15086378511145224, + -0.1494398368324558, + 0.14783141749346987, + 0.16783047033912177, + -0.01207598956257491, + -0.11892188327996826, + -0.15756525492180465, + 0.12164189105560833, + -0.1773144065703364, + -0.11929596563534438, + -0.020151443419762452, + 0.038976418871695416, + 0.02782954896618897, + 0.06085284235444891, + -0.19937490509158298, + -7.716721594853511E-4, + 0.07486739185277594, + 0.18135220230098914, + -0.10431019145185663, + -0.09516179157461098, + -0.16594138214247225, + -0.15850839433502598, + 0.01667070508704463, + 0.0265240289227063, + -0.17058383650206768, + 0.08307498230525193, + -0.09769537463503003, + 0.1333623565531713, + -0.171240854277227, + 0.03794261779514015, + -0.039039225769405446, + -0.05803424386045403, + -0.0011996199179239479, + 0.18962569244868807, + -0.08317607775268053, + -0.061803884880204635, + -0.014901230433182314, + 0.07605515445145467, + 0.1006084064396155, + 0.1878772643688151, + 0.1509760469444012, + 0.1035489269151775, + 0.18207194253333822, + 0.14191591381540092, + 0.09055747069678192, + 0.03858262526299647, + 0.1669933277413003, + 0.11084989906069971, + 0.010713484540430048, + 0.15038644218264344, + -0.1899493942733663, + 0.1891655030934658, + -0.025845280198578895, + -0.14761362427959132, + -0.02667281070646408, + -0.19474728777665462, + -0.18702350965717457, + -0.16528395402812468, + -0.09152571724464692, + -0.15180682060788092, + -0.14030110934746284, + -0.16230571263679155, + 0.1578774837584768, + -0.09789190111745014, + 0.15792542196854856, + 0.03558897425154271, + 0.06139365345519836, + -0.11404362481360165, + 0.05928220265436175, + 0.15718875222890263, + 0.15311191743455438, + -0.004626271043716598, + -0.17804024039436955, + -8.975211895461928E-4, + -0.08791573953638517, + -0.1771583941705107, + 0.17492440641981216, + 0.12331545994569902, + -0.05608716225094143, + -0.08901133279309119, + 0.06529828458073295, + 0.12905695340886844, + 0.14613881001266185, + -0.03655136679413481, + 0.03499286657104726, + 0.1515113390578802, + -0.13963790415436136, + -0.08269095798081876, + 0.04959615617650491, + 0.1980694421338741, + 0.14258665899935866, + 0.19216820217838623, + -0.1675573528674972, + 0.06998870981060999, + 0.008378349890727405, + 0.1787674852611516, + -0.02246704717481686, + -0.05039469060795496, + -0.1734229502720809, + 0.060552492816906556, + 0.07986245606373812, + -0.11088916270430144, + 0.08420627302345102, + -0.10548115886781102, + -0.036694200404809724, + 0.0615998585955465, + 0.15865408987153498, + -0.04939337265502016, + -0.05793285547884785, + 0.07318936260902792, + 0.05568028959547871, + -0.12962354953593902, + 0.060254702811059796, + -0.04735099566760522, + 0.012462725629451872, + -0.03510943969537443, + -0.048842037371016514, + 0.09522277246943464, + 0.10303906095534483, + 0.07459917835210296, + 0.16620108677809745, + 0.1518729600697371, + -0.0062567461029260085, + -0.058201237564610826, + 0.0920237235630229, + -0.12750191881666906, + 0.15916654860506904, + 0.09757396438861284, + -0.16508549184492805, + 0.09407688873035658, + -0.16127310057636476, + 0.14868946125609928, + -0.08852170550216619, + 0.08582375506221471, + 0.1233041154575931, + -0.1746557725184213, + 0.17209943026105887, + 0.17655396486851935, + 0.15748891837199938, + 0.19958380703520423, + -0.002693024982389338, + 0.07345929682603494, + 0.021777469521263998, + -0.1260523315571066, + -0.03211081373602234, + -0.016891706892010173, + 0.07149739971404653, + 0.049578658168737445, + -0.10856005314607571, + 0.1651749583500944, + -0.12835053360578536, + 0.08702475001534449, + -0.02850151153572011, + -0.14080568666208867, + 0.09039202052606406, + 0.014691828788041853, + 0.13083600066498627, + 0.1307774207065271, + -0.17667711081656395, + 0.1373257474869851, + -0.16509688424973268, + -0.13217478417537196, + -0.03719433218404791, + 0.0923258435781083, + 0.026034342811117973, + -0.14125429712470394, + 0.17216223525485333, + -0.16912142679905529, + -0.11445009464992194, + 0.11232851682541924, + -0.026793833055756715, + 0.03474114952252668, + 0.13901660069174973, + 0.1877502877607086, + 0.16958404592093188, + 0.13713967424070916, + 0.17388281940026137, + 0.0927198501847745, + -0.0741747782381172, + -0.1831591347054549, + -0.04240077541369592, + -0.05790078472312709, + 0.043953618601317204, + -0.15823902253811242, + 0.10033806585877422, + 0.06690764026902046, + 0.05804193983919541, + 0.01472255115823867, + 0.07816936935945772, + -0.14627631890676168, + 0.07173182186483165, + 0.015322115506240441, + -0.009294248590652365, + 0.03403444108228235, + 0.017245258761309775, + -0.06287002852106105, + 0.009662851258522698, + 0.1925990753491718, + 0.038906541420789684, + 0.09689363096408947, + -0.04261245726375749, + -0.0761149514599533, + -0.11339499429691706, + -0.009165472109040703, + 0.03203031051601827, + -0.10895902890199705, + -0.04290995125685201, + -0.09515084387095864, + -0.10997378941511987, + -0.050197495614369196, + 0.06349584842707784, + -0.09638002958583787, + -0.086022591749034, + 0.13387282599387676, + 0.11231783305332194, + 0.16092126861745792, + -0.1991431560392634, + 0.15189621442287793, + -0.11391041320144556, + 0.04500803047415122, + 0.13792153302700166, + -0.05990048509414945, + -0.0937774267497158, + -0.07948468878433236, + 0.04296863752998031, + 0.14627473796476687, + 0.0011106643177959514, + 0.050419975584060285, + 0.04974012716996725, + -0.0635748504293647, + -0.09671756056983152, + -0.09788229453406805, + -0.0025988104891110494, + -0.16852403781319686, + -0.12254011910437362, + -0.17365857301431095, + -0.1762961670722278, + 0.1903898028805718, + -0.014712612221873377, + 0.0303392751252388, + 0.07097373608521326, + 0.18555306453378448, + 0.05216383245637365, + -0.16661987985448762, + 0.1041170540981622, + 0.17881388126316305, + 0.009794408621513477, + 0.03999330471817059, + -0.17909669807199335, + -0.10063276898107151, + 0.032205497512657645, + 0.09129332657764726, + -0.05152485787772437, + -0.001527976170348439, + -0.016348278048760354, + -0.13417140156137913, + -0.05282993147523274, + 0.0591458629191965, + -0.16206528562849143, + -0.002848856283226611, + 0.08435489443969055, + -0.17055206333535242, + -0.08554131861008028, + 0.16834042338314031, + 0.024086047711388663, + -0.08498066195004249, + 0.1142952859640341, + -0.05951140009138608, + 0.14603374662693158, + -0.1535406123702238, + -0.036585911222914776, + 0.18265254658386573, + 0.16490080288271985, + 0.19855508979131536, + 0.01127777907086553, + 0.17788812413843624, + -0.05734138922806747, + 0.1489307543708164, + -0.00949066338234005, + -0.012424114462787678, + -0.0789283871750123, + 0.1323676395921148, + 0.11750671136701492, + -0.19304542403303362, + 0.10363736792781265, + 0.09546513927219955, + 0.10162341344954372, + -0.025436688275725802, + 0.05399489136135705, + 0.04288188621943463, + -0.00551652740518947, + 0.01903280710050653, + 0.02552969306293908, + -0.05190315245084936, + 0.11148680857832262, + 0.11713566820009065, + -0.025317542385850263, + -0.12020369329426304, + -0.1687138967996809, + 0.09464920167422239, + 0.06547822029419444, + -0.14399963467670152, + 0.024858452917146605, + -0.177486131623935, + 0.17987394195422862, + -0.029635701392709102, + 0.1742286356521739, + 0.05500042084908764, + -0.077925076896192, + 0.11908140846948663, + 0.13395897889562453, + 0.11235415785246491, + 0.046292618015988655, + 0.05605609978514746, + -0.09494351418615969, + -0.10871356360673047, + -0.10963618451489165, + 0.08013170474925871, + 0.11592230490763972, + 0.1759493787561035, + -0.17983465696706588, + -0.05841710893799576, + 0.19742916633917454, + 0.1624527101066375, + 0.06362015224848569, + -0.11041403977009008, + -0.15760936458073824, + -0.07980249408313383, + -0.0702191226646709, + 0.05908448671225921, + -0.08336824878259873, + 0.04101313658353912, + -0.053712509703041894, + -0.16480841482044556, + -0.0026276545000164667, + 0.009452318731809503, + -0.038068204070318544, + 0.07828388806796122, + -0.1976067798117253, + -0.0032268309242577176, + -0.1971475836364988, + -0.08736976417281307, + 0.02813750534440335, + -0.14621707353873162, + -0.01728159793227594, + -0.008947155400842944, + 0.1950412620392218, + 0.06698647361682036, + -0.05445914902361623, + 0.1481514587692459, + 0.0754140703770786, + 0.04725614282465697, + -0.11204645225597262, + -0.045042920882160505, + 0.07872952255635778, + -0.01325279452135222, + 0.0822617322394701, + -0.10974496757279756, + 0.17608189757925338, + 0.10313424680662112, + -0.01723199236172018, + -0.10178668231132297, + -0.16162948352744957, + -0.15688409407279216, + -0.049228240688714564, + 0.1790783964114267, + -0.1867506057437447, + -0.04835425378106986, + -0.09344181441628203, + -0.19404927285585885, + 0.0806487462598414, + 0.13430202982258727, + -0.037146011703329276, + 0.08020889470088811, + 0.04336955253707137, + 0.07988337055688567, + 0.13240583731736713, + 0.17515118397396767, + 0.07630733362846459, + -0.16609328767521092, + -0.1990334668307265, + 0.02794180274778539, + -0.03316097575795883, + 0.17530346465883317, + -0.15155636422683078, + 0.053842747683892946, + -0.17413988633570873, + 0.04908373194885431, + -0.14784820281255198, + 0.03325451927614181, + 0.18204926657993828, + -0.19314226789322678, + -0.10574620609070347, + -0.06486064166230966, + 0.17173501831832666, + 0.1831767251057167, + -0.023066946977714407, + 0.19288895858325844, + -0.16602112414473602, + 0.09661689927658858, + -0.13722984698956708, + 0.14572951207911614, + -0.04473073929424749, + -0.07691449328343736, + -0.04407622099039173, + 0.1802474953208796, + -0.145328207439, + -0.12441130945682619, + -0.07219247270501024, + -0.012495485050119715, + -0.12904165698618617, + -0.011507833228674425, + 0.07396447465202086, + 0.15644325543724322, + -0.018406232098682095, + -0.16100525468561325, + 0.08313159370307441, + -0.15648916315517947, + -0.1288103714079066, + 0.02764518146215225, + 0.11989305034471705, + -0.019947859939500028, + -0.06275571342462843, + -0.1111647713871097, + -0.0054510590331564015, + 0.05819107510152812, + -0.15649058417323658, + -0.18677913625701437, + -0.18331840188059167, + 0.14033547663252083, + 0.07100525790783452, + -0.13984826523896368, + 0.01325847439547089, + 0.03194235789554925, + 0.04969394530009904, + 0.04733389881471991, + -0.18657098484904452, + 0.0017374804294335423, + -0.07810831935729601, + -0.1628585952175208, + 0.07815299534313266, + -0.17409611297069966, + -0.1469707338593502, + 0.05761731683472067, + 0.18978836143395864, + -0.08764249989353967, + 0.09902115905198056, + -0.053548108585865645, + 0.013669788027955891, + -0.0035748272555176258, + 0.05552417735439095, + -0.13404978282718485, + 0.16555777193194537, + 0.07606005148305041, + 0.12629399618590426, + -0.08679782601662996, + 0.17393132377470885, + -0.19821658711525084, + -0.11262777182600177, + 0.052525932960003754, + -0.16946790050869473, + 0.11228425803157208, + 0.12544306287072812, + 0.01772897201677089, + 0.14886410720346271, + 0.006991031990090253, + -0.006442647594734867, + 0.12811189362060346, + 0.1924888348944825, + 0.16038002215760586, + 0.050139929921076805, + -0.09167209964268484, + -0.01655176627192157, + 0.16442909765689326, + -0.052301166309132986, + -0.09023716257265418, + -0.16754878775096688, + 0.09726949152770399, + 0.1600715070047059, + -0.02645778799868808, + 0.07011886203960499, + 0.05140457169580433, + -0.09589865813710126, + 0.19197888648660932, + -0.0242073442209946, + 0.16852690320828836, + -0.14090543065940117, + 0.13288015586794355, + 0.09188395877242088, + 0.1641263582003591, + 0.11036718814306928, + -0.1289114281401321, + -0.12105832574136031, + -0.10609177601292838, + 0.04881396916763168, + -0.11208401770662547, + -0.192183106155809, + 0.1558830434517862, + -0.0386146282141011, + 0.02908134068990104, + 0.08054667538694897, + -0.03580534734608488, + 0.08444604481350872, + -0.10128319481627837, + -0.00200215623817172, + 0.18080183965072177, + 0.12051269946176323, + -0.06007460103716991, + -0.16789674142876723, + 0.037160538967277834, + -0.16253727439151278, + -0.16710302240245656, + -0.03865347431205883, + 0.043814695086405904, + 0.19696033498812282, + 0.041020032505267576, + 0.15843062052416845, + -0.15153443752285514, + -0.11080164420620911, + 0.14549655212958684, + -0.10052569662671164, + 0.12335502468783176, + 0.19647501835503767, + 0.18684496429099792, + -0.18275108370719484, + -0.07454008189462806, + 0.11074317640624197, + -0.08887670562831632, + -0.12940408076409132, + 0.1274723921778534, + -0.12301283214427916, + -0.10351107656665458, + 0.11879361078974991, + 0.06396011775204613, + -0.13162418837360443, + -0.16370866669977807, + 3.650850885182689E-4, + 0.1603617655568086, + 0.13800291477906862, + 0.07711386150910893, + 0.044746987622477016, + -0.11904130817326251, + -0.026272503894780325, + -0.18309285990516555, + 0.06076288390168988, + -0.0860460503982694, + 0.16965254833893603, + 0.018603953733595226, + -0.12786620630114215, + 0.004612376546319326, + 0.07174500173296007, + -0.17879073352128, + 0.18403323267961672, + -0.11241595176120489, + 0.03509820624806027, + 0.05638167953974119, + -0.1552109648999061, + -0.17739480313960784, + 0.1386932681293576, + -0.0061091553830226525, + -0.15495438236327394, + 0.05829132715308791, + -0.030449030939981594, + -0.15474129365502262, + 0.17418045571540894, + 0.06555046341539839, + 0.07334640366468893, + -0.1564547453010181, + -0.10757558308255401, + 0.17275732248217024, + 0.11917494901945166, + -0.16439037956484728, + 0.06649479364388569, + -0.03909413626232206, + -0.09935408274326876, + -0.03264782317801145, + 0.14190535752264985, + 0.015910400888133037, + -0.007906629947160352, + 0.18213502709919205, + -0.19583631876488466, + 0.11561457314211676, + 0.15718771552981006, + -0.0394230414856907, + -0.16763740582535477, + -0.1677104610112869, + -0.06384042515851474, + 0.11917385591884541, + -0.059132323858937186, + 0.19488579862766445, + 0.17959798499149723, + -0.12903197323204912, + 0.01024408381161234, + 0.12599834641228985, + -0.03886135001106977, + 0.10574644497541168, + -0.1806918872282867, + -0.0394844121526865, + -0.1796204139779458, + 0.19254380286806752, + 0.06449056492896607, + 0.032695717107363145, + 0.14790801223845113, + 0.16411981453004632, + 0.08371385886939776, + 0.06402496723449408, + 0.03047747820803436, + 0.051991421321087, + 0.12438178514889481, + 0.0702563749805695, + -0.11203048662078259, + 0.16627533059669594, + 0.014953393860441413, + -0.16754025286724655, + -0.001418978375324632, + 0.0884864864593314, + 0.16695103522618993, + 0.02937700082707056, + 0.17167645208439414, + -0.1870094412518139, + 0.16690487576698051, + 0.06114358863599677, + -0.19244433290402208, + 0.16798474799002852, + 0.13799611398418396, + 0.050896402205573454, + -0.024730810526508846, + 0.19327843881704013, + -0.06470347894010486, + 0.18732311002837962, + -0.07875801288866859, + -0.12253883010377208, + 0.12481496751819393, + 0.05009954735803061, + 0.08406759303053156, + -0.1818711815636282, + -0.19029464063177495, + 0.19178031715273974, + -0.07269924253957752, + 0.1666147368333791, + 0.019477557255148534, + 0.0117107470448594, + 0.11875235112142306, + 0.1270761356344667, + 0.1351082619889936, + 0.15782582168013812, + 0.0030894050476605126, + -0.011771045657168066, + 0.1384417550108171, + -0.005690029449463711, + 0.13366461883168773, + 0.11194859609257117, + 0.15275965942533132, + 0.19839069062149498, + 0.06860607778602736, + 0.19138483065822687, + 0.028410812309215418, + -0.021497756611524053, + -0.014487944425044169, + 0.15905890775308845, + -0.1622303203765569, + 0.06742181180015476, + 0.155793346965189, + 0.004756803329882492, + -0.06327903213761919, + 0.032842170391322506, + 0.14427152423659223, + 0.11310652270630443, + -0.034729901281548375, + -0.09321753816265167, + -0.16376612209010852, + -0.19355807295984812, + 0.08882743956229643, + 0.07183175868180543, + -0.04955293323756576, + 0.008462834032571965, + -0.1523643349832165, + -0.020327044896547884, + 0.12393513782567933, + -0.07264849310966938, + -0.021217316528053014, + 0.08163797433043138, + 0.16366659010732268, + -0.19786724316916554, + 0.015181515958383794, + 0.18814168608088377, + -0.1700700633600206, + -0.029632202007796427, + -0.1563507006074318, + -0.19755741745836475, + -0.07585063061599828, + -0.05444179881282189, + -0.19420969486714695, + -0.09578950083687317, + -0.04335308793157698, + 0.13044173659876748, + -0.16548028281066715, + 0.127321449627096, + -0.056525480057566704, + 0.0682609407323179, + -0.10530842224663947, + -0.13231020942279434, + 0.16519939237977307, + 0.06597675302693969, + -0.0435358702250673, + -0.08951034424417262, + 0.17175644178837599, + -0.17308491067846724, + -0.03738699249649797, + -0.08705166537495944, + 0.1932328344355016, + 0.01642331494984444, + 0.09505457575569666, + 0.19890718879738895, + -0.11042996418983733, + 0.029279805835938897, + -0.1908957824907252, + 0.12133578794776616, + 0.12707648780660952, + 0.058824155414906314, + -0.13096631890499838, + 0.03991639252741276, + 0.10022223580514499, + 0.11344484828518069, + 0.006770934812037278, + 0.19126476673534448, + 0.19229569243885838, + -0.1282746952982785, + 0.1852530233854257, + 0.17983057535584523, + 0.015616906108438237, + -0.0316011058492896, + -0.09359737931183502, + 0.11015760194777596, + 0.0015657764156027337, + -0.16052196080136324, + 0.06320405882931217, + -0.135808267779229, + -0.06983968327269072, + -0.06478946940292905, + -0.18714277393116446, + 0.19111148023091182, + -0.11335813203797414, + 0.1157254153822772, + -0.005435794188040034, + -0.026715930431068537, + -0.09297878594453649, + 0.16321273383050838, + -0.1849454451324987, + -0.14365943838401818, + -0.040242229078669166, + -0.18407535440528883, + -0.09428638083437463, + -0.07232436491087878, + 0.14975388094695158, + -0.0628300591965549, + 0.01870037048837482, + 0.11411931505963074, + -6.325152846889858E-4, + -0.09934323399460339, + 0.031031608988341976, + -0.056833655738336694, + -0.17726736783934907, + -0.1226042197026864, + -0.1551597706790028, + 0.026455351207313186, + -0.041445514590729815, + 0.031000713614763628, + 0.0966282199037142, + 0.019765493172613578, + -0.15368514707041767, + 0.1172638836432798, + 0.15679014748376038, + -0.11422787742640801, + -0.1088074631862024, + -0.05449385881863939, + -0.023610539993304418, + 0.06027346343254199, + -0.06915455770471578, + -0.1761555005276724, + 0.047383350733487956 ], "y": [ - 0.2566037486234132, - 0.4338005475770033, - 0.25559581721940555, - 0.5161263256472108, - 0.2679435104334891, - 0.3376956525561604, - 0.49188000825586237, - 0.5218593590401204, - 0.9874121580210224, - 0.9801130212624256, - 0.3910606740613632, - 0.5336985934244526, - 0.4623115483375859, - 0.20804948427684394, - 0.46211881648675646, - 0.35955731548757636, - 0.437640565586519, - 0.382481948405784, - 0.5197235337549346, - 0.893812928420704, - 0.6261251775980211, - 0.45639139342056617, - 0.905808539429479, - 0.21597864799032235, - 0.3794221180634396, - 0.235531195660041, - 0.8097502082139453, - 0.20214239397510803, - 0.5676388058881596, - 0.7083680320570571, - 0.6530558065372658, - 0.44900014720788245, - 1.605911396989044, - 1.1038452805485555, - 0.23266432816447322, - 0.6458556818369409, - 0.5926594842098929, - 0.30377652112045406, - 0.6576787243204616, - 0.6379470027124354, - 0.5237367923018311, - 0.6149073408294097, - 0.5192273628071946, - 0.6101037213392053, - 0.7112842247198318, - 0.20619408243727808, - 0.6086939867796265, - 1.0084880905900209, - 0.6170726665075505, - 0.22357547931973146, - 0.5193943252166164, - 0.43095467008585076, - 0.427351377163177, - 0.3168327718840377, - 1.0874108753644935, - 0.6373106434911443, - 0.4826192219157633, - 0.8425834497557578, - 0.6532909185252268, - 0.39713570790948516, - 1.1319612754409958, - 0.640287375664083, - 1.2596197180104662, - 0.8788584430814002, - 0.6065349300878045, - 0.560632892537006, - 0.7610610050200446, - 0.20431559923357745, - 0.9019709214079731, - 0.304403119235649, - 1.7117473706813158, - 0.32280366189057985, - 0.503304798109607, - 0.32090997277238925, - 0.37378804892781187, - 0.20688518955202206, - 0.33042597999732065, - 0.5719487196985407, - 0.9967212282927205, - 0.3363672513825333, - 0.9707226854209565, - 0.8716420411029757, - 0.21129603658409146, - 0.5498819311592517, - 0.2987611795401591, - 0.33533622525921547, - 0.21151876531713798, - 0.5524931150815888, - 0.28730764162284084, - 0.3309132996559782, - 0.4186916602441724, - 0.7567636502041801, - 0.3695430151066479, - 0.2016205150089975, - 0.543483601791543, - 0.9868707989415589, - 0.5011755502629445, - 0.6061083791241644, - 0.5989637026674027, - 0.501898799334069, - 0.445648738115646, - 0.316567547960087, - 0.6570974123567351, - 0.6866628127241557, - 0.5070358412901328, - 0.7690373850916251, - 1.3487682821304343, - 0.6169778532912853, - 0.7041235888543859, - 0.5131470496406333, - 1.0315332441963028, - 0.8238546671787381, - 0.7034623303814408, - 0.6898586922436255, - 0.570543207369912, - 0.40530739470417926, - 0.38059233699237327, - 0.2899703648694561, - 0.6281353891174138, - 0.2348961103820507, - 0.3913493391371191, - 0.40105649167369833, - 0.37264544115206244, - 0.34494124894964706, - 0.3260018969106401, - 0.4629135289632776, - 0.3318751184021369, - 0.7100250735773201, - 0.5202806439571696, - 0.32294292799982366, - 0.4832450295639911, - 0.2117985162156336, - 0.589942550736504, - 0.3486611228969728, - 0.4857029188994103, - 0.9683017745998579, - 0.5378379757108024, - 0.24609448862482844, - 0.9329885213760652, - 0.25278319423201695, - 0.22108111637735292, - 0.8936584787207027, - 0.8584939449804072, - 0.3862051440112111, - 0.6275400828440323, - 0.9514009356856387, - 0.5694931144959244, - 0.27119744428130854, - 0.31222914761205345, - 0.24555984684609072, - 0.22395121271650373, - 0.204177716024457, - 0.39787365489334314, - 0.41578290472891943, - 0.2610938366245187, - 0.46469297182126756, - 0.6347780437726943, - 0.6747106785903171, - 0.8305244992156924, - 0.5971505726779339, - 0.2928565649387206, - 0.5179389794292119, - 0.5450929703784482, - 0.2664131930848552, - 0.5123053860967297, - 0.23609029958047584, - 0.5186367054802166, - 0.8350143273300654, - 0.20356957161905329, - 0.22343432680454858, - 0.5778964313278704, - 0.20576060644798608, - 0.8369676740971085, - 1.1961908996778936, - 0.5256296058593397, - 0.9387432321088571, - 0.8691167085857773, - 0.20789896807733713, - 0.24778807649340764, - 0.35769859874230536, - 0.32444527034453075, - 0.8082139729169612, - 1.008741970759875, - 0.8902134851810352, - 0.2956679241949859, - 0.40960395446129827, - 0.4685330566772964, - 0.3231686647648351, - 0.8078731393153292, - 0.23693123177435507, - 0.3606252567638713, - 0.6878333482490296, - 0.7199529266991492, - 0.20728490205145134, - 0.5132933408599581, - 0.2380564584266797, - 0.6878492555097939, - 0.41380283208869467, - 0.6326902744619366, - 0.44723393344470064, - 0.26121157785784277, - 0.2105588447586591, - 0.2626368112677408, - 0.36660218015484725, - 0.7107535499551507, - 0.7112732760581217, - 0.26785945865150723, - 0.30022571807018433, - 1.4983297279830525, - 0.4377888456821634, - 0.3446039176657132, - 0.3693971427125268, - 0.22693692832901285, - 0.6606095163486714, - 0.7089913512547384, - 0.23745047063702152, - 0.2942128572177469, - 0.48965638445025295, - 0.45786530380478185, - 0.36050523619854075, - 0.23273615584058868, - 0.307853971791551, - 0.330387255586519, - 0.21614354770960797, - 0.6978836459744252, - 0.5931444138070214, - 0.4869074881769293, - 0.2774290505759709, - 0.5199765584086796, - 0.2739342098854992, - 0.4662540043573414, - 0.7434449439511858, - 0.5060866152437129, - 1.2704296642075181, - 0.8640625307425287, - 0.3484332109408252, - 0.22324013617829766, - 0.7450159963210014, - 0.3114287303877603, - 0.5208740552131286, - 0.7931313995044873, - 1.094439740507025, - 0.43556832510957655, - 0.4717566693956416, - 0.2662858143047447, - 0.3501851906796441, - 0.4688686583090523, - 0.6823040113120147, - 0.4183290322641556, - 0.24107958222047682, - 0.6599459309983366, - 0.2998819849185813, - 0.8648637435566121, - 0.47364679656386555, - 0.30589715271925566, - 0.22499124825458136, - 1.0717159036603754, - 0.3827608560827718, - 0.6261788811752206, - 0.9866494180323987, - 1.1376041976367157, - 0.4367985719972222, - 0.26414152498198457, - 0.29675459360905604, - 0.7764595066176162, - 0.45971929672671685, - 0.3891386856179823, - 0.6327286320257852, - 0.6103183468041512, - 1.4080085470130836, - 0.4003108715401011, - 0.626326575092404, - 0.8113040397141904, - 0.6603366861209062, - 0.4768305433320755, - 0.5867157828274909, - 0.3744697131265719, - 0.7414270355519854, - 0.7350947193721327, - 0.7803385367018848, - 0.2698254431704646, - 0.5693558212296972, - 0.3668402640266227, - 0.6430532627884307, - 0.23272540321699783, - 0.3133401152894428, - 0.5446304812262416, - 0.6955908853052183, - 0.4022251712177557, - 0.46203721667433906, - 0.3171420254971118, - 0.32956449759843537, - 0.42193170288788084, - 0.38499482757038556, - 0.7713031341546861, - 0.3516872475602967, - 0.838084063150151, - 0.8571815704316006, - 0.7440902184782, - 0.4895862472819576, - 0.7565642483773182, - 0.31966342149678906, - 0.3588709015584363, - 0.3274447884837866, - 0.3017924565122165, - 0.8162343796261621, - 0.5777284586292041, - 0.3553738015024624, - 0.26028101982656476, - 0.5982471837633953, - 0.20470385364230498, - 0.7715795716891565, - 0.25664733412934526, - 0.8697336181367745, - 0.622296574193236, - 0.6526446341940696, - 0.2861913240038754, - 0.4160769166134428, - 0.8395024471447995, - 1.074516728459507, - 0.5965725176335056, - 1.2306091290555183, - 0.9048150905806398, - 0.5058878371443809, - 0.7361678403946019, - 0.5332142700790974, - 0.2803329955464374, - 0.4104958201089752, - 0.847567921232644, - 0.471415208754419, - 0.43753106359177873, - 0.567526385601946, - 0.9342983258860392, - 0.4850553539827832, - 0.5027659074692696, - 0.9302669583923143, - 0.2254168838037099, - 0.8634235558106813, - 0.408176205566693, - 0.2961286111785741, - 1.381548130668435, - 0.2751648625017731, - 0.3496101181342335, - 0.757651106596413, - 0.6278191442513856, - 0.8301238466656633, - 0.7886172845612959, - 0.48384255307612867, - 0.3996182603856786, - 0.27205261078865334, - 0.6100332532988698, - 0.5635034890599905, - 1.0296799276107313, - 0.5219873943129762, - 0.6749659285392441, - 0.5515904753959094, - 0.8197985720017142, - 0.36413255678551243, - 1.0256843077716709, - 0.290851493878268, - 0.833187144724238, - 0.37386362554499686, - 1.1091889127239483, - 0.4003324564991696, - 0.2432163784907656, - 0.9230897342580131, - 0.27846683510529696, - 0.6464484996670011, - 0.25410226216337917, - 0.46888566407322907, - 0.34850729458196184, - 0.37586457931783723, - 0.9299287845811502, - 0.30857104701618404, - 0.31063853226193683, - 0.8492267050858618, - 0.5380017278043312, - 0.30466037352629916, - 0.7793708493488818, - 0.7718616942485464, - 0.8800306183973923, - 0.8706297152586586, - 0.740250939292865, - 0.8801426261727117, - 0.615439343267807, - 0.8853338053903973, - 0.5797841109173633, - 0.3331881481554071, - 0.2576399924569789, - 0.5819610945180718, - 1.1147141265034057, - 0.911837309886682, - 0.21945009212927635, - 0.3241550513587271, - 0.2629018683442367, - 0.7202966934775945, - 0.2998311101059486, - 0.31372656417501144, - 0.2714009616281381, - 0.3015775966659682, - 0.2236913658506151, - 1.4486541083130684, - 0.5024840406645907, - 0.4307271261380855, - 0.3511019456249469, - 0.7462870895869771, - 0.36648212310565553, - 0.26363408354241763, - 0.5849117116342937, - 0.6707945503752639, - 0.59199258917086, - 0.41386434931756155, - 0.6749191405751628, - 0.3042004044034799, - 0.5089338013963136, - 0.3819584269143087, - 1.036775789024792, - 1.061836864562248, - 0.36163477526283894, - 0.5970741568511014, - 1.0224684044349375, - 0.40950944164156855, - 1.9956869280789078, - 0.5451581943723366, - 0.22599011858305387, - 0.28162712079748814, - 0.46199474186265116, - 0.24470037709514333, - 0.4366504877979437, - 0.9969567593875002, - 0.47433569908162004, - 0.31902879029141296, - 1.0886613985647207, - 1.0912564513454555, - 0.5763847416010928, - 0.464815701797187, - -0.5408294482381625, - -0.45604185184919394, - -0.5455830060941664, - -0.21104509719846812, - -0.49709482905236113, - -0.22585452222738295, - -0.4280488061276665, - -0.5707419009329798, - -0.42771379062690684, - -0.22394255787410772, - -1.0481966087371275, - -1.2282928381204428, - -0.44000893224909016, - -0.21308352038002984, - -0.2578329300608292, - -0.2702205721515497, - -0.2229908392230683, - -1.155413514168876, - -0.7110977919592472, - -0.4237688822286549, - -0.5262958606752463, - -0.6902125877295098, - -0.5766152659245866, - -0.4742086667784537, - -0.48919325160794164, - -0.6120878913956663, - -0.4581621863999065, - -0.29284257757852156, - -0.22809714537233916, - -0.30008012381169574, - -1.2850301416949874, - -0.7888611230927379, - -0.8908045917557692, - -0.291795155182089, - -0.4456897428026389, - -0.5979022224703536, - -0.3925767186516406, - -0.28781178003573693, - -0.38785664593285346, - -0.45156921180204485, - -0.3521413318863171, - -0.373499951561969, - -0.5183364226723355, - -0.6085518497158161, - -0.6310927914560828, - -0.3109344397913909, - -0.7587417682318068, - -0.6117048245034316, - -0.4831813291666294, - -0.31105353289293936, - -0.2938111450384017, - -0.6013826912063421, - -0.5481652590524762, - -0.9083982273462775, - -0.41921787842261615, - -0.2288688328320977, - -0.29920294426542654, - -0.25249184208892683, - -0.384719172456995, - -0.44607433075745667, - -0.8914468769521039, - -0.31230058472280825, - -0.2394293330014835, - -0.5033870826799494, - -0.6597452506534363, - -0.4720473362718575, - -1.1385676371768447, - -0.5760240356723765, - -0.47617644273986715, - -0.6413087098944711, - -0.6891064261076895, - -0.7684143146299116, - -0.32395719329864997, - -0.38222658409066834, - -0.28734145365268143, - -0.5040776869253449, - -0.20777957774361389, - -0.6482203089177337, - -0.5341659322707396, - -0.3563757535175292, - -0.3154771769842043, - -1.0176208285072499, - -0.5080683969370965, - -0.38050896545778157, - -0.43629254496919223, - -0.7126376812116875, - -0.2984202151144287, - -0.3632862894658254, - -0.3191958623184186, - -0.26543286893119367, - -0.9564650745195338, - -0.21675106075431896, - -0.5331220295391766, - -0.4966765045988805, - -0.29997819434979733, - -0.5734833795439122, - -0.9034032631507279, - -0.549512159795366, - -0.23624949671722903, - -0.5039917423467485, - -0.3307962921052099, - -0.22789661288375515, - -0.2478218246045798, - -0.550444022334402, - -0.3549970501951722, - -0.3249289833251618, - -0.2719852569034738, - -0.28959808081953325, - -0.8582161792093268, - -1.0547635694363768, - -1.0082050688619077, - -0.22510926606121004, - -0.2808660580156746, - -0.22096397313004718, - -0.2388862284144205, - -0.47096576577706883, - -0.37384036852754843, - -0.49232887284285887, - -0.3742218891132017, - -1.0528762190974044, - -0.6395158724045542, - -0.40227207975815227, - -1.1055730288250394, - -0.667719296102728, - -0.3117824977473936, - -0.27343407610951004, - -0.7244421334365303, - -0.2551997886459179, - -0.7004059746255182, - -1.0564647910906617, - -0.33227796364826223, - -1.0251591574353927, - -0.3907446233175244, - -0.6745940822506199, - -0.5101988292251124, - -0.2058409181925316, - -0.37030896766160526, - -0.23777419131554375, - -0.24903807810376904, - -0.4582351097792219, - -0.6691127707325099, - -0.3058559404791133, - -0.606480539072585, - -0.9090330957745122, - -0.38695003725404886, - -0.5258026157115094, - -0.366927089456592, - -0.5461827826189812, - -0.23671299360432696, - -0.6671392247660524, - -0.8940102241187291, - -1.245970637389159, - -0.2113199178255871, - -0.3050469808067724, - -0.35379889486556254, - -0.27673385698250824, - -0.9545617421854695, - -0.6633211594575391, - -1.076549617298208, - -0.237328128993872, - -0.7791411076420433, - -0.6781554095896108, - -0.30328705712172455, - -0.5826236393583618, - -1.2934867290250633, - -0.24116151445177347, - -1.2319781895107975, - -0.916513624583707, - -0.9546500380974939, - -0.29337618882450106, - -0.23186843366579882, - -0.7982293537665728, - -0.8934635587669923, - -0.8303439820655862, - -0.6448300244814895, - -0.6300744278104505, - -0.47646920301450874, - -0.4237854416164229, - -0.3355867466010379, - -0.3335131695915488, - -0.5330380942143075, - -0.6412851297182564, - -0.21234703043651887, - -0.8201486138004948, - -0.4788546154440152, - -0.6648844166661088, - -0.7194304638534758, - -0.2996669473188828, - -0.7109430276036721, - -0.2907779804187741, - -0.5882395564508026, - -0.604509014349813, - -0.34144360257623607, - -0.6326429736512861, - -0.3206682371971302, - -0.4149485783928966, - -0.5098776349196433, - -0.312738057687458, - -0.8826780422309333, - -0.7657583907605298, - -0.4730945494754913, - -0.566614969199544, - -0.7473460576334614, - -0.7188507358443533, - -0.5010688612748853, - -0.2192453618096455, - -0.4173542861912398, - -0.762624394682709, - -0.31164637669649414, - -0.5527857900958555, - -0.5893479474590249, - -0.560241146242215, - -0.21256240747550387, - -0.20984945097189414, - -0.976353159750065, - -0.3633719213517616, - -1.2646331258851278, - -0.6019550645923789, - -0.8349105119317299, - -0.6263327286969771, - -0.8881939115961877, - -0.4018968011879927, - -0.588436464031344, - -0.5255131413200186, - -0.6235491064577943, - -0.5548745308364091, - -0.3344153679941323, - -0.6839837986304745, - -0.26939536122009056, - -0.44588121510119794, - -0.485313932156993, - -0.3147053441266654, - -0.3447690639850808, - -0.42425948773490235, - -0.6368746857704862, - -0.7570443076745386, - -1.3453048021275225, - -0.5779919824925038, - -0.8534155852292701, - -0.8255586714009041, - -0.23939991881521916, - -0.8111910186858374, - -0.6654921850439084, - -0.7589918274888436, - -0.2762055761308225, - -0.37807717054341883, - -1.0419192767012604, - -0.6285095632657347, - -0.22177205398710081, - -0.7326297394654618, - -0.5396440611332485, - -0.38068710359951635, - -0.8764036453761905, - -0.3752574855585719, - -0.5757405895809263, - -0.4831581058215938, - -0.4464895229605658, - -0.5809420752235194, - -0.7112452479430796, - -0.424922962737669, - -0.33133906375246713, - -0.274329812891702, - -0.5449365446271565, - -0.244601353933172, - -0.27432690087567024, - -0.29762989357257713, - -0.30944334000388796, - -0.4289367839196025, - -0.5577857081613212, - -0.90030267692961, - -0.6166448093512893, - -0.3906123146232961, - -0.4087456929981435, - -0.4587407464849406, - -0.36189558693590457, - -0.5232743487854815, - -0.21520459303544157, - -0.2850347912701139, - -0.4386710738765606, - -0.6653917514438257, - -0.457655081280787, - -0.21700157390916555, - -0.20297149665397624, - -0.5046802114579172, - -0.7773467501124288, - -0.5613180696644268, - -0.5503974360309747, - -0.3331490536368712, - -0.45225498681455406, - -0.8474808186051138, - -0.9377951742318713, - -0.8769410716136192, - -0.8403858645732496, - -0.9240711818121738, - -0.6176249537225077, - -0.2509193496021725, - -0.8576833189911257, - -0.30091858809440497, - -0.7669135902207821, - -0.4657725378411706, - -0.6698475643345316, - -0.3607747482587682, - -1.040042030285679, - -0.442825144725377, - -0.26504427183110735, - -0.23448580730551077, - -0.3681753144690551, - -0.2673147672051021, - -0.741424346567405, - -0.48531019209685006, - -0.4712821639134847, - -0.217445156763336, - -1.321645743549355, - -0.43308604363608755, - -0.4777114306813022, - -0.9340244846784727, - -0.6047300955961723, - -0.8596598303282811, - -0.8287837593827051, - -0.23870304474730977, - -0.8756574298270264, - -0.3984478195524307, - -0.8412903582189284, - -0.47065184352342687, - -0.3142473747940003, - -0.8615276626845476, - -0.24055079952702108, - -0.35552680812532744, - -0.32801192321669476, - -0.5640379077621963, - -0.3653161470500674, - -0.2115777682869174, - -0.4862829719050994, - -0.8148397276441456, - -0.4452036189712971, - -0.6952598949926917, - -0.4649440036455148, - -0.5997568275505806, - -0.4670078625997723, - -0.9823301913786967, - -0.3846479350165762, - -0.49536881339028604, - -0.8639744048824797, - -1.4774526781784538, - -0.7156341755693922, - -0.8093856241735209, - -0.5977852884799321, - -0.6567663803672231, - -0.22648421280454567, - -0.39198910642671614, - -0.36440786319928026, - -0.6449608242419067, - -0.380385716330645, - -0.6511153646460348, - -0.7396119221460706, - -0.40627694714943746, - -0.6904134235709265, - -0.9670917356668344, - -0.3802191359527102, - -0.34530478644851026, - -0.9796003617249744, - -0.49886375787312226, - -0.37442115345560545, - -0.411150230085362, - -0.797603193563481, - -0.42770264810884284, - -0.5343000105619126, - -0.2785783752962981, - -1.2818491153783163, - -0.4754660543321748, - -0.36432532773409676, - -0.7589103712872918, - -0.2410503867514095, - -0.7202753171454854, - -0.7192083957565272, - -0.44217472032326877, - -0.2896983296151617, - -1.3007450297687988, - -0.9322973116193422, - -0.8251203719727379, - -1.0457044573555139, - -0.30444824692000755, - -0.2835072453039032, - -0.3083598409583672, - -0.26369717424145034, - -0.23156278754735013, - -0.7600510426241852, - -0.3752332319973472, - -0.5749069476063188, - -0.26644579326473705, - -0.6143220417517447, - -0.632724618254878, - -0.9591636822834401, - -0.3156092356247571, - -0.36357376368195726, - -1.5127870260983063, - -0.3064838022941795, - -0.3838081673240108, - -0.3095661778335, - -0.9204433154183151, - -0.388522734809646, - -0.3941712389147528, - -0.8360807462606086, - -0.8191308586380911, - -0.4527424668054917, - -0.8520978919267658, - -0.5619878543316896, - -0.23638579109165223, - -0.33423425883543256, - -0.2105913163196201, - -0.5683957212090525, - -1.1077257565007086, - -0.6146355147489587, - -0.4542781416069577, - -0.7024180929554568, - -0.6589687798241961, - -0.22645817055878836, - -0.20946299900384957, - -0.6929104250493654, - -0.8163168634368114, - -1.1110108455032048, - -0.5158645992980698, - -0.4847149017207668, - -0.43367028443444416, - -0.7959801325628257, - -1.2236901741688657, - -0.4171544416208314, - -0.20927994937132852, - -1.0248930499020965, - -0.3476088225601031, - -0.3061307300884403, - -0.47195027361860215, - -0.3246867716784313, - -0.8516366330765569, - -0.3047971749295124, - -0.7318310309226493, - -0.7634725938000214, - -0.32299659490204274, - -0.8334933218730198, - -0.20718854670971995, - -0.33142516826255664, - -0.22884595572818292, - -0.31474669537646466, - -0.4742483280210875, - -0.8191720710254512, - -0.6795987242717813, - -0.5916088066725763, - -0.32054147521207255, - -0.8018069038679584, - -0.22039880030071016, - -0.6231813165661775, - -0.23868157126283693, - -0.4717710436079827, - -0.35743893577530567, - -0.3633873474408522, - -0.7767452287921047, - -0.3966514011618025, - -0.7884185613619231, - -0.7924416861175206, - -0.3667107986107969, - -0.7799682089027363, - -0.36401220297826353, - -0.6991708075402606, - -0.45659419170086574, - -0.4139813463905407, - -0.6984533041957992, - -0.31907372684477636, - -0.4542797359141556, - -0.6741132294507625, - -0.2682650378171883, - -0.2836601182868475, - -0.30249053039198825, - -0.22965095109308253, - -0.26261548265937007, - -0.03817104779142484, - -0.2910509490528511, - -0.3156275783267642, - 0.19601813440835336, - -0.49125642719436113, - 0.5410586987770436, - -0.5397130781829862, - 0.608969985709463, - -0.11706182429390423, - -0.8777262637798143, - -0.021860703880180736, - 0.008824672789006671, - 0.9208445168561946, - -0.1182624601316533, - -0.017809055324736877, - -0.41698028446835256, - 0.6224917253963723, - -0.38463760292900095, - -1.1442058053898065, - 0.021328314422519087, - -0.16142624088766142, - -0.6498303822232933, - -0.24006323913494176, - 0.910173412000089, - -0.04483764379623041, - 1.916955724315686, - -0.21217845490697837, - 0.2504817256753592, - -0.5177492357083789, - -0.6370559825098843, - 0.48191231787977135, - 1.1007570842708718, - -0.2818412775048299, - -0.3214451121282409, - 0.1178172030846644, - -0.6212047256206287, - -0.13426358593957116, - 0.7141142891182669, - -0.30970760228543076, - 1.0853546521177935, - -0.11446658557014482, - -0.04895504986473096, - 0.21356602761265758, - 0.733944315490934, - -0.8685801745259494, - -0.28789931586113227, - -0.05208227461311188, - 0.5627668520813549, - 0.221755685823175, - 0.21908774612039103, - 0.1127953490779814, - -0.3194984644507552, - 0.19756667287034382, - -0.44237855408258064, - -0.6085212578817282, - 0.6146275024146, - 0.1757562758187039, - -0.09605233482320327, - -0.4746348588702133, - -0.0475294323261065, - 0.5845852915459844, - -0.5480532605086048, - 0.32446750622421533, - 0.6005201742574101, - -0.4428662709465853, - 0.41125730861603094, - 0.13890238075974506, - -0.008752482709014488, - -0.3652699389580146, - 0.53771733051436, - -0.20117573386377396, - 0.38317699822720347, - -0.13842346807553543, - -0.1552389548686607, - -0.18137039814846773, - 0.08369713168185684, - -1.224238941557559, - -1.1208140952086731, - 0.39404102712221456, - 0.2947385482041874, - 0.0505590378266428, - -8.000563270374798E-4, - -0.369492755402888, - 0.11393939659158392, - 0.31169538742734426, - -0.5127273559280063, - 0.5058253825032447, - 0.29382041425636946, - 0.2484589332526816, - 0.7088310956183603, - 0.045364052662200394, - 0.2567238548196754, - -0.19013916136350348, - 0.2173448706978465, - 0.4493990762080962, - 0.36953785501688863, - 0.04295387947382388, - -0.5105321146917556, - -0.7585056105330047, - 0.2187767457317859, - -0.7558792889447961, - -0.20853420928905422, - 0.055710129187102615, - -0.087519217117483, - 0.05479306158156762, - 0.9611609696001119, - 0.8391163091133917, - 0.2751685677169972, - -0.4452512057820674, - 0.05438323501053352, - 0.4870657675227263, - -0.6748371756372947, - -0.27986284505380227, - 0.41395947560987406, - -0.3230528784204731, - 0.18225618462103568, - 0.6868860322460456, - 0.31778191483568125, - -0.4827812755855378, - 1.253549263627396, - 0.8913086866182066, - 0.5224474199125826, - 0.33061686111734484, - 0.54707370683367, - 0.2907316753133328, - 0.100878894591145, - -0.33146087585205464, - 0.5336365175266338, - 0.6301612193919673, - 0.22383519672313976, - -0.7604675471954038, - -0.3843239043099286, - 0.10451235624592613, - -0.47751320526431945, - -0.6361948428387786, - 1.029903969933344, - -0.12248791688126522, - -0.101882913245582, - -0.2428008812015598, - -0.09474381367380463, - 0.8392758547244135, - -0.5563449313429639, - 0.2294097694107958, - 0.14118767908883567, - -0.1656972725985513, - 0.17033505750104475, - 0.08809985529380845, - 0.2858914140359182, - -0.04429990789790772, - -0.020507852862988594, - 0.15664011785970278, - -0.10517489099064434, - 0.32618380677136816, - 0.8802221362068096, - -0.5558938608294055, - 0.5701074252561188, - -0.10909013894575904, - -0.3732620442941795, - 0.5161242325481133, - -0.040037102401993895, - -0.07265373097988863, - 0.2750359221513548, - -0.11592142694768622, - -0.8614626128107978, - 0.5327897030857511, - 0.1675213750323001, - 0.304842448798015, - 0.7126541748120478, - -0.9798054697818567, - 0.20784289127010447, - 0.28971215426085983, - -1.0070598356211924, - 0.6736335084463706, - -0.08944244284353171, - 0.9252296539016819, - 0.5540218687514763, - 0.3097921658718703, - -0.8096872186523328, - -0.6203829145279515, - -0.8065168504324293, - 0.3117674607380043, - 0.5598382089478117, - -0.8040433243094871, - 0.4886479099894751, - 0.07903444181102365, - -0.44679272618096827, - 0.853697292554005, - -0.9629619934395436, - 0.4999766997733485, - 0.28783331383367167, - -0.1569412394891151, - -0.2683882442846077, - -0.030938412464069726, - -0.24061609133526302, - 0.11947995137654913, - 1.0363179005481333, - 0.1735504598213155, - 0.17714073122547258, - 0.23656218831579764, - 0.34351562766517224, - 0.05653900850848084, - 0.18191859545078123, - 0.5753193268840996, - 0.5687990689788226, - -0.08017778053414513, - 0.5527975193669029, - -0.2269996668136193, - -0.905762126340816, - -0.24899708840033416, - -0.2794720716350875, - -0.873784375094944, - -0.1826740903266034, - -0.12542440461791468, - 0.7391134996587577, - 0.45099505353232594, - 0.4436018352229829, - -0.3167483181654096, - -0.24311946670243967, - 0.07613835896436134, - -0.8674872313278186, - 0.1393183234436533, - -0.600246189150925, - 0.7514537190241705, - -0.14222391825214883, - 1.2220702861107229, - 0.5918991777389218, - -0.5301133712480979, - -0.39152021653138397, - 0.33611618054259046, - 0.24659278607007198, - -0.0178354944345779, - -0.5059749628948966, - 0.8642546013706397, - -0.1932725119920872, - 0.3472243085141609, - 0.5350222923138556, - -0.34070640895203, - 0.36466645738625203, - 0.2214559971759717, - 0.6144739122526096, - -0.2371301068944, - 1.3395721518620958, - 0.5629099215708365, - 0.16044573315716223, - 0.14505068075048894, - 0.11424543358386488, - -0.4440228505634782, - -0.41394691215549184, - -0.909393459090444, - -0.06880368367419264, - 0.3662348591363356, - -0.3825304297558582, - -0.398721754458867, - 0.2903069249832717, - 0.3332627977440068, - 0.11185448986985243, - -0.8009236432127675, - -1.0531419799880342, - -0.6059929402954768, - 0.4286477642439754, - 0.5610051793406894, - -0.2569330299138732, - 0.7444427150580065, - 0.6431115222071787, - -0.0983380875247111, - -0.3549537071497913, - -0.340874803622953, - -0.833975806755661, - -0.189187347060581, - -0.5264029235349389, - 1.192260509372475, - 0.15498638217778035, - 0.6780135121982845, - 0.5137341527330768, - 0.30588680541756136, - 0.2689330190697315, - -0.8064197769485445, - -0.061806227933282075, - 0.016817412882300688, - 0.026838613378250917, - -0.24057046228408813, - 0.1307083174300678, - -0.13712087070489712, - -0.45454608453036355, - 0.13563998758513643, - -0.05484848609769456, - 0.8933853427948175, - -0.4489860992691959, - -0.1935608022276255, - 0.6302653658216816, - -0.312039777401686, - -0.3510030644460262, - 0.5195294804995814, - 0.7117962653251989, - 0.1655916901248009, - 0.8115164257624897, - -0.23591850002953832, - 0.09643744822402422, - 0.36869527512767114, - 0.3595388534703552, - 0.8131016731589593, - 0.09381087512966135, - -0.04451759477035232, - -0.30349317548974575, - -0.49160705757420536, - -0.009060640747065604, - -0.2460851904001795, - -0.11733439690360163, - 0.48209147042072614, - -0.3162894819050262, - -0.7390548067429628, - 0.32795078762097557, - 0.7461068827706027, - 0.5959766829483254, - -0.486789079260241, - 0.32905515634574634, - 0.148721430935003, - -0.6829090187543206, - 0.7885271565574424, - -0.5308354223664568, - 0.03992348471004486, - 0.7085920717357378, - 0.8128839179185308, - 0.615475270496968, - 0.329026071997751, - 1.2686701757200146E-4, - -0.37877482833705667, - 0.1362661321194172, - 0.35672553830063813, - 0.3492533118204576, - 0.1432595017909271, - 0.06890343823145847, - -0.9513338107020919, - -0.059664606176056616, - -0.6946799721375945, - 0.16778981987324026, - 0.49455857091123767, - -0.32495872386365154, - -0.29112497299257467, - 0.8782352339946882, - -0.3244205195643498, - 0.017713177788795897, - -0.03085715618394564, - -0.43516059699345067, - -0.36799803899418626, - -0.6156169363578035, - 0.21016517960804182, - -0.14952088955864098, - -0.05122627645992484, - -0.5594497143659528, - 0.3758455650557043, - -0.4830771823897407, - 0.2131928557261785, - 0.3445167678840139, - 0.5774123461167114, - -0.007257279278375885, - -0.34191194909630496, - -0.16499390795512076, - -0.3705836454673454, - 0.6243109463412245, - -0.45209099307016554, - 0.3164540485850262, - 0.3245627227484264, - 1.0481323018927666, - 0.7092340485243148, - -0.1375491124586456, - -0.1305489300241356, - 0.46724062979299885, - -0.8246821201041895, - -1.2598233317194054, - 0.6456528946617398, - -0.8497798399421971, - -0.8266914575764185, - 0.17474565487788207, - -0.19284887071061724, - 0.15819761936814353, - 0.23723964654346513, - -0.6651315799564171, - -0.8947634985471487, - 0.1382876071428532, - 0.04978140546108593, - 0.15260024466366087, - -0.6331661806966886, - 0.8137761574033872, - -0.5297319746746058, - -1.0483486178801638, - 0.35835243961356805, - 0.5774782685572899, - 0.3224913546759679, - -0.9446985534911483, - -0.001690101901343399, - -0.13869034749118447, - 0.38418925905219176, - -0.47552641640663296, - 0.22564546717023418, - 0.336484323680889, - -0.04629780640292501, - 0.15291578993094154, - -0.28823215858427037, - -0.5639122256227689, - 0.07174948428048285, - 0.04727502617393123, - -0.00821160725337061, - -0.10759582015904459, - -0.4704640299100564, - -0.7383787732206255, - 0.3824231712567961, - -0.4614093747761056, - 0.644279323421874, - -0.20001323851299618, - 0.10839822322190326, - -0.21868872210079995, - -0.20264077483923604, - 0.6385934549041254, - 0.5266358288225826, - -0.17832825319684545, - 0.4739337877399701, - 0.3167887730531193, - 0.24098690856203714, - -0.10379590423138949, - 0.2772861559379589, - 0.4264687871961075, - -0.47941562260131504, - -0.7122572149413191, - -0.28647631142681784, - 0.5039483158694638, - -0.34647073127371236, - -0.39538414318506054, - -1.055381314750056, - -0.3994151112913603, - 0.2917674837156484, - -0.34008985010127885, - 0.22101150755696317, - -1.3004108690769989, - 0.8749716997835447, - -0.6058168293619467, - -0.49859243371062323, - -0.24312237864259, - 0.45856538593437446, - 0.264764103777927, - -0.020894653066722665, - 0.29150008500557884, - -0.9250996929816823, - 0.19071709489567962, - -0.06735414085125764, - -0.5529837044971846, - 0.7262030232826059, - 0.21217266104873791, - 0.2670593064228071, - 1.0627447969084847, - 0.22174601232246952, - 0.5379097949374008, - -0.2921976288255095, - 0.9145077299160117, - -0.10706414794135831, - -0.14841188049270992, - 0.6292296732416409, - -0.22943895588947247, - -0.7918497981031826, - 0.5485365814234074, - 0.1347837745669405, - 0.3456485140910097, - -0.23828007093854392, - 0.38686059506659837, - -0.2641426756014251, - -0.22678243538445117, - -0.5624103327958901, - 0.18226778593655896, - 0.6791369074717434, - 0.3133412574177579, - 0.7237787315122619, - -0.3350410211224158, - 0.3238470393040141, - 0.4103117778782601, - 0.33461246894533203, - -0.5600334870067301, - 0.030847104560746123, - -0.4415108555130807, - -0.037632801284491486, - 0.1922114725291312, - -0.2516527394591881, - -0.05886304619864766, - 0.5174297693130024, - -0.2533846221013904, - 0.44733792990299875, - 0.06554938229422065, - 0.06796117502011043, - -0.09711847475866846, - 0.4175158471420206, - 0.6055418304970908, - -0.0435842114174724, - 0.057200511472983565, - -0.08304893646145155, - -0.03037276850711745, - 0.08437785580751614, - 0.3886857201297951, - 0.5616145212579788, - 0.6382773577148229, - 0.38500242014698055, - -0.37517786538833486, - 0.23166180614212112, - -0.3484255443419305, - -1.0549073907619124, - 0.7077660847173138, - -0.5133571814925163, - -0.04312833745759847, - -0.024439861012468804, - -0.4312867502143171, - 0.4345549584476139, - 0.2259487388531965, - 0.19245313638569694, - -0.18003567973544465, - -0.04090884449174077, - 0.08244453963185396, - 0.08381783401997672, - 0.5483398628616845, - -0.9185536421099973, - -0.6572149649523289, - 0.2781839772596736, - -0.7694935715841588, - 0.3210579559922107, - 0.3409525417901707, - 0.1755988189666986, - 0.020600958710273676, - 0.2135383951852806, - -0.06678689714235378, - -0.35271217219341755, - 0.6659824304458942, - 0.8051332155781753, - -0.5979555082324945, - -0.03528188501271454, - -0.08704869459554272, - 3.693566552633058E-4, - 0.11497945514559495, - 0.09603843921010606, - -0.8173838458734517, - -0.252384942865219, - -0.12987190679280097, - 0.06775113558928826, - -0.049553534043273166, - 0.4129332299916554, - 0.20773587011312442, - 0.4952810880022795, - -0.2936352394652572, - 1.021833210182474, - 0.3766576558473247, - 0.3074419159455055, - -0.1289542585840997, - -0.6243085553690129, - -0.5329564369695358, - -0.5609775472705257, - -0.5403527236297802, - 0.6816188753124867, - -0.30092692636196594, - -0.47139482338401495, - -0.0571506556647281, - 1.188476224971764, - -0.17568465789340726, - -0.9104961360692826, - -0.10135253938415147, - -0.2845012693214476, - -0.39891197482805135, - -0.32480442265157383, - -0.2928767252708514, - -0.16958747032269314, - 0.4108591355731355, - -0.19821165380721129, - 0.26002856676567776, - -0.14267028144975993, - 0.11359204545606412, - -0.2014606644043016, - 0.9960153534044054, - -0.5385379375125751, - -0.19061986450436672, - -1.103639303353586, - 0.17235325885340586, - 0.042887377317216986, - -0.1551503975597968, - 0.6460299863397363, - -0.33034561412264574, - -0.28867003454635026, - -0.4158779125051136, - -0.005406790335179987, - 0.5274359079871412, - -0.8689980726127233, - -0.14116036196713283, - 0.21069291624110925, - -0.06482082352234948, - 0.5369754754044417, - 0.30275805051276683, - -0.12040700303206392, - 0.36184634298574503, - -0.11345536013357072, - 0.2184218177582618, - 0.36471661119571513, - 0.32695833608343866, - 0.3604379332664702, - -0.020522661682516697, - -0.1828189279227813, - 0.2736713975589797, - 0.33318167330091364, - -0.28917566239938913, - 0.08233130210236768, - -0.03141925140479963, - -0.7736884089440618, - 0.12039014811347266, - -0.46294815432578185, - -0.15091328462561907, - -0.6577708780371454, - 0.3494826157492691, - -0.010518576372731141, - 0.17799195318145133, - -0.5840912028674532, - -0.1160866642855159, - 0.37721958953498885, - -0.3423664421790033, - -0.4546936199799205, - -1.036884270104919, - 1.0172544278073246, - -0.4338042019445904, - -0.599664484512815, - -0.14054060485992034, - 0.3029779550531127, - 0.41795506547472416, - -0.5829402517203184, - -0.5154892343592423, - 0.08707000723953734, - -0.268071931121387, - 0.19937653007202183, - -0.5148433430383687, - 0.559325855490158, - 0.03379565109458052, - -0.14647001861680536, - 0.5018823996322521, - -0.03137403722548306, - 0.2519118335580802, - -0.2504693556557634, - 0.6947272157426265, - -0.15225296056600404, - 0.6834712947259622, - 0.7541381306212789, - 0.5711953304822419, - -0.6305190677468379, - -0.44460558692767893, - -0.3242415904261663, - -0.304799209817425, - 0.2619219314947768, - 0.37679433444259885, - 0.6115097311337081, - -0.6004269051452832, - -0.3468567066048162, - 0.5012246308582128, - -0.4901051567271819, - 0.559213576450334, - -1.027949013439089, - 0.00229216671027465, - 1.6682172943055174, - -0.0434116341076329, - -0.3505899363929725, - -0.08658288048121385, - 0.45590170401144287, - -0.6056305584850532, - -0.2296487755985895, - 0.7473513831313823, - 1.1065236004060377, - -0.8896046855633738, - 0.018500892539229943, - -0.3305880183680724, - 0.06751232711072962, - -0.032456157701858536, - 9.261424101317552E-4, - 0.05411149832171211, - 0.1669624780111665, - 0.14532960616456844, - 0.21882840467295414, - 0.39959856529201815, - 0.3262666155874591, - -0.29053870216155925, - 0.9344080452313128, - 0.131775994355041, - -0.1779196137676346, - 0.031263563055388, - -0.804638968557037, - 0.6319840332958934, - -0.36747401535996005, - 0.09147870614696182, - 0.53170538872953, - 0.41081994233128577, - -0.05635034005851303, - 0.05935637095985267, - 0.20858753597812257, - 1.2250389848196355, - -0.17009817103614022, - -0.8876333052361831, - 0.03420387427752622, - 0.11853390694679941, - -0.5736675846276115, - -0.16764836669332567, - 0.002852756263559731, - 0.24737866725751045, - -0.07845496223043197, - 0.5598252269804503, - -1.2568775727652868, - 0.5721015901702079, - -0.46800205815959706, - -0.9396662633368602, - -0.0847515103562564, - -0.4470411896209145, - -0.17290933841494457, - 0.4529627999886324, - -0.41910041872642345, - 0.5397418037442943, - 0.5123435761371071, - 0.35466665231234934, - 0.4922003289826917, - 0.31605396533623453, - -0.0014109613421838798, - 0.16693265407391233, - -0.6818476368624842, - -0.4162358644723245, - -0.3705114431793343, - 0.18377732707237837, - 0.2511326027934921, - -0.719742190851404, - -0.9745380615670967, - -0.3233612019250429, - 0.40358010814072787, - -0.8019338709140069, - 0.0662507609978993, - -0.3795699271781252, - -0.8584540755340972, - 0.4375153728976843, - 0.4182309921234334, - 0.8086244878667582, - -0.23252689715984884, - 0.710684157526248, - 0.12661005783806706, - -0.2955742342166093, - 0.32910255573980857, - -0.10825151437163451, - -0.7871962776757813, - 0.3506443603817044, - 0.13905997052254315, - 0.2901598736441624, - 0.08996281774743743, - 0.08385108896196972, - 0.12274250144874, - 0.5589261645346796, - -0.016633446177650953, - -0.32887102738933843, - -0.5475643188196259, - 1.17876734006634, - -0.25060579636579416, - 0.14564177479911386, - -0.72129627999251, - 0.28875017803293784, - -0.13848068201294053, - 0.13742958893142054, - 9.553132214683523E-4, - -0.2831289576638589, - -0.6605564846775537, - 0.12755512683785786, - -0.6717412431316867, - -0.25970505966125434, - 0.6692555512265299, - -0.7757413428222353, - 0.06405055287731817, - -0.42230995231942287, - -0.47229464379098846, - 1.0023128932804084, - -0.5134605114939613, - 0.8288705857042545, - 0.21864923447600912, - 0.323682636687858, - -0.713547803621029, - -0.22065559077861813, - -0.32674471286924234, - -0.18289562700943604, - 0.5457617634326197, - -1.3504247638544553, - 0.5304517397158799, - 0.32654882936972734, - 0.2331439199477361, - -0.4518046546894535, - 0.14354698972790744, - -1.1232179495726693, - -0.7551308690949894, - -0.6851343208163893, - 0.03358291490290455, - 1.0549765316547484, - -0.026191423866340807, - -0.40737766514949086, - -0.37280172484639057, - -0.7575386803515212, - -0.5656585532520405, - 0.38862651939906045, - 0.39447003635520983, - 0.11714556320619983, - -0.027844086175857694, - 0.7980464583533835, - -0.8079538950782431, - 0.4709768930371605, - -0.5198694764439922, - -0.007593198385661972, - -0.11576653170617197, - 1.0256338496905335, - -0.03751276093641733, - 0.8546934445281865, - 0.12743976702170537, - -0.6720519260254065, - -0.642699917000843, - 0.45928188216205273, - -0.03641885426051253, - -1.1727962187843344, - 0.5178970156616434, - -0.7555427235483954, - -0.14568634462229257, - -1.0037206040789477, - 0.32979649302857744, - -0.3291044931854076, - 0.3705623430250672, - 1.0010534478116184, - 0.7664569105449525, - 1.1167627987631852, - 0.24500978262160839, - -0.8395121482778768, - 0.4592256025270221, - 0.3127827187121016, - 0.3111966623072532, - 0.08837040135229575, - 0.33598371263951343, - -0.44931400941748556, - 0.6776257263579172, - -0.7366525101878583, - -0.4657539110733632, - 0.9374070652280783, - -0.14331150867302903, - -1.0863974283259246, - -0.11654768670560436, - 0.23168836101177973, - -0.3252827272669917, - -1.5892741553138794, - -0.7413981966809062, - -0.5011447522752318, - 0.03550199542811674, - 0.4828601821235981, - -0.06275672814906817, - -0.6405741919447273, - -0.732480151356652, - 0.05825027386686761, - 0.35365731221996416, - -0.3617854427235135, - -0.263690072825186, - 0.15024454547135874, - -0.10378940359470748, - -0.17772004968202973, - -0.161962804644436, - 0.3942349296576306, - 0.0276823505522331, - 0.32110890120971014, - -0.7864802177811314, - -0.7623396895396773, - 0.6407865389911019, - -0.21373012232009, - 0.17242668378715417, - 0.2472587102669878, - 0.6618258616258281, - -0.2930933544799525, - 0.41299795694290103, - 0.7118147576318926, - -0.026132312998063813, - -0.2541225161074079, - 0.6686519749269144, - -0.13354705496980412, - 0.06768669821775283, - 0.2898314054429277, - -0.6655425490555952, - -0.30307016167300893, - -0.8715816056841393, - -0.26965904452801004, - -0.6313760878634979, - -0.5199414875634343, - 0.22112219139956374, - -0.5194644440312928, - -0.0016312506140538693, - 0.18829899686857554, - -0.2477055933828424, - -0.9013683035656659, - 0.8962039543913566, - -0.3792821355754274, - 0.3022732361898666, - 0.2809278642772571, - 0.052871599835034144, - 0.29057270849636935, - 0.5377715162979552, - -0.05749076574962327, - 0.3444699839323082, - -0.05381482436564679, - 0.0672206868771642, - -0.8446581226232337, - 0.554632540352178, - -0.40173964572975535, - -0.3866892601776155, - -0.018927459322024102, - 0.6104550285766291, - -0.11777215691152854, - 0.23436565255305544, - -0.20760513909979675, - -0.6762305907659607, - 0.5857470868464575, - -0.5707688163493594, - -0.4409394605853171, - -0.19408421076233803, - -0.14106043360745207, - -0.10598005799884558, - 0.44096327105320926, - 0.09309029185301616, - 0.3730583360241077, - -0.25454979359480906, - -0.23310574405331488, - -0.7626124662482641, - -0.048824367882240705, - 0.06506603610130296, - -0.25512000919444533, - -0.03817696929526814, - -0.3707018475647308, - 0.43266381427319023, - -0.23088920719234635, - -0.24884935596277397, - -0.7947528728694675, - 0.08621262209211894, - 0.49750002259864634, - -0.6269213306122807, - 0.4635420028674318, - -0.6346328664808236, - -0.30419560749594127, - 0.010698776856225568, - 0.02189083091299843, - -0.2224512011147649, - -0.8909737157889422, - -0.06770397385050334, - 1.3552015305543985, - -0.7111556769352063, - 1.4798608391662753, - -0.3234976434527399, - -0.4229849485534559, - -0.27124701198068835, - -0.2106943250335011, - 0.4472771354370638, - 0.4557564728496606, - 0.48356182214543947, - -0.022110225386464805, - 0.6698263121857896, - -0.3385361364221551, - -0.45094331679734123, - -0.34196922742190106, - 0.28746925708069093, - 0.04565359425672195, - -0.33366711218713285, - 0.5889469400504893, - -0.3504814470677913, - 0.38447181854654006, - -0.5565575113186031, - -0.24920477864744162, - 0.5861957285274227, - 0.29444328340425857, - -0.07857564015945981, - 1.013709324389851, - -0.25792883735670663, - 0.46547803104711893, - -0.25176077418874515, - 0.07306176786118729, - 0.8337940709148954, - -0.20624371065746014, - 0.039734878125337984, - 0.01818964606616424, - 0.86600314343988, - 0.09460900825971406, - 0.4092813305629706, - -0.11767184629301881, - -0.2509325013104455, - 0.022141315220243433, - -0.48264716882915226, - 0.1350179909155875, - 0.39447303802249056, - -8.765488944559773E-4, - -0.6837300940018703, - -0.4577023965749626, - -0.3870946891243373, - -0.3184319483191667, - 0.121664676000852, - -0.23645394743843842, - 0.13760503281725997, - 0.42904490961223485, - -0.14796644894783786, - -0.007430583414494881, - 0.12288843619965975, - 0.6646436424175204, - -0.8813328913293358, - -0.07519941500887982, - -0.7588950442195134, - 0.29686757257444873, - -0.6695775576159163, - 0.3141821991863775, - -0.35787537462139457, - -0.2785086318225875, - -0.056621320409022416, - 0.24355423552662317, - -0.40656035772321697, - 0.17599292241738956, - 0.4365825197878952, - -0.30846694862376395, - 0.3160019769976463, - 0.4475176492714073, - 0.598427164694399, - 0.9422734905573112, - 0.191292921591815, - 0.9935015901955127, - -0.7395842373611574, - 0.05158076765181148, - -0.1613244040464165, - 0.42807006755068366, - 0.47079396087505704, - -0.20893258231150677, - 0.6542001716368617, - -1.1840067269932455, - 0.028075098520681255, - -0.0660144195412645, - -0.47943198455104247, - 0.5244698496232381, - 0.2275527280364697, - 0.06831769925604353, - 0.24462743217934185, - 0.45890108027926185, - -0.4582404140768472, - -0.4040184926575437, - 1.439182751224251, - 0.5956008221502718, - 0.30803204550469804, - 0.19875301933882367, - 0.6276265705754281, - -0.4307947318461316, - 0.2693442017585369, - 0.31071356522436927, - 0.5400030819859845, - -0.20414455844894605, - -0.345380798703284, - 0.9169481926411673, - -0.3305760634651498, - -0.8858987628845113, - 0.7238698485631346, - -0.1798896193525728, - 0.754860034785688, - -0.18068891326413794, - -0.26697871963629055, - -0.286493124526174, - -0.6326232137998018, - -0.20027478629097933, - -0.1549409363451169, - 0.04009391252866989, - -0.6089310861396873, - -0.588055050224599, - -0.5068951560040066, - 0.10005214330952684, - -0.25298200404077453, - 0.2587101268316333, - 0.380233736485277, - -0.5247816580205462, - -0.06886268008993496, - -0.5409619284818575, - 0.7207508335541457, - 0.6893377762431682, - 0.4098674230175342, - 0.09328422628285489, - -0.2345830723008188, - -0.200640691156873, - 0.3746086120537716, - 0.649074418633649, - 0.10774228206649844, - 0.26186532423585485, - -0.3300303457913025, - 0.4424500726815029, - 0.6475588569433618, - -0.21313423374234283, - 0.8783062917441551, - 1.0414805215105247, - 0.15958709865128243, - 0.19096042755647344, - -0.3179380539253038, - -0.18314344426433218, - 0.3213111298126417, - 0.3725986667276611, - 1.0288417530279548, - 0.9320899473064722, - -0.6251906660796055, - -0.9257515126962341, - 0.1410768722599302, - -0.055292534030485896, - -0.06628744024530867, - -0.182523789904703, - -0.5525142599056476, - 0.2287880596030263, - -1.0743695785726863, - -0.0066535673918458604, - 1.0162509718242, - 0.056561567516317975, - 0.042340887355571656, - 0.2390748590223536, - 0.6096658490871495, - 0.020905068365038658, - 0.22305203431988238, - 0.07541298457180473, - 0.24819055688159594, - 0.24544998793754547, - 0.8923175571790795, - 0.5436868165988735, - -0.10315820299471846, - 0.12975629660673246, - 0.39931212240959074, - -0.887178848913508, - 0.4337983388728956, - -0.2774491562078079, - 1.1227972090598017, - 0.8192791847678846, - -0.5074871365814763, - -0.6054186153203269, - -0.20108475733858255, - 0.14238330756618792, - 0.4643992356402479, - -0.6906702525955049, - -0.6158923745989063, - -0.4500430000058145, - -0.9047479129351941, - 0.0741173914086573, - 0.4946021251827052, - -0.31930015047040067, - 0.39660356773491756, - -0.8423776993716284, - -0.49016896857792636, - 0.7087978209801762, - -0.2450804454562255, - 0.5282941372385471, - 0.3440081267367188, - 0.27826327948581914, - -0.20605281254871718, - -0.3049272328702357, - 0.7420212455586478, - -0.7223025899188925, - -0.160411054190388, - 0.011469294837418905, - 0.5863979219825516, - -0.5659346843608578, - -0.17316499358505888, - 0.21284939858296448, - -0.31885388467832076, - -0.3418886655086353, - 1.1000693937860984, - -0.2250275833920788, - 0.22445260489274912, - 0.16122622017976357, - 0.07706005230611986, - -0.25744552970185997, - -0.12943165145971305, - 0.24496352816683076, - -0.6399059603680483, - 0.7123327155507104, - -0.68106303085003, - 0.748259378724428, - -0.7633099907965363, - 0.32537310789434704, - -0.007165184889189364, - -1.2356305740951892, - 0.8711717843831607, - 0.4493356504276116, - 0.07157685558446075, - 0.9714793064801456, - -0.15256196626804278, - -0.34269254623744233, - -0.03098856557803488, - 0.7846926340193595, - -0.5009210843603172, - -0.015734448933246624, - 0.6652043003776361, - 0.14861372727208372, - 0.7297362769878726, - -0.71830873086002, - 0.5185846951994068, - -0.11595748845655245, - 0.8290104081869456, - 0.478673933394981, - -0.40066308592273475, - -0.06277951776713955, - -0.5079011396682633, - -0.3258207155495142, - 0.4542299377252704, - -0.30737640747104666, - -0.320301804729313, - -0.0025376580806470575, - -0.5110608289529966, - -0.2692593702719417, - -0.018786870485836115, - 0.8138787026566151, - -0.23908008246031054, - 0.26404924219331405, - -0.6053709414030928, - -0.19075419066814456, - 0.4851354109941027, - 0.7337159160571566, - -0.21711526559427408, - -0.05237571313803025, - -0.5092373913769414, - 0.6383272035836157, - 0.4311677864004631, - 0.338799662459676, - 0.8600543593936448, - 0.5906279174529252, - 0.30174545204894687, - 0.042411240072264954, - -0.6241193920531022, - 0.1832250959172181, - -0.7043142722887967, - 1.1439049615902042, - -0.1784258171077415, - -0.22823553009774603, - -0.264759452881655, - 0.8214484785248662, - -0.7005898240363909, - -0.17966430165379535, - 0.16691674944159732, - 0.28820836603216116, - 0.5847339194116028, - -0.16746185188166013, - 0.427021281018509, - -0.230242258003711, - -0.822225729672262, - 0.14544432089553874, - -0.36992573457476446, - -0.05826545884937925, - -0.6072942263684806, - 0.13486529376207546, - -0.1571240046052996, - 0.3304450462991217, - 0.11099354280624879, - 0.5796005258934182, - -0.2458709659855075, - 0.6271986904010844, - -0.478590779363801, - 0.03078424772301749, - -0.0819724209169479, - -0.4675125543460988, - 0.056275141425626465, - -0.12347611374161385, - 0.27499201823047176, - -0.313472965496322, - -0.4748833558466236, - 0.038003676693877574, - -0.026884677628464367, - 0.16640028991113723, - -0.4138947844670019, - -0.16548231747154088, - 0.2466390911281533, - -0.3384936284317674, - 0.28833758298526846, - 0.5672185632374375, - 0.009564008550116816, - 0.0908830002213425, - 0.6845844863781286, - -0.12446005752734847, - -0.04653873428099154, - -1.211105892929442, - 0.100509770625372, - 0.4292640271104591, - -0.24308887246655925, - -0.30694528294581497, - 0.008613700625505405, - -0.13279160281230792, - 0.3324172433000594, - 0.1827791123966303, - 0.5974581011912596, - 0.08274173835233749, - -0.014964832948177178, - 0.8323744082399404, - 0.1829537313734922, - 0.08396846959798698, - -0.5543593418633028, - 0.2080748247028107, - -0.08493338626185393, - -0.76370307616336, - -0.08214933184953695, - 0.2669874404408143, - 0.17815320922077493, - -0.07463175320068169, - 0.13305721810551985, - 0.28308805027684575, - 0.08149225273992959, - -0.4980713070318863, - 0.25315135261304006, - -1.1292301718466773, - -0.35536680429513645, - 0.3624331024729196, - -0.009579258815126734, - 0.7106443232724804, - -0.42396309704126345, - -0.1626289771243017, - 0.345636230514865, - 0.3526444579584952, - 0.20659258041284223, - 0.29841649227677197, - -0.7776229028134032, - 0.4543021423018764, - -0.5068958419070422, - -0.4944624592223691, - -1.212076218444531, - -0.7065235592969751, - -0.23233127112933222, - -0.1849342794057974, - 0.7195206199925291, - -0.33200310218534146, - -0.6253828478897543, - 0.026448407644182482, - 0.45765923007331366, - -0.34712843359255285, - 0.2387471681684943, - -0.8033195785099042, - 0.23640371113055414, - 0.7066980875083303, - 0.7286876344763814, - 0.0254952883317286, - 0.4256707159430452, - -0.17708855111828195, - -0.3639209987610695, - 0.16845333390295333, - -0.07509515971746587, - -0.5018084769343679, - 0.12341817553518786, - -0.20158239064259723, - 0.4594337014387559, - 0.2643795554582897, - -0.004969232127133383, - 0.9590846546643322, - -0.10687237683180097, - -0.644720593433246, - 0.2826504325176223, - 0.863700705917049, - 0.05658063627755368, - -0.9118378427879467, - 0.5653124363929594, - 0.7046090185780663, - -0.49206296377366976, - -0.5494711684124616, - 0.22091372406824938, - 0.06564683118931199, - 0.27283642093486205, - 0.8106998590905122, - -0.5939771768863986, - -0.34996277997784636, - 0.19613361964994094, - -0.5331638223753831, - 0.015332625914329, - -0.0939020648354496, - -0.23805156518379525, - 0.689501364523257, - -0.002643364903664622, - 0.1535268235020077, - -0.21318739722323882, - -0.2384722613637918, - -0.19151678821151563, - -0.7629446243205892, - -0.5785696280113072, - -0.1310396339149448, - 0.2756503294600308, - -0.30447724436520757, - 0.29583558866011544, - 0.8160007352344422, - 0.5512828546508092, - 0.5154488140754505, - 0.21961675721011764, - -0.034234378621034185, - -0.16334669554931466, - -0.2428776642807275, - -0.40578418546128125, - -0.29050860146188556, - -0.18442136560197292, - -0.30961623136235633, - 0.5607100231223399, - 0.577889931585101, - -0.28299940733283313, - 0.3692489418780197, - 0.678095020440845, - -0.14871413346573545, - 0.39990192105131134, - -0.09603833185800578, - -0.04319411783449059, - -0.7782989299033232, - 0.4562025615089642, - -0.02245175100083207, - 0.12351048756000849, - 0.6212996417450626, - 0.3030820437390097, - 0.2965905774501651, - -0.3121383245066927, - 0.11676294652291366, - -0.05829263604494386, - 0.09580334040143824, - 0.3337716485306577, - -0.1489304812057951, - 0.3004175372663075, - 0.06091850348948695, - 0.4185604236457288, - 1.1372184267049936, - 0.6494557155352202, - 0.009789810497674523, - -1.206261581793785, - 0.15565234798308167, - 0.48336028224203376, - 0.2862408995174694, - -1.036883367157201, - 0.7231664538773499, - 0.1451490283397106, - 0.5668812616509981, - -0.6836709549298638, - -0.2658356868964457, - 0.19257296884804814, - 0.08770300406738489, - 0.7775010930597761, - 0.5838392267141628, - 0.054222883367851464, - -0.3967066249959389, - 1.1922775299632862, - 0.2988672426416141, - 0.018033735879780077, - -0.6070194576474688, - -0.7264798599254251, - 0.29329241668360995, - -0.2225900893140014, - -1.2333407359424287, - -0.3727852817108851, - 1.1952959646743557, - -0.11713414222017621, - 0.4925134076987495, - 0.4282043033232446, - 0.6391542989981023, - 0.32125777845271425, - -0.46384326865623143, - 0.29563975040682394, - -0.3728728433976728, - 0.43777576109515853, - 0.1140000529652219, - 0.3621855102092855, - -0.41066915654411035, - 0.13594257585484582, - -0.219626865351634, - -0.01750961942745235, - -0.4835183837690749, - -0.22880152716402752, - 1.2708557817319095, - -0.3506617573598598, - -0.4025957809935701, - 0.1614238477915869, - 0.4349507097243005, - 0.15559705716093086, - -0.0928199814351636, - -0.5538720330972982, - -0.0368399384917237, - -0.07630336920846019, - -0.08162175887972001, - 0.17406041696527344, - 0.11574043666150666, - -0.14095918712915723, - 0.4539170411745455, - -0.4163214040884682, - -0.6349497677276021, - -0.6143132481110793, - 0.781608524947533, - -0.08373943660232554, - 0.22534550706579343, - 0.5823636686262691, - 0.7220700442459649, - 0.3502011895973844, - -0.016843393125154697, - -0.5484249651008474, - -0.3068134843088501, - 7.111527788470732E-5, - -0.055245625997738926, - -0.13011848435523074, - 0.186424022766494, - -0.7260867487724446, - 0.03720583750652812, - -0.8642562745023386, - -0.10328161265200951, - -0.08933006787922562, - 0.6323410608884679, - 0.6552393687386934, - -0.5512954114048948, - -0.7811501967345577, - 0.25368089522596965, - -0.1519010067172595, - -0.6467712375017498, - 0.7205797646541069, - -0.953968217318987, - -0.5032888911980099, - -0.7781389706731818, - 1.3367921668882814, - -0.46036160808703824, - -0.5298939062749941, - 0.31917977072531645, - -0.5769500372173997, - -1.0170532729212878, - 1.1042170749195817, - 0.5519895686129157, - -0.02597773089990848, - 0.3951632763788548, - 0.12625841591497478, - -0.3188392143937161, - 0.34108731525532304, - -0.7686349676956147, - 0.4041481648923015, - 0.7665547645604406, - -0.27456350693219944, - -0.8648448763696188, - -0.12896869732971242, - -0.7743947483051283, - -0.5013460174333598, - 0.5813607327224777, - -0.4748528590362455, - 0.35520189035798366, - -0.38710494982049537, - -0.7307198460891556, - 0.2083530324567979, - 0.2476959006657504, - 0.34814711174247054, - -0.16043746119625948, - 0.5394059772312705, - -0.56720199606602, - -0.04332049490496804, - -0.059607022337596516, - 0.6982661001109767, - -0.3498047700721005, - -0.13833939797284261, - -0.23122151802828256, - -0.16146366250497252, - -0.13201839680796504, - -0.23863166609736453, - 1.038715948653314, - 0.21201457413903516, - -0.04809174433648228, - -0.652996839208173, - -0.7067695871042076, - 0.00540972462186599, - -0.24096672438386504, - -0.4337367389368826, - 0.534424805997926, - 0.055661308291385894, - -0.36344570871272686, - -0.44995557827161814, - -0.5153298444913855, - 0.34200634579882155, - -0.29812384038483536, - 0.0620799481394107, - -0.36720305261207037, - -0.3064747288467314, - -0.15111496542716701, - -0.1534292474851057, - -0.15359079769954898, - -0.03465211736802999, - 0.31765882826922043, - 0.3680653522402268, - 0.02382957133266949, - 0.6291487979729484, - 1.079547835745111, - 0.9223157735212971, - 0.0774780678779352, - 0.2508525127172434, - -0.35277594105123916, - -1.0727814018387858, - -0.8257789528900782, - 0.8700999198381695, - 0.8645197508078699, - -0.6009510104646589, - -0.42212274968944546, - 0.46886319917504554, - -0.39599981618759705, - -0.29876531867969686, - -0.22366244161450338, - 0.8858020842681643, - 0.33621182372482694, - 0.451487637357076, - 0.26434278200614936, - 0.06740234302439702, - -0.6626665132810299, - 0.2254223548405641, - -0.1529568862848488, - -0.9196355052801797, - 0.30452233343353097, - -0.42599997298687486, - 0.4589787533139927, - -0.4394413517168315, - 0.39881700302305306, - 0.5991396624351999, - -0.1822711710920558, - -0.09541097300295649, - 0.1996738167384375, - 0.3849388318372545, - -1.0311913818459877, - -0.07628048640012965, - -0.547537336782924, - 0.20339613611805132, - 0.1468342432502418, - -0.6696536864916429, - -0.4620259793476623, - 0.7203857962364244, - 0.015867304887148548, - 0.13359380843826013, - 0.11709394698416797, - 0.7275453132433812, - 0.6563633899826958, - -0.9082865237021602, - -0.36488984204707947, - 0.05275366653614986, - 0.23616221374699362, - -0.1067136403270636, - 0.36122665300596624, - -0.050198776621853326, - 0.14018989748588917, - -0.0605987440634769, - -0.8062476641267237, - 0.5378780338672285, - -0.2044046183830166, - -0.7687401344249463, - -0.020159268962907834, - -0.6619089025678035, - 0.30540727647252286, - -0.12317439026165587, - -0.7028971392780006, - 0.6629802000610018, - -0.7759411949485375, - -0.8558263388808008, - 0.04337188968156345, - 0.5775830557833808, - -0.29420668458312316, - -0.5438595883108012, - 0.17310969569270657, - 0.16398273531678986, - -0.8856913798152013, - 0.12512064405323448, - 0.940441249039064, - -0.710273180659619, - 0.2294010040466725, - -0.4825190347372098, - -0.5905127555807186, - -0.054791852829571164, - 0.04465441356476114, - -0.10809439151713135, - -0.7313631718264957, - 0.20015354750259431, - 0.7883752866248066, - 0.36048117348950787, - -0.022930816124258076, - 0.31368361769644404, - 0.4537468163964768, - 0.05432539661114927, - -0.3660636353668861, - -0.3383839007664131, - -0.33248356889057873, - -0.03282651044406545, - -0.18532061036055608, - -0.11766250444581525, - 0.4365844081353962, - -0.13307579326069865, - -0.10389029960859071, - -0.529546366253356, - 0.45360145545391123, - -0.29838216591152317, - -0.6399383292732101, - -0.5035517570496674, - -0.06748960262285579, - -0.081618010256577, - 0.31414104398320764, - 0.5278052939008615, - -0.10802230574573295, - 0.20222857501098263, - -0.22925882455709032, - 0.5493044086466793, - -0.6833858021690894, - -0.7084842184991456, - -0.7306973500654781, - -0.34176485261744144, - -0.29413403060706883, - 0.6094432379984157, - -0.09206483307754702, - -0.006041911660009003, - 0.48970235810934254, - -0.648853708543614, - -0.030671129078558946, - -0.3125985075397023, - 0.3840348113858886, - -0.5388047500924424, - 0.9303048044072317, - 0.49651672322439144, - -0.26359822968909863, - 0.9003996868195874, - -0.005934170649017582, - -0.38872517327997114, - -0.39555337973877286, - 0.12095780980981187, - 0.20400975330875668, - -0.025274746364998893, - 0.05245448173564031, - -0.15273857666010937, - 0.37323872289744087, - -0.07430672292545744, - 0.705482465324855, - -0.6391468479208802, - -0.2615011078107022, - 1.0409150145615882, - 0.4172837347462759, - 0.27697207160392245, - 0.29338890717813104, - -0.7492929910232815, - -0.5380628196284702, - 0.6673801089994243, - 0.28914394902870333, - -0.149010942108842, - -0.0212164654643544, - 0.1952708836716755, - -0.7787749272570638, - -0.5121959177475607, - -0.0143521701941348, - -0.45003194257864104, - 0.14182290827706504, - 0.42190452684454544, - -0.25230160403584256, - -0.47948932855198134, - 1.2635309717130778, - 0.14624851825635643, - -0.40019110414048953, - 0.790078831137851, - 0.0418526530653616, - -0.8706095252234377, - -0.49196815180504927, - -0.632244065844982, - 0.01771107519616518, - 0.34136672695545306, - 0.6934516350818769, - 0.10196767867475189, - -0.22969911343526164, - 1.1750962803993297, - 0.31585161837401926, - 0.3168447298529725, - 0.14524919852294538, - 0.8415286859629392, - -0.23088309551363717, - -0.27431935812170316, - 0.8617916075040212, - 0.7517248616233594, - -0.019423409601521044, - 0.18729380689913608, - -0.5526616871123714, - 0.2229620909895118, - 0.8232842879352144, - 0.2535121312642814, - 0.6255905503322401, - -0.4213763745259546, - 0.856644380564914, - -0.6434309300716494, - 0.5589294244408515, - -0.11771767093940479, - -0.09672376519408173, - -0.3932556089580158, - -0.20127473311440186, - -0.43351924610345005, - 0.8346134603628055, - -0.20595828385681275, - 0.3773680642766125, - 0.046041293421983424, - -0.5929430162069598, - -0.47285910302843037, - 0.5501319072147316, - 0.9989271317925263, - -0.30922975704283, - 0.4569601501827621, - 0.14772271369296378, - -0.48567276024614703, - -0.07167339610329003, - 0.03219613294221341, - -0.09600976035213603, - -0.14896533116739202, - 0.8215878859829672, - 0.21007691302843245, - 0.21252095158567597, - 0.005955010887097358, - -0.6446238524931492, - -0.2034181931565579, - 0.3079123519601869, - 0.598762524612319, - 0.21113240260482274, - 0.11632595382744855, - 0.6971088541128727, - 0.04338385056002774, - -0.9114500069844101, - 0.2054234353076899, - 0.059777714892311595, - -0.5453489855247069, - 0.011489338008468969, - 0.056533161670923794, - 1.213737833640158, - 0.07151916144141938, - 0.1999211914569798, - -0.0043954919037539845, - 0.35061557719590053, - 0.7891937731709305, - -0.058162392953444386, - -0.42262148342184264, - -0.03371875229092541, - -0.3540394037558757, - -0.12336330763492603, - 0.2826414392373615, - -0.9726010247085078, - -0.4754574696399304, - 0.5361542055484915, - 0.7418224883169813, - -0.07203053558191094, - -0.606288074604243, - 0.47493314718460455, - -0.04426175663165219, - -0.11234238828919954, - -0.5523827275147865, - 0.4328589012238976, - -1.0264589560257658, - -0.2623972330079222, - 0.652641686846444, - 0.4357751278518842, - -0.4460590726809208, - -0.28598646540097283, - -0.10379790944078413, - 0.5157365207722606, - 0.5487295588099516, - -1.0269044045700702, - 0.004810490103320599, - -0.777818909251016, - 0.45751519689986764, - -0.17898119394553164, - 1.0390881557698244, - -0.05876227935755385, - 0.29619746033821837, - 0.4276847207190276, - 0.746245882246576, - 0.31508971113587886, - -0.9311932014521583, - 0.9449938984467737, - 0.49609612759656524, - -0.37379200787166433, - 0.5859513759947469, - -0.28958665297124975, - -0.4821941831834446, - 1.1743103802377584, - -0.0272638882889035, - 0.22315500091398038, - -0.08127892807975803, - 0.5809969499803682, - 0.9063000225630679, - 0.25492030500698337, - -0.05030193506456007, - 0.7970305041393678, - 0.2500202531205713, - -0.48602945071212206, - -0.14410950720466528, - 0.20927156170756422, - 0.0604801965156025, - 0.910001129677289, - 0.162900695915433, - -0.019654074839774754, - 0.255779169011535, - 0.019291443118384627, - 0.23304253975508138, - 0.15494775266559627, - 0.04388271266794561, - -0.19389331192252723, - -0.8281461011652611, - -0.29493291651969855, - 0.03964660529211029, - -0.43989086455862075, - -0.010738153139213467, - 1.0359451394587258, - 0.8764079700175075, - -0.14305024744521633, - -0.4270223912425378, - 0.1577131281383971, - 1.320900768599718, - 0.13854099783537913, - -0.047981951037909774, - -0.6368633710130909, - 0.9524874855089464, - -0.1963602163327778, - 0.10219296666860161, - 0.33786232645383163, - -0.15262754508994816, - -0.18225758093056557, - 0.09300206543806046, - 0.38971475332076105, - 0.17456230836994557, - 0.6656190292020064, - -1.0326448933648296, - 0.600880150126038, - -0.4487552856344297, - 1.0053702544435297, - 1.172315087950002, - 0.7465978072379887, - -1.122897115307407, - -0.9166764837435756, - -0.4073541058206747, - -0.028518327177697145, - -0.38245777278082305, - 0.43557784535611904, - 0.6587133805026313, - -0.4265413305049349, - -0.32204722987774587, - 0.08665157099440657, - -0.25167613393874305, - 0.6394630478133636, - -0.260199893333357, - 0.6921904922867463, - 0.021194071880009418, - -0.7524887384979058, - -0.2910854448862131, - -0.7316078596136685, - 0.23630829608306747, - -0.4653223417235628, - 0.9505718192804934, - 0.4462677650393119, - -0.6055623364321803, - 0.23291472280839282, - 0.48507324207739005, - -0.4052575213880698, - 0.21184493150856062, - 0.32541705462257, - -0.4563679621466524, - -0.3856460173357099, - 0.6458482831037554, - -0.6648282809527816, - 0.17752154637475723, - -0.8935780259246778, - -0.07378625878263119, - -0.5443405041914363, - -0.006847167825833758, - -1.3052355509301816, - -0.04134383393210064, - 0.049368069977782134, - 0.26534840569769663, - 0.025075904988794476, - 0.08230446175975357, - -0.689741938838445, - -0.4318633199091742, - -0.29176065868729606, - 0.27645817225699, - 1.065340386790319, - 0.5528915548843436, - 0.6405077986558763, - -1.195343828199126, - 0.028851260594355395, - 0.6004242636522846, - 0.658241941202215, - -0.4993459851457912, - -0.9738455902098351, - -0.08786706190947535, - -0.5798473787790974, - 0.13870701697870078, - -0.15785500567609548, - -0.6789793971918883, - -0.0858772215467059, - 0.01876931684972065, - 0.5595876402737213, - 0.13128450454433158, - 0.10628118173471494, - -0.5374342548110626, - 0.48908049362090245, - -0.05622279626177297, - 0.17490803530765792, - 0.6866100420508521, - 0.33734581191156027, - -0.3056649463158992, - 0.6652124405948101, - 0.12434710752469694, - 0.9635872133989406, - 0.2135565370217047, - 0.14164790832947527, - -0.7463255900943591, - -0.7400310357506621, - -0.006906278641772543, - -0.7945730247087424, - 0.7929789319407802, - 0.22998635491609976, - 1.246205362394133, - 0.6069320334434593, - 0.5899210397281006, - 0.04432225348996146, - 1.0998400425295551, - -0.07050574007499516, - 0.24924934442803817, - 0.65235162460416, - -0.8036720184052554, - 0.6019098095301503, - -0.13856418664912162, - -0.7330837926801392, - -0.31299386826044506, - -1.04983338717993, - 0.0068569058230939775, - 0.21234457606658858, - -0.23896758549414443, - -0.4162190242817385, - -0.357089283408986, - 0.5472312083834182, - -0.5043866905872953, - 0.15718958054734297, - -0.5218377335526366, - -0.21706698359240664, - 1.1516235535045, - -0.6705954308831258, - 0.4187799777332822, - 0.6276729800620804, - 0.6731445304393164, - 0.0681812502016418, - 0.17827847847445993, - -0.5167806720847452, - -1.0065305536076186, - -0.21899817501739577, - -0.22992871315418245, - -0.14505092171120595, - 0.7365641522660931, - -0.4537615748857939, - 0.8156879748336537, - 0.19128869248721836, - 0.3878123664907725, - -0.5247677512050923, - -0.568925514274822, - 0.6969600894767766, - -0.16354196813134217, - -0.7813088376664002, - -0.24287428196088348, - 0.08324398095787384, - 0.27084545511985664, - 0.09368654668359831, - -0.2333791801586896, - 0.4945062279346102, - 0.6106899076628114, - 0.055966641542470344, - -0.461854937709428, - 0.15470586557772611, - 0.5107578215043787, - 0.3950027091005244, - -0.312614111486202, - 0.032546337497358406, - -0.16005462960461872, - -0.15964260756954665, - 0.2310184251898556, - 0.08405896352821453, - 0.5891321933643252, - 0.4240339785867362, - -0.17566832935310386, - 0.19446980171654893, - -0.6793115290577755, - 0.2829941682062497, - -0.06665603129109925, - 0.21737783126082053, - -0.4844859564567258, - -0.5368642058111798, - 0.46838815929675326, - -0.048945237876588416, - -0.7933452423039562, - -0.5895573530175575, - -0.24747935711821603, - -0.40381123657285223, - 0.47719645064880356, - -0.08363822783612758, - -0.6338767989172547, - 0.3386540850655683, - 0.9236919475250204, - 0.06205069772121719, - -0.32359826986122187, - 1.1006131179914544, - -0.2943040763316632, - 0.2955976694435221, - 0.24145530606223806, - 0.06631594717353909, - 0.08789649440850224, - -0.04936619028522857, - -0.8476947931905632, - 0.3244141641120632, - -0.5266945899060665, - -0.299877991177528, - 0.02684597451776383, - -0.047738619532128136, - 0.4995948422144622, - 0.11665594981147881, - 0.6955482083595088, - 0.1402271028927436, - 0.28022760012330034, - -0.1211286742346983, - -0.25508078609249524, - -0.09722227587869485, - 0.18818775902369628, - 0.31862289530301496, - 1.0017114816586932, - -0.7617728068688098, - -0.7244560082297864, - -0.6544398752617073, - 0.034903841773354184, - 0.3728967649222923, - 0.6586131954786282, - 0.18035596089500525, - 0.08050999259197686, - -0.6064376967420373, - -0.4549053417650624, - -0.4029107965450371, - -0.27549539892129227, - -0.5896071005140817, - -0.477774467385108, - 0.21087449939623965, - 0.41808218455978685, - 0.43335058630941553, - 0.28635030055994504, - 0.3762002482161518, - 0.16443812816722064, - -0.04419132598954477, - -0.08975246243095619, - -0.3929501457399977, - 0.03516635343935506, - -0.37687287073405246, - -0.3588262067021767, - 0.28192682751784925, - -0.7026081514277897, - 0.45302729603240083, - 0.3369333207927739, - 0.7572458299523072, - -0.5526832779728597, - 0.2859933915563802, - 0.5320090849035753, - 0.03415165566398335, - 0.4320229973420908, - -0.2168701937319342, - 0.1540855590187154, - 0.47789533782556903, - 0.2400431749109787, - 0.7329951057322988, - -0.23116889129761586, - 0.4411775151240617, - 0.5143893692860041, - 0.3678525748203706, - 0.36071949730106867, - -0.24358879342354792, - -0.5836817731264584, - -0.846200442752447, - 0.01608858228385791, - -0.14586562625061833, - -1.0716258865227386, - 0.33808736045593973, - -0.0890253589439743, - 0.022535402381066605, - 0.09430915511621925, - -0.640409074341378, - 0.5914688558710987, - 0.2504917751202848, - -0.008304524660633233, - -0.28662442146442907, - -0.42993575250239613, - -0.030866524676943792, - 0.3113532947594844, - -0.29742889265422096, - -0.6839354754359409, - -0.13051145409893106, - 0.08693435272526077, - 0.3400066084127077, - -1.3149565799762777, - -0.4638643342932284, - -0.6780104221492977, - -0.08911910074837485, - 0.3595086185895514, - 0.29753491674464505, - 0.5604952943582102, - -0.34343585055417925, - -1.1750568135500972, - 0.1615569343119798, - -0.2781149259871724, - 0.10264766651615388, - -0.20226765596735796, - 0.3474372466346745, - -0.43741519299148585, - -0.33929256541242236, - -0.6621608158055214, - 0.050405933947932594, - -0.12676952467744398, - -0.40674772690822475, - 0.09556537217232473, - 0.29347176374876605, - -0.15195727158023267, - -0.3524315590314354, - -0.13319726491924783, - 0.02077451884921444, - -0.8551039008748194, - -0.10253820696336828, - -0.5916441472395806, - -0.4329201921749799, - 0.9106659746583464, - 0.21178115859143423, - -0.13742427409108068, - 0.09544605221769156, - 0.22150358375328416, - 0.6821176676991049, - 0.7388538607510733, - 0.4326832690269564, - -0.9708872895608176, - 0.2121078849768985, - 0.10885234552972156, - 0.8380952677312423, - -0.28207775378887795, - -0.1040150343706729, - -0.5287177379327666, - 0.17352849531275266, - 0.5036042131643096, - -0.950764877031125, - -0.3430939390021036, - -0.8452381547022207, - -0.10198169163655353, - -0.4690568311893388, - 0.3714434879920362, - 0.2327635652779266, - -1.0945809171464689, - 0.4750211480941239, - -0.6644844558158566, - 0.2231430320142775, - 0.34023997095295055, - 0.7416126958846114, - 0.3585018896105474, - -0.4246902126189448, - -0.2997481818959107, - 0.08213670104824847, - 0.10512319450923004, - 0.6574208179785708, - -1.1433527824404677, - -0.16613259191393434, - -0.5485210816890741, - 0.5927916171979478, - -0.14743038838563066, - 0.27771053979670124, - -0.06853408178007711, - -0.7464324298395405, - -0.22384522272801827, - -0.1389342422875893, - -0.6882272991192281, - 0.040845331469350155, - 0.20717151908814221, - 0.3405564680009828, - 0.1443281498401373, - -0.7714378801427347, - 0.6592133422571897, - 0.47807485427018626, - -0.11029540397781296, - 0.7427572187587802, - 0.4938901793025756, - -0.17430836108016184, - -0.7490694380749866, - 0.12120265715202265, - -0.45982609208961295, - 0.6723460208059001, - -0.3969021678296493, - 0.4139821133370383, - -0.11210269364723395, - -0.7931930636825794, - 0.013662686324885263, - 0.12033579415869063, - -0.5775918909731873, - -0.40647454926829574, - 0.6160733551162, - 0.340810934382009, - -0.4117699026757177, - -0.28169103171419196, - -0.29919320240407116, - 0.1614037097036092, - 0.3376048943598212, - 0.5966309311056271, - -1.0870274261967177, - 0.358062759875987, - 0.7245642793464019, - -0.9599470498876714, - 0.24337662457964282, - 0.3939949140471423, - 0.6000338875959387, - -0.4595719825946448, - -0.2401040045856812, - 0.007260440480356048, - -0.20227421597225242, - 0.6219674221785481, - -0.7286743593433466, - 0.28472182427250503, - 0.23138829880199757, - -0.28345680506154075, - -0.4533534879049796, - -0.4020519786073195, - -0.47652150657080694, - -0.1419072704163134, - 0.04466419815032677, - -0.220444035762438, - 0.08901331054063014, - 0.5822281028452772, - 0.01921178151810437, - 0.3536372354791637, - -0.559354142416778, - 0.22835069777158504, - 0.6226068537955329, - 0.46451835267012137, - 0.09587491758115962, - -0.6294883881853905, - -0.17982095786073302, - 0.11340883894229342, - -0.4223113120851259, - -0.15808710226466138, - -0.5144985938367772, - 0.1884044104941129, - 0.28235045037727835, - -0.18769223954818873, - -1.0044021388215891, - 0.20835648834056014, - 0.10482345866535686, - 0.552834793776946, - 0.35767406585876416, - -0.6573742362554678, - -0.23291125182704714, - 0.5427241857735985, - 0.12233764208472392, - 0.544859296998514, - 0.07410251154193731, - -0.29432635480488895, - 0.881199422578265, - 0.48565658849914345, - 0.3327991068916601, - 0.8949993772386148, - -0.10431255808240655, - -0.5479331928183702, - -0.3618237021470328, - 0.7306312382358604, - -0.018064901269905235, - -1.2271348039313803, - 0.4900584059029632, - 0.060668720097922096, - -0.06900908313074833, - 0.5528439064442608, - 0.316862537402162, - 0.09169537402300657, - -0.4867697655046628, - 0.8481733431648897, - -0.004283313825968816, - -0.8357944827165358, - -0.6399390036371232, - 0.011721898251122399, - -0.5885438331907908, - 0.17223828298249938, - -0.7887594472221392, - 1.4966151979063693, - 0.6546855445447912, - -0.2575242136149322, - 0.2676954513497695, - -0.18722873577111807, - 0.2511587028835003, - -0.10740285414736352, - 0.05971597200058524, - -0.3257102199554298, - 0.07228269254608014, - -0.6282064803226255, - 0.5903931228491826, - 0.2436318957111145, - 0.584123395199028, - 0.09415215679202533, - 0.48761049578586524, - -0.4909886867163628, - 0.7177253466240823, - 1.1453574548063696, - 0.6044657661237298, - 0.6616883086560281, - 0.4230210495777431, - -0.03208700778653465, - 0.41075964942614435, - -0.48684959620659746, - 0.03060240310687673, - -0.5624459042485369, - 0.3172788828606825, - -0.7995349886117088, - -0.09899609902013845, - -0.18669402634560178, - -0.2276538104704906, - -0.15468047467951396, - -0.20499755146840434, - 0.15146140941871225, - 0.8387006715265187, - -0.020561858482012817, - -0.19855403365743934, - 0.5756648040518265, - 1.2834768459929242, - -0.21406202588413542, - 0.9093389565336598, - -0.38676893482486707, - 0.23369363364594267, - 0.30305848951501, - 0.2994027843658154, - 1.0731839057250316, - 0.11624129575106341, - 0.8493955536990978, - -0.14020773619603627, - 0.253844307573321, - -0.044906675958291405, - -0.10976894163131676, - 0.232624175361266, - 0.06085802190831846, - -0.08948904446828586, - 0.4245130761667721, - 0.3602019213000162, - -0.02354511766977905, - 0.9095771072820213, - 0.3560937263423685, - -0.24908119707138332, - -0.03561535649802615, - -0.17073443325727206, - 0.18352117481111638, - 0.1772938002336022, - -0.5441318490655283, - 0.07885570450628385, - -0.6344349310721457, - 0.7014672785147847, - 0.33030673274796024, - -0.003400326934972185, - 0.4740043904440225, - -0.25059540874747077, - -0.04670781437410747, - 0.11643938232655025, - -0.29788961401258307, - -0.7347463644400749, - -0.19226085767962114, - 0.26687968881324514, - -1.2865114046375439, - -0.31316584122163627, - 0.7774975514316111, - 0.2735686021687313, - 0.1618496087495595, - 0.024818069272958754, - -0.06290391031238791, - -0.649631072750499, - 8.6541339463122E-4, - 0.5488040136236035, - 0.9012551217095234, - 0.5805476240399069, - 0.3056926078136023, - 0.045567923916599334, - 0.4900998577345622, - 0.5431694619498607, - -0.3306388082332372, - -0.21918855038665366, - 0.12946371969599532, - -0.9432003034698953, - -0.8175869187477641, - -0.35009083215451103, - 1.1544130375774428, - 0.8890387036196377, - -0.5479054356369326, - -0.5903055225211713, - 0.2972780186053584, - 0.08370974315819997, - 0.5672597415463663, - 0.6059816611094818, - 0.7647642177434228, - 0.2120811040036082, - 0.4588066014900466, - -0.738667122175592, - -0.08058431860857336, - -0.12898819450995658, - -0.012042699482470408, - -0.10703052728843596, - -0.21223571797810656, - 0.5430544276109641, - 0.04474053735082095, - 0.9985177625520392, - 0.5197447462162932, - 0.09046310668356065, - 0.04446310482710809, - 0.1438321021336056, - -0.4696250177192626, - 0.6135489039659278, - -0.006300720151904689, - 0.0942022163026333, - 0.2587831380778056, - 0.15543033523964797, - 0.3072768846505245, - -0.12271348837356813, - 0.6373834706211373, - 0.3525096597874165, - -0.8151622025164874, - -0.9787088458580708, - -0.10180076303659875, - 0.3394569636991961, - -0.32616943042019186, - 0.24816779705006842, - 0.2287532458297408, - 0.5965241472373843, - 0.4354070764037712, - 0.7568958838166511, - -0.8014430301181096, - -0.3021086224891428, - -0.5502745757224538, - -0.1372338237906923, - 0.677078851268391, - -0.6524060399438443, - -0.28385488720389485, - -0.5083621221827842, - -0.4592000473380405, - -0.490701098916406, - -0.6954257204199236, - -0.11992751265761047, - 0.3951996508912118, - -0.22728933601063336, - -0.8718884949639188, - 0.23570414172889698, - 0.00791939429951704, - 0.3292473435852542, - 0.34091642978318554, - 0.1680993404422315, - 0.08076683971005781, - -0.5876024977011169, - 0.6890918236950886, - -0.3193860401813062, - 0.382417881010766, - 0.3599328692931661, - 0.47114407561450283, - -0.29090938905782143, - 0.010391711937859338, - 0.6170132191553391, - -0.8160569818172043, - -0.6355773994846821, - -0.4969171771394528, - -0.6817341862785457, - 0.8305164883794202, - -0.1613493427351121, - 0.6649175312089013, - -0.12454221897062434, - 0.024964352519365445, - -0.677654574840974, - 0.2982134896430111, - 0.4112035690073395, - 0.051913709500224274, - -0.48585736533878765, - 0.35273871181472966, - 0.16513439863110202, - -0.5560614117763244, - 0.6482190155823735, - -0.13094723317572354, - -0.7770982362877448, - 0.280175108927668, - -0.9427058505789907, - -0.8561529514973579, - 0.4321526857607337, - -0.4913246494818182, - 0.6825466805411267, - 0.40695827013011915, - -0.11698128469143514, - 0.07249846276066708, - -0.8346913582810828, - -0.06666105949549025, - -0.10078499419187445, - -0.7476967147985769, - -0.006908303199848676, - 0.43475273000439574, - 0.5391978849323303, - 0.47091272086025315, - -0.8433431454909537, - -0.008716412422724388, - -0.017475397554262653, - 1.2969379969778132, - 0.4624159343575939, - -0.8035509023946, - 0.03948928893392751, - -0.12057583860925725, - -0.10449822914681434, - 0.2071117286772501, - -0.28763941395594983, - -0.1940879811111626, - 0.2842968995447024, - 0.12411491750971278, - 0.7217270586692769, - -0.5842341583739831, - -1.5480871123243383, - 0.0703230596672693, - 0.6329874394114172, - 0.9397110732413351, - -0.8021591812132881, - -0.19033813145745201, - -0.2792464052929784, - -0.8628237277540379, - 0.0021226499819362115, - -0.3811901972229455, - -0.4411552009988894, - -0.3045866409744438, - -0.3668971194030874, - -0.512387976338756, - 0.378277908163456, - -0.1301009370079531, - 0.3031172583189975, - 0.022597508253019732, - 0.6761892372719414, - 0.8490708772972121, - -0.3278111658133403, - -0.016176047257257124, - 0.06130351299076814, - -0.697243469394654, - -0.4428643792804455, - -0.6626024181868236, - 0.9973766293079043, - 0.8428147601277156, - -0.3060248450112049, - -0.8752765940031824, - 0.44700593205772926, - 1.5872779396899273, - 0.009374071667485445, - -0.4043245041511832, - 0.13123803908760562, - 0.2941234860024019, - -0.030342482803068192, - -0.9611762267965556, - -0.04066412183732023, - 0.22600457955721642, - 0.09310288723979346, - -0.5592497422806504, - 0.4900619998049691, - 0.6125451079762974, - -0.5677058589590096, - -0.07045180215068174, - -0.34523085164942885, - 0.007559050321314975, - 0.8800366153280309, - 0.2522682326843465, - -0.09338514795782049, - 0.9635788382848033, - -0.49270489562693237, - -0.5294739925879098, - 0.036518215845918967, - -0.16474125584956234, - -0.573488378643038, - -0.5275232260007766, - -0.4059222933320923, - 0.3786948881462482, - 0.19362090707955784, - -0.14529724945613634, - -0.18638288217676752, - 0.3310383511490871, - 0.15091724520372224, - -0.12825855937770478, - -0.3683063772413265, - 0.15230769101921895, - -0.11982033012193007, - 0.04341374676919775, - 0.31301860505264817, - 0.11003195573708394, - 0.3992820274284283, - -0.11352092598956481, - -0.11910033531638095, - -0.05762178864861991, - 0.4398615783994841, - 0.6880341673847331, - -0.6508965615991031, - -0.269822910239957, - 0.14373589410065216, - -0.5645432900619035, - -0.09496257257727851, - 0.2603610991110313, - 0.7198986640336792, - 0.3335508240047488, - -0.029550374296028113, - 0.5208014433719882, - 0.11234485190073784, - -0.1992876232776666, - 0.09824860345159862, - 0.19384046926744028, - -0.35879383125167025, - 0.3691342118736365, - 0.0025921416307764186, - -0.4457442371786919, - -0.14889379263168565, - 0.2474310323354143, - 0.21946059210672447, - -0.12737403177608692, - 0.07502874358319514, - -0.19462739497086975, - 0.6837457062955513, - -0.873347199909732, - 0.739170826461599, - -0.667860292266383, - 0.08641963242011996, - 0.29265071806498927, - 0.5974211196661607, - 0.4581657947207609, - 0.5199872378307461, - -0.3740299460717029, - 0.0077342259630966866, - 0.17450472981503487, - -0.1440407167616328, - -0.5852938677391306, - 1.143447933371389, - 0.4562334969644213, - 0.6085842651463841, - 0.5445995367059386, - 0.4204832900488584, - -0.5129947288224491, - -0.6520825235767891, - 0.07500310805566368, - 0.40772670820918716, - -0.4613736904942434, - -0.5463228880079616, - -0.5568313552826161, - -0.19417716637574986, - -0.3687988559369366, - 0.0894037293108692, - 0.14256140822645813, - -0.4204555861697317, - 0.07800492592600818, - 0.3623238624931313, - 0.49622595099068334, - 0.63475142311071, - -0.6439844944059466, - 0.08234317506034683, - -0.4259674745908698, - 0.34871855719777706, - -0.4197619223363908, - -0.39507199914890145, - -0.4396716892275248, - 0.372941549332204, - -0.05250369802735773, - 0.47080713654272477, - 0.06454021495218104, - -0.4238406853805178, - 0.3850059018977594, - 0.3904194832262193, - -0.2414186003674454, - 0.717109146598475, - 0.11903683957518287, - -0.8497432772962292, - -0.13365839705154686, - -0.8161824988625986, - -0.1269847281339346, - 0.4013578943587286, - -0.038919703327211355, - -0.2829371575710157, - 0.20540700543204823, - 0.2622146997138323, - -0.2592096109845527, - -0.2619767505230994, - -0.16813663020444808, - -0.35417180893615685, - 1.5652494748057264, - 0.28998344270372356, - -0.73645707469938, - 0.16492432693580555, - 0.10937196827809688, - -0.850000412617926, - -0.5830925548467703, - -0.19999789112140717, - -0.08075965768705928, - 0.0256087098719199, - -0.2868875773057683, - -0.251921358635813, - -0.022497315103036892, - -0.7059760115060887, - 0.44207473049126006, - -0.3121989443806198, - 0.02072037314430101, - -0.605542674034284, - -0.24083976562750264, - 0.9279661618995997, - -0.36050121693485787, - 0.22169541400845003, - 1.2900359164524255, - 0.3154042182252195, - 1.2996722284468298, - -0.7480581417388008, - -0.8022751179143358, - 0.47562816230731475, - 0.22615579925935222, - -0.6986500466267374, - -0.7587342999600065, - -0.12843508584788538, - -0.971165589170821, - 0.04878374693936048, - -0.19941235905455135, - 0.4084494971042225, - 1.1844611748176046, - 0.09860740695883005, - -0.36553760282205777, - 0.15823503210947273, - -0.0722138248227844, - -0.05766030278467465, - 0.08687330006971608, - 0.3881186768986014, - -0.5766629816436373, - -0.09181505158326318, - -0.14253897741861282, - 0.3293864580448902, - -0.3604386921133454, - -0.16421735628067227, - 0.415042067857294, - 0.5518886594782638, - 0.3650151540392235, - -0.277914913652127, - 1.471714466751969, - 0.38800304522675894, - -0.5102658016100804, - 0.12301901649056964, - 0.5339833664873276, - -0.18510982591987776, - 0.24255820699264896, - -0.8558874698182806, - -0.18835896799435495, - 0.377604214883821, - 0.49556146525985234, - 1.339652007909707, - -0.44238427073293646, - 0.4671107753901409, - 0.8652021783425382, - 0.8852697300107577, - -0.7101849468959821, - 0.9383035918591203, - -0.6343188718395356, - 0.843724561112742, - -0.24195917778001508, - 0.5424279322588267, - 0.3139902643597003, - 0.17910442018394523, - -0.5400219531903183, - -0.24533342339317665, - 0.2034150387847529, - -0.7369937257722317, - 0.47989134159655283, - 0.42405418673633555, - 0.6477547575066469, - -0.6649316982440793, - -0.6269238539704908, - 0.4546340786426019, - -0.4775217854536654, - -0.05981646428076391, - -0.02073692715356148, - -0.10185771128871536, - 0.44341012071636077, - -0.16128589155548337, - -0.8575790686924429, - 0.372838978258427, - -0.4986484593219495, - -1.2692599765504768, - 0.6228239623671525, - 0.6091739149557233, - -0.92711254969074, - 0.3672137901476918, - 0.43196223552142815, - -0.11935015832078434, - 0.12725416446256785, - 0.66586818600513, - -0.11428899372052348, - 0.32887872494182313, - 0.4064328748189897, - -0.14320967922054278, - 0.19532167323937047, - -0.5164068038319866, - -0.12337624318239838, - 1.0248909422049677, - -0.7378230365560801, - 0.9902293216256397, - 0.23974415005867392, - -0.0705354747040768, - 0.10877478857457315, - -0.4255568693718224, - 0.7291834837424465, - 0.3375696204870997, - -0.33750281157187084, - 0.9294015014502027, - 0.6887160811116007, - 0.29424846421494166, - 0.6171998243413831, - 0.7702610117271163, - -0.3596354342969468, - 1.1529970635271316, - -0.5362274927310585, - 1.0507287145793034, - 0.3051972766956809, - -0.08506679905443482, - -0.3530015379680545, - -0.13544122741642933, - 0.10170486453047024, - -0.4984978836948726, - 0.10850933254116732, - 0.5191553430171449, - 0.16592177149066514, - -1.0182084917920597, - -0.563552704385589, - 0.7303523192582606, - -0.3321070617763999, - -0.734468506975291, - -0.4346938427893915, - 0.1311758188752009, - -0.3163057533092599, - 1.1450127107221637, - -0.4876807829493449, - -0.13013965441433495, - -0.4203914565653482, - 0.28230443170216923, - 0.19497275691973104, - -0.2903401311916879, - -0.7437274282002928, - -0.11579226218844528, - -0.773943318998974, - 0.09511486831990991, - 0.6408083928011844, - 0.11796162530693481, - 0.8962933379022248, - 0.3400189394328802, - 0.5095156314152947, - 0.14183285246685573, - -0.6447346262337913, - 0.4780560512660803, - -0.37398551206286446, - 0.13252380460536656, - 0.3864371353622362, - -0.6494726793178919, - 0.5991648774432834, - 0.23575127333241755, - -0.22476966532564374, - -0.7253374581232772, - 0.26352784542129043, - -0.3002468352060426, - 0.5832829333402947, - 0.30484800266523326, - 0.26472029749290454, - 0.9429751350595323, - -0.17191808559650654, - -0.0772859646530606, - 0.439726095500953, - 0.8788415356839314, - -0.24790492988767418, - -0.6289269049467824, - -1.1387960806388158, - -0.10753670485733371, - 0.3780089956546254, - 0.4147290859993261, - 0.19647155904048144, - 0.44234140442034303, - 0.18933679288027858, - -0.39965304716629935, - 0.04324139147181743, - -1.05905516698763, - 0.2279409166608211, - 0.6110317434630281, - 0.11049971375167657, - 0.1945781302950614, - 0.36829998917393125, - 0.3297819764370583, - 0.19245649902098735, - 0.6417978700887987, - 0.7143173286214569, - -1.1557097693288965, - 0.1659247723008794, - -0.01859412837139466, - -0.735129991267123, - 0.9213978238012169, - -0.2510207703555514, - 0.05280287132784413, - -0.5844555304383292, - -0.6379208937088113, - -0.25305400469912204, - 0.6622252519996202, - -0.0431625966386584, - 0.05788382721653707, - -0.5035185518763373, - 0.24771357845398467, - 0.21985011575761937, - -0.6403356166217858, - -0.5143499080053588, - 1.004714366702728, - 1.0020973304118312, - 0.04165730469363723, - 0.8421481845487809, - -0.3158044821232022, - -0.23010776181400108, - -0.18053074731366486, - -0.3585367378720256, - 0.08393696525622878, - -0.4408250787596759, - 0.26537963999918496, - 0.12050295030057201, - -0.05383306149113338, - 1.0611155945025716, - 0.867751205692966, - -0.16947941176772008, - -0.267827307281706, - 0.33095800349969245, - 0.4936267241058893, - 0.09421085209018075, - -0.40490708487024535, - 0.6373007178904577, - 0.29892269061321575, - 0.21512310569067877, - -0.25864867061544433, - -0.08603201557251501, - 0.1843780594653337, - -0.5425883044779902, - 0.16455903674469433, - 0.4805362498335036, - -0.4961285217826754, - -0.2885938685300875, - 0.42675937537813713, - 0.6982279966978492, - 0.2602411814583424, - 1.033051542146733, - -0.9521987650393967, - -0.1756001929740777, - -0.8726918514072575, - -0.28010853742759423, - -0.6648020314680386, - -0.4191202071554369, - 0.31883172962738004, - -0.9486230364626658, - -0.48051191374212554, - 0.2738153273581295, - -0.3239477878217959, - 0.8768866464157368, - -0.36524654163630244, - 0.20392757715762236, - -0.45922443889980596, - 0.12467716395101097, - 0.05989973482972542, - 0.5138714137944806, - 0.35192306201922136, - -0.0751130915363845, - 0.47857312326417145, - -1.1557134481483107, - -0.4459186952648106, - 0.14392109849753898, - 0.8844297774790056, - -0.44660012939304017, - -0.16736319236821792, - -0.1483081747013685, - -0.30971943749543474, - 0.8676963602029127, - 0.07595564115926205, - 0.3125369966059476, - 0.12761723112727266, - 0.7051688928212887, - -0.32157999060546893, - -0.01910242968882209, - 0.5116756159751147, - 0.02521512323127391, - -0.2594861049813122, - 0.3587408513492048, - 0.9178931075525364, - -0.47169053618929135, - 0.8765587464571958, - -0.20042586646550264, - -0.15978430834988447, - -0.2560491789561202, - 0.061307469136801226, - 0.026782563242266078, - -0.06531183585464709, - 0.16351089926913975, - 0.12813746579462512, - -0.36890936349761616, - -0.5834242947195636, - 0.22242680404133625, - 0.3737420471967625, - 0.14360836430816568, - 0.04977184564742089, - 0.7286611455428414, - -0.016671331521445086, - -0.19112980681506228, - -0.6230782385493938, - -0.28625598970597854, - -9.716228416794157E-4, - 0.7479451881672213, - 0.49634971935534, - 1.063842001888112, - -0.12271229966645433, - 0.006408940961579769, - 0.33158231897414486, - 0.4612247192583437, - 0.1987705637401479, - 0.6000822906487715, - -0.7095164990983787, - -0.06950798560587752, - 1.023266137649077, - 0.4595582406196412, - 0.7606064249193494, - 0.09728054814962345, - -0.5097812990700868, - 0.06432157494193774, - 0.4084094072526226, - -0.38087359130501575, - 0.17576066340410595, - -0.5079700013366049, - -0.492867121571001, - 0.9579190360303693, - -0.25175897543660386, - 0.32533345781668943, - -0.18727458531124214, - 0.1448216777781906, - -0.2957323020573493, - 0.857433068184419, - 0.45180356760408563, - 0.02296101932725712, - -0.0843839869425344, - -0.06938991130281814, - -0.5188525570982776, - 0.3437366273865001, - -0.15456599071779414, - 0.38082683148249696, - 0.4897051233638246, - 0.2785208646801673, - -0.7573110364292484, - -0.09350870965449705, - -0.298712695001785, - 0.1621894811109311, - -0.5945911661117145, - 0.25262894203707803, - 0.07998784332167659, - -0.03804736360104036, - 0.5189130801091415, - -0.17633235728144142, - 0.8011496205982287, - 0.02565793589954941, - -0.24473128035173572, - -0.26978777275242666, - 0.23029550372904692, - 0.0055725423803496595, - 1.0549230421242826, - 0.3316478961867615, - -0.1427109980708727, - 0.2516955968278833, - -0.4158614007649655, - -0.2720523757365537, - 0.11235706057981754, - -0.24468513450091148, - 0.41526431215342624, - -0.4422711603863182, - -0.4466646136396873, - 0.46320360431038804, - -0.7541472001378534, - 0.14935037783047528, - 0.9761025510472409, - 0.9623889477154578, - 0.9110778011703488, - -0.267465606036707, - 0.21425279315306248, - -0.6355420589485448, - 0.10348860508142187, - 0.0032692429815560104, - -0.029531588549322283, - 0.2442745730674079, - 0.07159349968208799, - 0.1034921344168161, - -0.7396303918919609, - 0.4086384091723204, - 0.18389087982849786, - 1.0554626307465553, - -0.3217685992765091, - 0.4591416807597406, - 0.32880329345043885, - 0.620825281068937, - -0.5045786493861133, - 0.4622922895380342, - 0.026935589553663753, - 0.6521847943582367, - 0.5760028739662154, - -0.05285273108872079, - -0.6251328364875907, - 0.6227543570500779, - -0.3833155911477306, - -0.6613627660583069, - 0.2524489351939967, - 0.5333348713725465, - -0.47038762003361667, - 0.1749138052860271, - -0.11755291393610624, - 0.3153630056889536, - -0.7002624886329761, - 1.1183619249278076, - 0.08803805224737325, - -0.001333279401114332, - -0.6466180023119696, - -0.2465143616487976, - -0.5847569425053151, - -0.4459361499770947, - -0.6543940269750178, - -0.6754005807166564, - -0.07019525431428533, - 0.1706782834735933, - 0.683325163045258, - 0.15192728851875187, - 0.2953067493090175, - -0.6535039528129214, - -1.1463042860642942, - -0.09718787536098297, - 0.8341956321812846, - -0.3911262986732778, - -0.4681953256740698, - -0.021513163015525364, - 0.21555077251750027, - -0.10772522159019195, - -0.5293490515890974, - 0.24394440285734204, - 0.2235716958595985, - 0.21572544682221179, - -0.24178506946314882, - -0.09251553399101611, - -0.41038322306875785, - -0.09415908742816836, - -0.2987494174976976, - -0.7575575821583468, - -0.39858588300353326, - -0.3869721986531278, - -0.10327201251209944, - 0.12367644794965897, - -1.1085412907480228, - 0.462828069166039, - 0.305477121559244, - 0.26388657439581714, - -0.3453174384757816, - 0.04898337474973867, - 0.7397575507644372, - -0.18852430360613376, - 0.1522995318627737, - -0.019564887687040285, - 0.8397093012832169, - 0.06259699570173823, - 0.56458976333587, - 0.26923260261513626, - 0.02774667718511441, - -0.19762885374886915, - -0.5282532357345194, - 0.24659512013955007, - 0.17215141310249182, - -0.576977618373091, - -0.001307432566523196, - -0.4928164561960127, - 0.17552281894054608, - 0.545517467868219, - -0.4368774206086415, - 1.4056174328699842, - -0.2092277656803149, - -1.0723785333702012, - 0.004028420630222615, - 0.21208265115376468, - -0.12413808541049173, - 0.6714076714393362, - -0.36827142848573335, - -0.6647652537134953, - 0.205289614031591, - -0.4468464894587243, - 0.3852241616699611, - 0.3397947285345333, - 0.08134682396737554, - 0.20112483488878274, - -0.06081418114600655, - -0.13239198278406666, - 0.36731520930444744, - -0.5340206551858419, - 0.5229232244145544, - -0.8569045280699509, - -0.7432991605539166, - -0.32854756072989155, - 0.153008815173896, - -0.8040362209721341, - -0.3363853455423464, - 0.3431538377082436, - -0.8227534967305767, - -0.7838126320460231, - -0.14726075032608024, - 0.7894218942050574, - -0.13444770075355805, - -0.5959266214802927, - 0.47052717430396557, - 0.35062467389816515, - 0.187391945716482, - 0.5025860819849027, - -0.8468435265926609, - 0.1991017080592005, - -0.21077481152813252, - 0.2744161600676941, - -0.9980012335702388, - 0.6590109469324898, - 0.45150188270712677, - 0.6645888449648466, - 0.2085499681439138, - 0.3168595429285203, - -0.2928358253544951, - -0.36472829231368153, - 0.6336112759497518, - 0.13527028386546455, - 0.10038343415774617, - -0.0806137958110731, - -0.33538790232187793, - -0.20439385065541804, - 0.28506484171099206, - 0.9420727313723356, - 0.17902883455060967, - 0.48958322175574287, - 0.7155302698866662, - -0.13576440135726134, - -0.24202062278234, - 0.7752379787458963, - 0.5177396070475366, - -0.02733090345964281, - 0.2257386893588496, - -0.8672625988220956, - 1.2152000914595262, - -0.14782103043584582, - 0.5427525547468874, - 0.20150568568996674, - -0.0767237966678069, - 0.5439428960024414, - -0.2560311531024653, - 0.9239691408074969, - 0.9536066103087522, - 0.5081405440047085, - -1.02367181616046, - 0.3611827291029796, - 0.24935384549345338, - -1.0103912561955293, - -0.17478392582653626, - -0.4394856576287452, - 0.09667870994489222, - -0.44585874158849365, - 0.2675047947606846, - -0.5449661365512515, - -0.012790536884581021, - -0.31792074455683283, - 0.2358193688184147, - 0.11467026482523604, - 0.3568892662775117, - 0.01717071224051155, - 0.3547371199674853, - -0.40532733985046987, - 0.3394981107037031, - 0.7858530263211408, - -0.5659573503510678, - -0.4817744315549516, - 0.45492684894251584, - -1.1595745829928421E-4, - -0.1654089777106352, - 0.07226347758958741, - -0.8558357140527267, - 0.5918617624340342, - 0.3152033270966913, - -0.6480034253257936, - -0.3644680900583909, - -0.49920682887609075, - -0.08342746283548198, - -0.0312888431543164, - -0.1108038740400521, - -0.27813476108508234, - -0.05217874084878623, - 0.014762279174314268, - -1.1193257380454775, - -0.5451922647681527, - -1.3789208482976714, - 0.842503974624581, - 0.1363206245611739, - -0.23680388804051455, - 0.6113136676245079, - -0.11190710484402867, - -0.15736454174380457, - -0.31051439662493663, - -0.15581090625083013, - 0.34876850701826395, - 0.33991721199984676, - 0.17859792203730815, - 0.7800323600601394, - -0.5697038038419023, - -0.6495442614205937, - 0.07152291096554532, - 0.31998738544058164, - -0.13376009619532667, - -0.5044105433611392, - 0.38563497691281845, - -0.22631982813377016, - 0.04829479714614775, - -0.06554965707907372, - 0.42152783294055385, - -0.35004783254444727, - 0.23098455778885213, - 0.834900073036026, - 0.5301533376054692, - -0.5206676930975196, - -0.4210628265515592, - -0.44971136646348003, - -0.443181658752685, - -0.070309740487359, - 0.9035740045773296, - -0.03757595114303451, - 0.7144453226485485, - -0.41196295010224215, - 0.4974814143716506, - 0.016626523409269515, - 0.34721717385576023, - -0.7322583237705423, - -0.3565579179537604, - -0.06644775969828873, - -0.2630457448367186, - 0.2315624081685451, - 0.0861323803935954, - -0.08923718730941113, - 0.5254286958542582, - 0.13436282097560973, - -0.0334957847446756, - -0.6408098226669393, - -0.042333284489823875, - 0.21573026182384242, - 0.23923950762900104, - -0.8757095983016141, - -0.5036336200829084, - 0.29559054864470125, - 0.04117507078190117, - 0.05460063203862095, - -0.5727858310511027, - -0.06003788749821638, - 0.2504705039980353, - -0.3698050595155861, - -0.3756851863454764, - 0.21242948200235331, - -0.7315945292879835, - 0.6918003915860473, - 0.38006951236484365, - -0.19897516509075905, - 0.12916054195464366, - 0.5196977463324011, - 0.3939751752175035, - -0.3123355329145355, - -0.05251455998080317, - 0.12556021920148913, - -0.4656026185305583, - 0.11852424982240788, - 0.466714544292596, - 0.37414257518862765, - -0.2533712212078051, - 0.08724011138779941, - 0.793330595760543, - 0.6372919983662313, - 0.17401917902216438, - -0.08679810954372937, - 0.002322171563408508, - -0.13725295840104712, - -0.11717578212444107, - 0.3631539937917358, - -0.07916803922272973, - 0.5215255385073381, - -1.4665896751882088, - -0.44995166791653757, - 1.038780011162494, - 0.911609071411119, - -0.19735443875558692, - -0.14368916643872748, - -0.06935344341037689, - -0.9350924088675734, - 0.6558615502317279, - -0.31321192669612624, - -1.0756451204472963, - 0.19708140655809933, - 0.17539529371020998, - 0.3555742250208546, - -0.39530584241690875, - -0.1756093783617431, - -0.3242261795394855, - 0.45660841672553265, - 0.009146389003239719, - -0.46744802905707983, - 0.7625951816450124, - 0.252488575926289, - -0.24436480533791355, - 0.21661998058937806, - -0.4482338866785615, - -0.8588269748980155, - 1.145118321036956, - -0.08097843145096537, - 0.4601341847407788, - 0.3948100480151731, - 0.16702749420762725, - 0.3018513648498909, - -0.4400089250512287, - -0.3988708691327584, - 0.15876642500655044, - 0.4463968764755361, - -0.5442975360196067, - 0.44757234602137563, - -0.35581732294060053, - -0.45877802248913985, - -0.01674842554855359, - 0.6425383758716575, - 0.18721888067846743, - -0.7473954872776197, - -0.11724073655748264, - -0.9208600056151802, - -0.27386809185190925, - -0.9125674654798034, - -0.1047213018866131, - -0.21785162016427564, - 0.172878738954347, - -0.08172099267505342, - -0.019280340631440174, - 0.20321473921332076, - 0.7516503865585108, - 1.0946380753195992, - 0.39510620185834333, - 0.10181329659593041, - -0.5424479571238633, - -0.3437241241179415, - -0.33209799291579967, - -0.35357532509095135, - 0.7232075377877607, - 0.01356161583343072, - -0.16695392840447823, - 0.19098860505614695, - 0.5911454583195964, - -0.4689035552651417, - -0.24600620018726085, - 0.26475613936571285, - 0.06111860186388969, - -1.0217232750319176, - -0.6896169636821123, - 0.7440448531928078, - -0.5379708446724466, - 0.7596339154885019, - 0.4164847036477266, - 0.4527531326135437, - 0.3463395896688557, - -0.029196273931151005, - 0.33695004945662127, - -0.05591114475514088, - -0.19446152141284387, - -0.7584936911580594, - -0.0949599513656403, - 0.18220126224143807, - 0.8626317734130986, - -0.6362243464003733, - -0.7007977910524299, - 0.6780156579735013, - 0.17623200180943635, - 0.5899284181873026, - 0.20827033977893591, - 0.1341655821752448, - -0.1738385326302753, - 0.06524054388433274, - -0.7914791182743541, - 0.23114122692197148, - 0.18321616302747037, - 0.0982179793655221, - -0.05707454126011096, - 0.32375378492686885, - 1.111185977788627, - -0.3401273205356177, - -0.6220040479683215, - -0.6718162264631309, - 0.239828836109992, - 0.3799250885138682, - -0.3804418477086159, - -0.6634457415113144, - -0.11523168226495499, - 0.4229757846707339, - -0.33158470344008756, - -0.1469749619475542, - -0.8518878287315873, - 0.5763381756373839, - -0.09639925969402943, - 0.07815878673909085, - -0.06150706857220479, - -0.08029110151168316, - 0.6215196412518922, - 0.23718511524268923, - -0.7067722099008557, - 0.4526998019704481, - 0.7024070136178067, - -0.28090285727995773, - -0.09773515014696618, - -0.6555651825652842, - 0.3321402988639488, - -0.26580376062659933, - 0.470014262314039, - 0.5660041877521795, - -0.5407047901187298, - 0.48673467172228313, - 0.5433129796045233, - 0.31811347029092324, - 0.5001937796908089, - 0.3520265287201373, - 0.45865210066345197, - -0.060427926864642774, - -0.2114983724516997, - -0.1296121208449373, - 0.3901334998880927, - -0.18607879965546284, - 0.01728925152958765, - -0.23575185246868915, - -0.8602283012719, - -0.4258650374899231, - 0.08232995888534789, - 0.6245420648914282, - -0.17456369632723762, - 0.2492445742636192, - -0.44935724587650194, - 0.08251120442462756, - -0.28569325209238916, - 0.6184536081961549, - -0.38290453800978524, - -0.3522536567944448, - 0.36168241673342044, - 0.32158989254422027, - -1.0047679998790062, - 0.5236147164715718, - -0.2367214809905328, - 0.6284102929730141, - 0.06647400515356866, - 0.18267513658523346, - -0.783457334908873, - -0.11768605364495068, - 0.12510400468089047, - -0.9477856588271111, - 0.08384144906316449, - 0.34038876756513187, - -0.0907709433535497, - -0.6741031176914399, - -0.4475988862881968, - -0.023554653581140603, - 0.21848427622474692, - -0.3938567451398739, - 0.48647050254821955, - 0.1666550919233633, - -0.012761851770200451, - -0.21882766707025303, - -0.05248947338808115, - 0.7836886355382918, - -0.0700513593731002, - -0.7103958130066106, - 0.4836104892610029, - -0.646604773214478, - -0.7714293235950663, - -0.2109361888416753, - 0.16505984938148488, - 0.4971815951792223, - -0.19560384700408234, - -1.2767234359430029, - 0.23015904434057985, - 0.39460827311931057, - -0.23228068731387683, - 0.5950575964709445, - -0.27462980882381766, - -0.6227272607832338, - -0.14999879955948173, - -0.6819734921387065, - 0.6519138123587889, - -0.03001154256673038, - 0.18248103000671007, - -0.04506756633605857, - 0.311733185510685, - 0.6552209999773051, - 0.147653994010542, - 0.5655202431905109, - -0.0329903928095445, - -0.8432744624624251, - -0.09363131420687594, - 0.0761777911607344, - 0.8521108429803123, - -0.4881718294668573, - 0.12507954057730472, - -0.7335750787176764, - -0.23407121016985752, - 0.4878623981186339, - 0.07294244198790437, - 0.06549599939049408, - -0.910672594991788, - -0.6896030329801914, - -0.2816025224512147, - 0.377920835276355, - 0.12803528865556751, - 0.4035970839068622, - 0.32315019154676133, - 0.06847259665297704, - 0.517401328550497, - -0.6085197885308148, - 0.5094349070583631, - -0.07498333477093076, - -1.4173598565994407, - -0.013171948605072545, - 1.276791352821259, - -0.10027368718020443, - 0.2563369064974001, - 0.09756155348393895, - 0.04064672389329554, - 0.06872516397052109, - 0.01632481819640155, - -0.7327694231226659, - 0.41363028515068345, - -0.3648612270824531, - 1.0734317671797668, - 0.1340114678919988, - -0.26764083209328626, - 0.14437309451475466, - 0.5461827828154427, - -0.4240212255881515, - 0.5549947071207366, - 0.2678734492020504, - -0.3143547235418209, - -0.9250666508760268, - 0.08745118138690493, - -0.15309717328187597, - 0.6132498760713249, - 0.6220037298230386, - -0.4266059919620472, - 0.03996735749234103, - -0.30960644321033054, - -0.5935577637119211, - -0.0664295661023027, - -0.4530277412284363, - 0.782226472120303, - -0.8251057670381734, - -0.12203613517324614, - -0.6012341620460864, - 0.22402863315881658, - -0.4620838125685489, - 0.8514465097504251, - -0.3590134364523141, - -0.7406551121728662, - -0.19490637819272022, - -0.06419067583321716, - -0.020883313849627667, - 1.1036680665551433, - -0.0727476502869127, - -0.15807922456346263, - 0.7162389582634741, - -0.40319028579502864, - 0.24110503312533998, - -0.9616582665233876, - 0.07706756316060098, - -0.25214477328110607, - 0.6027598660779756, - 0.6258116393134727, - 0.4000393082324752, - -1.1093082633906128, - -0.180683304538419, - 0.05871287109896471, - -0.5244947098579517, - 0.9701496126974338, - -0.36310127640694306, - -0.3286505477889763, - -0.16143240650474094, - -0.6312172537134166, - 0.13884052359895382, - 0.25712058079500794, - -0.15051545282470932, - 0.5841280621120951, - -0.4967757515775927, - -0.681575910184917, - 0.03081696690710492, - 0.6032844048142009, - -0.4436030394059043, - 0.28687176377159074, - 0.511097625418121, - -0.3972649152792352, - -1.5751755156038731, - -0.209528574182538, - 0.030296352427096628, - -0.0877802763874778, - 0.4856892140729886, - 1.0620340474667598, - 0.04560355497637868, - -0.6474355117558587, - 0.7103615728616395, - -0.5014329801136508, - 0.832714710694109, - -0.5429303228291606, - 0.9240706216768299, - 0.8176671276308436, - -0.046606202109693656, - 0.09650286265970884, - -0.13246773171117898, - 0.4510483849213636, - -0.16948269339454217, - -0.8477180816937552, - 0.7797325086499212, - -0.6367443436688749, - -0.6775956146881843, - -0.36566007218225155, - -0.9798479865265017, - 0.45774649391123945, - -0.15663984338569717, - -0.05054852032646836, - -0.34923188321924203, - 0.17141728169850626, - 0.12872278620221236, - -0.17855060550653395, - -0.2407534498598676, - -0.28124203597355985, - -0.05308762729109838, - 0.18551947882207867, - -0.8754883495043346, - -0.12036947094802675, - -0.528661316293109, - -0.387182305660987, - 0.026403877861405627, - 0.6412398830735127, - 0.5144039247839122, - 0.27977993189818945, - 0.7097478046334266, - 0.29127759421644717, - -0.42874766569802236, - 0.3718743411662989, - -0.5680216541726988, - -0.2354845439671175, - 0.7645075708549504, - -0.11276716624173076, - -0.03691748334149052, - -0.9113360777638024, - -0.5363316702014732, - -0.0313972075022165, - -0.43852726544401266, - -0.05297138245296899, - -0.4590939960589609, - -0.10534145035146075, - 0.37367431290957964, - 0.19525571377992287, - -0.28287917764400156, - -0.6332229814484742, - 0.3175464091673168, - -0.2282787118930688, - 0.14607157907486099, - 0.7095777993669959, - -0.4032368265100457, - -0.30403027415678247, - 0.410752521078759, - 0.6392618879493231, - 0.1864672669087524, - -0.21210121527663667, - 0.2924764551144565, - 0.4890026979726461, - 0.19933483542118136, - -0.3641535997172094, - 0.8422377964245344, - -0.46349772982996457, - -0.48628702263859463, - 1.0324503360089203, - -0.3380450024553553, - -0.050454212601193364, - -0.6995234240616538, - 0.12382839485969599, - -0.8128796006631055, - -0.23292502448794591, - -0.7139739392309751, - 0.23328061326637475, - 0.1262114075673982, - 0.3717728198669782, - -0.5851428799433248, - -0.17567918149240777, - 0.07582797984025261, - 0.0608918522610429, - 0.48771355042968423, - -0.29379348604498035, - 0.7978986711751586, - -0.7968706966473663, - 0.15366711981548908, - 0.1822578654084795, - 0.03843292884400496, - 0.32999275504921577, - 0.17718680191575648, - -0.4240976059824379, - 0.08698798803852363, - 0.6761792026960439, - 1.4509614057093239, - 0.0747481913728879, - 0.50165017139505, - 0.5964564999657626, - 0.6117360184753181, - -0.4486284920372023, - -0.19051418535865702, - -0.0746785726619179, - -0.27973811603301757, - -0.3395045934317218, - -0.07325943764827593, - 0.49778771679966005, - 0.3030001845008675, - -0.36948742713770716, - 0.13389746100736166, - -0.5426069962688149, - -0.5112079534351525, - 1.177390601482372, - -0.14709295074905498, - -1.1857547878593313, - -0.6936032944321014, - 0.40447742199575515, - 0.4267203600793748, - 0.7404066420744362, - 0.6235417653881472, - 0.44388364917654505, - -0.06639340199862723, - -0.06880505788879757, - 0.5168220141919477, - 0.5232893212361187, - 0.18712589760323592, - -0.11046257067340699, - -0.0032565065830755372, - -0.29755052497372164, - -0.2791963323193198, - 0.2048061196042408, - 0.15160007144415566, - 0.4840547337907758, - -0.7847811626837707, - 0.006828997394177513, - -0.11065483141144339, - -0.030536241661434083, - -0.04372406505563321, - -0.336891728517789, - 0.13853434579638813, - 0.05956977202940873, - -0.770705715240804, - 0.3152744657159453, - 0.2960908209464067, - -0.022748947045715465, - -0.7881263139529932, - -0.2524313299934408, - 1.1702142149043016, - -0.13280842817534164, - -0.14067748964987353, - -0.13543939833371813, - -0.4255319096185529, - 0.7184166014007247, - -0.253156388531516, - -0.8793508844440259, - -0.17293709320281886, - -0.09958466423987074, - -0.004709639354747918, - -0.10959021474954102, - 0.259358608046494, - -0.5228857818246252, - 0.6227181813938895, - 0.17152035424889858, - -0.1262798986175739, - -0.3512405915808945, - -0.5213068433876017, - 0.4437742812287624, - 0.5721251114293866, - 0.5254061003018089, - 0.611661238109802, - 0.38214358216542177, - 0.06554801247741072, - 0.2884390427958489, - -0.43161555812453506, - 0.08658613453348951, - 0.6426945678086934, - -0.5293348988522681, - 0.43404963062658186, - -0.2157588959447191, - -0.07591807714166189, - 0.43173158478608525, - 0.21985295236056068, - 0.22674516501848838, - -0.1612056759153861, - 0.01311576386664337, - 0.9356029602049314, - -0.49602270449050984, - -0.5112364461839168, - 0.5037222384222496, - 0.14249945519969898, - -0.8621552074200709, - 0.29397856400074224, - -0.007811036606722055, - -0.25451483241209044, - -0.19310219146284843, - -0.6340128806126176, - -0.5198544565207726, - 0.01826115148079571, - -0.15628993556778495, - -0.44285320887168195, - -0.2801490671193716, - 0.6921319143008946, - -1.4316373742063078, - -0.020021453904491948, - -0.17614140145527127, - -0.070936752164447, - 0.3113280545020903, - 0.7410798782559488, - 0.5977325886408298, - 0.8151077629912663, - 0.23433799162921964, - -0.6038138651220689, - -0.6187298226701177, - 0.21400024645040322, - -0.18428338544528755, - -0.35169714692262627, - 0.1452892986210685, - -0.5756945104939302, - -0.40281576642499367, - -0.3142471624864186, - 0.29177246721727806, - 0.2007035525932184, - 0.48085250545015185, - 0.7590247830834684, - 0.954364863244428, - -1.1048567154220874, - -0.43577329626326733, - 0.08510374865819167, - 0.41509511846209063, - -0.2744206446426167, - -1.3205752224870186, - 0.13350756866201927, - 0.6747961396840011, - -0.40966221889063803, - -0.13634348523483936, - 0.2119567936772304, - 0.9679581333239415, - 0.49185844714333, - -0.4063501334693813, - 0.2162342722222803, - -0.1701992042866548, - 0.1188790100582231, - 0.4513680832626596, - -0.760230169948003, - 0.8588335829609166, - -0.3396816897588314, - 0.2405893439130126, - 0.18930257128996691, - -0.6013724130711863, - 1.080411113904536, - 0.9581508609259503, - -0.5743535962758062, - 0.7524733711889123, - 0.5695491424580847, - -0.011772447839763592, - -0.09153066099898773, - 0.7452276267697916, - -0.18484430031470986, - -0.2059305030060334, - 0.3460864475702802, - 0.1542861696561623, - -0.36953040015110117, - -0.07472114505399985, - -0.29313589233986964, - -0.4598551172234108, - 0.014610849617448239, - 1.0207727843302563, - 0.9789556523104779, - -0.1975375142663491, - -0.4617852764949311, - 0.3111278119673187, - 0.24597816435213152, - 0.552245870965368, - -0.0914332920414296, - 0.01254253496564698, - -0.2139118804949628, - 0.4666454327360651, - 0.21873488133514798, - 0.06340043030176139, - 0.30855309502025124, - 0.11333483075261891, - -0.17384708375592206, - 0.8555901044907039, - -0.360648186818699, - -0.0018990473261746924, - 0.8619082410108906, - 0.18316576008187183, - 0.16898526624110374, - -0.1472898831052865, - -0.27763731461808167, - 0.37244110587496554, - 0.09947539711373854, - -0.39759312002123137, - 0.26171333354740006, - 0.6106026472235069, - 0.18112746009435807, - 0.29383047201704193, - 0.169873904986124, - -0.3272168493986347, - -0.027966153985505865, - -0.6628342291207348, - 0.05301932204352518, - -0.39657723252721044, - -0.13624491994448604, - 0.017654875078349192, - -0.009416446776719625, - -0.9208548331049673, - -1.0819350802984256, - 0.27375550610757965, - 0.137119656370571, - 0.9597069821070661, - -0.06276598934713953, - 0.046701141651870615 + 0.22581057491713455, + -0.7555525299494774, + 0.7061542631836198, + -0.14251526530817654, + -0.49902536922290436, + 0.49808482019565015, + 0.7142698584858577, + -1.1030357294605402, + 0.8354273265850677, + -1.1737044069715559, + -0.5087943004780094, + 0.338348682442462, + -0.7616186659470676, + 1.359895585386145, + -0.40555331197136335, + 0.3452102936077957, + 0.5866814313646292, + -0.8456938382324591, + -0.7226873124027765, + -1.1070210534479732, + 1.4555411613442424, + 0.39024613138822334, + -0.8755171226968508, + -1.490070462359629, + -0.2749173907473734, + -0.6702503971070106, + -0.07998492373744431, + -0.3705417147503839, + 0.2724774132119271, + -0.6817898413821614, + 0.6824369269820013, + 0.6008578018322807, + 0.44817308212443424, + -0.5437002027793826, + 1.0065576557261782, + 0.36688553779800387, + -0.7008966531612852, + 1.1900149391519126, + -0.6835238906995311, + 0.6635030833158693, + 0.371887976564945, + 0.5561890843522083, + -0.7098949338247245, + 0.4983879583393943, + 1.1073292425577854, + -1.8864941628707539, + -0.9157104181248075, + -0.7614840063589026, + -0.6037954479033565, + 1.272872703315874, + 0.3740691039985632, + 0.0863099547293534, + -1.0116568545919549, + 0.7799348927833867, + -0.7043751322419637, + -0.08694458511522828, + -0.5362685166161957, + -0.4026267209020467, + 0.051873049661518365, + -0.06765064694659792, + -1.2317098887120155, + 0.3880981630950874, + -0.8146979696814807, + 0.34669233886586387, + 0.41276110432715857, + 1.0064895060536019, + 1.0676877865376224, + -0.4238712073885056, + -0.4692570644992179, + -0.1324125890387308, + 1.2165195795047705, + 0.550713932383961, + 0.7153909821784352, + -0.5150588100820731, + -1.3897976150606455, + 0.7516509921827651, + -0.0817130582200184, + 1.1758564722576983, + 0.9920852010237554, + -0.7335925532036951, + -0.8010509489955293, + 0.35676432351141635, + 0.7087288245790081, + -0.7269177525652983, + 0.48316317001281167, + 1.0090456271988664, + 0.6417867550326055, + -0.015257847830362813, + -0.5579121373092467, + 1.334179361708464, + 1.2576153223623432, + 0.4203074874025029, + -0.8169693904121051, + 0.22127882039346372, + 0.1864403246189347, + 0.1892222317067498, + -0.8585267877958156, + -0.73824601503979, + 0.043203740878487676, + 0.05976595600794346, + 0.5261161914707796, + 0.05459848631662281, + 0.8142284701960866, + 1.1775008077482425, + -1.7129966555936227, + 0.5392137283668005, + 0.843815511957197, + 0.29610215011004415, + 0.010076698023272365, + 0.7989359456424733, + -0.2815943341510233, + 0.060063191965934556, + 0.20279760251420467, + 0.929976027745352, + 0.985550148186668, + 0.01643802474185192, + -0.23270600995770813, + 0.2229492860545625, + -0.12635979664555114, + -0.33387213960733203, + 0.27795688518645384, + -0.17508795369203964, + 0.8622069455482206, + 0.8369705202290594, + -0.5208180341905181, + 0.6156412922969859, + 0.42234273140315637, + -0.8205162022484536, + 0.17043714014643982, + 0.27318959190130787, + 0.9413071679261175, + 0.7039346254644773, + -1.148157225953073, + 0.45167277477908346, + -0.9411999755700768, + 0.3188119056130634, + -1.4172685658681328, + -0.2165631652477366, + -0.03487709736178642, + 0.11954521216605046, + 1.1524294060032279, + -0.8800339877873813, + 0.7875617610848998, + -0.2623836882730456, + -0.48707882501285626, + 0.8284434730987982, + -0.5665121935067422, + 0.7121491236511686, + -0.4398810039989182, + -0.2785586416816685, + -0.9289750855525667, + 0.741023736238737, + -0.25099304001439837, + 0.9786387275465588, + -0.7959486803753459, + -0.22671534175766622, + -0.2746817285805446, + -0.7425732308535506, + 1.047137573752546, + 0.44944721666083465, + -0.8866101063131535, + -0.13527251784871677, + 0.016541186519590086, + 0.23534599988348684, + 0.3293233355637657, + 1.2224222043976736, + 0.5425720071517154, + -0.1280049209984564, + 0.001954906746421222, + -0.6009086802039767, + 0.16384335679273568, + 1.5803708057165295, + -0.28989263189086, + -0.1301239663211736, + -0.16463503091997453, + -0.30443291610618034, + 0.2985409154238687, + 0.19531598620970717, + -0.21456932917972713, + 0.2500909060962191, + -1.135796520481747, + 0.6188216892289365, + 0.3307002800510084, + 0.24302926903883282, + 0.3685656400089314, + 0.27293395040415663, + 0.02455066237522903, + 1.397736507042045, + -0.1806759448304557, + -0.8717818303869675, + -0.6338053892215219, + 0.4472063655658238, + -0.9065170445529103, + 0.3423070939100835, + -1.3207380541952656, + -0.6586629756222226, + 0.4784879705542129, + 0.8611123262251095, + -0.6486491304755804, + -0.056746238794017814, + 1.2859551868123924, + -0.32955356162878274, + 0.45548904663402273, + 0.8245109405028375, + -0.4691995298001649, + -0.19701317827327966, + 0.12205905283070795, + 0.17462383000119264, + -0.7055472335608791, + 0.1299135712172751, + 1.9648533012399907, + -0.9403371500631832, + -0.646381722278297, + 0.5506873318561567, + -0.5675854454899318, + -1.0862346998756935, + -0.9228663038611096, + 0.010263563924376606, + -0.49808937027175443, + -0.6395213330376674, + -0.2635271427689068, + -0.8100371164587012, + 1.079023163150245, + -0.11295304746255676, + -0.3691110411298641, + -0.11834567007635845, + -0.7452955418987628, + 0.5915537788963555, + 1.0123314803877685, + -0.076155767563474, + 0.5559717690282117, + -1.3868680777093125, + 1.0110250526115623, + 0.9019604875825002, + 0.6611993272164889, + -0.17391310525384215, + -0.5443946356373669, + -0.6843010586406989, + -0.23277252710922183, + -0.18576216029402462, + -0.08450657355518323, + -1.0246767240345434, + -0.8041241286043328, + 0.3673925893668525, + 0.530213083167197, + -0.1900178597680876, + 0.35771637689415103, + -1.2757172231761582, + 0.14380347153636755, + 1.2952558937606042, + -1.4890814520863103, + -0.5621138799608508, + 0.281919361478034, + -1.1979452653763896, + -0.17691580655744107, + -0.5087830784588762, + -0.5095606386070051, + -0.6332914807548731, + -0.9728811839814172, + 0.6688601649884033, + -0.13408256293210383, + -0.6739136941705696, + 0.11757512907418821, + 0.5749907695299332, + -0.9938956377761491, + 0.10261734783947324, + 0.2535253363451298, + 0.08552041955220045, + -0.4469264054699886, + -1.7246017682372727, + 0.13284389619069248, + 0.0491883392943624, + -0.9874234908854084, + -0.6956412808914685, + 1.0249374246163798, + 0.8846557705619997, + -0.3897796061691658, + -0.4246759751842552, + -0.9375603681431798, + -0.7069207650803873, + 0.4852605420247119, + -0.8376977090476627, + -0.4211325533573659, + 0.7289854383714515, + 1.0182040447589418, + -0.76056864447848, + 0.7933754159223438, + 0.8497946768955317, + -1.1196725024682328, + 0.9034078133318303, + 0.0612195863183778, + -1.0505219002817943, + -0.07153014833423438, + -0.10404723244436741, + 0.7407384504362097, + -1.0927127138756534, + 0.14158344021663313, + 0.07327684699513348, + 0.11411333298973687, + 0.02550415664275217, + -0.10225576519178894, + -0.07948288042697577, + 1.2458958743494382, + -0.29194926995511195, + 0.1448199977196793, + 0.3406474058451205, + -0.07562839085124551, + 0.7961130070965331, + -0.02311917278020422, + 0.7733280529853241, + 1.3703058387731841, + 0.19873837945184925, + -0.6714479272203295, + -0.430123777121825, + -0.5709069894296309, + -0.5470078603960333, + -1.6443650075918779, + 0.9460515490573355, + -0.3560894182985467, + 0.8376152181461695, + 0.7402722323827282, + 0.35465701241556097, + 0.43359749831275923, + -0.1536049810249272, + -0.12821278460719376, + 6.49196777831491E-4, + 0.46561281981544644, + 0.24111366415038518, + 0.35628928492539463, + 0.0623387256635804, + -1.1380471706768431, + 0.22405928818903006, + 0.3824119581911595, + 0.9332116993414362, + -0.12611917328989006, + -0.978643116734847, + 0.13359853166678054, + 0.5314424116584618, + 0.6333824459796656, + 0.06231006248323324, + 0.8676200901796222, + -0.8708879752393366, + 0.23274772671841587, + -1.0191816836094563, + -1.4174230706981952, + -0.5280675772527871, + 0.15162815468513977, + -0.37920194343486185, + 0.2941610870184977, + 0.14728913361810067, + 1.8274401721118496, + -0.8123796173776915, + -0.556700386909594, + -0.017440315525096964, + -0.6567944243180327, + 0.084308141461343, + -0.23176343464131707, + -1.2401283485849333, + -0.8232509030499763, + 0.5343647887511552, + 0.6018538677068249, + -0.03466287181104459, + -0.909606757431864, + -0.028397673872803727, + -1.4140060174965372, + 0.8939158319499381, + -0.8146770808355384, + -0.23329157237371803, + 1.2718140057358542, + 0.2337631325617532, + 0.3211474277859989, + 0.44523823816414093, + 0.07989423749448611, + -1.2276507561777295, + -0.5379388201664222, + -0.5017519170155844, + -0.13821153238288536, + 0.05585924621849932, + -0.4005268439820973, + -0.23282171147698186, + 0.17281351707649728, + -0.06144934176114243, + 1.509815080691037, + 1.1403093674820928, + -0.18420679845210106, + 0.5773301136685434, + -1.4000423272233178, + 0.30051378019590297, + -0.27220135566704917, + 0.9616441127407971, + -1.1490713111477135, + -0.9203356721101424, + -0.1003525424855048, + -1.4364776663047742, + -1.001226553794056, + 0.611824565898798, + -0.6765344191046045, + 0.4256003540677437, + -0.4982806868133972, + 0.2746631415435092, + 0.05589120630033349, + 1.2970754119245622, + 0.4356403619037077, + -0.14125991488118445, + -0.05961435337479555, + 0.7367662127966675, + 0.3726109422765364, + -0.03533577400832389, + -0.6907012751606492, + 0.3255737618453472, + -0.25764736032797636, + -1.1962627046759193, + -1.0574399611592442, + 1.175076141840186, + 0.3414532622280549, + -0.9217332312140928, + -0.3145901852671427, + 0.4503573942165019, + 0.8225031665325426, + 0.1785429175876435, + 1.9503315920545632, + 1.058741356376456, + 0.35182248120380294, + -0.7568249929760497, + 0.8761124653145035, + 0.327272777048996, + 0.1402861932587994, + -1.5266398409081976, + 0.1816471525029312, + 0.957917196315535, + -0.25451221636511645, + 0.6539944689458818, + 0.3851947124728646, + -0.09158079160724909, + 0.600106083617232, + -0.4816649661417832, + -0.9697757868121046, + -0.5395085769864477, + -0.2898051299514991, + 0.6002629575457717, + 0.06699931245679014, + 0.022237313295914527, + 0.25616169382912635, + 0.9351008932144117, + 0.9563287876025994, + 0.7420811483222566, + 0.08939713240650962, + 0.37632814430903005, + 0.413092766399279, + 0.783979108571533, + 0.3560554358959674, + -0.4556981066139604, + 0.8203292299027013, + -0.4115678953763108, + -0.5318579743683625, + 1.3023397151245875, + 1.0902867769137505, + -0.6119168878025163, + 0.30999607098124116, + 0.6926755519999811, + 0.384096283086795, + 0.32489992263816864, + 0.1299607519416957, + 0.11803294550307544, + -0.12532252643427366, + -1.2854100740495062, + -0.18150156929449535, + 0.21903106419232887, + 0.501503816898262, + -0.99918686966443, + -0.327998709849929, + 0.007553477881515701, + -0.2502236609772384, + -0.5794048080540146, + -0.6172771200722736, + 0.5269063018773714, + 0.42622109936220076, + 1.0540739030930986, + -0.7938729006801694, + -0.3662477719750114, + 0.461299785119118, + -1.0440737404144884, + -0.6410398987913348, + -0.631684226490742, + 1.1785267774204573, + 0.36256695630386815, + 0.6338799113499919, + -0.6257745511615775, + 0.0651180904263486, + 0.9259553448929975, + -0.34959142414515654, + -1.152383681562509, + -0.41063591392446425, + 0.08276871850189294, + -0.32479036907195286, + -0.5585471991028644, + -0.8451778644757777, + 0.9191318778449474, + 0.02558043263572796, + -0.2676354209535612, + 0.4497435392476262, + -0.7712835228191226, + 0.5639542117200494, + 0.8096078281117319, + 0.8363083672356082, + 0.5775603371963004, + -0.36407230352730335, + 0.6220020001251491, + 0.5530522629604667, + -1.4961709489310173, + 0.02899562401342768, + 0.6483090671245396, + -0.18925856487240336, + -0.91455133413417, + -1.2458285253180086, + -0.4088913068275607, + -0.6639236911018132, + 0.6496268084497087, + 0.8748747624350439, + -1.7538502053597902, + 0.32527368352582053, + -0.3905816685411035, + -0.32588477173291347, + 1.3965951261514113, + 0.2782696928449692, + -0.8293903282251018, + 0.8913478195938188, + 0.28780403974146695, + 0.9001838146802946, + -0.8208568712371727, + 0.6755223899533574, + 1.1719216181107925, + -1.1998567024506799, + 1.0108125345445964, + 0.32919189603391213, + -0.05433668989182214, + -0.900280237084277, + -0.01514848858602373, + -0.25581664388619213, + 0.5506287109450075, + -0.31471828083078834, + -1.6571013982280876, + 0.3197521353079883, + 1.0005708863878893, + -0.5819557982377349, + -0.5808946335237062, + -0.8425390030865211, + -0.0933837971241486, + -1.6717526486262964, + -0.33559577299496013, + 1.084272757407083, + 0.1259769545589422, + 0.46249789310422373, + -0.5879614134278448, + 0.2559706854976619, + -0.5127489360058787, + -0.31541245795248696, + -0.9658858113054846, + -0.9420957413925777, + -0.8283979800883676, + -0.06783887979452527, + 0.13198744553710548, + -0.8583101709132408, + 0.8208282937008239, + 0.5608682931346576, + -0.025197378962191895, + -0.9647085987028116, + 0.3103635091198763, + -0.5738424597452569, + -0.45102256913671607, + 0.36970597662799604, + 0.11714409644908041, + -0.1973155155056156, + 0.8141909546570981, + -0.1675621275746925, + -0.2381579815921225, + 1.0591044278935913, + -1.2744616987229391, + -0.7079124377208975, + -0.530610384151215, + -0.0605283154883338, + -0.07688393735758133, + 0.3683203794030785, + -0.7852457829626989, + -0.6363760045845597, + 1.3833091396486403, + -0.29060003407533486, + 1.5224212265283763, + -0.6395253321332137, + -0.34457755419900743, + -1.2189201890930992, + -0.7720801671998679, + 1.026120872004667, + 0.283199536625748, + 0.5812393544373742, + -0.9007446158623735, + 0.8607664668710883, + 1.1241089893590812, + 0.7912616088808438, + 1.4096102307347647, + 0.028648161939558776, + -0.2777442336392911, + -0.20838502750143068, + 1.678808105525636, + -0.4239822290469965, + 0.8750986544646978, + 0.12262395328937312, + 0.6752763418073516, + 0.5163960742001409, + 1.056870549578979, + 0.3353915737630295, + -0.2584178059659167, + -0.01727983470092072, + 0.028429339791272875, + 0.601167472703748, + 0.9293816164473908, + 0.7393664542950381, + 0.893894654560316, + 0.9340677011225839, + 1.5333776711853986, + 0.4221756936825875, + -0.368794189368784, + -0.23671056296914342, + -0.11318492935018513, + 0.3483082020103635, + -0.23502888798575983, + -0.33329867386200673, + -0.8826633712406937, + 0.6717470662969026, + 0.05828718094625693, + -0.2206703009604105, + 0.42084267273266024, + -0.0339740603892286, + 0.2565489978655381, + 0.0778869582208532, + 0.5517045414619153, + -0.4712984454852447, + -0.9200159043081717, + -0.23309842573675751, + -0.49189502201513735, + 0.4609346453299388, + -1.0701074907388946, + -0.626614009925888, + 0.9813458910283119, + -0.1351821586051257, + -0.26701433839613026, + -0.3358908060434502, + -0.23915561158893053, + 1.7850911895852795, + -1.1703108733427277, + -0.7706151388400482, + 1.1963004122938996, + 0.2470977973840883, + -0.31151912653781905, + 0.9083925253257805, + -0.1471144766031167, + -0.3288720215603332, + 0.08555919161064852, + 0.7202692882346969, + 0.19240608354864455, + -0.053529432542048894, + -0.42058244919372223, + 0.2596422747690001, + 0.8894159221980785, + 0.6086295707374386, + -0.539538209612982, + 0.8238540332302681, + -0.9950340409941782, + -0.8944278442088213, + 0.48988787574596404, + -0.34766525511485996, + 0.7834453996364572, + 0.825402318064817, + -0.2763513868532986, + -0.026507324901821457, + 0.09849317928527006, + -1.1167407247292296, + 0.1673932649627926, + 0.8572315280834386, + -0.60357786464392, + -0.31632710737924974, + -0.8820815804816532, + -0.7316103055060604, + -0.5376750718481408, + -0.8076820105227237, + 0.5369373510473556, + 0.9253082163313726, + 0.9772504454893794, + -0.10035983781712543, + 0.38175244020941884, + -0.31000075380174874, + -0.022621946766257294, + -0.42397131763726625, + 1.0190382311215205, + 1.2880661625597927, + 0.2173688837281541, + -0.9047889473325674, + -0.12121469342973681, + 0.0392708294817509, + -0.05315110596560169, + -0.2119272181457451, + -0.6303868947708517, + 0.5983827732091003, + -0.10633944567939747, + -0.15160095827295847, + 0.5035245021562633, + -0.22316542996834488, + 0.4865548338774132, + 1.4406480446424332, + 0.25635178707954676, + -0.024640274557348078, + -1.4575704865806178, + 0.5970418579037489, + -0.4955006824705506, + 0.5568831132948406, + 0.20567714525519346, + -0.444099025218937, + -0.028606981722013456, + 0.324759932879378, + -0.42951372302483304, + -0.01133268649808806, + -1.5859109106041736, + 1.177168811805723, + -0.8753854736095613, + 1.702246061892162, + -0.9875627714858153, + 0.41373624141176274, + 0.29618185531009894, + -0.654174310458635, + 0.1328581514331377, + 0.6792914981732645, + -0.07210221821442975, + 0.19429672578789908, + 1.0226729378261623, + -0.7688122498210705, + -0.42798936368356616, + -0.7613872043755698, + -0.005314749267161489, + -0.7860868614171456, + 0.6556729492171747, + -0.5997134486900979, + 0.3657367351726428, + -0.3383483611977645, + 0.6693781117952465, + -0.6311124418194285, + -0.759425039316103, + 0.30715142490546876, + -0.09726946438438668, + -0.5089184967265056, + -1.7676179632374347, + 0.17653579676512388, + -1.1257657808085701, + -0.4877223625343806, + -0.8428061615626831, + 0.607434571901166, + 0.32021647524600505, + -0.42767578268381523, + 1.6781122647662745, + 1.3995147235543668, + -0.525581021726249, + -0.33197411338812877, + 0.3374374381303774, + 0.09434086973794019, + 0.473360745623101, + -0.27158616688047926, + 0.3624479892635374, + 0.024591267901440977, + 0.23757319773550215, + -0.727382560914306, + -0.33101559064460534, + -0.9872883815605951, + 0.30187007154967216, + -0.8419985008230509, + 0.006779742378594004, + 0.42805822236624536, + 0.25704974652601287, + -0.7277156809396401, + 0.5180473348518403, + -0.47808901596668696, + 1.2542759113985114, + 0.16756080999391948, + -0.36315993045796324, + -0.42736019964488864, + 0.7388606405115329, + -0.3907619871808913, + 0.2967166185257014, + -1.7035115840875255, + 0.7983206440165865, + -1.1156167621376984, + 0.14798479874966913, + -0.5954513537004886, + 0.9775324397744445, + 0.9041130672115311, + 1.0333211279705554, + 0.9369820911728406, + 0.5704177437311566, + -0.37982737597297256, + -0.8069052611710181, + -0.02081673703928856, + 0.3703370270104549, + 0.4460603064237247, + -0.6769964364189409, + 0.6079572489850419, + -1.41707958850137, + 0.10799479541620641, + 0.01035776533718632, + -1.00708446727484, + -0.47414326896088127, + 0.5397979734520985, + 1.1686015571376658, + 0.2689570309241253, + -0.10692406820655266, + 0.9048532588922983, + -1.0744646319458973, + 0.439757289965748, + 0.5310510681332139, + -1.023314036225095, + -0.045337474209076384, + -0.2729572573296618, + -0.8776813706518083, + 0.6774535169695244, + 0.6743253590081912, + 0.5838913579119881, + -1.1548115757312352, + -0.10439345935638797, + -1.1173507621383476, + 0.5525220521876202, + -0.8349367388250455, + -0.05059244423410762, + 0.3839577585046987, + -0.3530129383604799, + 0.9350265974499704, + -1.0748000475112676, + -0.6924112921651915, + -0.2393969690505475, + -0.43749949286825457, + -0.869175432112403, + 0.02891999600589748, + 0.40731974899826257, + -0.7494511700715862, + -0.6675961329527746, + 0.6115450522621351, + 0.33046633998389013, + -0.6566671325827715, + 0.169952477407331, + 0.6550463729828243, + 1.2983146377901527, + -0.1601259543088185, + -1.1053917097399992, + -0.7295514539327685, + 0.8072821518935439, + 1.5547501869812532, + -0.5295070351520885, + 0.826702955312558, + 0.7939999973874061, + -0.19988795515380528, + 0.2800284718619882, + 0.775291729961488, + 1.0685573371166799, + 0.051559646193605785, + -0.41401482581819515, + 0.3600648698166844, + 0.41659746450779567, + 0.39756176479507876, + -0.5362735712329036, + 0.9466402761833356, + -0.8209360364880305, + 0.006182899884917939, + 0.8999301932818933, + -1.1106635876542978, + -0.7123116071630884, + -0.7098451181015517, + -0.14890566143977763, + 0.11036374252550857, + -0.6454050026563863, + 1.147775203217776, + -0.7211397986028572, + -1.339451742228596, + 0.3746310728439534, + -1.3583172173087137, + -1.6446577337571717, + 0.6161367952985476, + -1.1425130228482239, + -0.037570210730017865, + 0.4030134883812271, + -0.400686573145709, + -0.7082801079830241, + -0.16429907561451262, + 0.4618083202950133, + 0.0190658383939589, + 0.1836329677956855, + 0.1649592148102684, + -0.15592901244541274, + 0.061412668030431536, + 0.34596319857240754, + -0.1830411372993747, + -0.7497688161651386, + 0.5013741127483994, + -0.5538710906363148, + -0.2220558788214132, + 0.497350629430469, + -1.4431642117570103, + -0.24877111641284122, + 0.3440172430361173, + -0.8295403893028395, + 0.172123278157397, + 0.21451093449408556, + -0.31758667277136887, + -0.0036267030511498073, + 0.027501333617553442, + -0.15810261830157532, + 0.3591977179010084, + -0.14848741622265982, + 0.43662115612054697, + -0.851068220950414, + -0.9534589099828956, + -0.9813458151449947, + -0.3843146098194592, + -0.94399321918055, + -0.7397762419110041, + -0.6102789623994576, + 1.8334497213022811, + 0.46543551882337325, + 0.31389385872707887, + -0.5426072304634011, + 0.4500130914153145, + 0.5883897446292493, + -0.08317163997718037, + 0.2580906676581969, + -0.26088899013053884, + 0.8445533373592534, + -0.29536381304803927, + 1.0963251028668035, + 0.4986561385149771, + -0.2788433874652022, + 0.4010668858410041, + -0.4573190071763419, + -0.6801845619505689, + -0.5902456520689139, + -0.8166041000424777, + -0.7541765883557234, + 0.4041150956114814, + -0.5615630045880211, + -0.6912982906495069, + -1.2224009036046963, + -1.3326604694230708, + 0.47223477905863914, + 0.9508568531476248, + -0.2570774162972418, + 0.45473992341038344, + -0.23011309504804203, + 0.34777872951888394, + -1.2950829266528014, + 0.4158401022337146, + 0.5873328921499591, + -0.3269706324065838, + -0.044137633812677546, + -0.29250827049589045, + -0.4383112410690243, + -0.20575529961353933, + -0.889158779424565, + -0.5359509556427238, + 0.12019663410873517, + 1.40357325217853, + 0.19168301312084948, + 1.1559201689467602, + -0.6673517788123999, + 0.6079219849799701, + -0.15661210754059426, + 1.014541470323748, + 1.4486199131069313, + -1.2688402472467732, + -0.33022375180663344, + 0.835774457458948, + 0.3734823394630973, + -1.229913930469054, + 1.0759472310725982, + 0.021414460631092973, + -1.0562104091504487, + -0.036754652870054694, + 0.26838167946191005, + 0.14195120865801197, + 0.3795118673864675, + 0.5105512354491412, + 0.3482386580546316, + -0.3647201016428821, + 0.2815544011440519, + 0.46626693321682033, + 0.5941789677415064, + -0.803181420888348, + 0.3642983159049418, + 0.33588266633554203, + -0.5161049046917251, + -0.5591030556262818, + -0.11641258497321476, + 0.22857499468428205, + -0.2862321831587048, + 0.5591848309598676, + 0.41547455119771637, + -0.020038967285205607, + 0.10900646118716517, + 0.7955892457913483, + -1.0943722601701702, + -0.4345894099001662, + 0.24211594391732613, + -0.459438808437112, + 0.8029519320384176, + -0.45359842932903977, + -0.8592541039020927, + 0.4675739484627175, + -0.9043728824190049, + -0.9675602710110005, + 1.012560313430148, + 0.08047390503749473, + 0.10958105746928024, + -1.1089214145879027, + -0.6803275828638772, + 0.3238795314519774, + 1.0082707155704338, + 0.0949440620922667, + -0.32069791862153574, + 0.730444545643361, + -0.4132797223686762, + 0.08074618046890324, + 0.30652463771685506, + 0.22163581519772008, + -0.8007704142836509, + -0.10563501060022991, + -1.1131642543050728, + -0.13555300608738632, + -0.28207194855306655, + -0.7680194441633573, + 0.5546473584862986, + 0.9074011370576573, + -0.5239359596456445, + 0.5839651201471265, + 0.7839720646600637, + -0.7970842175707351, + 0.43474100329953946, + -1.0706700029132352, + 0.03697382011460123, + -0.931250696165399, + 0.360075579911591, + -0.08882376119445384, + -0.589607000589516, + 0.33040461026310675, + -0.07419710368754553, + 0.2628970334325892, + -0.8046846836378863, + 1.1263553136607716, + 0.8484626855602659, + -0.09528479896997293, + -0.26086115901095713, + -0.904939236161272, + 0.5105288472758391, + -0.044989952000329056, + -0.8654894357871853, + 1.0036600952506174, + 1.050985156138883, + 0.5146626633365701, + -0.2861917806727243, + 0.41801581519798336, + -0.09504753722725343, + 0.4936249405248634, + 0.05488538686772187, + -0.8700158028464694, + 0.3060084400924658, + -0.7644097644254422, + 1.6509768090182904, + 0.07893240533541891, + -0.3371485542049521, + 1.156975810484945, + 0.14319680434597096, + -0.3203634311416935, + -0.5660505284391752, + -0.6170426333353194, + -0.9874119621612985, + -0.02076376815707847, + 0.1433024133572904, + -0.001336048960237034, + -0.6578615485245441, + 0.3939537139471049, + -0.020138517746786107, + -1.3218316026329249, + -0.1284665180698584, + 0.24233367662776967, + 1.9824549989409948, + -0.47546595245161566, + -0.09570277196127953, + -0.2139161871254592, + -0.28917573247360107, + 0.6716062331090861, + -0.0017393085056248104, + 0.8715943431102501, + -0.8802402485571954, + -0.11539115540758492, + 0.03054140625106302, + 0.37000348421464, + -1.0914148511963653, + 0.3475520463003323, + -1.1235733341831708, + -0.3070632599169776, + 1.4184881577953055, + -0.7764277269464427, + 0.5645443315989552, + -0.25326488183725454, + -0.3411948389350975, + -0.7201961067824945, + 0.5611711287500282, + 0.029465456828790804, + 0.1914560530566959, + 0.12283784201611943, + -0.7565194765184654, + 1.554802947482272, + -0.8148512469424934, + -0.5739152546224789, + -0.19407011211053546, + 0.3913057171128396, + -0.7148920636907814, + 0.3483079106863455, + 0.04421947991196336, + 0.4854989633426633, + -0.19043835457681318, + 0.37012804360539864, + 0.4687866879159493, + -0.7485505662462333, + -0.8301455733279911, + 1.1061472719720384, + 0.6111658811165368, + -0.8784159872393369, + 0.3296448735450702, + 0.9405078483395999, + -0.035379807550377854, + 1.2519350903935245, + -0.25064003782766175, + 0.713427245917066, + 1.0252514402629296, + -1.293846285135419, + 0.45040967742770593, + 0.4805717891799093, + -0.6850783423205864, + 0.08823059069135887, + 0.8273501734671956, + 0.8109054845604783, + 0.8363381149264987, + 0.8204146291350582, + 0.6294432188546892, + 0.1826696912787225, + 0.12293101270609731, + 0.4118851652361567, + -0.09651774973862194, + -0.3423731042278782, + 1.2577474984707493, + -1.8171478732066038, + -0.08416554017219506, + 1.381731063454478, + -0.9597641005960948, + -0.18905915457008463, + -0.03692196382981605, + -0.21469532383304382, + 1.0062876240026803, + 0.9248130432700498, + 0.17793343118362687, + 0.22449434667590606, + 1.1164217168654726, + 0.3668150330974217, + -0.41981065870053397, + -0.2233303966233545, + -0.4673926321230647, + -1.3849584756919646, + 0.1481190070620572, + 0.024598918545035566, + -0.7891834528256187, + -0.7825817739946559, + 0.4768470804358827, + -0.9897328284168524, + -0.334255898028088, + 0.10657609103571412, + 0.552224898613296, + -0.5852246821178494, + 0.19463866290387735, + 0.1543510915251605, + -0.03204328704413729, + 0.5487707959474943, + 0.9233419306306392, + 0.02917468734570423, + 0.6424498774109453, + 0.32905653021129727, + 0.25315815933274444, + -0.008170857404164893, + -0.6457632263316845, + 0.44141802942891634, + -0.1388729995669764, + 0.6866942957571021, + 0.195825011298127, + 1.7429116831692726, + -0.4797611843209409, + -0.325453533263531, + -0.003801540845491708, + 0.5117371432380605, + 1.7013133029693839, + -0.3286665944847144, + 0.6012850400097202, + 1.0140720006340298, + -0.8835259423726022, + 1.556312099909457, + -0.02266487691388939, + -0.43248272066319304, + -0.41655468514435523, + 0.6198883402247043, + -0.731550120174707, + 1.2506809590772494, + -0.1715376536924724, + 0.3659938484425762, + -0.03139703214974267, + 0.24345889885875463, + 0.9308138403082806, + 1.0799136316603517, + -0.45279267665171086, + 0.14861663186924534, + -1.3224850921216307, + 0.1548491124201422, + -0.523136746228905, + -0.08369597063624121, + 0.6000898952205294, + 0.45807081454611304, + 1.4214420403089834, + -1.1842827554965325, + -0.4746647635913183, + 0.9270167512565919, + 0.3933270372160252, + 0.9190582171212928, + -0.10579117425564262, + 0.7902559753187547, + 1.0403135025520962, + 0.8835505538939364, + -0.4797230169515335, + -0.8552933833283598, + -0.49155433491556144, + 0.0968290918710188, + 0.3324756929705791, + -0.2626245175407086, + 0.5996829795020312, + -0.21645005501652437, + -0.43453909983943706, + -0.2766026786506875, + -0.7202525479022936, + -1.2379452716187482, + -0.34424688008905424, + -0.9809469789191079, + 0.47894431600301834, + -0.6018668205342163, + 0.5393121069720134, + -0.32082091268888036, + -0.6162673398498182, + -1.2318549833547667, + -0.2745049661130077, + -0.7978387092693566, + -0.4881649121678243, + -1.5354029202814123, + -0.1752374932087464, + -0.8071796761464878, + -0.25800740445218245, + -0.7368569239816569, + 0.4702342694091765, + 1.2211731040564333, + -0.4389431778708901, + 0.11171779778145217, + -1.88654268442136, + -0.3545092156774006, + 0.7897727944933931, + 0.47312498091475996, + 1.0856296483184724, + 0.12076966717618282, + -0.22661593368982133, + -1.4719290277904051, + 0.5205291394413994, + 0.05637474221201101, + -0.05225106221832735, + -0.2001453576224704, + -0.6371435256572249, + -1.8563193757802703, + -0.08521039598469358, + 0.5650813939882395, + 0.3131648656020043, + 0.2946468971199408, + -0.013792038663241125, + 1.500246231931897, + -0.582098236601673, + 0.329926647810943, + -0.8745412062550058, + -1.134965370859406, + 0.4850007253927052, + 0.7577007141794824, + 0.6113765189106802, + -0.12276334309842706, + 0.5945830550817743, + 1.229974179652727, + -0.9826667417801267, + -0.231703047108116, + 0.606635318984383, + -1.0401456137029323, + 0.8204613185140475, + -0.5978095093810816, + 0.951120775477081, + 0.6517559812224247, + -1.145957287855198, + -0.5439394108070957, + 0.9275195935756497, + -0.8335547101705258, + 0.10568826215936188, + 1.630229084823943, + -0.09303458289866659, + -0.9321979254157955, + 0.6598632117334566, + -0.23608731118438253, + -0.4573019421830119, + -1.0452952435006595, + 0.09571308264799154, + -0.9054229131702658, + 0.5878655724128509, + 0.8326688769162389, + -0.39483191553537805, + 0.5817767407794986, + 1.3489333296140613, + 0.9431291911160674, + 0.6069361246798253, + 0.5269825257052063, + 0.07772303833379442, + 0.19088443990104156, + -1.4587782091960184, + 0.18305916163570993, + -0.5542983282234523, + 0.49086910520948723, + -0.07721350598604239, + 0.17016581192950408, + 0.8224316098663108, + 0.03874839777050268, + -0.9841472255743171, + -1.0034202716259601, + -0.7428673251334743, + -0.4523508140760706, + 1.5580946867612357, + -0.5350319789341146, + -0.30352160056322164, + -0.4625200393759016, + -0.2669075856231583, + 0.14563683099838134, + 0.028517604047529267, + -0.1312757788383631, + -0.3449716191165003, + -0.07114355768744793, + 0.9269882384764461, + -0.9476723812451734, + 1.7046139188259595, + 1.0589127315562392, + 0.8461183040250446, + -0.3334588611109272, + 0.10621701481026327, + 0.18634427828063466, + 0.40545281755863705, + 0.15506775842477444, + 0.5097511730519685, + -0.23613073399461582, + 0.10868305836408285, + -0.9735180890483002, + 0.09656353229606042, + -0.4475290597465769, + -0.31544150511912095, + -0.2291971565623386, + 0.2269410463081218, + -0.3879272811645546, + -0.6178455066630337, + 0.3551461821920009, + -0.8447361316819642, + 0.34846120416658616, + -0.14100619070388207, + -0.4184128367288558, + -0.4268112188996432, + 0.5704818078007571, + 0.0264524400499089, + 0.6342907068650715, + 0.6536605366385979, + 0.6859092172189757, + 0.05060236802544388, + -1.6725441427358234, + -0.23792819842588522, + 0.40446815971273814, + 0.30216099119326945, + -0.38799217811164155, + -0.27325499423341, + -0.8418904080912575, + 0.032400740021618184, + -1.5200254293352882, + -0.1748663477534164, + 0.3903153645275759, + 0.14616493584079318, + 0.24048754446368611, + -0.061984351284842955, + -0.24067656288712222, + 0.033159288257615153, + -0.752509546401384, + -0.4081650806706688, + -0.18443960336711973, + 0.2925194927676805, + 1.7212304511278378, + -0.08604369929148671, + -0.3186660582702458, + 0.2565569224852848, + -0.45761667612649914, + 0.554294916927056, + -0.34442364000951503, + -0.6594195294259827, + -0.05823396602940674, + -0.28080394816461446, + 0.34376184285169664, + 0.23093079771878997, + -0.332458023308733, + 1.2974023501929193, + -0.4969786844193175, + -0.8418607940437458, + -0.42366577809593825, + 0.1705655691797822, + -0.12778955595193478, + -0.5887691352260487, + 0.038202108991667226, + -0.22233938026864766, + 1.2603217519600833, + -0.5402353832256354, + -0.7054578493961903, + -1.043468684893464, + 0.9748938970764933, + -0.6111968487017386, + -0.8680847038104083, + 0.6753813756464225, + 1.0929247834211533, + -0.4815790113329555, + 0.12883827722803165, + -0.8157951533811354, + -1.8918365396414343, + 0.32726008995803035, + -1.5973033288464826, + -0.17159980793853225, + 0.7513252499201335, + 0.5183140999752861, + -0.8210759509082276, + 0.6542776457226581, + 0.4206438309651816, + -0.4832802644862663, + -0.43812655869020356, + -1.1166529193665045, + 0.4817700794767304, + 0.13089461546728667, + -1.6640063817852988, + 1.0182697281458706, + 0.23732160887642065, + 0.09442350768519793, + 0.4682053895479278, + 0.0025447393318453904, + -0.5507362090430624, + 0.6951641726401679, + 0.8142357431902297, + -1.0670863654804053, + -0.9437557961983467, + 0.10175596851610934, + -0.45916559103087357, + 0.32562855752529174, + 1.0680184029792386, + -0.20636086814998275, + -0.5970877796435924, + -7.221705488182924E-5, + 0.5262973841308263, + 0.9724201418527403, + -0.46410907049731603, + 0.3402928299855614, + 0.8733450488799538, + -0.936926559624971, + -1.2065926079133802, + 0.5951533491801347, + 0.596645331789714, + 1.0424619276685552, + 0.25382964904076344, + -0.04015896890563075, + 0.763263023032693, + -1.1877683170550144, + 0.650443836988411, + -0.8950289556626325, + -0.2548931275155301, + -0.5139812513906907, + -0.9654336795521736, + 0.043909275117828835, + 0.20499881881059379, + -0.08012938237905855, + 0.382862170756538, + 0.2157402195740094, + -0.5915084427900541, + 0.6360729914203259, + -0.47851331812391884, + 1.5905888162486952, + 1.159566172895383, + 0.012373735478452911, + 0.9054423382425489, + 0.4480861395984455, + 0.25226003732522656, + 0.4899270641800722, + 0.579588489203703, + -0.21752523013091632, + 1.1129728756768726, + -0.2005010588645229, + 0.7926258487128335, + -1.1965915680341093, + 1.3788496253497557, + 0.1637815084900439, + -0.09115904515355314, + -0.26582902112736834, + 0.17588755695748629, + -0.08877701510781989, + -0.5243222293172044, + 1.3228827040259454, + 0.9262253968627655, + -0.3642219777951094, + 0.9394620869346078, + -0.43660486716807206, + 0.4953157628927619, + -0.7723421963591677, + -0.48541145510522343, + -0.054991237173844854, + -0.0139640473626178, + -0.15390427958616212, + -0.8847154682327827, + 0.2644781330763411, + -1.5340670295970196, + -0.10139437525774743, + -0.41507435325236114, + -0.03687290518083887, + 0.573057740823546, + -0.26727576274516146, + 0.1701640722821519, + -0.6133558973236756, + -0.16844012935538402, + 0.39868349190910746, + 0.7049551474249233, + -1.1321895790540362, + -0.05110967024388022, + 0.6182728266948363, + 0.2762020714398501, + -0.8834875321076368, + 0.2846389328037131, + -0.56104606234374, + -0.6846952802270082, + -0.4781883122872362, + 0.010826369083624197, + -0.07509629771508321, + 0.1968676003566423, + -0.058513748262445736, + 0.5022393297488233, + 0.39714494241388065, + -0.07299524497932494, + -0.054941284522993176, + -0.21604656294470723, + -0.11572406660529093, + -0.20004933317864462, + 1.691342928080218, + -0.4603538039262368, + 0.6028132958324276, + 0.49616786128771867, + 1.0814896160822756, + -0.26778221864978924, + 0.9004006603275626, + 0.736202258910116, + 0.5275806519957436, + 1.0278237983134855, + -0.005677155242057378, + -0.7262329940786016, + -1.070893138874757, + -0.38846253830266575, + -0.33388036731163595, + 0.4600466216985231, + -0.4105340322234548, + 0.36798957862446013, + -0.6694003308037635, + -0.6670997399275698, + 0.9411495250035393, + -0.13007370666486043, + 0.7758201077390988, + -1.0776106362101352, + -0.6672579798065104, + 1.4634861428665331, + -0.1332078257585901, + -1.2719767315813422, + -0.8576768835811226, + 0.12702402682763983, + -0.28167300058842765, + -0.23026954594230756, + -0.778730835721499, + 0.8937666841241508, + -0.21906481848929044, + -0.614892245445127, + 0.7630724743414027, + 0.6977460954915252, + 0.37179797138145515, + 0.24412124707147168, + -0.4393232425770946, + 0.3162358047502925, + -0.7211636756544504, + -0.3052567350829913, + 0.40063358969952034, + 0.12963455517715036, + 1.25771065402064, + 0.7571889944751001, + 0.6432701928631567, + -0.35367063571316615, + 0.3919524218117187, + -0.9069188949114001, + 0.10086381763421036, + 0.4256431028971201, + -1.390796072988329, + -1.2866229133672462, + 1.3214376414531437, + 0.4812024297170675, + -1.5118876880328433, + 0.7087222702556554, + -0.11352191741722445, + 1.2926202980247248, + 0.1948402888638738, + 0.14741446097618244, + -0.9897888756675797, + -0.6951070732600582, + -0.0870312307140383, + -0.2863025077709952, + -0.7503912760239634, + -0.8466400723228316, + -0.22555190676165754, + -0.3285478508525733, + -0.16290579184944265, + 0.23407520613141036, + -0.33288216179029984, + -1.0566363058777646, + 0.7215202655112148, + -0.13322082703221255, + -0.16396940106114488, + 0.5021689036081144, + -0.9370511672385202, + 0.5568309644689932, + 0.6161213461104608, + 0.6990963739274302, + 0.7767868910247882, + 0.6112213292164408, + -0.38148618767509557, + 0.5976610034078136, + -0.31568667708929565, + 0.10858316496799149, + -1.276576872780308, + 0.3606515775058528, + 0.4193602035038773, + -1.1030256389469488, + 0.31921978924385824, + -0.3305559974225766, + -0.651604975552594, + -0.21358961708490257, + 1.4668453688093033, + 0.8188674107701006, + -0.20180378806875146, + -0.7755157160832096, + 0.09965010448958198, + -0.02716358484271662, + 0.39750600269690894, + 0.2851630213949631, + -0.5651609100663384, + 0.32335376936366794, + 0.4621799128767035, + 0.4657788147523565, + 0.48304281048629993, + 0.013515963731236891, + -0.41452575265496006, + 0.3134355354967543, + -1.3296126471255385, + 1.1348116591374986, + 1.1892960801077792, + -0.0980757144347182, + 0.4424327262604032, + -0.3096333201589782, + -0.5711572179100678, + -0.16467834680452953, + 1.141816786981025, + -0.07942045614147326, + 0.1716537383803548, + 0.17163129514175388, + 0.1236684981820409, + 0.7785970374958131, + 0.6666415073658389, + -0.33131428668648777, + 0.8162695189188831, + -1.1178787380133315, + -0.8778114640914576, + 0.2388932755061637, + -0.24711865534805946, + -0.5689536049909595, + -0.30611415220346505, + -1.2613648835590032, + 0.9556896786822446, + -0.665862892212003, + 0.2905831290534933, + 1.1991179133595626, + -0.49071760158144784, + 1.266506050939945, + -0.9001689015396086, + 0.07442147093250231, + 0.28081543258173947, + -0.32373835622923414, + 0.3191920010265317, + 0.6550334699806141, + -0.07896286308664, + -0.04602218651248663, + -0.7568471626991178, + -0.07920521101603116, + -0.12047677275366697, + 0.6511470895845551, + 0.5771195429659159, + -0.014108442041702465, + -0.3645042752568558, + 0.14625261215833835, + 0.5961775024555239, + 0.2651523371597429, + 1.2694988359873656, + -0.5341875593733184, + 1.4320329942549583, + 0.7053740455575617, + 1.2071494495862514, + -1.2026826351138888, + -1.6487546331638452, + -0.541827478797718, + -0.22098690700630497, + -0.3707518720381047, + -0.7903400892947574, + 0.10364251712556394, + 0.10270286132252841, + -0.41674249778139943, + 0.4140342032399112, + -0.7732117379292598, + 0.553492616948765, + 0.6388700890051959, + 0.695601742426622, + 0.04293972242380883, + -0.5080851422507405, + 0.6156352266155545, + -0.06942630109571854, + 1.2925103679782357, + 0.04861728561651028, + 0.5378494746219737, + 0.09153398967836698, + 0.4902890554875303, + 1.5826175052316718, + -0.1659654915870279, + -0.3534990399792605, + -0.5008924061707827, + -0.6222152940831637, + 0.001441417049529025, + 0.705847551472865, + -0.31683494095165804, + -0.8598133773631108, + 0.8210676479251459, + 0.7266320773365682, + -0.46186950873554883, + 0.5608454211403288, + 0.04212257851893451, + 0.02105224500485436, + -0.4832406663185655, + -1.495512137156534, + 0.38468400817593584, + -0.35411801233373674, + 0.4403240375362745, + -0.48011696560823097, + 0.22766015652660834, + -0.6743473635990247, + 1.894051172554497, + 0.6935924919980333, + 0.23529225748567076, + -0.4999119605852003, + -0.6790342351153206, + 0.5423980894756396, + -0.5603879155711682, + 0.10471997191355605, + 0.962801452544877, + -1.620135954194966, + 1.2524613682376227, + 1.0713253966522165, + -0.31306622976717347, + 0.433950218230435, + 0.13243492360627834, + -0.46740055261987484, + -0.1614078091896175, + 0.27029073629509137, + 0.41160239004916443, + 0.45540324619758926, + 0.01650911617648907, + -1.0756881765583888, + 0.40893785705568947, + 0.3858965319116341, + 0.8318624966651189, + 0.7785021796095742, + -0.2795497196034648, + 0.8527021766726255, + -0.8125360383984019, + -1.0912759615135452, + -0.3408029264214645, + -0.022282240923993026, + -0.404836950557368, + 0.977533175805398, + 0.5400257394719054, + -0.05289530513373186, + -0.02317416361325725, + -0.0027616132551210397, + 0.003965688041764556, + -1.143659069033356, + -0.45544578476185477, + 0.4645853474554458, + 1.5865935461805514, + -0.5276455537655175, + 0.5277439823590627, + -0.6459828353105976, + 0.9168903883276444, + -0.030341533067806657, + 0.5986712722149602, + -0.7528492333874813, + -0.46976646290795704, + -0.3219554200904396, + 0.5108510198951278, + 0.408955626237284, + 1.3428603516911706, + -0.36280836111588005, + 1.1202990991156383, + -0.13273464167668067, + -0.37149162721145407, + -0.23183846251560727, + 0.3743569184975426, + 0.08756649806745609, + -0.5094401884062024, + -0.6918649605104976, + -1.6878340135167225, + -0.35882879827458114, + -0.0441733076728191, + 0.13532595208957499, + -1.0315723956465428, + 0.7705358877935261, + 0.0018093532902564732, + 0.8626882413949419, + -1.4519382902075497, + 0.025687216969939253, + 1.477706085589478, + -0.4797970994506882, + -0.15558989924187527, + 0.6449457431127413, + -0.22926549884098077, + -0.6171220739593166, + -1.1998711832574562, + -0.6662526503766615, + -0.7595564471324655, + 0.0916171348781091, + 0.5349107389300212, + -0.9000672571611865, + -1.0907805072096322, + 1.2305089472456956, + 1.2902694767297846, + -0.14962069413088655, + 1.160398985885996, + 0.6910170623851727, + 1.3252503482232914, + -0.7602155401469415, + 0.5613634249457329, + 0.3686246284098914, + 0.8789843614058866, + 0.8558717468321526, + -0.03314134978565286, + 0.11053273879845435, + -0.1707885634290593, + -1.2545621153024888, + -1.6763226031354366, + 1.2743567978193533, + 0.6572187295124351, + -0.3397978419088825, + -0.301337600393316, + 0.13471333496508386, + -0.47292404246627245, + 1.2068798719595442, + -0.3431258089842669, + 0.5335059070180562, + 1.364555813127829, + 0.36895328865679844, + 0.6559977183023445, + 0.6157265884514821, + 0.024818705523119676, + -0.23847695328588212, + 0.616251440534213, + -1.243192378392851, + 0.33308929634692447, + -0.3433105120244716, + -0.5967056528190393, + 0.11386013343503229, + 0.5514991034717099, + 0.21477749080265335, + -0.7169813594074932, + -1.09800053602547, + 0.4817202359913052, + 1.469184617687773, + -0.6231797690165988, + 0.4379914292961987, + -0.8847412009325284, + -0.28670802314487187, + 0.9731223986453968, + -0.2965103940011041, + 0.34630100870604563, + -0.41142802665377476, + -0.0987422550921826, + 0.04498484538100011, + -0.9379994363406947, + -0.34663272772282167, + 1.836815118469638, + -0.6034133159874328, + -0.14459773614811153, + -0.0887308906434631, + 0.39417580682951436, + -0.00724354536510244, + 0.25490214853402804, + -0.6146496402696634, + -0.30683109347696474, + -1.1001297796123821, + 1.0497926401130295, + -0.6440123415926262, + 0.8898147430305169, + 0.7962547907699568, + -0.48302587520805756, + -0.1574529367775975, + 0.41530942894632084, + 0.08861745019882757, + -0.5834944601726361, + -1.0346374968920364, + 1.3950494864179055, + -0.2647032738158709, + 0.008775624153535996, + 0.17172240590015506, + 0.0683052866766208, + -0.011222781853770989, + 0.8707105076541362, + -0.12050081253891672, + 0.1518653999149061, + -0.42500906884500783, + 0.05808354545946904, + -0.13713259066784778, + 0.6970201184926418, + -0.24824346153018156, + -1.7006007307473943, + 0.22729465801920798, + -0.8851269493409654, + -0.4358148653596721, + 0.8056798338480583, + 1.463809924108246, + 0.04587839546096847, + -0.8558419837940718, + 0.5978845677846237, + -0.5081824641132909, + 0.7640278684544642, + 0.16568976146247805, + -0.6886514176668204, + 0.26110385521718543, + 0.36289717297489194, + -0.2493139519344772, + 0.978057519719013, + 0.11413480953484484, + -0.634406254656509, + 0.6340981210361982, + 0.32291395566169256, + -0.6878049767264294, + 0.14127030844244123, + -0.7365154953725991, + 0.4769650893094816, + 0.863416880658564, + 1.1674404898362583, + -0.6109182365424511, + -0.6868045891335992, + -0.06361109831573354, + -0.14001513163449744, + -1.385099069275414, + -0.6034613613556488, + -0.4650415288632003, + 0.25001521180116043, + 0.31661603432042185, + 0.8178611045721403, + 0.17644879002196706, + 0.05364191281847722, + 0.45668171057423657, + 1.0364570373351236, + 0.9525540656145315, + -0.49592512882409323, + 0.5262838726835137, + -0.12577223792487682, + 0.3037345562933145, + -0.677693304115602, + 0.539272355570669, + 0.6889044008276897, + -0.7666126790831939, + 0.10804200209852412, + 0.2368088299616745, + -0.08608767284589734, + 0.5740308900317976, + -0.44651601368010196, + -0.37967658886607797, + -0.039178384084516356, + -1.2457635233226636, + 0.5312622932961008, + 1.2704162057442134, + -0.6263080682421585, + -0.053947549860278145, + -0.34970533114162033, + -1.1806478226541328, + -0.16373168095234797, + -0.48172279623373443, + -0.3649198098380734, + 0.019025011398716624, + 0.7647734517522067, + -0.04308323727212713, + 0.8093607666759461, + 0.34876653289441867, + -0.2849468182204559, + -0.3413774775003602, + 0.6779671215520818, + 0.2980709715316988, + 0.2658157213428969, + 0.05500571048061165, + -0.3229936576931585, + -1.0738703831031091, + 1.0113738844926325, + -0.04986150424349363, + -0.5540998897570684, + -0.17159907638852454, + 1.6264470259456114, + 1.0693153152699653, + -0.6307253263810669, + 0.06783102456535736, + -0.4373747878413376, + 0.405230742707392, + 1.0217333374905635, + 0.825645379104167, + -0.02968628966375385, + 1.0714165058482916, + -0.5558086828641379, + -0.0026779347990618747, + 0.5747685982098251, + -0.09327579681993609, + 0.11086362345096092, + -0.6287689671910606, + 0.6144177147604392, + -0.10246309381106271, + -0.29101848939628644, + -1.1774773120714466, + 0.1844787550549397, + -0.1674803136157369, + -0.2743530893356679, + -0.6191842817695612, + 0.01983636395679388, + 0.7709154102398389, + 0.2454173070545025, + -0.3169337278597216, + 0.6866384157750863, + -0.501528084106169, + -0.1469660780573908, + 1.0332543014955762, + -0.021128692342363073, + 0.5013463359106646, + 1.0058837225453205, + -0.8951277545698741, + 0.06617307633697088, + -0.8356282411090258, + -0.8803029326288954, + 0.41182265727096196, + -0.44281843149947087, + 0.35946183351891214, + 0.13736724682152746, + -0.9491227404526681, + -0.4762023869619631, + -1.6889770923929126, + 0.3707929718216545, + 0.45946191546983256, + -0.5449616850441528, + -0.010056945306117834, + 0.24576104070297825, + 0.5827467930460816, + -1.402110060020355, + -0.13490175908391852, + -0.5375725490127, + -1.0361447765891567, + 0.2564649575379413, + -1.3179226550286178, + -1.048376646733955, + -0.7018207131408709, + 1.6118015662821445, + 0.14574678374355013, + 0.8862144447411281, + -1.269827117909097, + -0.41536276724489885, + 0.28756431633938495, + 0.5465668472193231, + -0.3772877154307233, + 1.236625703546004, + 0.33661289135489497, + -0.32760345808792224, + -0.6993497400085746, + 0.29309863839767086, + 0.01599339334097133, + -0.12156922446443551, + -0.8517737481424241, + -0.3627178782380739, + -0.43584759739824225, + -1.8552863609022299, + -0.01819948769871202, + -0.1789248040584536, + -0.31464447463046624, + -0.5386754021833876, + 0.4594969496900089, + -0.10017802253605256, + -1.498774029830221, + -0.25761882825186966, + 0.2927459392625371, + 0.6782423604926814, + -1.1424031535352634, + 1.00356850070115, + 0.4330179227158189, + 0.6501032778430907, + -0.16416233161805538, + 1.7107063241857527, + -0.0069171425972216795, + 0.2495321947454131, + 0.23417140569164238, + 0.050230997625114876, + 1.0012611611022246, + -0.42416337609267, + 1.704553601212991, + 0.09528875963484848, + 1.1415735987267845, + -0.6016510265145172, + 0.2954851939024445, + -0.44215778719748056, + 0.6738360164412168, + -0.4570724557171487, + 0.7403456283174012, + 1.0808762268349639, + 0.21284658086398472, + -0.5526778286743338, + -0.2806058973771006, + -1.9124003960346556, + -0.650629494472764, + 0.7080911814436216, + 0.7108724474422087, + -0.29292931863167837, + -0.9697023100979383, + 1.0319608749741171, + 0.07625737351567274, + 0.7096309994366847, + -0.4932960867502261, + -0.2142332273442592, + -0.13319859903668715, + -0.17227316453883335, + -0.5398415873616248, + -0.9297936555389112, + -0.775032166318096, + -0.4806679035358692, + 0.14206807599142754, + 0.43053349492144666, + -1.468448684423724, + 0.802306520728446, + 0.633857432398408, + 0.20305483270232752, + -0.42179369585728377, + -0.14440543186501842, + 0.21546537812306704, + -0.08328914194124926, + 0.19795634068622736, + 0.5467490281363835, + -0.7254654045560484, + 0.08179159614902685, + -0.6752167703830354, + -0.2539008225914516, + 1.1438031259982222, + -0.17513199787179815, + 0.4597780658484498, + -0.6527806962876923, + -0.11331054951891281, + -0.6133651720577485, + 1.939424455563487, + -1.6505786125304014, + -0.24099541867544003, + -0.47160339839903187, + 0.27944514613507243, + -1.880207154532335, + 0.4992751723088368, + -0.16232583903559317, + 0.3271341564114106, + 0.44554112017225267, + -0.18890978524205865, + 0.6636752374725944, + -0.6111119270505022, + 0.29766492146077006, + 0.043822728147528404, + 0.7274799587639498, + -0.10301766351201243, + 0.260620008229859, + -1.1822792987219213, + -0.3680857836010624, + -0.11394686831323668, + -0.8987599051450226, + 1.204204170318274, + 0.9735543495302659, + 1.5995201674789492, + 0.17248343673566588, + 0.2357520705308249, + 0.33443764537567094, + -0.151969451525408, + 0.6288149823711832, + 0.28270123798421487, + 0.4042577899173082, + 0.3523255301741432, + 0.6528594765661849, + -0.5229710718962383, + -0.4880326565988287, + 0.29116256537580576, + -0.30318769146311214, + 0.8676714892224625, + 1.3457108971565064, + 0.6571147815273161, + 0.7485142861526777, + 0.21419807442367986, + 0.22405894175146143, + -0.38395510984710646, + 0.34668333819694774, + -0.5015830361769286, + 0.7333891625686243, + 1.5452388838721227, + 0.6251048411032256, + 0.6861744458786725, + 0.507654012199629, + 1.0449440075599314, + -0.3011716151892002, + 0.5591800953998014, + 0.025702764500421877, + 0.5457378980062679, + 0.7605489898068066, + 0.37043610598208865, + 0.4203383058482343, + 0.4824288891100713, + -1.5614420601114767, + 0.7055592096369594, + 0.04381539902174389, + 1.2230817389662179, + 0.5716214347230976, + -0.8383901872880717, + 1.0850389328089158, + -1.656748966221915, + 0.24069949529469964, + 0.4706424413791538, + -1.6880279589095348, + 0.26948152520303, + 0.03733248763240174, + 0.5526019039104985, + 0.30257314242551736, + 0.3165865824631761, + 0.006239274487594637, + 1.459386885620723, + 0.17072608837078548, + -1.1288103995009755, + -0.34986082161226106, + -0.6584821157720068, + 1.1276013145720352, + 0.19147817260179392, + -1.1203700067337516, + 1.1048793112629671, + 1.0275371407344194, + 0.811762090834272, + 0.11711747990774676, + 0.35486884731773893, + -0.16564812677747653, + 0.22664687741538886, + 0.5164326879155503, + 1.4804977770893337, + -0.38775862789834203, + -0.5420971095181573, + -0.6607785505490398, + 0.1685530617555328, + 0.8882608875020936, + -0.7040438521861772, + 0.6216321399893534, + 0.15680636975707074, + 0.10043197470186134, + 0.42608197464647857, + -0.6999762676710527, + 0.13384363447658693, + 0.9365666604119369, + 0.17139054295183861, + -0.0370072329176551, + 0.7217404006146203, + -0.1682598617319071, + 0.2582088833876176, + 1.3057069339073737, + 1.4755851348484728, + -0.543097671604453, + -0.13466631950096325, + -0.8218050788043629, + -0.19006469935825876, + 0.3400289688235797, + 0.35085847858916386, + 0.10856646268393547, + -0.10093009103757822, + 0.09262717069375398, + 0.18021142785585864, + 0.6792246754229615, + 0.3275301750484162, + -1.0266358407277578, + 0.08410200417304944, + 0.5965067509331718, + 0.4943831490422964, + -0.44366546483862335, + 0.16480717972854295, + 1.0831550997228423, + 0.23377219919722722, + 0.5188579073898719, + 0.8897785396541407, + -0.3843518962414784, + -0.8099699553573609, + -0.6459204272691679, + 0.03370175103292529, + -0.2072742532595008, + -0.47961589947735744, + 0.7198204369692695, + 1.4173002958601124, + -0.03538514885028797, + 0.42189086701610756, + -1.0856896844540747, + -0.6150104459618654, + 0.25804326135812294, + -0.7972989936025767, + -0.14919517876535188, + -0.1194668263316388, + -0.8816152087938258, + -0.2466234945327073, + -1.0857886289589422, + 0.42872189375876363, + 0.03043533554741585, + -1.102363070442998, + -0.44344579787996363, + -1.3590266055236855, + -0.9796260788698102, + -0.9937551223987735, + -0.20914201896780638, + 0.3788667877224138, + 0.600793231785851, + 0.13863505228890183, + 0.4395408202739831, + -0.41188277657485955, + 0.175538347370969, + 0.2825312435681472, + 0.07051990668833226, + 0.26739890584452164, + -0.13224755228071478, + 0.98938068381416, + -0.03914084747462618, + -0.3769726807170498, + -1.0062489666449284, + 0.48269570452696936, + -0.8365604752348919, + -0.6499874708729183, + 0.4316159792554948, + -0.46709761832870544, + 0.6507708961778156, + 1.3775449171217797, + -0.21609555477641648, + 0.7694851982649235, + 0.5776739873879951, + 1.2493349593418734, + -1.9823515529374676, + 0.4412264126175316, + -1.258578263031326, + -1.276503704789019, + 0.33624555989555166, + -1.2440442143186252, + 0.025276567037369812, + 0.11817715549638043, + 0.5147250827776572, + 0.6749329521309559, + 1.1888125443509412, + -1.2573173077098607, + -0.07352576917849414, + -0.34900405384805916, + -0.45943656156190077, + -0.23340091110521363, + 0.5239590926554482, + -0.18268715252602966, + 0.33870121220999483, + 0.18474127269489835, + -0.7166091479942627, + -0.10958471382362486, + 0.8571464170613569, + -0.42114842844934797, + 0.40578473194442216, + -0.1959182049019959, + 0.16771568632428074, + -0.05347534726603301, + -1.0596404812642413, + -1.3415217914046722, + -0.6969239041141013, + -0.008409348402946762, + -0.08343707143062398, + 0.9869150172023041, + 0.5957006364348509, + 0.4415957693523004, + -0.9190621682436384, + 0.4248674726143014, + 0.40614736479081076, + -0.5684524449310908, + -0.08134064821049443, + -0.17490142039757842, + -0.40152296998937087, + 0.3347882209681661, + -1.1612433451184097, + -0.4141990443083995, + -0.7380683045657223, + 0.4171070078787866, + 0.9746769875232882, + 1.3774225681972483, + -0.8963393135071929, + 0.043655568478565346, + 0.5266667746238262, + 0.19931107265171233, + -0.5383560877072283, + 1.3172446498253791, + -1.106976616706722, + 1.0889901423918187, + 1.1473624868601462, + -0.14246629063525193, + -0.08959871941095401, + 0.37562426750433614, + 0.3683210613151284, + -1.9200737206356393, + 0.5387816095706531, + -0.33303004799590236, + 0.13727449949842846, + 0.6586027835560074, + -0.6895042974634813, + 0.8058981137222329, + -0.7613757762998404, + 0.4734251197408254, + 1.4395589749239177, + 0.15881505049665193, + 1.2958281402647558, + 0.16295759496698137, + -0.28058521326813723, + -0.9302811515874705, + 0.8625487632674662, + -0.8652442206910931, + 0.46570736455545747, + 1.0589597146855825, + -0.8156791449698058, + 0.8209243440402041, + -0.45519467024984583, + -0.10390915323073917, + 0.4479966491763664, + 0.3451210947562403, + -1.7737153683133875, + -0.17636994685759516, + 0.18148714971215532, + 1.015533962372661, + 0.11272363094786822, + 0.28471241209254616, + 0.442693784078425, + 0.6752769407411409, + -1.1382802611924947, + -0.653951355151634, + -0.2096696046777806, + 0.1878834131910243, + -0.9421968655769946, + 0.5440813434643369, + -0.09257072752759839, + 0.887780824397619, + 0.47695531997454205, + -1.0420567756599581, + 0.5177666404177957, + -0.6646335513005655, + 0.21821176353393673, + 1.2006463606083115, + -0.2511689878298143, + -0.3718878640173751, + -0.38004466286154903, + 0.32507411450812407, + -0.8674039361060987, + -1.254642590069592, + -0.6439649301160513, + -0.15623837999185514, + 0.20386840824106625, + 0.06881217523937533, + -0.4188818005967102, + 0.5457065038116408, + -0.7402349993095853, + 0.6989146139148867, + 0.45807712873958323, + -0.08849137470673604, + -0.8505181613373801, + 0.27211779815354903, + -0.762629410812476, + -0.11051969211837254, + -0.6216004614403103, + -0.19211360697387697, + 0.3415279819769363, + -1.4580309568865752, + -0.511598841172685, + 0.15516376136992585, + 0.8177022937802579, + 0.5607864259689417, + -0.8090693864710219, + -0.019998959266655028, + 1.1470266914555178, + -0.027483452522784613, + 0.1602522261186996, + -1.0569332107815836, + -0.13654434943341323, + 0.03571611445365606, + 0.23957626123112877, + -0.8010845468022763, + 0.6005808735621354, + 0.44846568981843665, + 0.39537532811471066, + -0.23020122357041423, + -0.5995363314841939, + -0.03141508817679958, + 0.8539242498753956, + 0.6364606337454376, + -0.1241093694006147, + 0.47057723281441227, + -0.8194382597914869, + -0.5879606423786545, + -0.5177021290696114, + -1.3360403423125802, + -0.6307418087462769, + 0.6335532894068775, + -1.2702684245530187, + 0.03495625529885746, + -0.912920845084439, + 0.9113164953465323, + 1.4344321308486567, + -1.0230686371430142, + -1.0783418027999816, + 0.7857519789748478, + -0.2797140660591689, + -0.9595816970425246, + 1.0833752397291072, + 0.09190437726713756, + -0.2657340051235412, + -1.1092185160305332, + -0.7018615672642107, + 0.06884397991767208, + -0.4708747641879975, + 1.1247650821435053, + -0.542506269621344, + -0.14874047730080064, + -1.0132519706607686, + 0.795075272251355, + -1.5585234655244997, + 1.4592779128971338, + 0.5265927483482562, + -0.13477696345414453, + -0.4870209682330952, + -1.5263957840056506, + 0.5500199908617637, + 0.5504457623613507, + 0.44065167570498737, + -0.9375920645880638, + -0.3007648340646733, + 0.13190501802282506, + 0.49265409259624643, + 0.440960072678645, + 0.5657969289063626, + -0.017744853008855956, + 0.22767497227652464, + 0.28915794994351474, + 0.2597793585379348, + -0.24921543766311016, + -0.43967373100249796, + -0.49439389350587126, + -0.3259441374121739, + -0.5870609501884569, + -0.36325146315970674, + 0.9006571517649166, + 0.6725293981409329, + -0.8802755648983007, + 0.5635031969769634, + -0.47526362464173105, + 0.20617678053643557, + 0.7744979345870414, + 0.41095824954013527, + 0.2452550101381799, + -0.4603798967541705, + 1.1849945836971774, + 0.32270582156063315, + 1.1683370598810907, + -0.6582671042035123, + -0.22271420244707932, + -0.18318772335376476, + -0.0853665116731709, + 0.9538519041716909, + 0.17191919718047557, + -0.19247868378071278, + -0.33553689704657275, + -0.09168092473499227, + -0.6993444901779324, + 0.5118585264229106, + -0.20640781876277492, + -0.2124673512786854, + -0.4370308339002773, + 1.0929052973749114, + -0.5234707905969439, + -0.45213792376834755, + 0.514726395405884, + 0.5170116656661623, + -1.0138774135369069, + 0.205219338846993, + 0.42024610993185085, + -0.933330602539649, + 0.6019790571655594, + -0.17927326379312897, + -0.8345804964427702, + 0.8128120796992118, + -0.5528101157391935, + 0.45889585262336513, + 0.05316747284812891, + 0.7667384801493857, + 0.27315857030093993, + -0.796552595494635, + 0.2801647483803801, + -0.022379026463224733, + 0.32359866029995066, + 0.06797681481522132, + -0.7120389307732714, + -0.2905210547175941, + 1.044061401134785, + 0.44178279697744693, + 0.2912870518280602, + 1.2500042913056741, + -0.4469603759996935, + -0.1576186555377123, + -0.7461508660807598, + 0.04008789282974856, + -1.3643282819288993, + -0.9135488602387324, + -0.13106087475989062, + -0.560500336409599, + 0.14086825551531174, + 0.4961438388506739, + -0.9699983947134555, + -0.1468420266084688, + 1.2351059099557244, + 0.12260843892318446, + 0.4843693987712069, + -0.6485584708125898, + -0.6816308821296627, + 0.21994171537319265, + -0.20808330924290538, + 0.4723726186281739, + 0.4114116138766932, + 0.09554903314284824, + -0.24903887138961342, + -0.45515686872768635, + 1.5038804801194097, + -0.4609032793023391, + 0.7474106413425582, + -1.519541375540002, + 0.16185663109397871, + 0.709485458666769, + -0.7890380407003529, + -0.296016530558015, + 0.4030482633157385, + -0.8786334011052611, + -0.09508681328050372, + -0.7176268550489104, + -0.6887679968115785, + 0.6655405968195924, + -0.8173010604731487, + -0.6516470387106671, + -1.2229184287640962, + 0.6337575116551283, + -0.46582199315354555, + -0.07495209880729858, + -0.4744084776187756, + 0.617096532803834, + -0.33525631428447067, + 0.22307490691984316, + 0.7514293537311364, + -0.051795605687575796, + 0.9835859300983009, + -1.2409730458082904, + 1.4098876312221045, + -0.708365730438222, + 0.3198853568072665, + -0.025855684881649018, + -0.7567335407173967, + -0.7946485973501106, + 0.09245750971461053, + -0.36309966338203736, + 0.7737798377977531, + 0.35541157574109666, + -0.487704759588691, + 0.120250654218864, + 0.23387134375596239, + 0.41139890237540655, + -0.6823643049829662, + -0.4120669885109566, + 0.7471321708387473, + -0.2935017921143151, + 1.9477210603518926, + 0.18941937682026433, + -0.6880637445096437, + -0.7473019109607022, + -1.0178355381563682, + 0.30497753871849376, + -0.31801876911060434, + 0.4027557595993629, + -0.8172255539404824, + -0.17554974515502328, + -0.5231772177378161, + -0.3923367635937902, + -0.9828887867418414, + -0.04768581958493587, + -1.4447966076351968, + -1.4955087666660773, + 0.8185031102857537, + -0.07950799560947115, + -1.0384843576569232, + 0.07226499523764943, + 0.5844688251437371, + -0.8449675783316928, + 0.6079431669058791, + -0.064071929198659, + 0.957605940162356, + 0.17347666036146311, + 0.15192622037920334, + -0.18746714670755665, + 0.5449497835597348, + -0.08607540249234172, + -0.8338153338530252, + 0.8270284796592066, + -0.5312195605038627, + -0.15633082730336556, + 0.46756955115851395, + -0.7085921495834842, + 0.1782348858178017, + -0.6484141338787993, + 1.0877135909109985, + 0.032887252982587954, + -0.46179808994494426, + -1.0059218999470563, + -0.47647271043431155, + 0.6878743865659501, + -0.2944067810877922, + -0.1487698473778369, + -0.32883459168138335, + -0.08856102628019707, + -0.007070434592180925, + 0.45149492553156234, + 0.6260071160958053, + 0.13448282872723766, + 0.8645765743049549, + 0.6348882131134127, + -0.8009188518677912, + 0.44933106748828655, + 0.4054330078796212, + 0.10623495501482573, + 0.18197768787166047, + -0.0287018638657726, + -1.5025208969133306, + 0.4547928513472485, + 0.2652287260563519, + -0.7701648465933414, + 0.7520110820276167, + 0.05822052918227561, + 0.16239379330652287, + -0.6206392436178785, + 0.39478689984126575, + -0.046649308007700695, + -0.7335416620414015, + 0.4343940007360643, + -0.08648189048158286, + -0.6337772188097794, + -0.12545618966121658, + 0.6695071383528649, + -0.2679270064988827, + -0.29174320895642525, + 0.4244204011838225, + 0.372151022428277, + -0.028290757395523846, + 0.10167843601370398, + -1.1647709095175465, + 0.40085692406472984, + -1.3553283206161502, + -0.16171665438328162, + -0.6795551632785277, + 0.7973058861315102, + 0.42289971907823976, + -0.0865856970799928, + 0.1384680487202889, + 0.1366697495720008, + 0.45737332768549027, + -0.4744948982194415, + -0.6432046350027784, + 0.08382286095519595, + -0.7566522036349137, + 1.095756422930531, + 0.30336793038163806, + -1.494989717857403, + -0.5262854732894316, + 0.491181284674469, + 1.1631264584346572, + 0.6003227334065553, + -1.5811133384232856, + 0.7378483489042135, + -0.13410279961426894, + 1.782033783455403, + 0.3295842260334803, + 0.13288173621555735, + -0.13926254124875054, + -0.7743302494354012, + 0.7630967726129286, + 0.5831233642637481, + -0.7417388561244692, + 0.21777528169263277, + 0.2573793827852451, + 0.003786149947321914, + -0.16821901890106397, + -0.06700242059667874, + -0.42660698368528827, + -0.3013879619144234, + 0.20182656457702816, + 0.29667203698424827, + -0.64500915122857, + -0.49665263950913413, + -0.21863623520689615, + -0.18659147270617737, + -0.6308473130743879, + -0.7320818310351966, + -1.4792819722720005, + -0.3844977691149992, + -0.1186995330955712, + 0.8907748230131526, + 0.09408590469436628, + 0.03262183054141979, + -0.32736857773833344, + 1.4114778444374756, + -0.887770452020757, + -0.4208985543877891, + -0.5150366008922029, + -0.4483642060160712, + -0.8669163552614383, + -0.4979233923867889, + 0.7502139611881247, + 0.01126991792633718, + -0.33822260317647773, + 0.14326232585378915, + -1.0929870727111446, + 1.2748295879788156, + 0.877858521813293, + 0.2275345518560922, + 0.6572926015872191, + 0.5296422112325998, + -1.7269636605339593, + -0.1698725077360964, + 1.0115890069543858, + -0.505318248973872, + 0.052854531815035424, + 0.5402031289504291, + -1.0744303940623001, + -0.12555524411812694, + -0.20270643824914011, + 0.15118391940765333, + 0.12816260934015888, + 0.3232508516578582, + 1.741827199995256, + 0.3416234022817028, + 0.45570298646621, + 0.1589917816708061, + -0.16789762398829886, + 0.326917208610625, + -0.5957792145744776, + 0.6038832498962073, + -0.5919875970841058, + -0.5497515422128213, + -0.3948507344762221, + 0.6229164197532354, + -0.8445024799884822, + -0.5586996620181613, + 1.099462252540485, + -0.2493897762270888, + -1.501687288968268, + 0.169108029003293, + -0.5649784185641539, + 0.08710214029005449, + 0.44195965301915985, + -0.4362932625337126, + 0.7293327335514227, + -0.4687090221732762, + -0.21133685968645427, + 0.49337572096989213, + -0.47043552963286495, + 0.18177422592313994, + -0.28514331836735357, + -0.02750264015627598, + 0.3608052381820234, + 1.1501023492419027, + 0.26837224713187996, + -0.24893385716268618, + -1.551846031506678, + 0.6838670167097874, + -0.8697934806588505, + -1.172426029739389, + 0.59388925598598, + 0.3534194205587271, + -0.6317583168434208, + 0.5936761284688883, + -0.8887417203991967, + -0.10285346393096785, + -0.2185920221784419, + -0.5681556476474232, + 0.5818278316896505, + 1.0549000207100048, + -0.6488008701255903, + -0.22743518588912037, + -0.0067933598463363574, + 0.7297378251946646, + 0.14354649297838437, + -0.07096764473162452, + 0.22247993126132362, + 0.36951684822844694, + -1.2061679069980058, + -0.23614820766228287, + -0.5534824321545436, + 0.3392409841264721, + 0.5530066261064808, + -0.6989295492748994, + -0.105305410948089, + 0.0821394905945466, + -0.484071853504418, + -0.012073875641182251, + -0.16753299252723158, + -1.2169461245174094, + 0.22894041506112112, + 1.0545993736066592, + 0.34340982664847075, + 0.2568966825322024, + 1.1520238448100169, + -0.982027688953476, + -1.110677322604094, + 0.534036588843534, + 0.8239711630468629, + -1.1938562809004036, + -1.0452674567515015, + 0.012391949699053197, + 1.790988091980898, + 0.2880074509159579, + -0.43313500904275687, + -0.38909470760996406, + 0.15479372896656407, + 1.658174304482488, + 0.1557585818501974, + -1.3281092737023084, + 0.04176109537615244, + -1.3326242236069326, + 0.25525776316232884, + -0.31493631722085474, + 0.20392495300116165, + -1.3798765823107988, + 1.4078049216858826, + -0.6979660601796707, + 0.7656330388282272, + 0.5132142610430969, + -0.3779369742344209, + 0.7088732267292857, + -0.15396585708164076, + 0.7296521381512034, + -0.7571185352325495, + -0.2850561925441809, + 0.13751314665896863, + 0.5446277584052632, + 0.22229407107197166, + -0.857807795081183, + -0.6953838521636753, + -0.32890304263246367, + -0.0900183764203857, + -0.3553980750755802, + -0.786527706592354, + 0.7984301391339762, + -0.22888055378864933, + -0.6242990785864029, + -1.1149744381404254, + -0.1941442803624044, + 0.27873070048941523, + -0.3199137776521092, + 1.2348911658676116, + 0.6734780386174298, + 0.49901366023337523, + 0.48014697399426376, + -0.29337507791582723, + 0.08225880554224127, + 0.8802983550713595, + 0.2583396545018127, + 1.360760852786303, + -0.11397400625150897, + 0.2076211081412361, + -0.16968684561090452, + -1.2872331768052119, + 0.42843779103301133, + 0.105760570509113, + -1.318081752075104, + 0.12270112454007033, + -0.1670376559827446, + 1.8337642201953412, + 0.6287265558019409, + 1.0560290284503675, + 0.6204594049806603, + 0.49064975727960214, + 0.5335938634020342, + -0.17171248564640132, + -0.8859589895230483, + -0.1887612329412379, + 1.2093862935150943, + 0.39278309219825397, + 1.1583416453387914, + -0.19082921081086454, + -0.8679684665533811, + 0.28272223128890744, + -0.5770159147117425, + 0.08349910530716644, + 0.9638535694734324, + 0.09839770948199071, + -0.4365887061292041, + 0.22759691772010449, + -1.1170667856430199, + -1.4130917911140064, + 0.61054208330673, + -1.2782577982410674, + -0.6897553881808179, + -1.0755752259205904, + 0.39676924636786426, + 0.085340102215184, + 0.7895209736012152, + 0.6785987100523093, + 0.7660605388686503, + 0.716632850027738, + 1.536657982451204, + 0.5354949338640931, + 0.5849263806173282, + 0.9235120885781783, + 0.0073301283589284755, + -0.45651809207140365, + -0.19855049591880963, + 1.2511664484726925, + 0.18261898290762116, + -0.39675272129572864, + -0.46111030923353213, + -0.6631755414878778, + 1.2942665232263015, + 1.5265229748149898, + 0.37251649000892567, + -0.6311914588727653, + 0.7762124526561299, + 0.02564113128862375, + 0.54275630934215, + -1.0669167820821417, + -0.29312322701453786, + 0.0339035935241595, + -0.27995180273988474, + 0.09808724011445961, + -0.6409182837998908, + 0.7751724122592102, + 0.2897926067126505, + 0.23292539591621111, + 1.0844882237080036, + 0.12547279629063463, + -0.9749542137728557, + 0.4097203878653818, + -0.48106415539749003, + -0.7896684988022917, + 0.9932295438398961, + -0.35375782706682335, + 0.9620456941374884, + -0.004284409008962956, + 0.6061433536297258, + 0.6519451670486877, + -0.2831849339205853, + -1.024618863049489, + -1.3465800467212743, + -0.275502399844482, + 1.2758175889755348, + 0.8642979420500911, + -0.6831402515101104, + -0.1299602296215201, + -0.36954859343902113, + 0.8470067980444513, + -0.7430118705587456, + 0.4392053235162229, + 0.059945729432058246, + 0.09751160011383044, + 0.19934629546990731, + -0.805858710291059, + 0.5446852852221592, + -0.34341736939092, + -1.742918009707482, + -0.5118832251383038, + 1.0485115602142419, + -0.25021696301938795, + 0.7271196860728469, + 0.6863182624183645, + 0.9619564008580614, + -0.2679554447163933, + -0.7889447984233433, + 0.3374208792519053, + -0.4142142290797021, + -0.7755113019021964, + 0.7100809833265777, + 1.1196911958336326, + -0.22194068827805763, + -0.34241303777300375, + -0.7032655989343063, + -0.1002641898738657, + -0.42116162258080564, + 0.7817906714863255, + -0.7713288098740732, + 0.19738741564697848, + -0.8856288316343764, + -0.41518642087234753, + -1.1392347163406686, + -0.3055898603808139, + -0.427998364680652, + 0.21427978758689079, + 0.17622857435179462, + 0.7153434973251428, + 0.7805362456730126, + 1.0166818888300564, + -0.9968423248629525, + -1.6674460931557895, + 0.12097345192552514, + -1.433588529035579, + 0.1866015340290623, + 0.6812848067407216, + 1.0875227350803296, + 0.7329419581019998, + 1.0618228165637948, + -1.1329908921679963, + 1.4995446836244455, + -0.19674384454030844, + 0.6027676753781694, + -0.5729045854908157, + 0.5216488685621402, + -0.18964967986589032, + 1.0425528439480078, + 0.4452609518242411, + -0.5437254207265879, + 0.23183896644583693, + 0.6214683125766522, + 0.548003534759076, + 0.6933710525855452, + -0.4093869648773805, + 1.7478644624320243, + -0.3403212260209395, + 0.6454034746342057, + 0.17918161668739957, + 0.4779810248130753, + 0.4853929689589163, + 0.22313485015808393, + 1.1607295342678603, + 0.23900836908466175, + -0.09228624052635327, + 0.21274239071367923, + -0.4227574850932684, + -0.5861837454121791, + -0.2678852404988809, + 0.16400568180241046, + 0.32978340855294747, + -1.2397601104998248, + -0.36486940073256635, + -0.434365724965236, + 0.7798797873080758, + 0.13714473215510303, + -0.939341183426802, + 0.6862548510164266, + 0.5481774599289254, + -1.7034450855161336, + 0.30384285221156265, + 0.5094614811121776, + -0.1095223895181512, + -0.35477386204301936, + -1.3972198718583297, + 0.05063883635947702, + 0.6342892712342395, + 0.7703223929972239, + 1.6263936968494375, + 0.08162939432711318, + -1.2034505781405733, + -0.1522901166335204, + -0.23967570488304796, + 0.05864981032249405, + -0.3755534766547522, + 0.19666446489635755, + -0.722281575910078, + -1.414641105194653, + 0.37611682503677013, + 0.6859064381817727, + -0.3942440906781303, + -0.08032439390213188, + -0.0746648243100351, + -0.38664232045466157, + -0.42683703228878794, + 0.04587421176051916, + -0.6350259933041658, + -0.1349188888618292, + 1.8351158647130867, + -0.5614924084028017, + 0.008988373239524278, + -0.7227675285577622, + 0.8956068593703579, + -0.2473751005248778, + 1.2857864043732363, + -0.44439064832423575, + -0.15238171081436783, + -0.9277796631011815, + 0.6757166398331408, + 1.0755842509859732, + -0.1371431378292294, + 1.235674453873236, + 0.4355603659777167, + 0.7964378335587106, + -0.9716440540645402, + -0.6068508935641467, + 0.3507383633709002, + -0.3004386474382056, + 0.4160813090310218, + 0.16181565557372352, + -1.1263100545724982, + -0.1141876618179268, + 0.973582488649263, + 0.10767480588268583, + 0.42684666173218133, + -0.33422994959013846, + -0.1371949076477445, + 0.575451373586981, + 0.9285007522877098, + 0.6096154674716404, + 0.8796619789974928, + 1.0460569176405394, + 1.5742926627077585, + -0.8269105697481164, + 1.011404395579523, + 0.24333758328691038, + -0.053843648769213895, + 0.46531450243318273, + 0.5690763937096683, + 1.0899994902343573, + -0.4145019374607618, + -1.2394445890146626, + 0.18211262887310523, + 0.04789052950460668, + -1.0446934921248565, + 1.0430287759311112, + -0.36871280348967295, + -0.20368450759922965, + 0.05824646408499881, + 0.06487757879587182, + 0.9580758321617238, + -0.5105876054552335, + -0.4780097471697111, + 0.08805232765172745, + 0.47800190542816745, + 0.4102964453458382, + -0.10051329503533676, + -0.17469221314531105, + 0.96986689061758, + -0.19426565700491252, + 0.08539869342090176, + 0.6020035804535987, + -0.530758478905817, + 0.5057976339606142, + -0.7354526974478715, + -1.5145045841543336, + -0.3397487854723848, + 0.3782907764046291, + -0.5967286384999242, + 0.5291424905988888, + -0.27492678985828883, + 0.829985099846248, + 0.08062083857282856, + -0.5841930675683065, + -1.0975400643288524, + -1.059879831495068, + 0.881701157768825, + -0.8457438950472191, + -0.4865020634894715, + -0.8650690747940056, + -0.12523741765634708, + -0.1640459562877513, + -0.6560056977029451, + 0.5690359817092602, + -0.2845604206126708, + 0.02028649722684742, + 1.1415596912974224, + 0.6314388992873794, + -0.06126520733316677, + -0.04017963053767146, + -0.5175400452724328, + -0.26673652425473515, + 0.18383659148568043, + 0.40324803809613485, + -0.7570483441490774, + -0.7763989560767288, + 1.5054643656234405, + -0.394244451538259, + -1.49753181690139, + -0.5464353936976939, + -0.46151299879399615, + 1.1729121262216853, + -0.8843604942519119, + 0.5720494787896766, + -0.66004131254414, + 0.18610505723116344, + 0.5496771875902983, + 1.9336714186801525, + -0.38601264685275194, + 0.7013398204743259, + 0.41148997849019997, + -0.26044594652600817, + 0.2699242965745019, + 0.26985249587112425, + -0.5936050482120389, + 1.0709426839156755, + -0.6953501243352503, + 0.05207656050622847, + 0.5850649092256894, + -0.036369747894558734, + 0.0979581134912118, + -0.5914787165137149, + 1.0613752817031865, + 1.217196702695111, + 0.17764140830690234, + 0.3227496710091331, + -0.6212418038837657, + 0.3002116855954717, + -0.004714660577525797, + -0.436931135945212, + -0.026193965163030936, + -0.05103455519550438, + 0.7493751218658823, + 0.33075305854207226, + -0.15040671033766081, + -0.5251863893245409, + -0.1493803996403526, + 1.2198099518398144, + -0.2910816860207498, + 0.18481285743627587, + -1.2600556470458772, + 0.3962958248893762, + 1.2190989913571848, + -1.460870965403021, + 0.004859936991082521, + -0.6251223272976544, + 0.8875830396596803, + 1.661390663565943, + 0.4665368120434624, + -1.001477512211956, + -0.23214509248668042, + -1.0384343092325508, + -0.217826131929122, + -1.1325147721093831, + 0.396787664551125, + -0.47628233878256815, + 0.03823844742116567, + 0.27418254265492203, + -0.6244077070509569, + 0.7737980046455042, + -0.4870647644054452, + -0.5128971042777725, + 0.8234703457101612, + -0.5955575362117251, + -1.5302316564909682, + -0.11047344400740013, + 0.36136644138424373, + -0.0703094325387444, + -0.6156787925488874, + -1.1738369067526713, + 0.7870042470957442, + -0.34348881626944555, + 0.2599287530179741, + 0.4985400821306701, + 0.759525262088678, + -0.6916453164317655, + 1.3545740475199164, + 0.9282789060445633, + -0.08431679451654707, + -0.49906372419251277, + -0.13562188895336283, + 1.8624427857295418, + -0.287648429376786, + 0.7632116663884639, + -0.2723010536820508, + 0.6590415763908393, + -0.09700302785963777, + 1.0236152120238184, + 0.25660390654862075, + 0.6860282326826171, + -0.3301241854654524, + -0.3669046923280785, + 0.4632834900407419, + -0.12180553049192251, + 0.40769414162008355, + 0.31161913770131955, + 0.16504565346766456, + 0.3055465399524757, + 0.3270627441180266, + 0.8825874237104491, + 0.6778622910165533, + 0.4475437072629082, + 0.3846580998133578, + 0.8491049394724459, + -0.21602586144239083, + 0.3473369352325926, + 0.3862087513555755, + -0.9697806096329105, + 1.5360488456034314, + 0.8009336046692054, + -0.14614108797000902, + -0.0012518920743948064, + 0.3092641250810671, + -0.08413467843829205, + -0.8174552696253392, + 0.920688778774063, + 1.4193216363564833, + -0.41009495917622496, + -0.4994319658426051, + 1.3654431409369223, + -0.3546262499462346, + 0.052323834987818826, + 0.17415534409787717, + -1.044479069947962, + 0.17449967964618154, + 0.2085090656892965, + 0.28775702483427384, + 0.39395693715142877, + 0.8490383586037861, + -0.18984606705819615, + 0.38682275698919616, + -0.21640798741010603, + -1.3072306140481444, + -0.06632243034032077, + 0.32448654470204463, + -1.3563577450450084, + -0.6280842213487907, + -1.055249491190314, + -0.40724106223841233, + 0.8388277725778701, + -0.08173671442216447, + 0.9331902192868091, + 0.28803757016540027, + 1.3427496172101623, + -0.1458920303349029, + -0.4727997440306465, + -0.20253854016616665, + 0.38264963407033376, + -0.28957940396262766, + -0.9924795821685687, + 0.18354543994309408, + 1.1541900278155193, + 0.39580418090081515, + -0.4965190039503699, + 0.7844895298136714, + 0.19399760230547075, + -0.39452555749950985, + 0.24616554961981332, + 0.42765516123248576, + -0.7970053348825488, + 0.31357167879034265, + -0.26947601925470277, + -0.7835108611290074, + 0.6256269541331272, + 0.8049806994066158, + 0.042644070447090406, + 0.9306461425655571, + -0.2219959724894706, + -0.7868260111174479, + -0.9303609335454589, + -0.1299330357618133, + 0.1401404004358092, + -0.2532392875114215, + 0.24363540737656042, + -0.6743875605231597, + 0.021389111351775857, + 0.9320361432554604, + 0.5335602014249262, + 0.18959593762075977, + -0.5489375275303403, + -0.9223279492456093, + 0.26320715192123456, + -0.5390016616514921, + -0.5794031430408103, + 0.903971370471599, + 1.1319033664807203, + 0.5713603766442786, + -0.10525782536850462, + -0.03838822752409796, + 1.2155106147092647, + -0.9358030735631692, + 0.5504579125801322, + 0.9907303182732918, + -0.5859810527619884, + -0.30778117225986346, + -0.6339554090327421, + -0.7423385758300518, + 0.047498438759831535, + 0.4709740511106152, + -0.11162932548556193, + 0.43236542072683504, + -1.4146692836788672, + -0.6882561441720205, + 0.7147286854733433, + -0.7900755878794237, + 0.7787357886144147, + -0.9979277326741647, + -0.09341766987843046, + 0.6967031166823611, + -0.10545318457548944, + -0.9290103732771762, + -0.014021882281549134, + 0.10438898116084262, + -0.21978846954352538, + 0.5174343654987535, + -0.18744779704832376, + -0.05491981443849977, + 0.47942559378370786, + 0.15966677787559072, + 1.504960241795981, + -0.06717847783729701, + -0.14735029994558652, + -8.592050991063547E-4, + -0.46910583872054495, + -0.5334680491847373, + 0.833351657392727, + -0.54844939176699, + 0.27419990161271174, + -0.535570099247952, + 0.9371819707370476, + 0.300345338405172, + -0.013945400104664106, + 0.09805282125366191, + -0.19074786413825348, + 1.5591094003185426, + -0.4349760536582881, + -1.5020441376450981, + -0.2548434155609863, + -0.5923783941180437, + 0.4449301572956163, + 0.8360318953560567, + 0.535443445476245, + 0.5992665430066437, + 0.3761372914424572, + 0.5709492891397149, + 0.04805860325676255, + 0.4597014984718585, + 0.42346789813675173, + 0.13564631996481546, + 0.21234261828235457, + -0.3264580375333933, + -1.3374498644909316, + 0.9848718947784196, + 0.08672225183811162, + 0.43853207230141905, + -0.5081933620989919, + 1.5874607475115283, + -0.23003161700301775, + -0.9310744799259711, + -0.30220337195095187, + -1.1430172204991367, + -0.4806563635571805, + 0.7957512642068253, + -0.42408982347615526, + -0.6173358111175618, + -1.6316159895569649, + -0.3351450875495962, + -1.3371720373187752, + -0.5779695084964919, + 0.6368552767958974, + -0.8144079940761166, + -0.6314752984812451, + -0.8143635693398926, + -0.8093983458273426, + -0.7885267696694095, + -0.08792137780069267, + -0.1838566959822968, + 0.27101388722195635, + 0.043236120892652045, + 0.018625508151299423, + 0.09930357163652588, + -0.3971230130085303, + -0.6093247305344645, + 1.4538449926530947, + -0.08572151205360955, + -0.8680794758004611, + 0.45410220965733117, + -0.3660257153077043, + 0.6044120273426218, + 0.7605402293063958, + 0.1497194154195918, + 0.47653008788133155, + -1.2263410252769535, + 0.1334496743614034, + 0.30171960890086247, + 0.35044992243647183, + 0.04791509222174255, + -0.61873825623117, + -0.8424123756983802, + 0.03187216760901489, + -0.5720782734832316, + -1.0958225586264785, + 1.0444769604840127, + -0.21079992797339442, + -1.076054734699396, + -1.286153608097536, + -0.6012901865865503, + 0.8010690055453399, + 0.31167790772181575, + 0.3953634774837432, + 0.7454536874263603, + -0.6256539532680332, + 0.8566835713126624, + -0.13051837888825987, + 0.9734264009417783, + -0.3488268897361498, + -0.7900191312670661, + -1.0603654335034483, + 0.3676132390745096, + 1.2971186361368046, + 0.12382712006381177, + -1.3408535272798439, + 0.8254293574560895, + -0.4400162272994744, + 0.7334318588051499, + 0.48970693925843684, + -1.1639837236380717, + -0.3763302211919709, + 1.609580804919517, + 0.6128173378208199, + 1.326948517171316, + 0.4078497892820217, + 0.28254911237792946, + -0.6821077474908077, + -0.28314392651475806, + -0.8420054005342306, + -0.4255974072603386, + -0.3586357818260362, + 0.1693381034554977, + -0.5539051548305344, + 0.9356546312952191, + 1.2269593374273298, + 0.7006854123120415, + -0.43949761041417224, + 0.07312855319636023, + -0.3860226929361916, + 0.6591494528440243, + 0.9175082166245292, + -0.14661080233663962, + -0.3816558412981062, + 1.3270052004579462, + 0.6275225410570822, + -0.6180703049002081, + -0.516015628573777, + 0.7354005006002845, + -0.08280745210536332, + -0.44198651559202295, + -0.2332308000470488, + -1.6340414485314463, + 0.06850494534370485, + 0.6390596472296025, + -1.2911390290537006, + -0.1493650015317618, + -0.9317716567593725, + -0.09975988158440882, + -0.2024438348377012, + 0.374302094838607, + -0.29360526651904617, + 0.8435046768658976, + 0.6579141571479452, + 0.13744804315362127, + 0.17295103656718822, + -0.640704105985566, + 0.4203830428700868, + -0.4736989928158018, + 0.5356212544426889, + -0.2481323217339209, + -0.5713229398463443, + 0.5037143250026713, + -0.9270313063157536, + -0.02920070173434151, + 1.9356233607883386, + -1.3456165810695269, + -0.9526783098241446, + -0.2682744190059359, + 0.07957767458131469, + -0.10012006147590753, + 0.7537785313484425, + -1.1323259915579191, + -0.07502997081476674, + -0.7157912758643565, + -0.2125734585287043, + -0.5614535539158498, + 1.0693515940069385, + 0.10491542016415821, + -0.5149470154856823, + -1.4798204607723386, + -0.04524365095665629, + -0.8259389194860004, + -0.4704485528631882, + 0.09030816358247196, + 0.5231537636400357, + 0.12271673128441482, + -0.8341146848611243, + 0.874586072171896, + -0.5493245493723378, + -0.24865184825192008, + -0.4488244109512523, + -1.431784863231459, + 0.42058419170135675, + 0.9452618023252193, + -0.12024888597478889, + -0.006289632395331128, + 0.14336000079565242, + -1.5333359841822083, + 0.6161589668729462, + -0.5480292956243288, + -0.021095614044636456, + -0.1436213414697192, + -0.3951134972668525, + -0.24727580093674287, + 1.065985350630018, + 0.6436485475785801, + 1.0406676144772609, + -0.42642677044472826, + 0.5115929900507022, + -0.06453320333742901, + -0.03461963114189568, + -1.19166289488359, + -0.41447969873312374, + 0.5680104422559893, + -0.1024881957505319, + -0.4467517017403401, + -0.010646936791590868, + -0.1632045792971032, + 0.3953590000937256, + 0.1729897748649675, + -0.46071838082870575, + 0.1541232145909116, + 0.5719505441220569, + -0.14634278700288444, + 0.19349193789244412, + 0.17643346528973178, + 1.0560425621583662, + -0.7572753237077463, + -0.386141765888099, + -0.061507020932257135, + 0.2720627367504788, + -0.8554587037618884, + -0.380452484438598, + -0.38312109929360477, + -0.2074748521947271, + -0.6919222066053603, + 0.5104504653222527, + -0.7552417748918074, + -0.209079285420422, + 0.3272977035373589, + 0.7493282014810917, + -0.47610239165902823, + 0.009935172734327341, + 0.5090821342999318, + 0.8441887800163536, + -0.5096198583679935, + -0.19987612130052393, + -0.14993106595134945, + -0.6304858986687378, + -1.0137766246119542, + -0.9417277605874586, + 1.0330126999397053, + 1.4764888694083265, + 0.5973000042810607, + -1.9504011113652482, + 1.3921597775231316, + 0.03770414877591626, + 0.8097915763130241, + 0.16868907680585418, + 0.7547293084061998, + -1.343211954724584, + 0.32144513874233127, + 0.2716168612507648, + 0.04979575542706082, + 0.3883513259284689, + 0.5422306025725053, + 0.0363914928053299, + -0.45507707921777857, + 0.6716982726431565, + -0.030674638056656378, + -1.5917379190611962, + -0.23892026583946585, + -0.0034759010929095928, + 0.2717353137819641, + -0.38790612479586045, + 0.5416978090021739, + 0.13964205570346047, + -0.8890706210484112, + 0.8379129084262522, + 0.7663673432846151, + 0.710602720368639, + 0.7561831383424672, + 0.24957471998720637, + -1.322348959928295, + -1.6345041214518945, + 0.2750700619661269, + -0.9637607477366301, + 0.7661093471669069, + -0.08888867660695889, + -1.1304924316503464, + -1.011395601372739, + -0.1705204862718616, + -1.2693569848279362, + -1.168256106156731, + 0.3194720438399732, + -0.064515110847756, + 0.6276720632865199, + -0.0037733153594706925, + -0.4467301878919421, + 1.082456236489502, + -0.020663365713479452, + 0.22762722000454827, + -0.7895998815148713, + -0.21198464945921267, + 0.39729476947102016, + 0.3438790939387323, + -0.2745575981308853, + -0.37855893818098046, + 1.8733171769121673, + -0.10654509030137062, + 0.5393747246514589, + -0.02820990447688615, + -0.23998438842390302, + 0.08808489714126524, + -0.2519928549273172, + 0.9235875186775968, + 0.6207242232221853, + -0.09887784352020701, + 0.2793765419878019, + -0.8206260026964326, + -0.04658395906939055, + 1.0489080148039875, + -0.6958713583563219, + -0.6504239840214354, + -0.5995592785876673, + 1.32391827430909, + -0.95191988218847, + -0.5162314677494354, + 0.3029474326896874, + -0.8146588766177011, + 0.3325674881166, + -0.17810736839230656, + 0.2667104067837368, + 0.4893850196771999, + 1.6366267439364268, + -0.560385097464848, + 1.2268934389884965, + 0.20143969340721854, + -0.8713659577195791, + -1.3935836270514357, + -0.5160587529114332, + -0.8998788804571584, + -1.612388518223931, + 0.3680486642548128, + 0.6406635374354267, + -1.1779053971879878, + 0.26513732314836214, + -0.008855620533102807, + 0.512362452073789, + 0.5216790598838382, + -0.7199907854422639, + 0.14488380566362694, + -0.9576973513128366, + -0.8411710830942507, + 0.6862007646071876, + 0.07666964196231241, + 0.8689087568643366, + -0.2973738677308538, + 0.9307060017078751, + -0.9332676224319146, + 0.4642970615575049, + 0.07032443401296798, + -0.5967094285635435, + 0.7081218265682027, + 0.14314771861489758, + -1.0503418007706515, + -0.37693976949200414, + -0.0024954305126532457, + -0.3060885246304231, + 0.1813418369799876, + 0.20858774763371685, + -0.17160186116930384, + -0.18694323352006406, + -0.033295761112460326, + -0.22075091280658107, + -1.2198873589445598, + -0.34102274893346035, + -0.5237048774323648, + 0.32284001570906923, + 0.6415897100937111, + -0.22512737344141967, + -0.1720736856113653, + 0.8799087000696779, + 0.8364410574337828, + 1.0949917181132627, + 0.10233233068231802, + 0.06102657790314092, + 0.8972039501552173, + -0.248245439834066, + 0.5916216031418728, + -1.9397829959846278, + 0.5402761839250746, + 0.5723504671540991, + 0.6344661782324666, + -0.32887906873738215, + -0.26035368166450595, + 0.705255056079645, + 0.2986561835740931, + 0.3298994090398405, + 0.9543212450383173, + 0.8682357469388963, + -0.14997427589621945, + -1.0508274001430755, + 1.6696416775530845, + -0.3000046109421723, + 0.680940547301437, + -0.6601879593814853, + -0.05273042319419791, + 0.012384568953981087, + -0.34195083080766026, + -0.06614017456801022, + -0.9974820559201162, + -1.1010206535226374, + -0.2567285570007266, + -0.7848697767565365, + -0.06622154341351662, + 1.282262757719793, + 0.6084088807863121, + 0.6564562999732817, + 0.6320668585729544, + 0.7075472654960896, + 0.38684419279435645, + -1.0964711164684298, + 0.2138724066987224, + -0.30733161640830564, + 0.6282114977620631, + 1.150147803750084, + 0.33166314302581884, + -0.75398783393547, + -1.2448938601582547, + 0.513246629293432, + -0.5436798242558291, + -0.08315352908423887, + 0.5481671187486806, + 0.7652949524645454, + 0.5346573293764313, + -0.9436845841823027, + -0.4640789642459167, + 1.693266122137922, + 0.7970846401770099, + 0.45539351597073224, + 0.967735170317499, + 1.3404073454664702, + 0.7075537045152527, + 0.6373038868051281, + -0.2132427438994596, + -0.06063777061869633, + -0.4492957095237347, + 0.024012799812637278, + -0.23553312834809284, + -1.0555370775625055, + -0.2870223133838145, + 1.2612518927068803, + 1.0912374192050163, + -0.3679964920157413, + 0.5693072817655015, + -0.9434216593894047, + 0.4126009498651139, + -0.7503647616334947, + -0.007051162086710841, + -0.18236421638893527, + 0.4532797882757981, + 0.8475142543363414, + -0.693222342201902, + -0.5731882916664218, + -0.306999643049551, + 1.0777048111466032, + 0.5973235393127204, + -0.13541523615413534, + 0.40246807400321455, + -0.38503102790435445, + 0.008030706967847894, + -0.6209001701058989, + 0.23278677572773085, + -1.1148999392735943, + -0.5672426516228352, + -0.41184641957343826, + 1.0868519705488449, + 0.6855210727874971, + -1.509084613443635, + 0.6235117377303321, + 0.6390012903572152, + -0.7218997021404321, + 0.7755167932073186, + 0.08235060704048569, + 0.7033229488230561, + -0.3397109595312596, + 0.4627724954109217, + -0.3683541115736553, + 0.06187119328605062, + 1.707016897277966, + 0.4127956643469596, + -1.346699569190101, + -1.0861824271391192, + 0.31491752212170043, + -0.37159898632692073, + -1.3587476695804712, + 1.009322213460487, + -1.2430147735942119, + -0.37192749793867474, + 0.6775642429062013, + 0.8564620457415463, + -0.46087668940903354, + -0.07268189657091448, + 0.25222408109126604, + -0.8470726367090862, + 0.4846930978022908, + 0.5824212104371621, + -1.7348494294551333, + -0.3682104782832152, + -0.48008885204401064, + -0.39491069767424253, + -0.7831207263080361, + -0.4880675161565158, + 0.43541091553034666, + -0.25498341121430407, + 0.7754247907662174, + -0.9342939083855994, + -0.8767042837225336, + 0.6253826916126856, + -1.277185490618983, + 0.4296277850624826, + 0.1703619581378831, + -1.3656273395295293, + 0.4572056781404194, + 0.6960956975342347, + -0.2095854829628149, + 0.63834873208355, + 0.3350276858929503, + 1.5042481552943634, + -0.09802455545505322, + 0.7622247857966905, + -0.43910509632246314, + 0.5840750348461431, + -0.32010751537374343, + -1.3734205331974976, + -0.9765890740951377, + 0.192981891357532, + 0.010022888139172605, + -0.028626446155770962, + -0.41928913890700736, + -0.4825643701004103, + 0.9056258149755855, + 0.15005695137761385, + 1.0861039254763354, + 0.27129248082837754, + 0.5699663838500552, + -0.13790175351753578, + -1.0070078092571761, + -0.5967746485646906, + -0.390518929570296, + 0.6273334741411901, + -0.17987078306118898, + -0.38266751924341935, + 0.17264700654026427, + -0.8249217162401131, + -1.1171026333487726, + 0.9546179827480552, + -0.4660456617786517, + -0.686979499513217, + 0.008031532846532265, + 0.572759374154629, + 1.3022116831770394, + 0.43153399302324946, + 0.19882442927845345, + -0.3810940688744658, + -0.4065193816152885, + 0.756200178911078, + 1.0432441266540398, + -0.6700902065902926, + -0.2769544786308999, + -0.31309548490418326, + -0.45864609406530166, + -0.21016549331602893, + -1.21243911235184, + -0.32617784246850945, + -0.6064381617053508, + -0.6705030060972672, + -1.5235545331645495, + -0.6249354569379139, + -0.6998536739858658, + -0.29938771489318455, + -0.4023183349399575, + -0.5797722438548585, + -1.049064700356333, + -1.044524430133194, + -0.21794681827992549, + -0.31563011311580397, + -0.9391905695828632, + -0.39090294427966293, + -0.5691308483358178, + -0.5923172497700606, + -0.5762803541030674, + -1.6089342815245433, + -0.9374894197955653, + -0.8048753759097457, + -0.553928257304195, + -0.9350593966731507, + -0.8478698961641636, + -0.3135893133975273, + -0.3665663264609073, + -0.7212047377102166, + -0.650110961789234, + -0.38134156050348544, + -0.8028754733644436, + -0.958431013130539, + -0.5659650972923278, + -0.26303376121386385, + -1.0746565819139824, + -0.3700900207623646, + -0.9235500492365422, + -1.1147113071774875, + -0.24332372571221733, + -0.2563757968131056, + -0.21983369481442097, + -1.3566205027018041, + -0.8016628527476285, + -0.6489573983230515, + -1.041630843390639, + -1.0176957556891268, + -1.1090487151570274, + -0.23016246135393437, + -1.0273043081088762, + -1.3229609747179338, + -1.0942932672833954, + -1.403897455156342, + -0.37164201941486946, + -0.6267050423185159, + -0.8319487214099826, + -0.21165892582363488, + -1.2892188249273902, + -0.540293857474258, + -0.46074447782573485, + -0.20042839130370432, + -0.5698874867509242, + -0.6486516073967856, + -0.4797689913107062, + -0.8887897991881624, + -1.0434426550038163, + -0.46674787089635456, + -0.21801145013388168, + -1.0386163628040275, + -0.5552090532879129, + -1.689988089850173, + -0.48120237598078935, + -0.9669117419848205, + -0.34033060745687255, + -0.37864259599566746, + -0.40814285842246056, + -1.2803508877352612, + -0.2627248514730833, + -1.810829978775253, + -0.2560662173038422, + -1.010497881289468, + -0.9440341245610251, + -0.710015205448779, + -0.4790472666281038, + -0.20397996570100319, + -0.88578552217175, + -0.27594916944082715, + -0.6085163558193714, + -0.3435085150034526, + -0.44297417632523306, + -0.665828137782273, + -1.6372023074957889, + -0.37012677833191454, + -0.5461722370145821, + -0.2847558473810911, + -0.8555804905971572, + -0.5245163838040157, + -0.9323824415018227, + -0.281871992131144, + -0.3937168267179932, + -0.3471071017715048, + -0.45993562660346976, + -0.6545243260205158, + -0.517653133326549, + -0.7744558789954079, + -0.9063067964840115, + -1.2159370702633934, + -0.5062259803399821, + -0.5670215557756756, + -0.3290262835089621, + -0.4840325820597405, + -0.536130048498714, + -0.2038168243712482, + -0.36158832456812023, + -0.7152477848138624, + -0.3292007218496813, + -1.1207144808243001, + -1.0050656154293127, + -0.2083461741788719, + -1.25649223597924, + -0.4672593394784978, + -0.8964571759779854, + -0.6164606034110302, + -1.1893340734195177, + -1.0857579867949145, + -0.3315583733353988, + -0.2601271810466358, + -0.7388417400573113, + -0.24795082010107647, + -0.9011198197810343, + -0.7421287841984938, + -1.090224653750375, + -0.38728122805832693, + -0.5194183472099788, + -0.49598628092571334, + -0.51940191736098, + -0.7331189851006638, + -1.7071041684779718, + -1.0164889597544666, + -0.22708174190049038, + -1.4576646585443436, + -0.634732219969472, + -0.6910896325796797, + -0.9816934970504132, + -0.42696947416331926, + -0.6651273448186423, + -0.6914393064794533, + -1.2827316419632104, + -1.022811487756619, + -0.244845562924568, + -1.9209608367004143, + -0.3485953048402353, + -0.349623020597202, + -1.438756798499032, + -1.1341049296558654, + -0.30379977457127916, + -1.0155498415149298, + -1.837070145099175, + -0.5780040294495481, + -0.6660521829876345, + -1.874015204581276, + -0.6150494084421985, + -0.7249154597747995, + -1.1296896720954985, + -0.374148522830097, + -0.4763801432297795, + -0.6899328504125798, + -0.5375582345351355, + -0.5117167114649146, + -0.9626174764522315, + -0.49008439698556105, + -1.1178651724796456, + -1.6529817734135002, + -0.27981375974147127, + -0.20633696180610006, + -0.4119105759781471, + -0.8987789405109835, + -0.4824157399945097, + -0.4131170759291495, + -0.9028878400151085, + -0.33967918900750504, + -0.4565547089509539, + -0.28336393026608797, + -1.1645123396188233, + -0.30002568438263266, + -0.8283064525918642, + -0.32599255259795074, + -0.7625638835211482, + -0.4762696809840598, + -1.1293381610534272, + -0.7188878026090431, + -0.37224460289256484, + -0.25058746877295895, + -0.7763610500595394, + -1.6017290287771055, + -1.615398857421461, + -0.26964628046907757, + -0.9994722928497207, + -0.6784372775220285, + -0.5793774355055378, + -0.6417459652183312, + -1.2175311538465698, + -0.5678544951690117, + -0.8306219888222741, + -0.5693302836634007, + -0.5430455954009722, + -1.9064710856987268, + -0.6203341034558392, + -0.29547355456750835, + -0.215806709839707, + -0.317687005221851, + -0.3114263245498073, + -0.32898817213414866, + -0.8796398354648841, + -1.2700325947815279, + -0.6012621651366951, + -1.4720772848326094, + -1.222454236559198, + -1.6587767123384691, + -0.8335771508007195, + -0.37351144198755876, + -0.6931682225243582, + -0.5451260209697404, + -0.32457732556287106, + -1.052081024713513, + -1.082677852681755, + -0.5368932654051456, + -0.9778163209708134, + -0.38844092306268424, + -0.37235112251297436, + -0.7549192933164027, + -0.8890717733861596, + -0.3807034290402191, + -0.23244865018064514, + -1.1724351078793238, + -0.8747512043469098, + -0.42993290229194786, + -0.7378191147388838, + -1.1404609305311866, + -0.2896469655659367, + -1.2253127419850975, + -0.2123522946891248, + -0.2712139926998795, + -1.873870105547068, + -0.36061822501273894, + -0.6570527162275247, + -0.2159356975692715, + -0.937266984897451, + -0.7197097807850887, + -0.33413928995186915, + -0.3181376733001459, + -0.5950575848323421, + -0.5871912863856996, + -0.9897586743465859, + -0.6554949794271314, + -0.5656475194279046, + -0.365515879473213, + -0.6706722979742727, + -0.5209804203715434, + -1.3138400542445108, + -0.7837974870961965, + -0.5960066600218389, + -0.8956542415756501, + -0.3332354324728286, + -1.3867470999828955, + -0.746742535553127, + -0.650251319842868, + -0.445000268631785, + -0.7005403027520186, + -0.38324540348562997, + -0.3854304119898965, + -0.21709426622420092, + -0.43130768282713006, + -0.8244008618417824, + -1.2012358401225989, + -0.3231830557550737, + -0.4645923818375927, + -0.4218250112859031, + -0.3753430783375144, + -0.6433096341757331, + -1.7370919163416692, + -0.5299813856044773, + -0.851291234831129, + -0.43340910299492785, + -0.5628092208413957, + -0.6629400898813721, + -0.8598767417935104, + -0.6714117274667127, + -1.0312869173298578, + -0.37931329205261216, + -0.7439465060291085, + -0.9249260545043659, + -0.9495369351219503, + -0.5693241244430776, + -0.2201899517619367, + -1.1690920645560394, + -1.1430107822578992, + -0.8004688660327093, + -0.8957269947341436, + -0.8112947050306729, + -0.301999014979277, + -0.932094944406248, + -0.6981414144988081, + -1.2564480394164952, + -0.8630941675843744, + -0.43782055864981906, + -0.5879512097107121, + -0.2458442095486133, + -0.38524855824716425, + -1.8202020920840523, + -0.46500060827132816, + -0.9331397166195625, + -1.114006283534009, + -1.2158652191893202, + -0.6818972734998402, + -0.9791606045113055, + -0.4754488150462338, + -0.3524375257042418, + -0.2092251732405906, + -0.43828380870589245, + -1.3217731270596873, + -0.2930324731797192, + -0.6182349603183691, + -1.0845971698355168, + -0.5171861517565712, + -0.6163764227999722, + -0.9021565153082152, + -0.21523812816572133, + -0.7626489845197216, + -0.6067576403142491, + -0.21934374226916134, + -1.233953843219272, + -0.38113483560717765, + -0.21573566144301118, + -0.822976316159534, + -1.4071246107759938, + -0.9796764825995902, + -0.38732291070190433, + -0.4428888644176962, + -0.5870254665860493, + -0.9623665583854876, + -1.0949295776081294, + -0.4448839534911389, + -1.0318907290031882, + -0.745453928092605, + -0.5698291542981625, + -0.4358637283294949, + -0.38471535283491154, + -0.46102519850751306, + -0.27076408652673367, + -1.0402559031675411, + -0.8961798633172818, + -0.7113830218010951, + -1.0248964494253812, + -0.5534151671494509, + -1.3544905716140823, + -0.5655100095650718, + -1.014250743403296, + -0.3848224395582883, + -1.0300169980679734, + -0.2544820279657471, + -0.9022782843667297, + -0.7137941869121261, + -0.5834880033179879, + -0.24954765831413164, + -0.8851718746588414, + -0.3790537043018313, + -0.3930670904296514, + -0.28468056207690395, + -0.43671632395843857, + -0.7726501589098768, + -0.33969892788681677, + -0.6201223986434433, + -0.5413845170402038, + -0.8287192169307782, + -0.6840992609430893, + -0.2988192513886851, + -0.8979217032490256, + -0.992520466904213, + -0.45831958766082914, + -0.5204435488763746, + -0.4657195895764084, + -0.6915279302028525, + -0.2702918153279385, + -0.8741901219475343, + -0.23368859185782298, + -0.9446487738513568, + -0.6202678327801879, + -0.42947566920909125, + -0.6732352153189156, + -0.4879939955596451, + -0.5438282694426625, + -0.6502838291453714, + -0.8675569170327793, + -0.24361268934763655, + -1.0444282826645064, + -0.4419039196175476, + -0.4407271199051713, + -1.6012265094843834, + -0.6820557708435395, + -0.4052177075715849, + -0.6366607310637449, + -0.23771761351124374, + -0.41643263462373387, + -0.9561951379749694, + -0.7663147032004962, + -1.0431649657352595, + -1.3479413791130634, + -0.7907304591780814, + -0.5307430104107678, + -1.163968374737862, + -1.484049177723838, + -0.4500632473026825, + -1.3113985670537769, + -1.0113159178396234, + -0.6681092371509354, + -0.3558203580892433, + -1.2802916522468104, + -0.9102856905335889, + -0.30122401721325315, + -0.33329785297573, + -0.558109604020826, + -0.40985331210760234, + -0.46794968383241076, + -0.35915592751157943, + -0.9758244279811656, + -0.3105044888380374, + -0.8111092579057751, + -1.3652190998021585, + -0.8469947394497068, + -0.5551974112945685, + -1.2143906804970575, + -0.7203217968175905, + -0.28294096300034755, + -0.5888395253703702, + -0.5694643858258162, + -0.9534093184190789, + -0.713403175294715, + -0.9528970055984789, + -0.5342492593474878, + -0.35352788558041626, + -0.2719431078225173, + -1.1628519521087262, + -0.3848467343598421, + -0.7832027150343007, + -0.7244062231258335, + -0.7453578951392736, + -0.3709341540748588, + -0.49475091150648365, + 0.3577196337322672, + 0.38120152170487875, + 1.315387055786036, + 0.5953357555284627, + 0.25266074604351146, + 1.3852288134206934, + 0.6991267935924268, + 0.6468797718291398, + 1.980244591974188, + 0.2729866403886864, + 1.4523811501283959, + 0.7479003290357062, + 0.7916719442738713, + 0.32756788679220344, + 0.949492763683675, + 0.45651720706633653, + 1.026402069617886, + 0.7517544809329819, + 1.0928342592260316, + 0.29319195881965365, + 0.8928506923221574, + 0.8383094138808699, + 0.3946505680595029, + 0.33610643265683593, + 1.8810288334439051, + 1.2427288023918635, + 0.5449634683963884, + 0.5156079975915611, + 0.9433381518453102, + 1.099653282982061, + 0.6851906670382896, + 0.3151807072992044, + 0.41727255816454273, + 0.7241688429318504, + 0.24743456484205273, + 1.215472468638887, + 0.23310742491797648, + 0.33841686763415685, + 0.9746887592974112, + 0.27267411212996584, + 1.234599488724196, + 0.8914354343871522, + 0.22840601718040937, + 0.3338847629445979, + 0.3595773382937585, + 0.9705298425723349, + 0.40839936369462904, + 0.9378252727003911, + 0.2921721264679654, + 0.8743136171262818, + 0.5623369081799418, + 1.0412971901427597, + 0.5903870689802504, + 1.1040623104163163, + 0.37763435649736793, + 1.2746268534699852, + 0.8471582607294912, + 0.685972468721095, + 1.2182703151660814, + 1.1511799109314662, + 0.30277481528459427, + 0.7698294371471126, + 0.9673079275255166, + 0.29303309084238055, + 0.5792131725512778, + 0.7340473663190551, + 0.27444261414800675, + 0.34627748133747155, + 1.03514919498675, + 0.9266449416643926, + 0.7509990077997564, + 0.5608338328733573, + 0.36307118091577256, + 0.3362413571971963, + 1.7041054699837481, + 1.8797683472548667, + 0.66936675072242, + 0.25744809585514666, + 0.2883434827008925, + 0.7824477403339829, + 0.537513159252127, + 0.5487255395747406, + 0.5960954269753629, + 0.4421293827763971, + 0.936971276797393, + 0.35327681779017855, + 1.4649065961762402, + 0.7726042153132815, + 1.0930587783885501, + 1.053027269277877, + 0.26018840111199004, + 0.7903196304926129, + 1.6198541252188934, + 0.9822982240989394, + 0.32309623106764473, + 0.5705426716708308, + 0.688251842410987, + 0.47291761710490154, + 0.5131010875562078, + 0.8823633039296211, + 1.220985428996956, + 0.5833487995276065, + 1.1661257516769223, + 1.5127233673845273, + 0.3635530307964068, + 0.24923367382706216, + 0.26885811970881335, + 0.5741596517178412, + 0.43065236000542334, + 0.38389337849973226, + 0.5253431387231579, + 0.28111347408055265, + 0.8255618666892993, + 1.1390679366518868, + 0.4225848549356125, + 0.8461949437452831, + 0.8692202714557967, + 0.3966265262784202, + 0.45268522022075564, + 0.23902841443231676, + 0.374991261517544, + 0.25986163781144656, + 1.759535832173596, + 0.4827361428170929, + 1.606605940355794, + 0.7118294218004526, + 0.6115820781916033, + 0.9004661171993174, + 0.6670876124201572, + 0.5006568620698242, + 0.6004641733167774, + 0.3164447178392463, + 0.20223447811576445, + 0.7132482308984212, + 0.47288492360569206, + 0.5314598620790489, + 0.2331538747759109, + 1.4008507797516327, + 0.5442643078477563, + 0.644827534223932, + 1.031751496105358, + 0.4914511058486843, + 0.4990474281595659, + 0.9222494916344185, + 0.4074405933532646, + 0.42896864835007004, + 0.3247265156640924, + 1.0468945681380808, + 0.26470721661230634, + 1.603634864854594, + 0.24793516318995965, + 0.5199109075571043, + 0.586516436480905, + 1.2444541961453244, + 0.35250305506538854, + 0.271792654529859, + 0.7297455036212404, + 0.40128592542601615, + 0.5669865330104998, + 1.3746845928751643, + 0.32118246944077483, + 0.41253689304090396, + 0.5125855359382898, + 0.505088883611897, + 1.2136725049907318, + 0.32608250619123896, + 0.8720666728055683, + 0.5471772626688537, + 0.3435093867889516, + 0.6106459281492058, + 0.4886673474864161, + 0.5132792648972277, + 1.040907015761561, + 0.5752174039971493, + 1.1512781934777667, + 0.5165770973873638, + 0.20407828850520665, + 1.738809508600163, + 0.444025284600735, + 0.3657200917119612, + 0.8983986389754175, + 0.2944231301984469, + 0.5463513345906967, + 0.44453165184797444, + 0.21504916115601722, + 0.6613498956064958, + 0.6091857215859728, + 0.5755308667214186, + 0.780879965451381, + 0.5290236285838725, + 0.26750961741440366, + 0.8967488173818653, + 0.5754923766051254, + 0.5889925695137452, + 1.451903872608981, + 0.6327737537680732, + 0.39553593307983564, + 1.3155157731497598, + 0.5147536934689084, + 0.297565656980294, + 0.514080375710645, + 0.2983454831524536, + 1.082340314758559, + 0.7204704211314488, + 1.2192173246235365, + 0.33577090599280957, + 0.36870425412388724, + 1.266043357112656, + 0.3962122828023712, + 0.7824914285146274, + 0.928553108017466, + 0.7893322313585396, + 0.25864794688037146, + 1.2531232146560285, + 0.5490398233670406, + 1.1787584305274768, + 1.5435423624328741, + 0.43804310565712357, + 0.3200723465162274, + 0.8722512676931378, + 0.7488638692769157, + 0.29540605549521415, + 0.6231872563049703, + 0.8011190075443969, + 0.935763188910961, + 1.0611800335200954, + 1.8146796572974848, + 1.6356240266381514, + 0.8120776478592207, + 0.6605816529918048, + 0.3405196467838138, + 0.5130214933146788, + 0.637951715265005, + 0.2552184031515808, + 0.6161896356775357, + 0.3943074569986639, + 0.6524005038499895, + 1.0878004723210732, + 0.24820689579024485, + 0.380663540614841, + 1.0516167998199968, + 0.8422017562717697, + 1.6759350989915942, + 0.9299972840564763, + 0.6000562900011159, + 1.060019117066314, + 0.4897547089287059, + 0.7253546547478418, + 0.9956034171909399, + 0.42360295300140627, + 0.3000982150210423, + 0.7350911135921385, + 0.3073167013887763, + 1.649807290734707, + 1.5691343210752684, + 0.2718471193104512, + 0.7064058921765657, + 0.6144022425411559, + 0.6331359040312781, + 1.4092405306217057, + 0.6207268606261035, + 1.6693700372000753, + 0.25600648711234747, + 0.3519435120352017, + 1.1191473552310371, + 0.3774231208997555, + 0.47450758416703437, + 0.7959832054176398, + 1.2621648998355934, + 0.8829230479584954, + 0.23926876983838713, + 0.2014164766908565, + 0.64372202083422, + 0.7846210024920616, + 1.0986492276489084, + 0.8816037633956453, + 0.6821505014940485, + 1.0638769356562396, + 0.5382447834276641, + 0.485329538888813, + 0.9999288871473523, + 0.5471012780478752, + 0.6893033680269068, + 0.5842437570544678, + 0.7925440221315615, + 0.43319244430834064, + 0.7081168857642806, + 0.8449330277433325, + 0.8284446671194172, + 0.8784708437483, + 0.3532757071009893, + 0.3762208885195589, + 0.4794068228247771, + 0.7138490371854103, + 0.26531529694976186, + 0.35237168098810595, + 0.7377480046896951, + 0.6904150002775532, + 0.3294110573316787, + 0.23528332483366593, + 0.37939865252913635, + 0.542552959783536, + 0.7625866079989139, + 0.6208964755523958, + 0.92718293787701, + 0.4867500871726693, + 0.23271829789506374, + 1.2186061428197021, + 0.7727547382654337, + 0.9764308109282427, + 1.0808045865100646, + 0.6914127161937882, + 0.33663330451288337, + 0.9699119039263234, + 0.4028153706220258, + 0.2645753721122372, + 0.4768888485123658, + 1.4606014917942316, + 0.2975940098496993, + 0.2399539208497752, + 0.21353724114500414, + 0.27674303725213756, + 0.5131460225923531, + 0.3346750855304431, + 0.7138160192814548, + 0.8958545948070616, + 0.5228190161651498, + 0.7937743967596307, + 0.6430811109243194, + 0.6044878710388882, + 0.44480531385982464, + 0.22778498412697867, + 0.6711018579482526, + 0.3291987072778412, + 0.9373972791288807, + 0.20491195223504882, + 0.30944286565011275, + 0.7382449895402436, + 0.22428309477432262, + 0.5363156368015785, + 0.6535587951637901, + 1.4578485356392985, + 0.970000051725854, + 0.7436229532344398, + 1.0690326725745862, + 0.5801698637900816, + 0.5679630247571943, + 1.4629356655117443, + 0.4643407696770656, + 0.6529519518857706, + 0.5790746911995054, + 1.2244036105941307, + 1.538779433064309, + 0.5842595340481814, + 0.3364269767030913, + 0.6379984765411385, + 0.4359223830522402, + 0.7845685886523617, + 0.24237976380786844, + 0.49093953854035965, + 0.4744652226242779, + 1.158888701325575, + 0.23635050775107752, + 0.25992236997006307, + 0.6609907703513921, + 1.0810868109947176, + 0.764223258272673, + 1.2645195537371596, + 0.6413468077829441, + 0.897477188163828, + 0.24514598299729418, + 0.22452128437702193, + 1.3125056399239596, + 0.9836116917849962, + 0.583493961303654, + 1.0061981962352358, + 0.24940252025016665, + 0.8820726044896027, + 0.22968130912196186, + 0.8024035507952957, + 0.6369570292696975, + 1.012832741790917, + 0.7208655331483226, + 0.2875118484885044, + 0.7297991408733793, + 1.0736052473582227, + 0.2133339781187614, + 1.3528324299573153, + 0.2380617078911099, + 0.5184637886957627, + 0.8511794460643791, + 0.8516056034623126, + 0.586642396773589, + 1.2077239623465779, + 0.8067065485209096, + 0.6777521586021386, + 0.3022646644950962, + 1.4061804420665978, + 0.26016154824740495, + 0.40247528766552615, + 0.44659092290371244, + 0.40552738319478826, + 0.20946798416424398, + 0.8141303870442301, + 1.1178762604789265, + 0.3851499932133968, + 0.30556836337713555, + 0.6048858489135097, + 0.23236499725926996, + 0.5235608187512436, + 0.6893122195764066, + 1.1850991454218256, + 0.8368096077122636, + 0.3220611490326809, + 0.85101345032577, + 0.23531967259191575, + 0.6779113601779558, + 0.2272177555586885, + 0.20903006685523717, + 0.9020578518351583, + 1.0763529658785957, + 1.4725592977793247, + 0.8770946494362918, + 0.6149617683301464, + 0.778935648590221, + 1.9307329906822641, + 0.5625970585477897, + 0.6173526866951027, + 0.2558835775203929, + 0.45152534759254825, + 0.3326881761914924, + 0.7960471088964823, + 0.8156254332997396, + 0.4352505925001337, + 0.3418808292969631, + 1.928456026558719, + 1.3241718259969164, + 0.6801067068315311, + 0.34398984581997655, + 1.5659369088519786, + 0.931365517140982 ], "type": "scatter" }, @@ -20216,83 +20227,41 @@ }, { "fill": "toself", - "mode": "lines+markers", + "mode": "lines", "name": "Mode", "x": [ 0.0, 0.0, 0.0, 0.0, - 0.0, - null, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - null, - 0.2, - 0.2, - 0.2, - 0.2, - 0.2, - null, - 0.2, - 0.2, - 0.2, - 0.2, - 0.2, - null, - -0.2, - -0.2, - -0.2, - -0.2, - -0.2, - null, - -0.2, - -0.2, - -0.2, - -0.2, - -0.2, - null + 0.0 ], "y": [ -0.2, -0.2, -0.2, -0.2, - -0.2, - null, - -0.2, - -0.2, - -0.2, - -0.2, - -0.2, - null, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - null, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - null, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - null, - 0.0, + -0.2 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines", + "name": "Mode", + "x": [ 0.0, 0.0, 0.0, 0.0, - null + 0.0 + ], + "y": [ + 0.2, + 0.2, + 0.2, + 0.2, + 0.2 ], "type": "scatter" } @@ -21141,7 +21110,7 @@ "plotlyServerURL": "https://plot.ly" } }, - "text/html": "
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" @@ -21157,8 +21126,8 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:13:38.569644Z", - "start_time": "2024-03-13T13:13:37.609252Z" + "end_time": "2024-03-21T13:47:02.951463Z", + "start_time": "2024-03-21T13:47:01.712089Z" } }, "id": "24bc79646157a9bf", @@ -21183,58 +21152,32 @@ "name": "stderr", "output_type": "stream", "text": [ - "100%|██████████| 500/500 [00:32<00:00, 15.41it/s, Success Probability=0.336]\n" + "100%|██████████| 500/500 [00:30<00:00, 16.24it/s, Success Probability=0.228]\n", + "Inserting TaskTree into database: 100%|██████████| 5049/5049 [01:15<00:00, 66.72it/s] \n" ] } ], "source": [ + "pycram.orm.base.ProcessMetaData().description = \"Experimenting with Pick Up Actions\"\n", "fpa.sample_amount = 500\n", - "with simulated_robot:\n", - " fpa.batch_rollout()\n" + "batches = 1\n", + "for batch in tqdm.tqdm(range(batches), total=batches, desc=\"Processing Batches\", disable=True):\n", + " with simulated_robot:\n", + " fpa.batch_rollout()\n", + " task_tree.insert(session)\n", + " reset_tree()\n", + "session.commit()" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:14:11.029579Z", - "start_time": "2024-03-13T13:13:38.570880Z" + "end_time": "2024-03-21T13:48:49.425825Z", + "start_time": "2024-03-21T13:47:02.952200Z" } }, "id": "7461b696b899f603", "execution_count": 5 }, - { - "cell_type": "code", - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "Inserting TaskTree into database: 100%|██████████| 5299/5299 [01:19<00:00, 66.58it/s] \n" - ] - }, - { - "data": { - "text/plain": "TaskTreeNode(id=1, action_id=None, action=None, start_time=datetime.datetime(2024, 3, 13, 14, 13, 37, 62434), end_time=None, status=, reason=None, parent_id=None, parent=None, process_metadata_id=1)" - }, - "execution_count": 6, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "pycram.orm.base.ProcessMetaData().description = \"Experimenting with Pick Up Actions\"\n", - "task_tree.insert(session)" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-13T13:15:30.631935Z", - "start_time": "2024-03-13T13:14:11.030250Z" - } - }, - "id": "546851521d97359", - "execution_count": 6 - }, { "cell_type": "markdown", "source": [ @@ -21250,27 +21193,27 @@ "outputs": [ { "data": { - "text/plain": " arm grasp relative_x relative_y\n0 right right -0.034396 0.253821\n1 left right 0.027372 0.346807\n2 right right 0.051392 0.319307\n3 left right 0.074518 0.265504\n4 left left 0.174954 0.857668\n.. ... ... ... ...\n163 right front -0.721319 0.461749\n164 left front -0.407319 -0.462141\n165 right front -0.872285 0.151296\n166 right left -0.371555 0.522857\n167 right right -0.492056 -0.485929\n\n[168 rows x 4 columns]", - "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
armgrasprelative_xrelative_y
0rightright-0.0343960.253821
1leftright0.0273720.346807
2rightright0.0513920.319307
3leftright0.0745180.265504
4leftleft0.1749540.857668
...............
163rightfront-0.7213190.461749
164leftfront-0.407319-0.462141
165rightfront-0.8722850.151296
166rightleft-0.3715550.522857
167rightright-0.492056-0.485929
\n

168 rows × 4 columns

\n
" + "text/plain": " arm grasp relative_x relative_y\n0 left left -0.546259 -0.356499\n1 left right -0.203552 -0.605282\n2 left left -0.230694 -0.350203\n3 left front -0.366892 0.442297\n4 left right -0.296431 0.054815\n.. ... ... ... ...\n109 right front -0.014655 0.674613\n110 right right 0.039657 0.299975\n111 left front -0.173449 0.398118\n112 left left -0.155267 0.715950\n113 left right 0.148996 0.282944\n\n[114 rows x 4 columns]", + "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
armgrasprelative_xrelative_y
0leftleft-0.546259-0.356499
1leftright-0.203552-0.605282
2leftleft-0.230694-0.350203
3leftfront-0.3668920.442297
4leftright-0.2964310.054815
...............
109rightfront-0.0146550.674613
110rightright0.0396570.299975
111leftfront-0.1734490.398118
112leftleft-0.1552670.715950
113leftright0.1489960.282944
\n

114 rows × 4 columns

\n
" }, - "execution_count": 7, + "execution_count": 6, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "samples = pd.read_sql_query(fpa.query_for_database(), engine)\n", + "samples = pd.read_sql(fpa.query_for_database(), engine)\n", "samples" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:15:30.648040Z", - "start_time": "2024-03-13T13:15:30.632757Z" + "end_time": "2024-03-21T13:48:49.442672Z", + "start_time": "2024-03-21T13:48:49.426520Z" } }, "id": "5d9cd8fe3195d669", - "execution_count": 7 + "execution_count": 6 }, { "cell_type": "markdown", @@ -21289,18 +21232,33 @@ "variables = infer_variables_from_dataframe(samples, scale_continuous_types=False)\n", "model = JPT(variables, min_samples_leaf=25)\n", "model.fit(samples)\n", - "model = model.probabilistic_circuit\n", - "arm, grasp, relative_x, relative_y = model.variables" + "model = model.probabilistic_circuit" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:17:05.078605Z", - "start_time": "2024-03-13T13:17:05.071510Z" + "end_time": "2024-03-21T13:48:49.458656Z", + "start_time": "2024-03-21T13:48:49.443434Z" } }, "id": "8cfff78b3abd589b", - "execution_count": 21 + "execution_count": 7 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "arm, grasp, relative_x, relative_y = model.variables" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-21T13:48:49.462221Z", + "start_time": "2024-03-21T13:48:49.459897Z" + } + }, + "id": "77642e8f22ac880a", + "execution_count": 8 }, { "cell_type": "markdown", @@ -21321,20016 +21279,20016 @@ "data": [ { "hovertext": [ - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.6087440920448061", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748", - "Likelihood: 0.4763472330270748" + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.40984224003688025", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.646004144008639", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.24991480928232573", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457", + "Likelihood: 0.5706693888192457" ], "marker": { "color": [ - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.6087440920448061, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748, - 0.4763472330270748 + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.40984224003688025, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.646004144008639, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.24991480928232573, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457, + 0.5706693888192457 ] }, "mode": "markers", "name": "Samples", "x": [ - 0.4454473561983937, - -0.11089104000282013, - 0.5710393656759419, - -0.14941327254291925, - -0.2343010285350915, - -0.7064425950849652, - -0.4160717850731219, - -0.18899651957578145, - -0.24596804097165492, - 0.18196996886087424, - -0.21480242251832027, - -0.1531833304888266, - -0.037910297560927564, - -0.3613340342820306, - 0.2052353637234855, - -0.3328546807527252, - -0.19687224885880483, - -0.36197566515233925, - 0.5878302280032505, - -0.5369143872020734, - 0.2939919892381174, - -0.34051140638968386, - 0.3360232898700187, - -0.0514376397574795, - -0.25518848291088725, - -0.5016364980833922, - 0.0926896529838881, - -0.3917062214162105, - -0.5452430449116754, - -0.15342472035295984, - 0.022307171465376863, - 0.3727631759585074, - -0.6038972220319024, - -0.4125467312085292, - -0.4792189492273889, - -0.057668958594455755, - 0.19795037334856347, - -0.6119788879657624, - 0.39645623244559125, - 0.09077338834370385, - 0.19031569338785714, - -0.09286913770279304, - 0.2920901260889549, - 0.2544883545811677, - 0.1755033886815417, - 0.254342881598585, - 0.260064186859709, - -0.31946837557973273, - -0.4242086071497505, - -0.6083466187073574, - -0.44053732916181915, - -0.29918588039491434, - -0.4530847742256059, - 0.2712215520216418, - 0.44062569886432323, - -0.6762141742147593, - -0.09050006370943464, - 0.2746959833286259, - -0.5014160631466476, - 0.40196266798407565, - -0.6761542958848055, - 0.4209920678986031, - -0.7310488554882372, - 0.018931774908213517, - 0.6586608923032021, - -0.5778200340152329, - 0.1419540669601156, - -0.4796335851482425, - -0.3491291964353084, - -0.15971562688358232, - 0.47726886709147387, - 0.026747279552132297, - -0.39042250420619257, - 0.6353631054037182, - 0.34396651208376416, - -0.5457213960065672, - -0.18350937613701634, - 0.4145631392183281, - 0.08447456410897558, - 0.37718689042050435, - 0.4916723362526768, - -0.49287876454944884, - -0.4056174788424846, - -0.7078208781012341, - 0.5202264066337418, - 0.3199281650627229, - -0.2463919001552719, - 0.6056244705125414, - -0.27311203654258753, - -0.5033378923790488, - 0.49528165368911437, - -0.16585222832314472, - -0.6340662761126755, - -0.11434479827354549, - 0.5770408512693802, - -0.7251095320455188, - -0.10342784749299783, - -0.3101571093425869, - 0.5885193413577393, - -0.6457164555129192, - -0.7163295890084154, - 0.5327871833143311, - -0.6736464430689871, - 0.12019680121471743, - 0.2161231785343598, - 0.5365266425018008, - 0.25511315704874915, - 0.2980016937243134, - 0.10382408341614591, - 0.40130274440103986, - -0.5073820996034815, - 0.24962273439069282, - 0.27917529109147876, - 0.4438146926878145, - 0.06485110618531653, - -0.13705044744440043, - 0.14491586031211745, - -0.24043279144210505, - 0.11801545473424979, - 0.6052405723611004, - 0.23980591595745848, - 0.15206745288828438, - -0.6396294043009085, - 0.4329059418361224, - -0.02577503338713394, - -0.634843448088235, - -0.16755406067282996, - 0.1933862507825146, - -0.45282498370350455, - -0.4790792057209454, - -0.19806287448234716, - -0.5286828954058319, - 0.13922384348464079, - 0.0038429164225874946, - -0.6261502673990162, - 0.2700742964187667, - 0.36499176228053487, - 0.5618008462948151, - 0.5111525241773826, - 0.04113869506300183, - 0.13586592846289947, - 0.12478823553902596, - 0.20114095463350345, - -0.26945451278215127, - -0.13529106075861863, - -0.06243906067320293, - 0.15205570197985618, - 0.1795577892646375, - 0.06121462123879562, - 0.08057325412355443, - 0.07251019459850838, - 0.08941433477860516, - 0.5718029020486283, - -0.5141395438875778, - -0.38703237610081104, - -0.367497801569079, - -0.2992123215235272, - 0.06434460673374753, - -0.6392979685480753, - 0.2497979183947806, - 0.5208411618552454, - -0.24722311460322677, - -0.21771361560124258, - -0.619369201577475, - -0.5634006676828716, - -0.6136543848114238, - -0.27594865208188907, - -0.5357492000780432, - -0.488203400757565, - -0.3386784372126736, - 0.6100685999306946, - 0.6113964164570117, - 0.029999335047808606, - 0.3523266288981487, - 0.3089307094334036, - 0.5919613466883388, - -0.6385544979206305, - 0.23443226577135723, - -0.4094202986794217, - 0.4698963656276499, - 0.0026904757563149806, - 0.23499803871256086, - -0.5624944032182047, - -0.011093422485949134, - 0.3871925936976316, - 0.5241319636548026, - 0.034103050277218716, - 0.44382959317230386, - 0.5677019769564974, - -0.5058378296806741, - 0.02245062963453015, - 0.3812929480342552, - -0.19574067498531966, - 0.01629567545638122, - -0.07912271969116069, - -0.03425684556446307, - -0.2219077079913223, - 0.4940946790988169, - -0.7637178368160429, - 0.104909697543912, - -0.6874922707615666, - 0.04226433607847213, - 0.13095618794841812, - 0.44112843275643543, - -0.47714058249628677, - 0.45795306090913324, - -0.5027491995418384, - -0.2397162254251486, - -0.3189337392426345, - -0.2517467537850969, - 0.16122426536539913, - 0.412898953178677, - -0.14219088129616975, - -0.6684198730891455, - 0.13799144913620187, - 0.1967816040235213, - 0.5087855559844631, - -0.02780088259620439, - 0.3536029904545913, - 0.03937070277148225, - 0.593282925379199, - -0.05845702019210253, - -0.7608676820604792, - -0.1470772359020115, - -0.18311203447066493, - 0.396125534090089, - -0.3030989152827623, - -0.02906968731474402, - -0.11157891531967601, - -0.6653668697796462, - 0.646071074786735, - -0.7379637073476591, - 0.11078061158213992, - -0.4089957356936407, - -0.23680304101850058, - -0.7632491255517249, - 0.07173636066607891, - -0.4853024994660538, - 0.31775194308858234, - 0.47883272687866996, - -0.3619938171960608, - -0.5561588230998792, - -0.27504126091445974, - -0.5913563257180976, - 0.4619484789467808, - -0.4119386865876118, - -0.3176786617054978, - -0.1950615374141328, - 0.4751653297694053, - -0.6921517778243618, - 0.5301408835033486, - -0.0712180081562136, - -0.7450987127906832, - 0.0739454070547142, - 0.6043413456552228, - 0.18367023297933116, - 0.24267166191307454, - -0.38221791213921896, - -0.16014788203907337, - 0.21206927088093763, - 0.0940033745998119, - 0.23441359947803597, - 0.43136566388279174, - -0.740585551229173, - 0.6495145526600815, - -0.28617025762275033, - -0.47496829613500813, - -0.667009087379127, - -0.6642066603207792, - -0.512797083938951, - -0.39695089493176405, - -0.5965904458097978, - -0.43427492194153877, - -0.17120614531406952, - -0.22084142536748985, - -0.5196186074555198, - -0.35045541102004396, - 0.08806876335433245, - -0.3169996793997466, - -0.5400173170896891, - -0.7467051027910236, - -0.035279233856880476, - 0.5902214108846479, - 0.41010542964489505, - -0.22295481801700867, - -0.07610912771727718, - 0.4775996907726042, - 0.38173979032697736, - 0.5752087888290028, - -0.25185706678523934, - -0.20964873301744935, - 0.22323511202445767, - 0.21387250692121995, - 0.5035292880769077, - 0.28284832540660865, - -0.5384342673749117, - 0.09291721525068042, - 0.043840509213700085, - 0.5002092829661112, - -0.6508800611475185, - -0.08970985322255376, - 0.4670688743282684, - 0.1462599962618253, - 0.5879358115262902, - -0.049208816557356316, - -0.05714529006423752, - -0.6339161179657641, - -0.6630736868097262, - -0.6236633750572222, - 0.0622556676365984, - -0.23251952391653763, - -0.4271831850989639, - -0.29488763562405107, - 0.12636302661318488, - 0.08035345291713825, - -0.509263236072613, - 0.6131732277722931, - -0.023284234205435017, - -0.28342510325707343, - 0.4459998380090652, - -0.5155213036642088, - 0.1716912352870521, - 0.0975835432896589, - 0.1494410395441661, - -0.467053039443657, - -0.21196315849859126, - -0.6511785018685088, - 0.44925291945540213, - 0.34858085064833155, - -0.18873863106499877, - -0.6215564015476869, - 0.0375708297657964, - 0.585457305232855, - 0.04382419662490278, - 0.3354127405423021, - -0.435170121501985, - 0.5166266981899604, - -0.49089765148857006, - -0.2661189209654916, - 0.17312562466800963, - -0.6333366980503783, - -0.16861723200694934, - -0.07992530286640331, - 0.17091145296780663, - 0.5421165344069155, - -0.46852745746794483, - 0.18847954971923764, - -0.5461082018986758, - 0.02329059738810768, - -0.2321561655274743, - -0.4358176069167477, - 0.3313102982998889, - 0.03829364240359001, - -0.006706330774077673, - -0.7586669958016808, - -0.15712552828550896, - -0.692188506707252, - -0.6104156091526033, - -0.33167091735879484, - -0.25582187493649844, - 0.016789983508893713, - 0.5989359487354332, - -0.670628275408617, - -0.05835361096985536, - -0.5238973575318513, - -0.5881507271089405, - 0.3530955766140439, - 0.2062236935275218, - -0.3604348039355122, - 0.6347501308019078, - -0.5366631019083749, - 0.3931919788983286, - -0.4451802200770916, - -0.30046721292730394, - -0.3919875947583116, - -0.33859109506627355, - 0.4547614709269606, - 0.4881145908642305, - -0.3534570210690383, - -0.1860699714751617, - 0.5408336321716661, - -0.0693814365803963, - 0.515080681222582, - -0.2798175715713648, - -0.09122990594535485, - 0.07634033299789289, - 0.27422580412035347, - -0.3052427541490926, - 0.5574588840156159, - -0.3703679346003914, - -0.2997844539978946, - -0.6511525380603933, - 0.39095424488965, - -0.24216284451533387, - -0.5815825625845307, - 0.19485449168291835, - -0.6862639551223708, - -0.3799121530912541, - -0.6323439189294723, - 0.2875379790547853, - -0.350366894251929, - -0.1322078948049621, - -0.5062752128595371, - 0.5254376323037123, - 0.3884202595078051, - -0.3304884330307577, - -0.6667657864712184, - 0.15316024242915272, - 0.027744060821661476, - 0.2501203304356333, - -0.4639123267938478, - -0.3904244259136192, - -0.06597562080696906, - -0.26713156616262945, - 0.0062716455520841485, - -0.1520201247229267, - 0.5178080836165736, - -0.1906109884957603, - -0.6932576285423548, - 0.028856454236943496, - 0.49262180261020816, - 0.24123266164836166, - 0.4547329365849285, - -0.13321977059659051, - 0.46281042300921305, - 0.10595641279550028, - -0.2609588971932921, - -0.7182663124838602, - 0.19718790075320347, - 0.0010658669747334315, - -0.07131034610165266, - -0.21284208446774766, - -0.6913279096649312, - -0.15779075294318234, - -0.7638537467182946, - -0.618504671119156, - 0.5183725000298197, - 0.11495014200161535, - 0.5816704327262628, - -0.5977191211404708, - 0.30503296521116974, - 0.05360302602485345, - 0.08035245632534949, - -0.37272186399807894, - 0.07576571022307232, - -0.31998854618406913, - 0.5126926876653469, - 0.173992662133163, - -0.3442985417998398, - 0.2648927562666278, - 0.15296343765733555, - -0.6996653795055099, - 0.638044459580959, - 0.5355685261523561, - 0.1277276025658296, - 0.17664556065213455, - 0.006471631068764139, - -0.02130004581481637, - -0.46327785324886656, - 0.1907251219784427, - -0.15139081261131482, - -0.42209810635930695, - 0.28377765667615484, - -0.1269234652177479, - 0.46262505860245395, - -0.5666974434649671, - 0.6074308252740873, - 0.21021234909626174, - -0.6720909139642199, - -0.3539325376688002, - 0.5852422813550989, - -0.6720592245249544, - 0.021712705485522954, - 0.6038798819959942, - -0.4925080406239542, - -0.6623576349821093, - -0.2284514233705448, - -0.7390400391873496, - 0.6521284577670151, - 0.12444373266282582, - -0.04492727941953811, - 0.5491418282548167, - 0.5607219959558, - -0.7407689607533896, - -0.4143625297552815, - -0.7268494932628078, - 0.632518084641133, - -0.09078246197503348, - -0.28990377496786746, - -0.275949732726062, - 0.44631757341676426, - -0.027081649349994907, - -0.7450529791684767, - -0.7396780962079007, - -0.5423999933318188, - -0.08973838583615568, - -0.19824649680546857, - -0.6574091224605235, - 0.3637273111269378, - -0.49446698989081106, - 0.4708963546587145, - 0.2952170656286289, - 0.1187733780813085, - -0.3726546410291769, - 0.3878409953876135, - -0.5276457237342735, - 0.655436310592275, - 0.49631414893407866, - -0.7237397523633081, - -0.3327356771386858, - -0.2966723271323164, - 0.5610227932439006, - -0.3303973272360154, - 0.09539393697049126, - 0.26268163523968735, - 0.3995537749902177, - -0.49634084819803115, - 0.4869024334024138, - 0.25198167668147453, - -0.6418655159722053, - -0.05859807260904759, - 0.19034352974914992, - -0.028418279884116382, - -0.3197631856197805, - 0.41272534610492906, - -0.2539973332916965, - -0.08855529440328724, - -0.47122421117634317, - -0.37317323408430175, - -0.06236681970689417, - -0.6799379146557003, - 0.4561177766737602, - 0.234167316562213, - -0.5325268921929643, - 0.10910042387965424, - 0.32712526810059284, - 0.40069271560806763, - 0.42017793387510494, - 0.47779751195049125, - -0.7400423425623481, - 0.16764078237729862, - 0.207528846092498, - -0.37548467635139804, - -0.6612539485966953, - 0.5974618488759452, - 0.35348041606966796, - -0.12962942320605042, - -0.6139077053476943, - -0.13973605823265933, - 0.2058272029962941, - -0.2685567856973311, - -0.6861960801848073, - 0.33485058534877254, - 0.012302191940470886, - -0.464429676628864, - -0.6492438263057351, - -0.0186483312899266, - -0.3034344109110076, - -0.5753403737020971, - 0.3003606640987554, - 0.3738842535932009, - 0.3317222475015743, - 0.44077683159658665, - 0.42413783605579203, - -0.6799459394268741, - -0.2219445495837109, - 0.06572273452160615, - 0.323626056102151, - 0.10267389282155759, - -0.4821655135606116, - -0.3914517175969564, - -0.3637173277634637, - 0.6458602961337548, - -0.7299382027233633, - 0.5217938818268343, - 0.5751188644637223, - 0.47558825118566805, - -0.07104619594219086, - 0.5453804600973761, - 0.4520430083064383, - -0.6928781421017636, - -0.578549875339917, - -0.12918653367064492, - 0.6599652547352374, - 0.14127566386149726, - -0.29777245482695874, - -0.014450132344048128, - -0.3986156390495676, - -0.4935599717690233, - -0.1713895736367117, - -0.5440025780084298, - -0.660931180526871, - -0.5755296432620881, - -0.12006310476740045, - -0.4035378669957121, - -0.7282914742201707, - -0.11484126668617745, - 0.2233905148630454, - 0.009778565125774796, - -0.04322408804548927, - -0.2371440334263658, - -0.08460330279343697, - -0.518574054386634, - -0.5439202143814637, - -0.7266271084217321, - -0.5407201773557909, - 0.0568236414313773, - -0.5075969396304099, - -0.08597234963689104, - 0.13595270527235448, - 0.6507991187027932, - -0.41707429803211715, - -0.23265742324287053, - 0.2979060808711512, - -0.5725908930351131, - -0.12499795449448736, - 0.04879030177963861, - 0.2566040301414688, - -0.16360511469847783, - -0.10560251040753599, - 0.5460976364373579, - -0.3509915573845642, - -0.3315045548765893, - 0.1507572059984129, - 0.03190857722362361, - 0.46071345086087045, - 0.5051607796222896, - 0.5398185493527571, - 0.23780616594375437, - -0.615758263991746, - 0.31426244514781854, - -0.6723791868089266, - -0.24911796072647907, - -0.6649957224105575, - 0.5191901898549162, - -0.4428763638080709, - 0.30430986713474606, - -0.5958926684654666, - -0.2666460320944308, - -0.1220343900217945, - -0.23928373593625252, - 0.5550839666511328, - 0.646215361075316, - -0.21608378445286258, - -0.6642591472450751, - 0.5882991865117982, - -0.5546529522988672, - 0.25686514904074154, - -0.25169467778841415, - -0.6960175915026101, - 0.5408680960411237, - -0.03637887690681063, - 0.24827869445046502, - 0.48068841844208066, - -0.26861123913672647, - -0.35459059089325107, - -0.5824177589508487, - -0.38756478906344327, - -0.726212399410795, - 0.09730739037058955, - 0.5272987474151604, - -0.13009095506662016, - -0.31651358459512957, - 0.1444534162099187, - -0.6536066188314298, - 0.6196452890624212, - 0.14167467658799937, - -0.4065028888815495, - -0.1373783537470744, - -0.16455856693389903, - -0.7533191156474927, - -0.27525900938890613, - 0.2417824065530022, - -0.5482263597408826, - -0.09858566599689833, - -0.21228250720116104, - -0.18170899043537247, - -0.5667835579865961, - -0.48772774768923904, - 0.3181063866208472, - -0.6644781580050712, - -0.39495671173529734, - -0.5464351296259431, - 0.18166294050964904, - 0.015334581652788337, - -0.6331457497589267, - -0.20054735322816775, - -0.0656922960785149, - -0.1274671098553115, - -0.08247269815229252, - 0.31600827485772764, - -0.17872954074202785, - 0.10692108883807017, - -0.20112397026657258, - -0.7027652846057418, - -0.18849680150127768, - -0.3767936412144454, - -0.7117901339326531, - 0.6183102342042873, - 0.6153265660462529, - 0.5248112681878664, - 0.5679261790421025, - -0.5105721902201814, - -0.7259571130058946, - 0.47640907218925543, - -0.1432947759181078, - -0.24223385804294006, - 0.3630502073428986, - 0.21891573186827007, - 0.07578612403593965, - 0.5467677614750187, - -0.5623975078156378, - -0.018070012085878995, - -0.08860814382975879, - -0.13271457992111024, - 0.35262083308143766, - -0.5337631816531428, - -0.25236514367006535, - -0.018784804672243416, - -0.035294995785998706, - -0.23236229429039057, - 0.650399746411931, - -0.17800977781299954, - -0.719266033779226, - -0.09481671757913246, - 0.381615585099942, - -0.465857561420301, - -0.018604257957573478, - -0.6987903116773482, - 0.49046854109526594, - 0.6496744479740552, - -0.25177658206196407, - 0.24971840204541118, - 0.4476883892551017, - 0.1953134824390711, - 0.4840410826958418, - -0.13784493525811725, - -0.1373050037025637, - 0.1914783004912407, - -0.25877123196272933, - -0.2847999813229375, - -0.4618210854443179, - -0.5846882435138421, - -0.6480948143622676, - 0.35413951334678806, - -0.46533804105819493, - 0.07185115379740237, - -0.06897396982735271, - -0.16845402084397376, - -0.21796573216998627, - 0.3154797277461626, - 0.27541106748997246, - 0.5577951137842837, - -0.23971965553027352, - -0.484117093499168, - -0.5457885297271188, - -0.4183443961594414, - 0.5757166787127813, - -0.41079083279683226, - -0.3346332286545001, - -0.14243589548227664, - 0.39680647972323635, - 0.4391351554255295, - -0.5379486044438373, - 0.2907897525727988, - 0.043403324540364996, - 0.18152726668713737, - -0.27999270874055976, - -0.5900733419366777, - 0.12452162186914562, - 0.12999720548476212, - -0.20203897764848722, - 0.13375850222082641, - -0.5265971883880036, - 0.23343084490322863, - -0.20871759709971605, - 0.09862606866286416, - 0.17670901598085886, - 0.3069259983823184, - 0.39636890136521397, - 0.06006022140240286, - 0.07818468764010233, - 0.2559376260322884, - -0.44747442705888574, - 0.15727463150230503, - 0.3961277463651781, - -0.2518820151609825, - -0.1738453982828655, - 0.4245647766050963, - 0.5158322980546229, - -0.7319016760051386, - -0.052645090465298416, - 0.1382767032115364, - -0.1935751953409266, - -0.21867055004005687, - -0.12179021704730109, - -0.30702801335588353, - -0.532946579172977, - 0.3967257740808715, - 0.6619354085807173, - 0.4647882015839456, - 0.6308118110693396, - 0.22889346893265772, - 0.5019203694542579, - 0.0020636231182711295, - 0.17711252914996778, - -0.6253756150040396, - 0.21931753337675575, - 0.508025617543652, - 0.6170349439200241, - -0.5387170005830038, - 0.4948599227784459, - 0.018213150465743455, - 0.6165755876016944, - 0.30882618317028177, - -0.6557577325025716, - -0.5427022346805149, - -0.0756643420028068, - 0.08369855677171845, - -0.13167490274449334, - -0.544110732704644, - -0.2674397611365089, - -0.046825315658290734, - -0.7255157814166103, - 0.10918735830399184, - 0.07242167537168342, - -0.3015176205448372, - -0.1967621300258392, - -0.7201352121332484, - -0.41849225252372624, - -0.4146241568443396, - 0.11291303436102595, - 0.060385535656026335, - 0.1319417380867116, - 0.3191757536745842, - 0.06424574520681225, - -0.4306635644497059, - 0.5097487570126379, - -0.3557763992137541, - 0.5871641186898092, - -0.26477478113319175, - 0.5145137416832487, - -0.39198061071862617, - 0.010148426324029569, - -0.3477086924580039, - 0.34724681373163657, - 0.08307740690794707, - 0.26363352775588467, - 0.1644386396200651, - 0.36680632113026757, - -0.38401326132903496, - -0.3857137573627872, - -0.5279846937813912, - -0.5764858615286849, - 0.41999996119928495, - -0.49232605420471026, - 0.6086723462992875, - -0.20728926293212047, - 0.5903532214507684, - 0.5308086154652784, - 0.4911173966094703, - 0.1061865920319891, - 0.23746811308751703, - 0.28965743422058166, - 0.08902257008503578, - -0.07027803570937197, - 0.6198421334618379, - 0.5526174973186812, - 0.38047188370946794, - -0.5471641050375228, - -0.004035357924602634, - -0.5643212992061846, - -0.4574325907988678, - -0.20510920188248116, - 0.4930864679694854, - 0.43692524045196357, - 0.43975396052531723, - -0.5776661208070235, - 0.168308034413018, - -0.1297261490268915, - 0.057683987994021635, - -0.6999299919819586, - -0.08253893825638192, - -0.24212448951001508, - -0.7286085516030413, - 0.6629293731986564, - -0.3647386107272755, - 0.6094579643083639, - 0.5185893645254934, - 0.20638013794241383, - 0.4891526684672073, - -0.4944956477065197, - -0.38174585687265306, - 0.5025626484939486, - 0.6325974499663686, - 0.27470255884635686, - 0.3221312768956214, - 0.5453349265286155, - -0.2502050949034961, - 0.2432811855485001, - -0.5939923384697904, - -0.4036855776157719, - -0.1545761475846339, - -0.45585535909813113, - -0.3303404103174817, - 0.6093479801960603, - 0.5058677116487827, - 0.2991133312422899, - -0.5128604405728006, - 0.4184440239143389, - 0.4181284403070519, - -0.2356864990444102, - -0.1733364024444337, - -0.042314421662120516, - -0.4897324684591845, - 0.3644873355971091, - -0.353942461477021, - 0.17922121972080718, - 0.5110496126159777, - 0.5285160823947995, - 0.2690818131285849, - 0.33458942728620744, - 0.4439023936062504, - -0.49737622571923074, - 0.29938823109106216, - 0.5077578926343033, - 0.17893819952232237, - 0.10293898548278135, - -0.10399872419384948, - -0.19878926933359287, - -0.4471399804834539, - 0.6009856245070112, - -0.7251064642192446, - -0.5401545926592977, - -0.39600973044682675, - -0.233733876200243, - 0.629282324277686, - -0.6114877349684389, - 0.17198491385208559, - -0.7241841646995839, - -0.49239556762106984, - -0.24543860341030976, - -0.0020143332466923125, - -0.19927539671956696, - -0.5407710095263225, - 0.08049920333337157, - 0.014323414696309489, - 0.5139418317538588, - -0.3344135046299313, - -0.3693643341079451, - 0.3353680841161165, - -0.244921684832904, - -0.5396368901456556, - -0.5346956281164634, - -0.283939026281719, - -0.34861658248677135, - -0.20142876023435818, - -0.2209124525970677, - 0.36792677954325803, - 0.04413751512319419, - -0.3346086674963509, - 0.09966726418365224, - 0.5774907282758232, - -0.10217082116856069, - -0.7201988104703897, - -0.017159209956906007, - 0.05112133844694722, - 0.47908221351829716, - 0.07564829287326325, - 0.08582472966626298, - -0.3106519738106511, - 0.5484273646269066, - -0.09419425748937638, - -0.18227055128525815, - -0.5866069160463128, - 0.45160413406413513, - 0.025321496397673338, - -0.6301165642697986, - -0.295096908969683, - 0.35724896995774025, - 0.06710339897658746, - -0.18472358155124124, - -0.09836757463093126, - -0.6793673735986294, - 0.29012886853654984, - 0.4661803371881238, - 0.09926821815690723, - -0.3693858204877357, - -0.0805089366079994, - 0.14781786993220636, - -0.4467966795525286, - 0.4116263553130425, - -0.5988157637066414, - -0.1999167688685516, - -0.012836820490482626, - -0.08924794159367389, - 0.5065620714569589, - -0.5016061614589856, - 0.6461962730940166, - 0.1844330514225878, - 0.15496597225513242, - -0.5984869896974043, - -0.5040095744636994, - 0.3860262963265163, - 0.6212440008130425, - 0.21654078131525178, - -0.627630874274039, - -0.1921334027202588, - 0.0301399150296503, - 0.32008411886012345, - -0.7641279047060564, - 0.16384575618060626, - 0.04217931850589873, - -0.5769910840266457, - 0.0519096129679647, - -0.15104683985610035, - 0.3495271224166586, - -0.17459511768033886, - -0.3011279777345308, - -0.614746913079838, - -0.5220028737233989, - -0.3300862511150607, - 0.6039567322219374, - 0.3324184398076536, - 0.4981899680741416, - 0.42160656204251945, - -0.314017911513589, - 0.1814092028624057, - -0.422855972566006, - 0.22122647796856887, - 0.2346575244626029, - -0.4053076112409958, - 0.1732227756359752, - -0.27094607570671164, - -0.22670726325072021, - -0.1495344600392441, - -0.285721743925414, - -0.6960736928001995, - -0.307049900326417, - 0.3275776912342968, - 0.5269185796796808, - 0.22512831680844536, - 0.605007185595894, - 0.2705511596396003, - -0.09187118584261544, - -0.047872443912226226, - 0.36184894545690593, - -0.6676701684342297, - -0.2810181686079917, - 0.3681518383030583, - -0.5344973025963247, - 0.1375857821257488, - 0.0901315783524611, - -0.3096013114661354, - -0.45296581640202344, - 0.35244999845825287, - -0.5193024702220221, - 0.5827995922164148, - -0.25140774936269716, - -0.30115130428621406, - 0.045110756031254584, - 0.49291608391809183, - -0.5184223381518098, - -0.16369637782783175, - 0.12938186049066758, - 0.44649787444638356, - 0.5917546588794088, - 0.03994616722280986, - 0.5475446330406964, - -0.6604224577074518, - -0.14636845101607987, - 0.23984025244872587, - -0.048958320694745816, - 0.10831981909701494, - 0.6225738043450159, - 0.6589939647511843, - 0.46979188550277773, - -8.818194935741319E-4, - -0.15033426753243873, - -0.3527962311052352, - -9.362360717892759E-4, - 0.052569055611696336, - -0.39636990488399315, - -0.3256306652209891, - 0.03435267243991946, - -0.5023007964177431, - 0.46050905522261154, - -0.640741944038244, - 0.6227910332022367, - -0.5871922370677398, - 0.28729303375285065, - -0.15470813894370206, - -0.3587685722397697, - -0.2842136870801877, - 0.37571810685288776, - -0.5978175446083611, - -0.04630380090247255, - -0.7225427695566795, - 0.5365085585641499, - -0.003031906061449985, - 0.4974517262097825, - -0.6238507255374959, - -0.6107627110992793, - 0.03726388307865969, - 0.6485006529237901, - -0.11823626098028939, - -0.5001422739627053, - 0.2451732692010281, - -0.35217681171982124, - -0.17782632469550486, - -0.18693700534743507, - 0.33171326727914263, - -0.5892353169689322, - 0.39586752388272084, - -0.3779324643193454, - 0.4687001622099737, - -0.48842821078757376, - -0.74563703864726, - -0.6499411166686864, - -0.559350300668757, - -0.5566341357216479, - -0.5919244503109357, - -0.3063897300029512, - -0.10664058026628265, - -0.37957564491914214, - -0.043955713831441146, - 0.6302406005053917, - -0.20055175455952867, - 0.1951764438894913, - 0.534910152768859, - 0.22242384977816654, - -0.6757203005397632, - 0.4561337080040998, - -0.7097194666606957, - 0.03871627876630135, - -0.6252897632770051, - -0.7524435180478044, - -0.29228663668973964, - -0.21384402526638469, - -0.5719788516320157, - 0.2498954225338147, - 0.5478151673788089, - 0.43688653824911705, - -0.1134652569083704, - 0.6251549296587272, - 0.5772050008498261, - 0.3246125706529367, - 0.576478233048679, - -0.44696853699266637, - -0.36082359743435516, - -0.5722592790960125, - -0.12332002969450873, - 0.31753588381967435, - 0.1894413230429819, - 0.4527105652305229, - -0.08764749676435002, - -0.7603754305156462, - -0.5935291468150039, - -0.6995416781087648, - 0.34580546687505354, - 0.45322413200919887, - 0.6543843906819719, - -0.4495157296046501, - -0.4653979535380195, - -0.2682040111341707, - 0.41100936891707096, - 0.4116814649257269, - 0.6625227680579563, - 0.4049222848792625, - 0.30755664642245295, - -0.037166305405933464, - 0.35586231010025304, - 0.2427677395172555, - 0.05575871016348577, - 0.6048939048123126, - -0.020366992845705645, - -0.05695072300799442, - 0.06043799503053038, - -0.31306225894745093, - -0.05991040459300889, - -0.7424275958581105, - -0.6183850032235647, - 0.2884217266811794, - -0.4381078537321331, - 0.024570302952876544, - -0.6527492212542356, - 0.36565731309988847, - 0.30077812867101505, - 0.3673450029086339, - 0.1586277949607705, - -0.19067124587170325, - -0.37102280011105865, - 0.028940606976860628, - -0.3001647687192018, - 0.6078052747082877, - -0.48402593581217446, - -0.3978314744516266, - 0.6235542596207421, - -0.6774244025942846, - 0.3147714162371217, - -0.25342508511680095, - -0.5784582215254848, - -0.4491583821771359, - -0.09407705708406766, - -0.5882029645634469, - -0.6889070212982475, - -0.17793701634265424, - -0.5609096421496804, - 0.5427255201472708, - -0.35340714572183624, - -0.5392693271972594, - -0.7051624527486002, - -0.6205630960185342, - -0.7524888164772489, - -0.5968531741886746, - -0.3621176046618017, - -0.4676686327251963, - 0.2435558209729788, - -0.3994134147757806, - -0.5257498305260155, - -0.4273682668451701, - 0.16544337620944483, - -0.34667820343367595, - 0.1513930259994588, - 0.6529841416904142, - -0.2439762052369847, - -0.5078108435374106, - -0.3931695119513511, - -0.7597790134700139, - 0.2815044323875008, - 0.14916078179395797, - -0.726124015706409, - 0.024533833280849016, - -0.3612581465677304, - -0.7630393463085405, - 0.06679320752639462, - 0.22875642687509423, - -0.05946236676530514, - 0.24604845169906742, - 0.1742510842555678, - 0.01642816095414723, - -0.3594057209970389, - 0.3010053527570874, - -0.6934075278695504, - 0.34024731004111, - 0.3076058324549068, - -0.24131474432848166, - 0.5025387834470009, - 0.6376591877857624, - -0.35021394234837705, - 0.23436561174207438, - 0.4739198991936401, - 0.10926511571422448, - -0.517642502745002, - 0.34493796965922907, - 0.33019913425644376, - 0.019782680970543143, - 0.10919984546173134, - -0.3679492545772583, - 0.559931973641138, - 0.4051203152892878, - -0.44623279490740936, - 0.0814547028540028, - 0.045101742342410156, - 0.10051244402290471, - -0.6767937515294473, - 0.018457225652000586, - -0.29833167897317864, - -0.5767916028045526, - 0.20653918056896303, - 0.6076141551642339, - 0.6384748862322028, - 0.6344496380600865, - 0.3825654838276956, - -0.27288016834282414, - -0.5707631773874572, - 0.6270482024729519, - 0.569963398141908, - 0.3968387503416996, - -0.3436172376665723, - 0.398561376982001, - -0.746703660518641, - 0.5865584870802801, - -0.6933702950464723, - -0.7214648929046372, - 0.556408835347587, - 0.16300634792551727, - -0.3628587759699842, - 0.3740259221665744, - -0.300889686863034, - 0.48157705891971514, - -0.0962114401716696, - -0.1410898748305336, - -0.6754620354192252, - -0.39222328874248186, - 0.25787969057288673, - 0.6530590762961789, - 0.6442686160873753, - 0.005657077142275702, - -0.5315437343495297, - -0.6510710147919749, - -0.21102348854321618, - -0.6942177134120445, - 0.17789669062637137, - -0.07763449982235382, - -0.2054268230973325, - -0.26723973962220376, - -0.6496940058331719, - 0.595136113630749, - 0.31329727372173266, - -0.019137459775872556, - -0.6943498616730939, - 0.6592461255997651, - -0.10582521450500537, - -0.2125252031923759, - -0.6525397224589529, - 0.6227911950399444, - -0.7626298873551415, - 0.14896927055169207, - -0.1908068876487623, - -0.09281002903515179, - -0.6736604698969415, - -0.6253186507799158, - -0.04592336707711686, - -0.34186283377306875, - 0.5715419211866414, - 0.4999734078838657, - 0.13289049638979045, - -0.26118649872323874, - -0.16741050896379217, - -0.0844545048352614, - -0.6190999428378166, - -0.15287098812653444, - 0.46185306789203884, - 0.37239568880351837, - -0.25556609439957845, - 0.6624725086263455, - -0.14366090605513115, - -0.12327359647994007, - 0.015163873920581605, - -0.18808052795689167, - 0.1367170596272682, - -0.5982060022537283, - -0.05542125082857774, - -0.2241583990753071, - -0.2194984087879136, - -0.7402784596504098, - 0.1729921855527562, - -0.7090882407621556, - 0.4900150524774668, - 0.046937756795113694, - -0.7392289516288809, - 0.5662545185103814, - 0.5433856698594067, - -0.7284569903351779, - 0.5849546430414404, - -0.2242745811574245, - 0.0597056235765453, - 0.44722500089546313, - 0.3517238315244008, - -0.5029397455508533, - 0.6312926617168367, - 0.12460941960462502, - 0.13704327649856995, - 0.5039896373179652, - 0.24390143319322333, - 0.19149476837264723, - -0.5128823666914949, - 0.2647750424471641, - -0.3680611500494898, - -0.3877659201859463, - -0.08745799296309098, - -0.010918963738974052, - 0.11759932907751836, - -0.3549189407957777, - -0.3106979670701851, - -0.6311292816625387, - 0.5644052941943708, - -0.2835660917509549, - 0.35728039660841626, - -0.6365531691110633, - -0.04021901488599566, - -0.2969474192395863, - -0.5807621884390967, - -0.45655953319652354, - 0.27116701290613554, - 0.3327571098528247, - 0.05803543585105242, - 0.2562338076694751, - -0.5930939577819212, - -0.06503210584004959, - -0.5914807178864929, - -0.6107034874429883, - 0.1662709175832361, - -0.6317932727975925, - -0.04579067004309956, - -0.3405567537492535, - 0.5387461959661682, - -0.6939908489414627, - 0.05011615181184481, - -0.4266576649431623, - 0.36012893779381583, - -0.755043763434499, - 0.14867896304366746, - -0.2879646572605367, - -0.39208137179145947, - 0.4112568276705927, - -0.41076787311074064, - -0.6361352977967946, - -0.5235173701929665, - -0.14492607929403745, - 0.5151870778314745, - -0.7264239270645486, - -0.3387617194082069, - -0.009880847101307655, - -0.3110546259429949, - 0.4748778253472056, - 0.41429707857181775, - 0.46680296976386393, - 0.3357818340469786, - -0.5859626881646985, - 0.13256479004114807, - 0.33617224630379694, - -0.5549880672760404, - 0.28397077084360756, - 0.23777860272259332, - -0.08395837795507866, - -0.19647804765133092, - 0.2761081337452146, - -0.4898539487256357, - 0.4719317575464407, - -0.27419685617389994, - -0.3965249493069466, - -0.5895185426991184, - 0.2241746519485195, - 0.2878424189723955, - -0.09111455326275453, - -0.5383401465606218, - -0.172279074628364, - -0.02502154229012754, - 0.2380407934351051, - 0.3819371865508333, - 0.3588242740506137, - -0.19077276388585918, - -0.12089108279356775, - -0.33980485417897005, - 0.5166882785783077, - 0.12551868839129932, - -0.5212700342915406, - -0.15282263516079875, - -0.47605798404851846, - -0.41377308911519967, - -0.3543474967718771, - -0.3405805239065341, - -0.5858315718608847, - 0.20189480053598508, - -0.4842427173463679, - 0.03298416272108484, - -0.15678251560371614, - -0.6145454140422693, - -0.1723936611804633, - -0.302192136435797, - 0.2993893078463633, - -0.6384288020081698, - 0.3855856439991677, - -0.1120536132245542, - 0.5942777892581695, - -0.7624131415260572, - -0.5704291511309472, - 0.46380159428266354, - -0.09613517967037288, - 0.5671229326906985, - -0.12498937726827175, - 0.522145399606123, - 0.3903118428438691, - -0.209389200754597, - 0.20728848410383005, - -0.03776033853891847, - -0.7264212824644174, - -0.32327474180160115, - -0.1361725045519897, - 0.40613238499479565, - 0.47451818295344383, - 0.16089503089547608, - -0.019596125570276013, - 0.45724551158668236, - 0.4005784594013052, - 0.3408269618812029, - 0.15262373344309188, - -0.2916714823070263, - -0.6742343464956603, - 0.19656949186229744, - -0.5111788826915104, - -0.5919619805759616, - 0.5627448964462743, - -0.3727647530388363, - 0.22899350572726884, - -0.17661994619617838, - -0.3183784376194394, - 0.4985497410187151, - -0.048980978547962795, - -0.5320377783735929, - 0.02690259478667234, - 0.007165511726275553, - 0.2545178033072423, - -0.09254433425941755, - 0.5245336051197876, - -0.7085690692899164, - -0.4288427484944969, - 0.49580101642111096, - -0.13009580759948725, - 0.6587022953880161, - -0.5340439932077895, - -0.6171656909310699, - 0.21075094095861446, - -0.13388232536685762, - 0.43065127180799034, - -0.4037407696707578, - -0.6257240945109172, - 0.18276340082217157, - -0.31454035853182366, - -0.6283737491493212, - 0.016790606151071197, - -0.17359943906500042, - 0.2978542194295971, - -0.7559922801212275, - -0.3287643288193839, - -0.286614811514763, - -0.7164412056950442, - 0.6433045730574051, - -0.7507702233500977, - -0.7619105609973188, - -0.5100803077549615, - 0.38076859293449183, - 0.21505190998396762, - -0.6946669014887279, - 0.4428637974466255, - -0.7075667731033559, - -0.6470041985076034, - -0.06744519313389474, - -0.30168885809749785, - -0.6221798864595838, - 0.5114923124983345, - -0.7625905879845126, - 0.04251312531845253, - 0.2410836648557041, - 0.602758154832986, - -0.25777756489474113, - 0.33016803925634874, - -0.27442139381764624, - -0.6263079167041392, - 0.5410647351347372, - 0.21175746141441432, - -0.3939228843627196, - 0.544025096322167, - -0.6111689965692524, - -0.3277522771387663, - -0.032262441959112764, - 0.5968813727399692, - 0.11788952800158414, - 0.2906506807748229, - -0.5391163376552274, - -0.4156337451984087, - -0.28310014329522337, - 0.03358280118520607, - 0.2270453494359873, - 0.47984388119105625, - 0.6081633280283217, - 0.6586534654632857, - 0.03834041102447083, - -0.4509177829886213, - -0.34458407821559184, - 0.2350144808813467, - -0.24483660699835352, - 0.25582634248855507, - -0.4090153293818653, - 0.6311354901199046, - 0.31586079239154985, - 0.4198703253051831, - 0.20874406200862727, - 0.1363594554951978, - -0.003300423354864357, - -0.33303067640824313, - -0.716873708603178, - 0.5858673659439616, - -0.021851421216508515, - -0.17491228279972793, - 0.4093101453154885, - 0.015452312982516037, - -0.14290764405904288, - -0.09102895715608128, - -0.1673373329537976, - -0.41502011234700836, - -0.7037694702856487, - 0.1335840223169904, - -0.6298148824178755, - 0.19187903770895864, - 0.6317007442346528, - 0.007427434771815955, - 0.4716537853787687, - -0.6232688831589885, - 0.6294894047011467, - -0.7190662140514184, - 0.14357405236704268, - 0.2341710332629453, - 0.221677017804205, - 0.015848538101831067, - 0.4242650878050803, - 0.5795772112869134, - 0.0023819813014011038, - 0.17315257431547082, - -0.2942258123444146, - 0.05130901638233165, - -0.39854447098660367, - 0.43093852299348756, - -0.5523643192832345, - -0.5038144991574374, - -0.5991388515451257, - 0.19147778273300153, - 0.08994963774600506, - 0.49008218334825815, - -0.4275072136872958, - -0.35666666303729483, - -0.6991666877055732, - -0.5759002958418156, - -0.27549359728980466, - -0.5692269187114077, - 0.3162256916143492, - 0.004448404638537795, - -0.20479278129969325, - -0.3056934049594838, - 0.5589105525918444, - 0.09402371063490422, - -0.336647958761039, - -0.4234750228615038, - -0.22654557407478937, - -0.7455107446592906, - 0.15824529656329167, - -0.3665038158692616, - 0.6620153700389978, - 0.28157126327642346, - 0.5827621025770634, - 0.16563465260808452, - 0.30022260496549136, - 0.48766983659495444, - -0.16449889577467958, - -0.2511387670541849, - 0.4824483657052968, - -0.23431952307995074, - -0.21133012217583835, - 0.5066925245622252, - 0.16593000305115424, - 0.49246602218563773, - -0.526279195137921, - 0.6517174925222623, - 0.36356665312659253, - 0.6472289771486307, - 0.08550480052650544, - -0.6898301541456526, - -0.1678464117697559, - 0.6062761763975705, - 0.04428454475668597, - -0.4742631388410521, - 0.359353600604594, - 0.4478107562145811, - -0.15455664911442946, - -0.7626417911258428, - -0.17176991646232398, - -0.6733366115520428, - 0.538935701150569, - 0.07020134171744552, - -0.20119791165333922, - 0.5545863721287995, - 0.42571837017103953, - 0.6250829615661716, - 0.3072189607094641, - -0.052097952467348274, - 0.4510640550642392, - 0.2719051339070725, - 0.07080390704721706, - -0.08946287975297051, - -0.4847111719000606, - 0.2546907602981644, - 0.3684112059370833, - 0.12881550277047926, - -0.2838657506668141, - -0.20472073619664433, - -0.5090734699934125, - 0.5252021292231214, - -0.02823469275043211, - -0.1749659481409659, - -0.4436652041598651, - -0.41991413826624274, - -0.264577512632841, - -0.022587258071060545, - 0.312729278982952, - -0.11598258761557079, - -0.4322589459746922, - -0.4920414657241903, - -0.19981180920719244, - 0.48184959510956815, - -0.2618808605425983, - 0.5526990203770802, - -0.6742877080513883, - -0.2555243325948139, - -0.28435740490112354, - -0.5604940899721215, - -0.6987179283649345, - -0.08449551018875745, - 0.6067957789093003, - 0.10443700486915453, - -0.5267517176608622, - -0.5931698269315537, - 0.6060543617510187, - 0.6306772700438853, - -0.5482039084910377, - -0.4900799244651708, - -0.5729304163501201, - -0.4885144379896632, - 0.6449745906017516, - 0.16742658976876879, - 0.1288791469515851, - -0.2867352447352268, - -0.7045674418295503, - -0.13839894798727126, - 0.6396042382125849, - -0.6694724737379091, - -0.0312896691050818, - 0.30106465894184875, - 0.5623817907867424, - 0.1490755509294477, - 0.6580328611867085, - -0.7628907308545967, - -0.4381546223019964, - 0.13117197015201087, - 0.6165648898324013, - -0.6828497059170577, - 0.06678251218809883, - -0.2496848100227692, - 0.1862433427314797, - -0.7204760286605324, - -0.36480806995537945, - -0.3939679992939423, - -0.6526210170894378, - 0.5301319359260187, - 0.5568846748501964, - 0.15338102571992784, - 0.06296750912000593, - -0.4218504572839842, - 0.39501712621557583, - -0.1988508594026871, - 0.5314076647536675, - 0.4575696268781356, - 0.0304993765224868, - -0.03967159467993109, - -0.7300384633645136, - -0.3137121399667934, - 0.076773988300736, - -0.07043468666886876, - -0.7411103128942058, - -0.6606757787882339, - -0.5567913013456361, - -0.398495582892433, - 0.01530055736856728, - -0.5830750037030168, - 0.2972959948181023, - 0.42321769902460826, - -0.6416174255570856, - 0.0345224803640769, - 0.30453484425853705, - 0.11631414400355555, - 0.08715988030954192, - -0.18894690375918644, - -0.2602449998036829, - -0.6953571327348718, - -0.15955488162293052, - 0.6165161254026047, - 0.4844639890079775, - 0.6494051389329344, - 0.4407561989999912, - -0.36296548660298444, - -0.1416708487122309, - -0.031119572538864215, - 0.33246843160846196, - -0.22754969447451912, - -0.08751753394516948, - -0.22834979175244918, - -0.3729452186886337, - 0.6181476686892938, - 0.05320518403374597, - -0.6547171905212146, - -0.6467158424639652, - 0.00684038057857117, - 0.08731176920482264, - -0.7608267722626788, - -0.26210097783790653, - 0.5700409436492763, - -0.17621061608006494, - -0.634992954884855, - -0.5563112376793904, - -0.19910554818645443, - -0.6856566636475372, - -0.3371252522380489, - 0.549962080703308, - 0.2488690159667909, - -0.016178187499937047, - -0.40724029678151286, - -0.6715479332237013, - -0.4839098067716601, - -0.5358904094398551, - -0.7232867703174244, - -0.6775678282757995, - -0.3463296641412934, - 0.11278992164984503, - 0.19402727895686434, - -0.495714296222076, - 0.6556668667031759, - -0.39114136957533147, - -0.35198761994067485, - -0.6145240779243334, - -0.5799023830095942, - -0.24674894416865079, - -0.6167831795787374, - -0.054703924408976534, - 0.6243002154539831, - -0.20141154150155538, - -0.5460967605179384, - 0.5596095270816831, - -0.6312509658945377, - -0.593096869583137, - -0.05743607292841646, - -0.29685284224061476, - 0.011136656649245014, - 0.17770284266505376, - -0.047631205882770034, - -0.06456790222480613, - 0.20003968799197736, - 0.047001525887113704, - -0.7177236605274305, - -0.5830254550894531, - -0.4347195109318642, - 0.25418826454403554, - 0.5382054282591239, - 0.043524407647468344, - 0.04225788063640101, - -0.11121484130854775, - -0.6197477032142316, - -0.07769433519022662, - -0.06575380340942849, - 0.27973498047972944, - 0.2606723298384631, - 0.27221689610338917, - -0.5205776841795785, - -0.5202666271913218, - 0.2168496729652284, - -0.40868478499654387, - -0.17569757900423355, - 0.3782769591334313, - -0.7395277716501539, - -0.721016618123802, - 0.6619616555064346, - 0.5790684057011141, - 0.11230642416225656, - -0.14413732602808016, - -0.7577422646827519, - -0.581650000914853, - 0.11103849818175282, - 0.6114845524154428, - 0.6150246685048274, - 0.43857876728552714, - 0.12360194890655407, - -0.18221508572643796, - 0.021869007093694548, - -0.2424522437994734, - -0.6401433722777707, - 0.4229545167883656, - 0.4297830981196563, - -0.2750819500994322, - -0.6446401318147011, - -0.14271443272287443, - -0.24154758873895865, - -0.6859805898245431, - -0.32517338632714315, - 0.15361958833699585, - -0.2209959545069866, - -0.1296025121224097, - -0.5881579205705467, - -0.6559671338878557, - 0.46565899357555407, - -0.40107107076265425, - -0.4164316373559324, - -0.44497738273756376, - 0.16465835466822742, - -0.15877090520131998, - -0.2581874702070269, - -0.6602976416354241, - 0.007567106068037566, - 0.2954830826941962, - -0.12478141604510207, - 0.6165798678157682, - -0.46984261124445814, - 0.6085274134780628, - 0.13036245649927714, - 0.46743143460874326, - 0.27884686562277905, - -0.062320369253876184, - 0.5547742036695843, - -0.028612689268972535, - 0.29438440314814407, - 0.42690460439044375, - -0.10657349880034661, - -0.48379689103198137, - 0.1425077404913594, - -0.013597872607968298, - 0.01569002944441089, - -0.4159156132397436, - -0.6855899614587532, - 0.26621151589521597, - 0.053630451050860284, - 0.2954196737735487, - -0.6485096694135426, - -0.5609421163095643, - 0.4829317819432396, - 0.5476258668349739, - 0.1479630564768908, - 0.5694779052352236, - -0.5266388827858001, - -0.6283734419807878, - -0.7277462487773867, - -0.06428982491505353, - -0.2917418282665535, - 0.3642168660931796, - -0.6100216558992744, - 0.027756338311083595, - 0.30104984255646994, - 0.37357866620877755, - -0.6029926481302216, - 0.3490859310716167, - -0.2044706295387173, - 0.029688630285913176, - -0.20375452195436272, - 0.17986663130361058, - -0.02371636485639883, - -0.30254637263591755, - 0.46611080291898854, - 0.6146324527112569, - -0.2681382922204793, - -0.4391350788783636, - -0.5096989041282072, - -0.24985625807518508, - 0.5670775314829427, - -0.6339718154933047, - 0.6132337870334815, - 0.6293020928023209, - -0.16134100354175052, - -0.6601851790867649, - 0.005647503344351934, - -0.4420156754533061, - -0.11830953412420298, - 0.2969042558946823, - -0.4850224985370228, - -0.1752525105055226, - -0.5779190677048087, - 0.24840065828618763, - 0.16973398060707434, - 0.20947323424417785, - 0.651452432302, - 0.2079673916416891, - -0.40240300215485586, - -0.08704175759307331, - -0.38899993431573004, - -0.6557034538833235, - 0.07245099187308157, - -0.5065494715482497, - -0.7432607897526862, - -0.19353353448679056, - 0.47284317282402377, - -0.24308719110220978, - -0.05594266188868002, - 0.40853516210812335, - 0.039147063028111106, - 0.3430015362949833, - 0.2038335007037606, - -0.6873403871105402, - -0.07564670086896241, - 0.6010659517078619, - -0.4091900386262156, - 0.2743909275613189, - -0.6256670739698689, - 0.16239625163992877, - 0.058599179829225134, - -0.01107505148136223, - 0.19602975762417785, - -0.4524809523964616, - 0.0626683471567484, - -0.44464895344205274, - 0.5788121268573033, - 0.4689694733873474, - -0.5169921774179487, - -0.5549365611816774, - 0.41058659081322524, - -0.13980825723988943, - -0.25049343266713153, - -0.4431626570545929, - 0.3567809535711196, - 0.4961978377070634, - -0.7510411227246861, - -0.6279146094417822, - 0.40031954728839103, - -0.3303717826866608, - 0.4452879030312843, - -0.5381724690700783, - 0.3860062175001092, - 0.5852173409938072, - -0.6059231996502911, - -0.6942194374967876, - -0.3341315303701659, - -0.5492353422400551, - 0.13660737711241921, - -0.6160630933171314, - -0.6193146364945608, - 0.5069781731171378, - -0.2362186018863507, - -0.6111137325010285, - -0.6000425466985262, - -0.6881979195571591, - 0.10213013462066012, - 0.42298859476430517, - -0.23612042085563678, - 0.019564514876270644, - 0.3045220493093904, - -0.6047442322990123, - -0.16142879939230914, - -0.12199797126062017, - -0.09189046682124968, - -0.3600245134812375, - -0.20265012640716495, - 0.4852963373118201, - 0.4459406530738318, - 0.3684761682540588, - -0.519540024039166, - 0.4466304916459888, - 0.44358952852527767, - 0.19240768197971025, - 0.2951543245414011, - -0.003583666660804119, - 0.2372998012245523, - 0.14513685474634108, - -0.6937502881322933, - 0.11834087446814145, - 0.11192874297174749, - 0.388574729897336, - -0.25724537176992024, - 0.3232712401170569, - -0.6535731515244705, - -0.5414140454453734, - -0.49860044845256757, - -0.34545173763293024, - -0.24522914490335934, - -0.34762235610074826, - 0.3761005096939599, - 0.3165821535007248, - -0.3831842293592118, - -0.3140356681985823, - -0.5217241831196332, - 0.09111614121644529, - 0.2987590743042571, - 0.30346490744219745, - 0.36137588178714986, - 0.09877086450637629, - -0.001727159559440139, - -0.4572276484171078, - 0.10029472721560817, - 0.36358138128782713, - -0.1978793639019828, - -0.6808658433131461, - -0.6479137435005982, - -0.012788357799573102, - 0.2548131809986406, - 0.4093885246049055, - -0.5680841405783403, - 0.6034441909762319, - 0.31835942431766673, - 0.6407535734579889, - 0.26183000057129135, - -0.12187565506209319, - 0.1232235386591416, - -0.4793026636539617, - 0.13120806975642918, - 0.10225836757813933, - -0.413633063901347, - 0.4837084496231122, - -0.4874147141392305, - -0.2247179016845121, - 0.3135453553228026, - -0.4281259067695525, - -0.41176812111826244, - -0.39047228120408284, - 0.051087907854351466, - 0.05617201398781091, - 0.3551546786087426, - -0.5188140738078725, - 0.6037269952067538, - 0.6140481001321566, - -0.16040632604227778, - -0.6869330759797218, - -0.3122820296797271, - 0.6051215289138817, - -0.057156481366258394, - -0.45362055086183295, - -0.06102615287016122, - -0.13070622507331786, - -0.3375438798339792, - -0.03673697995105962, - -0.22354407382728814, - 0.19075339254549029, - 0.11612715552766972, - -0.7023767611917623, - 0.4127533085133447, - 0.20239974435784736, - -0.5275004583312355, - -0.4973257219261071, - 0.17970807649635212, - 0.42732596653629973, - -0.7258259011896722, - -0.7066848007964828, - -0.33266829268216025, - 0.2843589790510336, - -0.7495876593750447, - -0.07846923354240343, - 0.48054533998696003, - -0.05378250481226521, - 0.33624119335353997, - -0.4494080985945933, - 0.014872345528222697, - 0.5074608038167557, - 0.11976001478845921, - 0.23727519015866083, - -0.7508983511818221, - -0.14686689439792167, - -0.5144324178039333, - -0.6189778882812349, - 0.31722209185979466, - -0.13487946784728322, - -0.6052014221687714, - -0.30650806510855716, - -0.015241699646542761, - 0.2540517919126092, - -0.16869888441032543, - 0.09775661450293771, - 0.4441987363436958, - -0.3742311515727382, - -0.5658431594949489, - -0.7259137281592494, - -0.3542243759861796, - 0.1706580920630475, - 0.12477418435497112, - 0.20762976050906612, - -0.3083070675087068, - -0.7290025522585131, - 0.5917103756010452, - -0.08562853336500575, - -0.27715482256061197, - -0.41122320595733897, - 0.6223429001974562, - -0.2885050365859732, - -0.37841345922643516, - -0.19031272925070408, - -0.6537079735199535, - -0.17979219720708017, - -0.5475815732669543, - -0.35553132644379265, - -0.6843580780215366, - -0.04671404229931009, - -0.7110156146596188, - -0.5630039271079648, - -0.4522907220064117, - -0.6208648868024852, - 0.15564915465304419, - 0.04471929397853913, - -0.4270927801306462, - 0.2482375986539379, - -0.4786736709214616, - -0.6532248376733828, - -0.1472516135142451, - 0.30815201192731234, - -0.3093339875708195, - 0.2994936805758134, - 0.3194491943941252, - -0.05462494734790213, - 0.07211814780544379, - 0.610109089914317, - -0.24193042436308587, - 0.568125648517596, - -0.576556356611323, - -0.5836797463610257, - 0.27177612782238925, - 0.12607042853895667, - 0.3377091239457187, - 0.2617476619124802, - -0.06877183919933527, - -0.693564186708677, - -0.26672258268085913, - -0.6195625792531544, - 0.3664780266048647, - 0.2058470323845074, - 0.12856865301700893, - 0.013486196132596717, - -0.4482366399454, - 0.14855247523789195, - 0.3122808471376307, - 0.3492038097120328, - -0.7171117411874807, - -0.13910738370340792, - -0.33298121865038727, - 0.28222746569921686, - -0.19991913897313118, - -0.4878214509985586, - -0.6060715167895847, - 0.5828461454361266, - -0.6361983400178586, - 0.32441564762229824, - 0.208391093598289, - -0.330151015383208, - 0.13173228350703492, - -0.3153376391862849, - -0.5898061052376881, - -0.14171508302024327, - -0.1120608598017988, - -0.45964106015521206, - 0.30633787377408217, - -0.7263316271938302, - -0.3666508602618164, - 0.540490800996282, - 0.3693508193199434, - -0.2071130096748829, - 0.1100047791341705, - -0.08333012415789331, - -0.7225182205379367, - -0.044121204456633256, - 0.023680223017011004, - -0.2804509336919006, - -0.754010827174768, - -0.5808608125455037, - -0.4332602524892016, - 0.623741149126093, - -0.3720899586229709, - -0.12660409650655735, - 0.1706681423420493, - 0.5180081645014708, - -0.5028606614739608, - 0.44403310302442256, - 0.5893262378308025, - -0.19371150410091342, - 0.18692726352915134, - 0.2087357181402718, - -0.6854242408131991, - 0.12076642430959372, - -0.3350374377608796, - -0.20102618595471378, - -0.7029876340565926, - 0.6599189339178132, - -0.7502207706761215, - -0.23904914889892703, - -0.26364510267508234, - 0.6522508759548836, - -0.2752930996470513, - -0.5796887798748465, - 0.36826755959133795, - 0.036592494737797465, - -0.023624535011383396, - -0.42134863957835683, - 0.2331849025122592, - -0.2218962530562495, - 0.03772448056530331, - 0.6618427251950866, - 0.5050858412112335, - -0.5058076773458247, - -0.6462666805433973, - 0.19624583466640888, - -0.6797305433616194, - 0.36753883336845317, - -0.31088044572961476, - -0.5380437230946474, - -0.26441202335382985, - -0.09476977973508771, - 0.1211299411644372, - 0.4817217359690761, - 0.5613854321083968, - -0.5585483557448119, - -0.17858676501295656, - -0.3176093327883313, - -0.039642236025249744, - -0.09671318192789458, - -0.31290684605323593, - 0.3808475162058679, - -0.6391673573772423, - 0.3453611778396749, - -0.4385482938643188, - -0.7529620610014068, - 0.20091429294222507, - 0.17705290194207657, - -0.23965221247957724, - 0.032868039541271155, - -0.6775718430778613, - -0.3817424794205966, - 0.11629240306942001, - 0.19066322752235743, - -0.11208866406312179, - -0.2590965023550008, - -0.31714581087906496, - -0.30108436424131785, - -0.04316602237196232, - -0.766522987146709, - -0.24671875174373614, - -0.7224227556614055, - 0.1283643231152427, - -0.4698280557544534, - -0.06843339710561103, - -0.4041243889210961, - -0.4453550724191725, - 0.22474773136370052, - 0.49079844265605665, - -0.5981905589064379, - -0.2969973562852295, - 0.04676597572086161, - 0.14968630846148223, - -0.7231933319762865, - -0.07123257573639086, - 0.35810002341511693, - 0.07290085956822101, - -0.11855514710512316, - -0.7093688408175439, - -0.26574393868177637, - 0.0034958539364337016, - 0.6313602151030543, - -0.3041060707966816, - 0.19626310853165563, - -0.5098963663018229, - -0.29544369424555816, - 0.5539241666130822, - 0.5085267615245549, - 0.6316032350623361, - 0.40785135463494415, - 0.5498865438927515, - 0.6568861436687458, - 0.09955517217246346, - -0.7031253768947868, - 0.29877090746768353, - -0.0034393800322517487, - -0.48429428974494476, - 0.39773815742221375, - -0.325093969127755, - -0.619659652353058, - -0.4351362502521054, - -0.6244833221602306, - 0.3709650158279053, - -0.16440697879693467, - -0.2827792095188531, - 0.09021651093738514, - 0.17556005858960655, - -0.25118176356132815, - 0.036828772211130345, - -0.5751529767096863, - 0.541286224618522, - 0.6141932691787021, - 0.5311578835841363, - -0.26768888462645046, - 0.48481123370949464, - 0.6172197868428227, - -0.5025651491857155, - -0.23133769194995246, - 0.4285224850128152, - 0.19362710296795294, - 0.5984750889672724, - -0.5839174541195489, - -0.3921886713458141, - -0.40597695231079944, - -0.45464364048610734, - -0.6494642326909911, - 0.4459811745234611, - -0.13411476575527825, - -0.18442687604903196, - -0.4012230577108948, - 0.41492789770614247, - -0.17804051490341077, - 0.49266378743474004, - 0.6207442665425972, - 0.37052835167001963, - -0.7223073677387857, - -0.5811548534302843, - -0.10417040316493853, - -0.7288272307862701, - 0.14906598753798772, - -0.6482771540843674, - 0.44320351273345604, - 0.12531992270445003, - 0.16678215703592025, - 0.6273081806043489, - 0.5910547488703713, - -0.17396087365377388, - 0.6501356907363899, - -0.3079314905377853, - 0.5489641060352238, - -0.7021192456228238, - -0.6080071861794056, - 0.38929846174008464, - -0.26815911475827264, - -0.6772819443009973, - -0.4381133920620594, - -0.27382116128972356, - -0.5452243385703373, - -0.5378011708011309, - -0.6896750720573193, - 0.3594529568705661, - -0.3411802342337974, - 0.38820102408398827, - -0.08106446455860972, - -0.12719011244309297, - -0.6762472325142596, - -0.5684236215664435, - 0.16695928389379033, - -0.5432037972909585, - 0.15367790996842856, - -0.6560587737208035, - -0.736152907029002, - -0.47785244288349515, - -0.4276162644567797, - 0.2164318544654369, - -0.5392742751049694, - -0.21833663812926907, - 0.07389157077654229, - 0.12375324253894426, - 0.020099927354505276, - 0.5813967903863694, - 0.35383832587165986, - -0.2477268055505779, - -0.11900899382717123, - 0.06408422505147493, - 0.4942930667398552, - -0.18132834812961107, - -0.09708151366671802, - -0.4700937860207572, - 0.005535517631253595, - 0.5547503469615928, - -0.05376865210635429, - -0.16782695489167454, - 0.08923426046418104, - 0.19255295750457713, - 0.3760044336493552, - -0.10649023636659138, - 0.5855505089126877, - -0.24470274198556685, - 0.14196452476715415, - 0.49260046475671226, - -0.5626921458513341, - -0.6426884793796654, - -0.014289782042527954, - 0.5520490162793347, - -0.23690085776665892, - -0.5803558267079201, - -0.7294451773457725, - -0.4846970891883623, - -0.1848253060275361, - -0.479040974438224, - 0.1776908933845076, - 0.5072996210326858, - -0.10662944678450448, - -0.10681743985296122, - 0.49880580457014945, - 0.5301473336787826, - -0.24936914477368932, - -0.5141780264213314, - -0.44751623904524174, - -0.334622816124719, - -0.2673148117559813, - -0.503664319787505, - -0.7396285447760504, - -0.07130553335736645, - -0.3687836664681851, - 0.6319011373416917, - -0.2709377024787806, - 0.6097847707439196, - 0.355746263119083, - -0.41158869863375314, - -0.4311621437298894, - 0.25618485475125563, - -0.03352834681431871, - 0.21289655507270377, - -0.6775403121648869, - 0.1562762837433026, - -0.3839599129186803, - -0.7219661754366384, - -0.058458924385966116, - 0.37953389872756127, - -0.4430483410524779, - 0.6544517419340713, - -0.622318291509161, - 0.43517796476866366, - 0.5744183701546951, - -0.14830784892325388, - 0.26059807087108655, - 0.2401089875122292, - 0.07547640288651492, - 0.1698435686696712, - -0.5287222811456984, - -0.5470429936874179, - 0.6055494017243642, - 0.45564032341136074, - -0.7533499559059014, - -0.5394633917382917, - -0.1597604939325723, - 0.027365980608062723, - 0.015178442398115943, - -0.3293833782758871, - 0.4860506439970945, - -0.43259202085700255, - 0.3948140194989761, - 0.49944897199741745, - -0.14023079865675925, - -0.1940529714922653, - 0.304898240684242, - 0.2905760205644763, - -0.12127890763647708, - -0.09541013165667578, - -0.5917250164837924, - -0.2382505402261036, - -0.7191766848559619, - 0.15086742226694816, - 0.09245666526319418, - 0.5288185939990975, - 0.0554950735344919, - -0.20457810496102335, - -6.233852019705832E-4, - -0.31476383848305267, - -0.514762336775307, - 0.15347255788376657, - -0.824790370187182, - -0.6603612502639212, - -0.8439867325237941, - 0.374616007183844, - -0.2122661027003796, - 0.12124805210084888, - 0.06356529202782135, - 0.34669384301861106, - -0.8119762406470217, - 0.21086754969103993, - -0.7203698834890493, - 0.18507059823566774, - -0.4585292351823371, - 0.10759488435867648, - 0.14471153202603793, - -0.06189830826011733, - -0.2757256930447084, - -0.09822946217025785, - -0.39204303483978903, - -0.25961681571452744, - -0.23002573393326353, - 0.5614121312685032, - -0.24339332018855275, - -0.10284710486068416, - 0.21423960976071, - -0.6380278079620122, - 0.28162050241263437, - -0.6218905321273346, - 0.5339285784278471, - 0.44796228382137526, - -0.36894586625380127, - 0.5681988161516696, - -0.2326624608597081, - -0.1920324693663742, - 0.5264555426592312, - -0.37881567491696744, - -0.031203347098210044, - -0.4290563803968437, - -0.6629196585221641, - 0.08962769865965514, - -0.17615538798614538, - -0.7179495771177363, - 0.5124175348631108, - -0.5226773888070322, - -0.5841752984072472, - 0.08857007463148503, - 0.24391761295829273, - 0.096790116734493, - 0.06269788865935566, - 0.4691273192037124, - 0.009535184993131773, - 0.3198510904726082, - -0.8178818196963906, - -0.249643638790625, - -0.75148504306464, - -0.0048486025622652695, - -0.8006502992196561, - -0.409998617770215, - -0.6175708419830134, - -0.08353280655847051, - -0.7475084262349976, - 0.49342176290522044, - -0.25537814952813165, - 0.282921464507337, - -0.6497840894799911, - 0.3147523864222752, - 0.31213488277564205, - 0.38380844120081203, - -0.5690400764022097, - 0.18642414181926092, - 0.2806879341726072, - 0.16118326532381144, - -0.15319576576501792, - 0.4157997958005617, - 0.30321184155812997, - -0.2099403440370744, - -0.5281366541621764, - 0.01726316059532851, - 0.5321591864097879, - -0.10880678175705549, - -0.8562259554912758, - -0.07884185246366526, - 0.4316426497178718, - 0.06955246964723183, - 0.002014602554886613, - 0.2144855045482552, - -0.2084937761425515, - -0.5393937090888308, - -0.047454833027659626, - -0.1825052837335981, - 0.5319053855767659, - -0.4117237538259926, - 0.00921085422930723, - -0.142196875912586, - -0.24263388214974368, - -0.2513620032578111, - -0.21210257317022363, - 0.3187923311343903, - 0.4118307475599392, - 0.4269034779316996, - -0.7171306535557964, - 0.0716151869589029, - -0.5299446531400099, - 0.5465385634295152, - -0.1368613597682944, - 0.4465065742918537, - -0.5755893353425889, - -0.4424423111410085, - -0.6145585623583245, - -0.7137796601853177, - -0.6007549988996526, - 0.31121149065294396, - -0.034678470228454605, - 0.4547542468368668, - -0.0800495652650497, - -0.8577695890572146, - -0.8649032818885145, - -0.01558972979756268, - -0.12197471473310972, - -0.5127099408810252, - 0.094099895056026, - -0.025646016213168643, - 0.44073127926735167, - -0.7340745928134773, - -0.11112187260450967, - 0.3415193084309158, - 0.4969254022355636, - 0.39411403009360124, - -0.21868854928042825, - -0.03451272227627822, - 0.5078185491974212, - -0.8574122746490691, - -0.5965627325031317, - -0.534086147592677, - -0.03229926993855925, - -0.6147472091105046, - -0.0484747074696934, - -0.006795429549605103, - -0.6724457066840949, - -0.10311472462126015, - 0.12953061955799172, - -0.5299484021681798, - 0.3384221304318553, - 0.3906547044098101, - -0.5684453298908109, - -0.2616133558279662, - -0.4827556858529786, - 0.3858741163241861, - 0.27968632821899275, - 0.20119757114631298, - -0.6496693192132249, - -0.2148957611329888, - 0.027300407255205772, - -0.08929940244039491, - -0.44489841728088964, - 0.11465006952295254, - 0.37545232564655007, - -0.7828346854355837, - -0.8355271867686669, - -0.4027302802697345, - 0.15596888101675765, - 0.47320204031629687, - 0.4965761727867617, - -0.7906735898432456, - -0.3161936919507844, - 0.2291381380173647, - -0.7884841085811362, - -0.6808198899839839, - 0.3063183220993011, - 0.24806431111367222, - 0.0341848093576429, - -0.03349627552635159, - -0.5712349331251796, - 0.46528470137152245, - -0.5014205700622552, - -0.5001031931547097, - -0.2289359392418585, - -0.33367382917500765, - -0.022405703948518818, - -0.46193652937621715, - -0.18912990084229053, - -0.8400781323921843, - 0.1683845302627056, - -0.7966889801804031, - 0.2322987424762173, - -0.588893357017187, - -0.4262742182799753, - 0.5073492156927439, - -0.04479866710935998, - 0.1582206368421779, - 0.47990484208735773, - 0.4191550491424325, - 0.06780089335071338, - -0.6158369334326628, - 0.5656013110560705, - -0.3174692820393029, - -0.24857194422351614, - -0.42393207763017393, - -0.5764847464798737, - -0.6325494501302161, - -0.7378961264309627, - -0.7396713702858912, - 0.29194201040659395, - -0.4670815247846071, - 0.5441329534594739, - 0.38893256277072674, - 0.031788821945932355, - -0.054034490831131765, - 0.315040197536852, - -0.06939325740508218, - -0.21224083477555533, - -0.7805954395234711, - -0.5220556360111718, - -0.01569544306636461, - 0.29035985499113015, - 0.5037530466859315, - 0.5210925807322326, - -0.8409269898772953, - 0.5558278811219541, - -0.11251490306755674, - -0.7338553434271025, - -0.7412117770104789, - 0.15783016344046752, - -0.2214822715915824, - 0.446557904578335, - -0.6408520010698787, - -0.7599051457718988, - 0.5013046364614704, - 0.1026885043339485, - -0.7269589422996791, - -0.25793193787132085, - -0.03935030533049688, - -0.8514126698294248, - -0.36290029241809096, - 0.3513057615200528, - -0.05245204916151891, - -0.20063194301230003, - -0.39248402589150405, - 0.5440437946711596, - -0.8383876390818458, - -0.0946608215995075, - 0.1881765189303688, - -0.5328848701373274, - -0.434804289188884, - 0.40991022991026993, - 0.09055508935349321, - -0.17942135958391914, - -0.07723440566747364, - -0.7649319525494993, - 0.46790701888973363, - -0.40407738318346925, - -0.0072717656903154015, - 0.3121978841051587, - -0.42839082586246124, - -0.20774703062765165, - -0.285716377300687, - -0.12871690219017562, - 0.32552204609454427, - 0.46261245905064285, - -0.5756342348597254, - 0.34678946464274385, - -0.6088234162319979, - 0.3703144511494172, - 0.3317009018269603, - 0.4492145694688243, - -0.5143646174877878, - 0.029394092975071118, - -0.44724180169400707, - -0.35805917143588994, - 0.5289571595682316, - -0.49482209970685503, - 0.2620269774884503, - 0.4350504838633975, - -0.1602118518817568, - 0.20081598066513262, - -0.13826436703666134, - 0.40057536676021743, - 0.2538231974941709, - -0.05118815956805556, - -0.6078249956138948, - -0.30505893883306556, - -0.670427762110797, - 0.006243930065205738, - 0.24533833852394782, - -0.6996832150601122, - -0.06727870846870543, - -0.5568681719670704, - 0.016580367115645256, - 0.3323438350955008, - -0.15531542137698928, - 0.2208793364261341, - -0.2085627186390172, - 0.028177563237665515, - -0.16273604739168068, - -0.23083121217004987, - 0.4718754984079012, - 0.016410437754938778, - -0.6806876761966563, - -0.8507320123466507, - 0.15132766413889764, - 0.5391490349239716, - -0.47366104144604254, - -0.7483740988890837, - 0.03575078628490369, - 0.048236997337214094, - -0.3488139321991949, - -0.8565410470948713, - -0.44090617762239304, - 0.43620799193688353, - 0.05645671760360205, - 0.5192793071982513, - 0.1503144936362597, - 0.3041470787920415, - 0.4830168799628627, - 0.0759225538565157, - 0.23739863077966317, - 0.179057236411172, - 0.1733056521325247, - 0.28424564497034566, - 0.5605541612196294, - 0.09263165903170256, - 0.2754550849838835, - -0.3838241531760817, - 0.05667947155009134, - 0.45692281381549504, - -0.7147954215310331, - 0.4660639773672175, - -0.663320482855327, - -0.20301110528470667, - -0.5680608614788459, - -0.5182156301713601, - 0.11839130076986926, - -0.06290148538577811, - 0.07347788747786355, - 0.4198270718255588, - 0.31030886007789316, - -0.004483510580180261, - -0.7390706554968345, - -0.25473018188852004, - -0.6208399227947098, - -0.44517076536548766, - 0.20001180261209694, - -0.10525293670637237, - -0.4108488105507192, - -0.4749793245299859, - -0.7141347119311063, - -0.16578247675085844, - -0.12965632501927304, - -0.32378983253535865, - -0.05576225565107917, - -0.05821355913759774, - -0.20664282948630064, - -0.7788707482239364, - -0.6863292070379448, - -0.6879305808918867, - 0.08579259855481736, - 0.1860865684075741, - -0.5629486969409012, - -0.059895622367331924, - -0.6715743079933197, - -0.7482505678465471, - -0.6356396915163044, - -0.34874040439314036, - 0.058348508198604265, - 0.2315699067640784, - -0.050124488726073446, - -0.1732296614559764, - 0.30854851396069516, - 0.17266164152523222, - -0.26437902351799036, - 0.2824452963595292, - 0.0032204766068074653, - -0.057275475269848775, - -0.4007273534076439, - -0.0357667993146088, - -0.027800311817403056, - 7.01602968140036E-4, - -0.2877221333554525, - 0.2622305484685876, - -0.4557026168653967, - -0.1647907254356158, - 0.17634727586121612, - 0.37196744803405335, - 0.14825937099880715, - -0.8102823307622364, - -0.46964297580563363, - -0.06446033458484157, - 0.4022987080392213, - -0.5318114637715431, - -0.5364334778289647, - -0.05125624929436101, - 0.04071251619681138, - 0.11955611810793543, - -0.173020150148671, - -0.37928774944100674, - -0.27812732458144673, - -0.16747969873353608, - -0.24177291778991616, - 0.4200093655319477, - 0.35522827160021087, - 0.1310530907864792, - -0.727717025421091, - -0.692829496928937, - -0.21388955809521937, - -0.7972284803479865, - 0.1407831983513841, - -0.689326553395478, - -0.07827626080604033, - -0.192198485745403, - -0.08700701589026671, - 0.03976352971525243, - 0.45141386552009655, - 0.15422128102804833, - -0.3710017634086661, - 0.3865461641005665, - -0.44576708732159465, - -0.08641315202893718, - -0.5367746940434531, - 0.31032634796704817, - -0.32650217335958576, - 0.5407248174318948, - -0.6328345447812502, - 0.009754753258556792, - -0.11014378407078418, - -0.04317902752804792, - -0.7651567762006174, - -0.3080261290789803, - -0.13651181947086288, - -0.009068456922996182, - 0.11457513047419043, - -0.34184355285294765, - 0.10968523825727072, - 0.036314112656835595, - 0.40776821973510535, - -0.5319789659564945, - 0.021338633284716524, - -0.2437616537683619, - -0.6950510511234288, - 0.06629237507924146, - -0.4740083457406461, - -0.39861215594823585, - -0.10575616779158759, - -0.6758903688543212, - -0.6309834608542364, - -0.4061907140455842, - 0.13021249880055075, - -0.717391896090114, - 0.5072578107541357, - -0.818042348440045, - -0.05991745186028574, - 0.43766137293034824, - -0.3789233918089672, - 0.4031929447139311, - 0.5495317253936978, - -0.04618253937223704, - 0.5126505102087504, - -0.03928991128148818, - -0.6960834835252644, - -0.8279662878497888, - -0.5452726497506994, - 0.5402240394935307, - 0.008808223377965052, - 0.43239334738009316, - -0.5554853521712213, - -0.7362845899756932, - 0.3760090572300161, - -0.6471417826847002, - 0.5577038929153761, - 0.24171773893217718, - 0.5507994082881174, - 0.02747846553967792, - -0.191381930478573, - 0.20021878576965335, - -0.3195080229762759, - -0.6091663359513408, - 0.07572494795422968, - 0.5598133686491733, - -0.6356091054619364, - -0.1634705586228684, - 0.5439497493173309, - -0.4384803495393443, - 0.4466559907514924, - -0.09222991196862074, - -0.5840169797674009, - -0.8415047705133795, - -0.8517943165721304, - 0.45027465869578975, - -0.7277762600774709, - -0.6395959722845003, - -0.623068709903789, - -0.7949514812911215, - 0.28197781481646134, - -0.20774780558047212, - -0.8518237061845072, - -0.6947908526992299, - 0.5251174468911481, - -0.4078187023110212, - 0.3249199488120462, - -0.6850357078341452, - 0.4669330423805982, - 0.43448662355279843, - -0.07763640898389135, - -0.013196806964642649, - 0.018892850754874457, - -0.6758908589509383, - -0.24111485344321804, - -0.5377530876495873, - -0.11155032788347052, - 0.3519434100509826, - -0.37150871202988917, - 0.18590158591767603, - 0.5470375577073829, - 0.466550323693947, - -0.5199041643340641, - -0.2794156537271256, - -0.31309437280182095, - 0.05136772690773295, - -0.3124434032726281, - -0.7326459677518763, - -0.8114325604658542, - -0.1588949087406364, - -0.007099599037325155, - -0.63413548109464, - -0.18473698674722405, - -0.7855995251460426, - 0.31797656531617746, - -0.5511538277486376, - -0.18483985111448376, - -0.49282481457737204, - 0.37005554525158724, - -0.6576051100354118, - 0.37955125932174827, - -0.48211962146436643, - -0.6830168316638403, - 0.44975560403504655, - -0.17553972799844286, - 0.0752702828788886, - 0.4344892398175737, - 0.0017981072598352021, - 0.4249717974182792, - -0.3167487434502647, - 0.007194352438750218, - 0.4147450319431665, - 0.03870489098645635, - 0.43923664058837364, - -0.41410190555579074, - -0.5507562642642059, - -0.6002242494682576, - -0.10889498890575233, - -0.8211364250177392, - -0.05216695685383055, - -0.813435505687969, - -0.6406626215087391, - -0.8559721363598547, - -0.15171672614348708, - -0.45867492586058906, - -0.14565712992480384, - -0.1564171547689166, - -0.06328246972896578, - 0.43101608898524013, - -0.03778188962600604, - 0.10901000941306593, - -0.009638636199291839, - -0.37616334727358613, - -0.740900829544233, - 0.3599456294264247, - -0.7542439796216813, - -0.39732116522473215, - 0.04594369661437181, - -0.044118080137605986, - 0.5087345091062618, - -0.19611724639460215, - 0.4951832614567946, - -0.5016177379458797, - 0.49955609511961185, - 0.01876790277387408, - -0.8634371628892029, - 0.44313346139197973, - 0.23381745363397255, - 0.12391542479982032, - -0.19483092984335237, - -0.03115651222434801, - -0.0748923963326582, - -0.2909875517339614, - -0.8120242592617036, - 0.39125943606114544, - 0.3197149340035288, - 0.5037365780160594, - -0.7865169701103724, - -0.07842911778423156, - 0.5159106792120756, - 0.3787140268000646, - -0.6547044160307728, - -0.7764388745810463, - -0.5641987441097946, - 0.5459753927929198, - -0.7312173538202661, - 0.06377122475776886, - 0.36161889591916085, - -0.2011928652932965, - -0.02452917369304275, - -0.6623163571566645, - 0.19318402075496643, - -0.7680107225383619, - 0.5293349705021955, - 0.21250897512490563, - 0.02319244159671796, - 0.3329803930375561, - -0.26606297088924136, - -0.7211882188708287, - 0.5390969737854723, - -0.21079993924061557, - -0.864605342272505, - -0.38837941348160765, - 0.41823597843668536, - -0.2552342590944848, - 0.47685912562011135, - 0.1985543466987243, - -0.765263413888327, - 0.361471382404994, - -0.634890228910368, - -0.5502515879482714, - -0.7358340527613334, - -0.03290562162866595, - -0.6310675073706142, - 0.04800385316724831, - 0.13375379003360566, - -0.8652846394001897, - -0.2793727216909806, - -0.3937958094480469, - 0.3310692396487487, - -0.052468258565638526, - 0.3771169872589444, - 0.5637009912118205, - -0.8518855805981844, - 0.0015315422389104993, - -0.5926570510789044, - -0.6173962716125588, - -0.749087791410619, - 0.5210527522597037, - -0.5956184368946456, - 0.5369012082013984, - -0.11429498626221712, - -0.3056524866330588, - 0.4495692488647667, - 0.4503964372073588, - -0.7635852121326956, - -0.7198688334415346, - -0.07813682854911252, - -0.7253477646339248, - -0.7173358299905993, - 0.4435781861402128, - 0.5418804812575939, - 0.37541179008047276, - 0.367793648712466, - -0.4647432655410691, - 0.5225078456357366, - 0.192889566648901, - 0.12026637433267062, - -0.7157410791653203, - 0.1378599933829372, - -0.5887552907661215, - -0.2957678214516416, - 0.5632351071766402, - -0.6369362230310561, - -0.38698062283174695, - -0.18683594741251452, - -0.5594493911635658, - 0.2842042894066805, - 0.16058962227785867, - 0.04432197487432976, - -0.05770550757308479, - -0.6796031812773596, - 0.2674603432153968, - 0.16758932031493412, - -0.818725660312715, - 0.3504954759943526, - 0.44791000914801327, - 0.04598237220491208, - -0.03704179361504989, - -0.2309030030525301, - -0.0836164693584035, - -0.6796808305829967, - -0.40784190086486993, - -0.6066137203898629, - -0.07805674649748462, - -0.29385442236408976, - -0.11562649826440707, - -0.026921161793954873, - 0.2405436575349862, - -0.8355938382810748, - -0.32692775789958584, - 0.1499520575686153, - -0.017869928634047128, - -0.045928806531637334, - -0.5800190816865176, - -0.15883186816506134, - -0.36896359121993577, - 0.4862642781207913, - -0.6777043588550468, - -0.2622408658763954, - -0.2948227422362716, - 0.3806231540359224, - -0.6050025715190228, - -0.7564738508905979, - -0.2607694147142795, - -0.32665129689793715, - 0.4802266512899871, - 0.5514534603766414, - -0.32357829660776183, - -0.10966331648303418, - -0.18474308356253255, - -0.8282230594740453, - -0.059921587527557385, - -0.12601453819306552, - -0.04396626419907057, - 0.5139518760107307, - -0.2152452973364769, - -0.28785782734667664, - 0.5094144642382072, - -0.024440315940866486, - 0.20807240106587388, - -0.8315414195186976, - 0.21025281855639055, - -0.2701943176777376, - -0.7654364486815748, - -0.3215723566265446, - -0.7535751361087384, - -0.6392278810591489, - -0.6452437646269187, - -0.8431004263812488, - -0.3799961063253469, - -0.5825428212683781, - -0.8320893359579377, - -0.1697417912596364, - 0.5348883250576608, - -0.5398588655172005, - 0.033431877076000704, - -0.5936697758384981, - -0.5226161055642864, - -0.8005560044809275, - -0.7965105168861248, - 0.3691242412648177, - -0.6937862250976627, - 0.35040605694472116, - -0.17837693648816766, - -0.244417601573369, - -0.61445180314855, - 0.5285543882052453, - -0.3523988989368124, - -0.3929565690842258, - -0.25350446893161704, - 0.5494745589974974, - -0.784542909073046, - -0.026281905101789516, - 0.22426126289453552, - -0.48173770881949635, - 0.3657409224673236, - 0.22231997975545004, - -0.533008653233666, - 0.20366288727084259, - 0.5221387828568655, - -0.46873357382996406, - 0.25501152040421027, - -0.696628596467591, - -0.20655848053545944, - -0.5872283749478526, - 0.09218788896682362, - -0.3923477529963874, - -0.1315133296675458, - -0.340391297729581, - -0.49835602820474256, - -0.6831693073719277, - -0.6504985539682296, - -0.4464016029583402, - 0.3083473534329655, - 0.02955822240011019, - 0.1063968560492704, - -0.3854928272752617, - -0.540142312781615, - 0.4576868194109005, - 0.5334145898100575, - -0.0783177351659271, - 0.19813312007249162, - 0.008691486862014042, - 0.15814388878615793, - -0.817023886091732, - -0.4287405988809998, - -0.5299198482675674, - 0.18443690919759081, - -0.47348635773960435, - -0.029509244909436738, - -0.7253918341258397, - -0.05981434753028225, - 0.07553154012871244, - -0.6487033184681834, - 0.15544192300755477, - -0.5526306676535154, - 0.2975907768675785, - 0.15859166967871352, - -0.6899725342441001, - -0.25493758769107966, - 0.5089181953505029, - -0.12794362933392378, - 0.493937820145141, - -0.8216215855692749, - -0.2825159738467733, - 0.2008234845723289, - -0.13975043678519639, - -0.5203618613600492, - -0.44912390297532134, - -0.37013003121980265, - 0.3691974469982584, - 0.0805086096736567, - 0.17742568480365284, - -0.4895806193565768, - -0.4544061923636817, - 0.22068108536059627, - 0.12406554753917809, - -0.3706282436926665, - -0.806838857155417, - -0.515167385407844, - 0.28050884845879653, - -0.3635706768830289, - 0.23335914662882473, - -0.14422600712656497, - 0.3689729392521601, - 0.5679998549181433, - 0.5493094502722031, - -0.5837931163262116, - -0.5674625253155892, - -0.34442801379799737, - -0.6471531649982707, - -0.7507870983282026, - -0.6944123931368477, - 0.18044808988204997, - 0.24515893886268603, - 0.4210809629463417, - -0.32074006225673923, - 0.43770313780987213, - -0.08497637931289148, - -0.18821017236137638, - 0.35835074123863, - 0.4956150067880143, - -0.3514560599728854, - -0.8137668322032384, - -0.3758968042507638, - -0.13829848628368346, - -0.07520154368788323, - 0.11363502815012783, - -0.18416468255804352, - -0.6719914398681339, - -0.028741315801634082, - -0.8464461227217549, - 0.4468618451977715, - -0.5641194642674763, - -0.7845925640604738, - 0.1866804611778774, - -0.0782595327421759, - 0.004736717244885891, - -0.7248991953322157, - 0.0251440840829813, - -0.36125459080621347, - 0.1255743954403532, - -0.7830034669784431, - -0.4004280737190602, - 0.24042534826844375, - 0.1979768712552028, - -0.4971212024310576, - 0.12845008046197504, - 0.12906935510861617, - -0.07786114099226804, - 0.07613821286741562, - 0.38901439772730284, - 0.1924930486684493, - 0.5295942862003784, - -0.3355837376907339, - 0.013925460825616187, - -0.6732898797620178, - 0.19504827614124998, - -0.7398764086102974, - 0.01217470396702336, - 0.37511663833189957, - 0.14625413708500568, - 0.44743138184511233, - -0.6794539534138169, - 0.40631697652087584, - -0.44905709304703023, - 0.15724873243300475, - -0.5681133120449617, - 0.033024748357831646, - -0.33575436287438276, - 0.14243800229746184, - -0.27636035634004286, - -0.05226496569474026, - 0.23552971216041585, - 0.3800550089255532, - 0.22897184041625063, - -0.13122234458848692, - -0.4574266914753337, - 0.24521590428678386, - 0.49249512101795667, - -0.47678803189545765, - -0.8007984017689251, - -0.3083228062660127, - -0.5353439109907986, - -0.7218025206253171, - 0.4191604917731975, - -0.6975416090395639, - -0.3631013593262977, - 0.5352073909910875, - -0.7219811416690617, - -0.5539255072599483, - -0.6652274743309413, - -0.09919264590404286, - -0.6145302225191196, - 0.5276271932206136, - -0.6330568613761108, - 0.18913693557305256, - 0.4534704854495153, - 0.20373650512234165, - -0.5601386149996802, - 0.2802157176280955, - -0.8476046805121642, - -0.5075965674736702, - -0.3490687223262272, - 0.5570572791276351, - -0.7361946483728283, - -0.6852966525928147, - 0.027590744124519007, - 0.4259739665301643, - -0.7830952533086055, - -0.5355883104702968, - -0.7904282123555648, - -0.06736429362501939, - 0.540708371477671, - 0.5286358945430008, - -0.48263580169732195, - -0.7514243827223145, - 0.14286897210924732, - -0.16727085630210603, - -0.6070124151603566, - -0.13225482227463747, - -0.3314468164448152, - 0.2920115541570891, - -0.04575628085651473, - -0.018340822193554596, - -0.4182319253454998, - -0.6136847253541307, - -0.4301168921319787, - -0.01425078252921208, - -0.474368878550999, - 0.17293140248056504, - 0.4633194977124544, - -0.746684978621531, - -0.3919462569706351, - 0.5448759520751094, - -0.30548167992349995, - -0.40944603024368287, - -0.3047406673934483, - -0.332090196934439, - 0.03703479241840557, - -0.7727216710972382, - 0.33926568118023703, - -0.34395832657260383, - -0.18648553344840557, - 0.02687876592970695, - -0.7105134586242587, - 0.41325269902866024, - 0.3616897103275931, - -0.06421028504374637, - -0.6808524095612685, - 0.447597420481769, - -0.5491614182991906, - 0.1806061678375337, - -0.37473445105322895, - -0.664269864649377, - 0.46498704789542655, - -0.7555192592273756, - -0.5184121482221482, - -0.3626449182219448, - -0.47422205624506136, - -0.7751084049009909, - 0.08411480753090272, - 0.29719690626218664, - -0.5990086808572148, - -0.5553807339737875, - 0.21923756822552343, - 0.12030820760343441, - 0.5336754075185344, - 0.4019439775044771, - 0.23756253073395128, - 0.30259758668707937, - -0.3518200864697858, - -0.6758651062471108, - 0.3636108280246584, - -0.16509674238273864, - 0.5313374889795586, - -0.050060500679253384, - 0.3480436246076828, - -0.6932424322034467, - 0.4929567564859634, - -0.3566872783523307, - -0.22164540812772737, - 0.5229521382866256, - -0.012903842103757945, - 0.5577309796431029, - 0.550791623341123, - -0.516773962198853, - 0.5627772585576305, - 0.38989156888232945, - -0.5465594956888004, - -0.8111085789678508, - 0.4701006519748343, - 0.09823875501868484, - -0.3786097735868933, - 0.2797295557344053, - 0.5559322374639588, - -0.41665729240888427, - 0.06120996467200901, - -0.1671270305508512, - -0.43873272003944697, - 0.2985890140981238, - -0.6428538441707263, - -0.3686309715489465, - -0.09638444792369705, - 0.1659940333326515, - 0.09392284939313622, - -0.3045803736172664, - 0.26291525866111853, - -0.4824656301190116, - -0.36003908627023284, - -0.06944390122434396, - 0.21185959663048193, - -0.4188620110985345, - 0.1182208778250724, - 0.45103041119474097, - -0.13648572034979456, - -0.04840907213165002, - -0.24696817849099806, - -0.823396311110811, - 0.08887734837776506, - 0.2766553673182288, - -0.6161808381262777, - -0.03697671775790867, - 0.2870041617214436, - -0.2996751661607626, - -0.8545475731186042, - 0.2706173304917767, - -0.39957920065608715, - 0.172572874208633, - -0.33257787177256604, - -0.4271707014307076, - 0.08036805338013786, - -0.1585277273580744, - 0.2596625999053561, - -0.39554963137702914, - -0.0128343292869868, - -0.01859758486512253, - 0.1938838135686618, - 0.48347605551116146, - -0.1693997386974797, - 0.2538998612920156, - -0.22969455487795176, - 0.14825636759761118, - -0.19819041736481535, - -0.8511785371799444, - -0.30260234458372526, - -0.5838237605660784, - 0.5085614052921608, - -0.2558387996679009, - -0.7216271783255273, - -0.6473913134082507, - -0.03415364319750491, - -0.7705942702878886, - -0.7844789686820394, - -0.5172871281937925, - 0.2459992201187562, - -0.4140016875732543, - -0.7832431655223205, - 0.3354824702069743, - 0.08757387879491008, - 0.4887112463509873, - 0.4133873775805481, - 0.3986125462632737, - -0.020433470974657086, - 0.3759817453675589, - -0.16429306634824525, - -0.4496409485445045, - -0.2973903246058859, - -0.5531764752657968, - 0.02857891767457643, - -0.7656945087541976, - -0.3069412487621199, - -2.9339139748341125E-5, - 0.16444930287693982, - 0.08004641602338569, - 0.018552940207674284, - 0.24501962344892236, - -0.23693789984144986, - -0.18055276095596196, - 0.4700878128469139, - 0.13214753265969514, - -0.08809511495770528, - -0.008818773640919986, - 0.48663583734873694, - 0.27508381480623134, - -0.07125509785243445, - 0.24543873929169413, - -0.1555568462876854, - -0.04935969641120286, - 0.27797731140294935, - -0.5747905108081299, - -0.8039722740802748, - 0.19103319710078503, - 0.35951799447899035, - -0.12010778169832714, - -0.09080351213108129, - 0.03783202233067362, - -0.8270052965058172, - 0.40588328191117484, - -0.7468294832368908, - 0.19767561663869349, - 0.2663034101427002, - -0.11039115789620713, - 0.15080319839882406, - 0.30032685306330276, - -0.5866128667210395, - 0.49383716672175604, - 0.2208391157595888, - 0.3938260255309656, - -0.4087280171348672, - -0.6071583790195882, - -0.028408286992154252, - 0.2593256238532795, - -0.5221113248323748, - -0.7317739223555245, - 0.39585041620945005, - -0.7884772425522276, - -0.23462844103017788, - -0.10025489690330625, - -0.24932613374921453, - 0.2817420554898513, - -0.48417441650819015, - 0.5481741536989442, - -0.14588893822197735, - 0.373852427523496, - -0.8320621280084265, - 0.13929853702497663, - 0.10468847406626347, - 0.4573592304862921, - -0.0535902843239231, - -0.7721984427612633, - 0.1382930407234162, - -0.3546603011272409, - -0.6837331876032878, - -0.11391708911653375, - -0.43097924476130006, - 0.3254245428636089, - 0.28567450598869026, - -0.8368223096970313, - 0.28869060159296156, - -0.7047111878447386, - -0.4976193970939526, - 0.35772509427784316, - -0.16190107624252104, - 0.40865729875918433, - -0.22989843209421323, - 0.1838368764351348, - -0.13629426166655456, - -0.20564758737898436, - -0.08269713678006851, - -0.257389830597784, - -0.43797606688110186, - 0.26538446684887984, - 0.16591528586889925, - -0.22132367099498396, - 0.10246674854636917, - 0.22083527556054072, - 0.31270540736397767, - -0.8216713205459993, - -0.7399504979132201, - -0.5731282254729952, - 0.023249030412974325, - -0.142465486095666, - -0.5623512699184494, - 0.2849410996754693, - 0.4830821294376031, - -0.6378312895761763, - 0.1586643503401013, - -0.22838340861821327, - -0.12805649537705333, - -0.10076051685375909, - -0.7190836079097105, - 0.4686196454272311, - -0.24665761492293914, - -0.14356227206882244, - -0.386191159041871, - -0.519839893711838, - 0.4587390349146263, - -0.10966180747460641, - 0.15910901917446663, - 0.14465206081426896, - -0.651183917312661, - -0.5885570665902868, - -0.5162752337099163, - -0.19359279328204937, - 0.5072090265355209, - -0.6620416124274751, - -0.7241313026985603, - -0.6125636845098084, - 0.14390347023935224, - -0.15437367931826051, - -0.1274462406757968, - -0.5838669898686242, - -0.46174459102933435, - -0.3839577785790684, - 0.5119642595303484, - 0.24210914320392862, - 0.3583804875047085, - -0.826622755646466, - -0.09855911333253631, - -0.7118323520607587, - -0.24392228007965033, - -0.8146022151926732, - -0.6198078575303817, - 0.0784755487413098, - 0.41373113459009647, - 0.4619981795187489, - 0.21952352609328596, - -0.2472848319156683, - 0.19799427730591868, - -0.28374447051875806, - 0.007079231997767721, - 0.43656003856262715, - -0.6265632623887375, - 0.1798657805957018, - -0.7253869708671647, - 0.08171098632782792, - -0.2978513474041514, - -0.7120214557510672, - 0.19173830079081222, - 0.5027988288311183, - -0.8399318528498452, - 0.5003464865865319, - -0.4347200431393139, - -0.09691277873750304, - -0.30983848110079404, - 0.4075423126435229, - 0.2268882093482274, - 0.5561368910170614, - -0.39763361469738173, - 0.5241433313888846, - -0.4876121250561742, - 0.19096491820930317, - 0.3973743776691687, - -0.43088356571934217, - -0.4467982891687077, - 0.23255884136364857, - 0.34080635476806975, - 0.27220675098269864, - 0.4376670065845245, - -0.13769899481403924, - 0.17293374713489018, - -0.5667623705084973, - -0.7671770897427748, - -0.7760246435550455, - -0.29423808307869626, - -0.4803511497292016, - 0.3327034825386641, - -0.0032852746689013834, - -0.33628361798728335, - -0.8543778606917724, - 0.21653294331211237, - -0.44803110826274967, - -0.34815287082111934, - -0.32693329918356395, - -0.5838993082449155, - 0.5161453011066388, - -0.27214583517160174, - 0.478371069395362, - -0.5427008666329363, - -0.7472496823484759, - -0.7296097445817937, - 0.5379479738103774, - -0.7936348016395954, - 0.521937780632026, - 0.43269553441647846, - -0.4798156267542926, - -0.529941352807741, - 0.28936274065344425, - -0.05679734623287258, - -0.671970489788579, - 0.294671417884117, - -0.0926632726825114, - -0.04802166690918275, - 0.4380939642888164, - -0.820917202292079, - -0.530810740166737, - 0.4622882885797399, - 0.08179517691970761, - -0.5910279920730246, - -0.6283849573071685, - 0.2612493657671422, - -0.28379863953514284, - -0.7682602814727183, - -0.6901483195020461, - -0.32740911799000816, - -0.8122182029059006, - -0.8161978615964067, - -0.22173108398322028, - -0.21484511275796903, - 0.4351698751057522, - -0.49943780329045806, - 0.37373865864795563, - -0.2517712235348587, - 0.11441652508985456, - 0.45690846059522916, - -0.7262882339825423, - 0.22285950545990563, - -0.5572043367991169, - 0.3297195492682663, - -0.21997088771655604, - -0.8121951365899825, - -0.002949199893468313, - 0.47266610472493586, - -0.05059437563122282, - 0.01915827871697251, - 0.09990920329697817, - 0.11487142245890547, - -0.16640518488892087, - -0.3169480318327149, - -0.8196253007049188, - -0.6538643045828882, - 0.003833951857836193, - -0.6969470332941766, - 0.07553515316562964, - -0.36341782621793994, - -0.5082098575995855, - -0.3384125574616901, - -0.607746445005714, - -0.4848689353030491, - -0.27393683586370465, - 0.3795896630639908, - 0.32620422461386234, - -0.845121513988865, - -0.5251402005630181, - -0.14646010877621385, - -0.4320596768152289, - -0.5960265998816162, - -0.2053456245648213, - 0.29348158845873096, - -0.6655289275881517, - -0.804343236284128, - 0.001136767618878043, - 0.3903302551369001, - -0.1849599684513371, - -0.7975778199357929, - -0.02167356467200854, - 0.4646266254411038, - -0.036883737586110854, - 0.5126285582007566, - 0.45800724100259216, - 0.5300016641379626, - -0.51597633109618, - -0.6797595205355415, - 0.3838815017418995, - -0.4501081259041149, - -0.2201960030187895, - -0.5461491647945129, - 0.2548774838782506, - -0.730891958011938, - -0.3507750202651898, - -0.8136623947018764, - 0.26544231833408194, - -0.816149882898108, - -0.31084478813670613, - 0.43462556803397256, - -0.5336575174641115, - -0.1732820789621412, - 0.5056613742441027, - -0.04685607036013206, - 0.11509181199195473, - -0.494604929958633, - 0.4691410036633321, - -0.36908012431961995, - 0.16312148379471525, - -0.09141715004138995, - -0.4216367851055951, - -0.6234522698188647, - -0.3504034643138709, - -0.2322746526015016, - -0.6087751912905788, - -0.8223242087842576, - 0.09987350950193108, - -0.693795889554921, - 0.331716232575507, - -0.6473949468693431, - -0.8157628035462844, - 0.24673242826391295, - 0.39773546937337323, - -0.7726837690594588, - 0.5550201567397097, - 0.5397588664207988, - -0.01356568797047153, - -0.010355709694870763, - 0.09665648189374032, - 0.09643163252503828, - 0.5525956213096603, - 0.3201125854557003, - 0.5060481819807015, - -0.5138841650821728, - -0.729518438499001, - -0.8178923071380538, - -0.11953778471490684, - 0.27680521975370587, - 0.39763507537354736, - 0.01498941393026576, - -0.005087826377151106, - 0.3519816661558932, - -0.5552846674815681, - -0.12971691688895193, - 0.29656049862699096, - 0.20501047797864458, - -0.5263090487200806, - -0.043723700310382085, - -0.8323272505457582, - -0.11773278305854129, - -0.22354600991525675, - -0.7650617700026286, - -0.6740806203927537, - -0.13613636608620305, - -0.4935048748694338, - -0.03957734725089557, - -0.7820716239101202, - -0.23020456153102653, - -0.476976460986373, - 0.20721883680499142, - -0.21965638539782006, - 0.1732024966356258, - 0.34984900061228563, - 0.4628162707583343, - 0.18738010056399523, - -0.22638364389464916, - 0.3626736596607718, - 0.5584504553167955, - 0.03724852908205678, - -0.29268339110066854, - -0.7920714374751618, - -0.4206109851436813, - 0.4342110383730997, - -0.6161671399547839, - -0.789177316716601, - -0.8084048150789597, - 0.06928281617144794, - -0.0409907921804481, - 0.24701733680320292, - -0.4451454685808498, - 0.08929206142020374, - -0.15379070579359577, - 0.2764571107708369, - -0.3418804412705879, - 0.5278587379665842, - 0.487628766633702, - -0.40729223799899683, - 0.312296519832451, - -0.7518696551711974, - -0.3702391113126663, - -0.6778418998982564, - 0.2085760553257403, - -0.6159868274102152, - 0.02571529820832863, - -0.4615756031471907, - 0.09332926868048097, - -0.6669793065979778, - -0.551862119674617, - -0.3133654058636931, - 0.028255769822494337, - 0.2924729514617528, - 0.22517756121073917, - -0.5598195481392986, - -0.5775291178916446, - -0.21952995393780617, - -0.21665796071969445, - -0.5465625158839718, - -0.14279608207044647, - 0.394463518970976, - 0.2435030813984571, - -0.06760751415706057, - -0.6665881454912341, - -0.8282668824095777, - -0.5929707019752315, - -0.4073289837915071, - 0.33352339448083446, - -0.16146564136139163, - -0.02319098788081375, - 0.217785911817866, - -0.6652006040727956, - -0.7883822890982588, - 0.4599139604852436, - 0.29724459595651864, - -0.2925745394246635, - -0.493645556015376, - -0.6824403914651176, - -0.7463371866438291, - 0.4490323558684626, - 0.05791319027763586, - -0.2529956888612439, - -0.575803535095631, - 0.3954853773592475, - 0.5215011501210798, - 0.1963368870545683, - -0.5099219469631673, - -0.25665719260177433, - -0.5020263462070649, - -0.8347655085339043, - -0.7677215423738174, - 0.26410856899686186, - -0.39465277184458997, - -0.4505357584144548, - -0.8375777761969063, - 0.2878626341167063, - -0.6446236416734189, - -0.5338686187671586, - 0.014180661060455235, - 0.22426434092601188, - -0.36129848039186974, - 0.06136683205716642, - -0.2716065840234496, - -0.7644320987027596, - -0.7743964806259123, - -0.1524720300281288, - 0.4665351307447283, - -0.06097687183654232, - 0.5301934129930508, - -0.8437712167570767, - -0.5761843084814394, - 0.06674639747749189, - -0.3036514935020488, - -0.6135187444255745, - -0.8228758391998791, - 0.41298542900686064, - -0.3541270687857979, - -0.7024802209412726, - -0.08879579218636913, - 0.27594729223383907, - 0.5071080798514214, - 0.3189827859041001, - -0.6818899934015686, - -0.7137364786431868, - 0.38642558110904845, - -0.02891876228563728, - 0.2685057475664563, - -0.43013493354849464, - 0.27157265702743216, - -0.4380243751911918, - -0.5818923412800383, - -0.8281250757754761, - -0.10278284712326813, - 0.07098228054060907, - -0.745591555863228, - -0.01504730400134513, - -0.7153839507424147, - -0.5127424791200245, - 5.166171587234203E-4, - -0.06869248504969949, - -0.4740873726450752, - -0.7755807674593386, - -0.3961718453956403, - -0.12089187225779063, - -0.26945875958923904, - -0.5584126986264645, - -0.6412848981221669, - 0.03429907117993114, - -0.68212728151403, - -0.6398165094660291, - 0.3720557687715773, - -0.14270751741560728, - -0.7613728152649898, - 0.2232286867592843, - 0.10590663468450934, - -0.32196945446722103, - 0.16451053113784653, - 0.09795610880774408, - 0.06438009458199578, - 0.44590659422398105, - 0.43249074910783203, - -0.5105712978909234, - -0.14940623961537935, - 0.4751454793301697, - -0.7358790488907359, - -0.6679473691023871, - -0.09741553436029249, - 0.43012964449739766, - -0.7794358875942838, - -0.6554510498462447, - -0.5175693595531318, - -0.7444870038395576, - 0.564103375923138, - -0.43348787885316653, - -0.5956878597466553, - -0.2308333487988833, - -0.4953817042788792, - -0.36100597325944295, - -0.5545316836829939, - -0.08851129223895027, - -0.7793471938656209, - -0.26633352819861866, - -0.6140490129328349, - 0.5509510500120509, - 0.43900929996604976, - -0.003860333386092041, - -0.441056532701872, - -0.00581923059886158, - 0.18965817365625726, - -0.3568043833507657, - 0.1797892622635613, - 0.30266231017158396, - -0.8218046320525598, - -0.14972415268530515, - -0.37391870477099465, - -0.8049922693975204, - -0.28943990871793956, - -0.8591015370497347, - 0.3041503168018307, - 0.2968973726674409, - -0.5432936796671808, - 0.03910061120992603, - 0.14338285954623764, - 0.4573884792851506, - -0.7573608233414376, - -0.2355902125520427, - 0.09703410089697484, - -0.5897871294478001, - 0.257506352268311, - 0.00864968341769079, - -0.8260828474439624, - -0.4018902615880149, - -0.6264914226829033, - -0.3797456384037127, - -0.6622959445298957, - 0.4933275603326901, - -0.12994649602989194, - -0.28500531438516785, - -0.04515009407231707, - -0.22054077887130696, - -0.4811180922765364, - -0.8499027584130903, - -0.1466434037280332, - -0.23983496474791188, - 0.2582678125519946, - 0.4701630584072165, - -0.2461546968393935, - 0.10918250119934625, - -0.7557573902240986, - -0.7190456687665141, - 0.06541888813545371, - 0.03131404330099663, - 0.37532871648995103, - 0.22133708333819557, - 0.31284384457817693, - 0.29147372048995157, - 0.24556680095461858, - -0.7590794675231979, - -0.3557201865490648, - 0.557462757063351, - -0.5447793440644553, - -0.4820346850989318, - -0.5062957012308271, - -0.3719450801016303, - -0.6499193134937375, - -0.4055568071183105, - -0.5722790613430715, - -0.7567724826953643, - 0.3261423234576628, - 0.03803089004330362, - 0.4034514646690348, - -0.3502019219407666, - -0.7754054097391467, - -4.102516282837865E-4, - -0.31999109889843613, - -0.8419806815004366, - -0.44185083574541123, - 0.4695784786992938, - 0.20731201925556864, - 0.03079154930574657, - -0.6183765586812033, - 0.44900648946932553, - -0.6671793310563453, - -0.7042106927204742, - 0.2964843555521879, - 0.49821673793486543, - -0.6303171232727922, - -0.232922340492967, - -0.7679093976485243, - -0.01633565027112127, - 0.23064496848270322, - -0.2997482955042827, - -0.856058474912956, - 0.4661993388575747, - -0.15981589353011028, - -0.394061167078383, - 0.4067673953314317, - -0.24196522480687577, - 0.5563076697858429, - 0.2020917371841544, - -0.2641537304011262, - -0.13507007456295184, - 0.4190789112249662, - 0.21494976110222774, - 0.519319104237457, - 0.18263923550341077, - -0.6269684664621246, - 0.047195666074336895, - 0.03970602332429063, - -0.13407013995052453, - -0.371656793121971, - -0.02541464099509283, - -0.037373211916411964, - 0.1897585344555497, - -0.4653442037210913, - -0.8455771743986048, - -0.563420124738415, - 0.24016029118031068, - 0.09742361214212547, - -0.19901855216134523, - -0.48021073717877283, - 0.14676220795651318, - -0.3040210336965664, - -0.24226999004452165, - 0.19148390190898046, - -0.7046344097109309, - -0.7303125352820306, - -0.3490629757185213, - -0.1092297646073841, - -0.70170041324674, - -0.19197915171410007, - 0.14774304343586708, - 0.01584082447873958, - -0.49107873527290924, - 0.19796496313536327, - -0.6941026633607958, - -0.30993266214678283, - 0.10882444639857924, - 0.5635319671980363, - -0.48640068240705164, - -0.8025294710841302, - -0.27318043760721167, - -0.19601047258645776, - 0.18526558259972137, - 0.2018933873818629, - -0.7426793437673028, - -0.47935946992896034, - -0.4332091529209003, - 0.13377289307995732, - -0.5655513396574596, - -0.13619901846588767, - -0.7262581591677021, - 0.10599947488778727, - 0.351358708699002, - -0.4581710635553554, - -0.7099209613267268, - -0.23148794100046644, - -0.329103276299073, - -0.5584831073048581, - 0.5101647895325225, - -0.3526381411679522, - -0.005376570162258232, - -0.7637513834383449, - -0.4412261968333257, - 0.14959756894957565, - -0.5947039880399436, - 0.26357742891585456, - 0.3888577230124677, - -0.687350248381749, - -0.6977833385470689, - 0.1075640635352485, - -0.30196625521025267, - -0.6863618491057621, - 0.019003938341827564, - -0.6606320975937646, - -0.577554649286286, - -0.7987483633406931, - -0.014773010152043797, - 0.09384164407224638, - -0.4131303225673762, - -0.6063189317899118, - -0.8447397126355957, - -0.11228294561986563, - -0.8038011949381104, - -0.20096842607771503, - -0.24723660971366856, - -0.8038788334948839, - -0.7820399263198698, - 0.4571479074353091, - -0.7022847187472436, - -0.5079643064492989, - -0.8355930438036645, - -0.09134856163138383, - 0.45907980464373477, - 0.14436210023069918, - 0.44232742213617726, - 0.32911508793129407, - 0.013092312627932423, - -0.13983904317498153, - -0.24644998236332338, - 0.41798437316665904, - 0.32854665566834473, - 0.21660182119321525, - 0.3693794637818437, - 0.04803043763945092, - -0.8421015640790477, - -0.3494560618246747, - -0.42866861161020414, - 0.5706512209998398, - 0.5227151684933011, - 0.5404970339910813, - 0.2435249415991112, - -0.29896408874000513, - -0.47780190750091805, - 0.0041339929518200424, - 0.4338433887533544, - -0.13322790582038913, - 0.5125801980520999, - 0.050982400509599346, - 0.30648042961042155, - 0.4583194362785541, - -0.6473893764786641, - -0.0865642491387778, - 0.21233302980613056, - -0.03682270393084064, - 0.4710933174748182, - -0.7060194359633954, - -0.8361744706733536, - 0.19065540575204842, - -0.15198805830977102, - -0.16072590847917745, - 0.4954628439320681, - -0.33456536438609286, - 0.3523506268185266, - -0.38270513835537173, - -0.5605287987010588, - -0.598217458534931, - 0.42386616455225123, - -0.019934836908555575, - -0.8414222192812735, - 0.4083799126540959, - -0.7392800819457873, - -0.2961280870492181, - -0.08336964821704385, - 0.08279275222655791, - 0.5447767212308445, - -0.6775872741529938, - 0.2592159084456991, - -0.5821397467350549, - -0.8473613748331217, - -0.09914283241057953, - -0.7173849631973392, - -0.49055480832762877, - -0.6306798893997886, - -0.771872494593313, - 0.1860392007975218, - -0.4014380205990101, - -0.29425713081566696, - -0.31578185765298694, - 0.5353191303344871, - -0.363902878461711, - 0.23335467874254845, - -0.5402299877244316, - 0.04086475578084903, - 0.4445459048419582, - -0.1005782729601542, - -0.45388228946477005, - -0.3981207949219989, - 0.4233047222915767, - -0.5612772907821049, - -0.7249984227062962, - 0.292762579180865, - -0.3719521362592318, - 0.5728811799626004, - -0.8349791978604912, - -0.8393779201348534, - -0.10749833180330415, - -0.7534156164732724, - 0.29399993698654625, - -0.004699751408409059, - -0.6426471821326155, - -0.7418905515980931, - -0.3452685691327342, - -0.8340773208626224, - -0.44546462669263714, - 0.021299272116080736, - -0.09762399621991147, - -0.758097378942503, - 0.31649289729440677, - -0.6616885284773324, - -0.23189073492579348, - -0.7927868125862797, - 0.4536841035842283, - -0.6827385729724927, - -0.31049661739213386, - 0.1625371613620541, - -0.040848837164327634, - -0.7146485837546255, - 0.027379914217576795, - -0.5862451133367712, - 0.2774469423877528, - 0.47288682028554274, - -0.23127321740334383, - -0.19974458024039754, - -0.03627764878204209, - 0.06855182819409711, - -0.2769129354057822, - -0.7062550134215166, - 0.040709189645647514, - -0.1089695838659771, - 0.09189329847720251, - 0.3701151345036324, - -0.49839153720825563, - -0.23833332573410637, - 0.43532063094805196, - -0.13580450463739557, - -0.3107306055092083, - -0.10796789591487843, - -0.1129356744297374, - 0.04414333516864366, - -0.41535544002929703, - -0.0933015987091178, - -0.3628522633989384, - 0.11890020240483257, - 0.5209085085838263, - 0.39316619023254007, - 0.03647340574137581, - 0.14226698544693694, - -0.8006458107507269, - -0.119340650374407, - 0.07566420639994298, - 0.15928105854543695, - -0.2028089646032385, - -0.6041512843273265, - -0.2879573324504805, - -0.25765352693465793, - 0.4842749248734868, - -0.3629703668721579, - 0.09182527158670672, - -0.07117364396367998, - 0.38833424349242507, - 0.06075462259142761, - -0.37417015852735575, - -0.6858179512099302, - -0.407887497520941, - 0.021544409626290784, - 0.08678728227994925, - -0.2876838244909722, - -0.7737183222968134, - -0.49904155899093666, - -0.007529344728048337, - -0.20963427296309756, - -0.533604179969527, - -0.22863883306251742, - -0.46263203894561333, - -0.63042125808265, - 0.004450412048307206, - -0.27765390088873954, - -0.04169215734499232, - -0.5994180624575065, - 0.19565350964925954, - 0.4949863487128501, - -0.4727930355759016, - 0.47283280361127766, - 0.5693562819291889, - 0.13918734025945723, - 0.5127119710669328, - -0.00101023984999693, - 0.29596298497107565, - 0.4859467756430176, - 0.0944555685581463, - -0.5255955884913852, - -0.6633058534381584, - -0.020174028925330822, - -0.8345138662398128, - -0.26679228713768965, - 0.2649806186848267, - -0.5892787354192339, - -0.09904943547536038, - -0.2586155082498185, - 0.514999892165394, - 0.3772831836668722, - -0.5812464522426297, - -0.0055661197824189435, - -0.7585320930065418, - -0.42338894178707476, - -0.21324792137003945, - 0.09199814774719461, - -0.4233613612308073, - -0.3206860803591778, - -0.3448886868025909, - 0.23047131496098427, - 0.2845783607555119, - -0.24813832351420895, - 0.4878956651215016, - -0.5643743264169245, - -0.4356166709247325, - -0.4656796680587568, - -0.20145171119569882, - 0.45619263791077214, - -0.34678388889367806, - 0.3721550000917502, - 0.39947399350976687, - -0.43771748488133677, - 0.3815729848106064, - 0.48723092218744646, - 0.2764240095515502, - -0.15311412402176083, - -0.31827189408160095, - 0.46160799841518485, - 0.05602678907844594, - -0.7578481016495894, - -0.8136069926895493, - -0.3690540710077418, - 0.30753801300031935, - 0.39472361922957355, - 0.3635170630049116, - 0.5616253884247226, - -0.030103093605118314, - 0.10474345465618395, - -0.577578238222473, - 0.287569334821246, - 0.22393122248620134, - 0.08485310403960566, - 0.44761355675023085, - -0.04737165745440508, - 0.5494005906990325, - 0.1552231963127495, - 0.5386547486728392, - 0.2724478530148109, - -0.23297594833138957, - 0.14586346111885917, - -0.1381639038726422, - -0.6686556017942662, - 0.4415387029418185, - 0.4411483533329623, - 0.2854946921678645, - 0.30833432957405416, - -0.43145089700544376, - -0.3635346576418008, - 0.4111284595288862, - -0.5132017239166828, - 0.5035665923774908, - -0.299952442388995, - -0.3158712090127075, - 0.04575094395196888, - 0.2604773753994747, - -0.5475816470889181, - -0.2244989468959907, - -0.022246921386472773, - -0.28620977396509306, - -0.5838950140003534, - -0.6025022615460167, - 0.4779541770773261, - -0.7840128341448419, - -0.766778933957962, - 0.48958346814736675, - -0.2232867949770555, - -0.20211986737900023, - 0.45216180356497504, - 0.1972119576750997, - -0.003953787849516166, - 0.12426850696859337, - 0.5147599887682364, - -0.3521636253648526, - 0.3710559609743007, - -0.6956308449981345, - -0.3144053248674943, - -0.5302709381788782, - -0.8631466446298643, - -0.5254339096258754, - 0.18397739699082538, - -0.4146437654326068, - -0.13943477624903866, - 0.22292928692988534, - 0.3731414460369247, - -0.5924376212166305, - -0.670654130853, - 0.20339235104752063, - -0.5171121900065381, - -0.6475020017660061, - -0.7338829381800058, - -0.45630071974873454, - -0.50617842707646, - -0.6911233384886499, - -0.6393660733997515, - -0.7536547519170652, - -0.8394481213722493, - -0.8205846403345407, - 0.11309771742193908, - 0.35968499819740374, - -0.5601889237354443, - -0.3585604879673412, - 0.5029126837244855, - -0.18208066047830718, - -0.24456184264709835, - -0.5284968960535116, - -0.7838317556978269, - -0.4200331321205793, - 0.1361601071515237, - -0.7482036697792729, - -0.11247775520185921, - 0.1305622375996205, - -0.846454219948884, - 0.3057395776314229, - 0.35380788385744033, - 0.4977074096243046, - -0.4433327640485504, - 0.21594900649164184, - -0.14092464337069022, - -0.041291436636792245, - 0.49666830454059174, - 0.22273892329142853, - 0.020456381694762715, - -0.31316008101875104, - -0.3291585740141877, - 0.2348118025238679, - 0.09142166475314584, - 0.06530565418586531, - -0.10958439882470394, - -0.8457844565000228, - 0.24942669157600794, - -0.10548668091929603, - 0.09343214123431254, - -0.23546295252189287, - 0.546860394896858, - -0.6219395430569923, - -0.35836052557115816, - -0.31757315503816064, - 0.3767079264784172, - 0.37496532468736077, - -0.8458814517481306, - -0.762301500498061, - -0.02468502225597846, - -0.4709725730662154, - 0.4069867609210409, - -0.05176701007517126, - -0.6387367270858044, - -0.77179196461427, - 0.1844054493794811, - 0.4919813581907855, - -0.4911303107312647, - 0.5708464386559269, - -0.6022689004257256, - -0.7243333388942447, - -0.8570346701795286, - -0.3066904940910319, - -0.44667182997044397, - 0.004202003938535093, - -0.8019513478066388, - 0.2882247226545418, - -0.6452976245473137, - -0.28693734554979833, - 0.40974526324202243, - -0.499435481992257, - -0.5916332295879848, - -0.17581134975829404, - 0.1056053570488793, - 0.07441719249617096, - -0.8343770008451341, - 0.31792731418010445, - -0.6975894826707351, - -0.010582066100678356, - 0.38149590941843536, - -0.6895837900434507, - 0.5704488413693254, - -0.12345607380513268, - 0.4384739285572061, - 0.18131652186561031, - 0.08845470269074085, - 0.5213583908783384, - -0.2589663083102437, - -0.4392398753421862, - -0.16838911852892435, - -0.4905882091737129, - 0.062881703705427, - -0.021717688616054498, - -0.39412704022204037, - 0.17967681888394993, - -0.7646150453742456, - -0.2737471849990327, - 0.38549612703243197, - -0.3661050931451345, - 0.5238673733781103, - 0.45818262160689827, - 0.1378740998271144, - -0.18852184972011032, - 0.034099540973499654, - 0.1793190463160519, - -0.7328935225618745, - 0.4024423412172313, - -0.5724573457290482, - -0.07403465121995512, - -0.801585933191058, - -0.8033196728724308, - -0.2738422961858832, - -0.5323445644233806, - -0.8272132469354051, - 0.4498596461473885, - 0.5600466808703315, - 0.08460286768826675, - -0.10755658855067818, - -0.5806281151714756, - -0.7704424597510359, - 0.5062386676843127, - -0.5087712615598743, - -0.5311128435489452, - -0.5829941055381648, - 0.28979057415291587, - -0.820065151433655, - 0.5322089364117064, - -0.18761216072557563, - -0.1478977060834903, - -0.5981385172862348, - 0.2281972009327098, - 0.14019977177875442, - -0.7467477188381, - 0.23275936976178047, - -0.11321638964366643, - -0.250916453068045, - 0.14563791022800743, - -0.5122534135852332, - 0.08029737705703544, - -0.6177375076151895, - 0.4151527002026121, - 0.42713403792364857, - -0.5872000572556563, - -0.543015861445334, - -0.806996995989619, - -0.330269172923325, - -0.31927426990957064, - -0.8119198472961915, - 0.3534120666455447, - -0.6400297465578833, - -0.18547279939595473, - -0.09185626394271473, - -0.611429075951019, - -0.4636764065212946, - -0.36621085726517355, - 0.030722575876298563, - 0.17313923539013487, - -0.1117067083070391, - 0.47254724331108866, - 0.5288745386516029, - 0.45370733003651065, - -0.6823382950925105, - -0.5676855978425266, - -0.6139829383861428, - -0.6335854349684381, - 0.192811034899405, - -0.0024453584742725187, - 0.13287259354590053, - -0.08062337077732673, - 0.5430940797944368, - -0.16019653872928086, - -0.04386951397957106, - -0.6112084357525731, - 0.2615406621712406, - 0.1794387541782203, - -0.706724959686797, - -0.2677211110518841, - -0.16199289169964037, - -0.33918984898290705, - -0.43641297292400744, - 0.05313659266685378, - 0.4580781419627835, - -0.8007308149604145, - -0.6680551380161386, - -0.7537190028860564, - -0.08799855854286487, - 0.11084016799577345, - -0.37778740895354623, - -0.36332966410878076, - -0.07204611408079242, - -0.01529493553594452, - 0.5686046653543277, - -0.8395527796541046, - -0.016633495227694528, - 0.41205346144486255, - 0.2752146247224694, - -0.6728098557208293, - 0.3506942723278246, - -0.39524019014273126, - -0.3602045914124562, - 0.17252616559275502, - 0.5356794359277264, - 0.46050730721223476, - -0.642029403981299, - 0.4873610268111299, - -0.3226698330479385, - 0.1488254624966301, - 0.5398046846420335, - 0.16137235848981235, - 0.03957863452474464, - -0.6516271346629332, - -0.8463017858656255, - -0.7500415300996814, - 0.24999973380065366, - -0.6091414456980548, - -0.2864706525165953, - -0.5220705253484916, - 0.20521312304915962, - 0.1009401523536847, - -0.7274559675831669, - -0.36441437118022557, - 0.28764763954130745, - 0.10742469891767503, - -0.5460294289483456, - 0.4287826302972768, - 0.07280793256788543, - -0.3276652730581565, - -0.38552369474257353, - 0.15802279734002433, - 0.08170886447126591, - 0.0650523324289014, - -0.06012111545839571, - 0.4324843405930532, - -0.25825048147317387, - -0.4939002470337223, - 0.25484557003325303, - 0.34084108765516685, - 0.26097213713120504, - -0.05648978372583646, - -0.06647125935545584, - 0.2044151921154389, - 0.256030143676673, - -0.04229651909270171, - -0.11748387432538265, - -0.616180469564086, - 0.3449824361595424, - 0.3260382192583291, - 0.010464906529598417, - -0.8229935367077977, - -0.2520398365023133, - -0.8594459532099404, - 0.30599239877832685, - 0.09768198847719511, - -0.4573017708452276, - -0.17431084502802496, - -0.43057324468802394, - -0.09688258623184454, - -0.6211495625842187, - -0.7376756580000732, - -0.8010848891173104, - -0.17903467355950153, - -0.8608733954627402, - -0.2798176312469044, - -0.1745746651282204, - 0.43611588116351596, - 0.1979975468167614, - -0.4441290706589586, - -0.18150565301774246, - -0.5210464983211207, - 0.3562592108329494, - -0.21062571607352953, - 0.3123978061280488, - 0.011506478388027652, - 0.07795211593124018, - 0.06201783129639549, - -0.49456782283009737, - -0.4347485229601763, - -0.04859838861856258, - -0.7862496764436054, - -0.6765280005142229, - 0.10293472266127746, - -0.7987252139224961, - -0.45607156316864883, - -0.43227468621815457, - 0.5722411421385696, - -0.028401713094380998, - 0.41889620625055635, - 0.5051827108494422, - 0.12405763293684013, - 0.042888029323559285, - 0.4491948458333106, - -0.6711402458754786, - 0.21752050528299072, - 0.250672089315253, - 0.48804589378734375, - 0.48223358278711403, - -0.6896316707600407, - -0.8539399501747809, - -0.12157760624004177, - -0.36710488127882224, - -0.39271147490916924, - 0.2530016160029278, - 0.24660690951248743, - -0.36184035582751395, - -0.49414793878643093, - -0.11954415794111473, - 0.5112356181472113, - -0.8299896561651939, - -0.45531445116486347, - -0.31935873872526, - -0.23016687933675617, - -0.7477634602213625, - -0.5591401914743588, - -0.1971980767189182, - 0.4079030125358256, - 0.3449214255172506, - -0.8210374439075871, - -0.23402507231214764, - -0.40225341081975124, - 0.44772221986171434, - 0.19162965132609244, - -0.38417204418316475, - 0.27227511190322917, - 0.3021246679510372, - -0.4658214051793032, - -0.07879930020149961, - -0.07592510272171815, - 0.4264786993709573, - 0.17951503615006126, - 0.48513796816710375, - -0.06567131934352122, - -0.40146871009059387, - -0.7458729985800804, - 0.3806399532677296, - -0.25239470570092837, - -0.0030890730980135395, - -0.5552973917448436, - -0.5221980397724795, - -0.7222152811028232, - 0.5032009772484396, - -0.29945881332695956, - 0.09372621100139189, - -0.8031998810761245, - -0.012457078570529578, - -0.6262815753898228, - -0.21806505554406153, - -0.5600397023516299, - -0.2918344343451239, - -0.22105673651730473, - -0.41528659949327995, - -0.06546904655114316, - 0.20146720492658932, - -0.37917696152951214, - 0.23087909622096392, - 0.1633270169607064, - -0.29234460674042295, - -0.5686398740577376, - 0.03421441271894132, - -0.10935673009987035, - 0.45691895140658434, - -0.6687211478507818, - -0.1158754010601587, - -0.23461113115846421, - -0.8344722262888639, - 0.44401555327044084, - 0.34048450221485216, - -0.15292940628081186, - 0.4702370977532997, - 0.5027496769575219, - -0.4238032428820775, - -0.37895676352466307, - -0.24140186828921073, - 0.4261777098003119 + 0.09618009638148384, + 0.43031206381739107, + 0.6480203113993551, + 0.1837227321090814, + 0.08105428595766073, + -0.3843375423135814, + 0.36178157340983275, + 0.11699941046666318, + -0.7473585091225403, + 0.6336728448430832, + 0.5615223287930721, + 0.21687440026144722, + 0.5390792939564261, + 0.5714404163592525, + -0.08305626535618815, + -0.4231911079335651, + 0.31460970679235867, + 0.6533005980074417, + 0.6087344535558751, + 0.18387129534820357, + -0.12957626041442338, + -0.5990120980964402, + -0.21105887084732078, + 0.07805165758995358, + 0.6387755975111641, + 0.050906898145439694, + -0.6315546532399963, + -0.25890718171717697, + 0.5515949314935867, + -0.05190474393522282, + -0.4116031037743863, + 0.2162712648651034, + 0.01955231417691139, + 0.5567813587339762, + 0.590484480856691, + -0.16316844516034912, + -0.010759542356443497, + 0.2767242831551472, + -0.3615602986542023, + -0.14135154783946635, + 0.6276210972085193, + -0.7846459415160606, + 0.10809781761647352, + -0.7763539944442603, + 0.5013324609693813, + -0.5063812693225811, + 0.0857412386417793, + -0.6672209190227912, + 0.3890753110239914, + 0.3916496837911184, + 0.2519303396339111, + -0.45821256283648876, + -0.05293548818172489, + -0.2356455257029303, + -0.3566875365100312, + -0.6369941005475077, + 0.10206945894707253, + -0.1177095280787217, + -0.25777389558869546, + -0.22357293423288505, + 0.2982305225900873, + 0.5396621477037383, + -0.6833614419915796, + -0.08896950994035813, + -0.20831974783996665, + 0.16628666004929304, + 0.07139615803064514, + -0.4011160308319073, + 0.5024702508970894, + 0.36188009607341043, + 0.563801194834561, + 0.10849542571383519, + -0.4530440213622212, + 0.5828544373330892, + -0.009892835778867792, + -0.6663479376850958, + -0.798171048325327, + 0.028485163744129682, + -0.06002720476396772, + 0.4143337898442213, + -0.6487453918680048, + -0.46307044212758774, + 0.1798361175409493, + -0.7540630616722632, + 0.06548077363368687, + 0.5313612723541649, + -0.14311089991738835, + 0.23568588765003085, + -0.03616933489882479, + 0.5837079716151191, + 0.08401270671167183, + 0.10878518288200589, + -0.6850772436858547, + -0.7011900724851082, + -0.6639182304646254, + 0.4513502532250123, + -0.41661990727806186, + -0.6298159046415148, + -0.6073589670861075, + 4.0733739661813484E-4, + -0.4427820767119767, + 0.3571245430992317, + 0.04340328549447092, + 0.5510196185829189, + 0.1224609599751737, + -0.4513943401403866, + 0.554868188956347, + -0.4090243137326361, + -0.3338503721251483, + -0.48797296886954883, + 0.34835827277766607, + 0.5497918200641342, + -0.7640794248598187, + 0.18766627571154193, + 0.4035820305833945, + -0.18592142089055752, + -0.09469680130226299, + -0.1323892842319907, + -0.5938268958025765, + 0.6004523883196843, + 0.6360460263357864, + -0.1640263552014537, + 0.2400359236123616, + -0.4591688175050981, + 0.4181916124727022, + 0.4812868906013944, + -2.4440852064311347E-4, + -0.011952417539964455, + -0.28011537076049287, + -0.17425273771220173, + -0.7698759623360227, + 0.2505941217355495, + -0.7395177233835485, + 0.2775229362035593, + -0.36150401866332477, + 0.10309963243104758, + 0.640685345347409, + -0.0866408190870942, + -0.7517297893358256, + -0.7879027133225234, + -0.21468180353537836, + -0.554571207179249, + 0.38267844320798494, + 0.25992657292836474, + 0.5201698473001707, + -0.071062041009608, + -0.08407787728301508, + 0.5953240060061854, + 0.6248234664973024, + -0.44104830979401144, + -0.7817728888427216, + -0.4787668573331263, + -0.07949835481400958, + -0.42633772958905797, + -0.549112906661449, + 0.09071553461087312, + -0.009242834466978933, + 0.6238900302199456, + 0.009742829179126833, + 0.07177441273246554, + 0.6022276651221822, + 0.3594719970002743, + 0.4705851031230387, + 0.2030487257982928, + -0.5564354202549149, + -0.3498603028153076, + -0.7461148539195203, + -0.6570882747906832, + -0.20935581677545145, + 0.18104472027583451, + 0.10155448034978742, + -0.44825267289017856, + 0.0950007738535652, + -0.2382368118553223, + 0.22831535337121467, + 0.3493500780989306, + -0.6870312397720039, + -0.359988654674303, + -0.6331489009176957, + 0.6234122585220424, + 0.2171956787152124, + -0.11761582513571234, + 0.5583396523771996, + -0.1272454406978446, + -0.25266079601955826, + -0.6536017777018104, + 0.11532734448564852, + 0.23940983082934608, + 0.6073096785180127, + 0.5431556574085715, + -0.5034521412836557, + -0.4882366229832014, + 0.48369833385946903, + -0.2723094190859745, + 0.2894778419222098, + 0.24620697981438477, + 0.1996243320431853, + 0.09413885044061754, + -0.3187500760738638, + 0.1884973992784884, + 0.37594122607147373, + 0.21130778851405652, + -0.3783418335398438, + 0.49323766411428893, + 0.20918530070106567, + -0.6221859029580121, + -0.3931685286317461, + -0.30704293570936203, + 0.5058108160069189, + 0.3713092882350638, + -0.05136314665084207, + -0.1584752231912343, + 0.04093547005226772, + -0.7107908879752035, + 0.20580146171846347, + -0.7516000669599029, + -0.4762692947443985, + -0.7487140581771505, + -0.48595656504838214, + 0.032058247445664656, + -0.22064300932940373, + -0.7982985273141081, + -0.4425654512391229, + 0.17953828880738287, + 0.29110130540528234, + -0.1997834416855626, + -0.16955616928832196, + -0.4158273379112539, + -0.5654624992701776, + 0.30467624403354454, + -0.44188901775961226, + -0.7076302641124855, + -0.0029945393827358613, + 0.4509411459598466, + 0.3467190861255699, + 0.3727270230080343, + -0.022699908177690076, + 0.5732314888848068, + -0.41199096706318494, + 0.5702293061791889, + 0.09861289627832848, + -0.6539853856293838, + -0.24106281995132972, + 0.5400343270513929, + -0.6425981434071257, + 0.3834134905815886, + -0.15921932757792534, + 0.4243626150052243, + 0.6133824836678506, + -0.4376327006654658, + -0.8068263198270775, + -0.3638465806834738, + -0.09335370392301301, + -0.2173152764991284, + -0.6586118428189336, + 0.12023849072861104, + 0.1404718308647145, + 0.2796035911406608, + -0.18405176385982824, + 0.22104779717499923, + -0.20380663527558063, + -0.023388153934184253, + -0.4384938071238055, + 0.3538734642946547, + 0.5827065217502004, + 0.2639991041741724, + 0.17112971387689202, + -0.47276927383646855, + 0.06326702228698977, + -0.7897983972075031, + -0.4142373032757283, + 0.3821650412081058, + -0.6344288164068467, + 0.3489653831243599, + 0.5338484012729704, + -0.1880125372142919, + 0.064602986842619, + 0.42013606798242453, + 0.6216248029561567, + 0.4412411365388048, + 0.29712750732178483, + -0.5289647339877787, + -0.06658564885171847, + -0.18650627690803823, + 0.0810268983440604, + 0.35615804921737293, + -0.5856780498340928, + -0.7114436742034521, + -0.4426962312021077, + -0.326580269104615, + -0.3812057360768767, + 0.5940497896801632, + -0.5808231818180757, + 0.41993312328475285, + -0.6897540082546849, + 0.4670896465575908, + 0.18233535370059328, + -0.10701920554814937, + 0.11745191963640955, + -0.3381502341025981, + -0.5528426333251475, + 0.08724384710913446, + -0.21266161254962268, + 0.00483416629314648, + -0.36107209882486535, + -0.6348984588521968, + -0.32290477647064003, + -0.6446898829889958, + 0.21224109501517574, + 0.5489947806037029, + 0.5024958300902681, + 0.332416567648831, + 0.37184149464480487, + -0.4691174481655676, + -0.3558070165233584, + -0.2583065417846234, + -0.3637440589638966, + 0.6032083538422256, + -0.7576865575093402, + -0.15476055816590728, + 0.36115507750381937, + 0.10421108033503101, + -0.7755124804779497, + -0.11787011817862514, + 0.027745086991828094, + -0.7463929360840328, + -0.37137830551694095, + -0.6880426148548564, + -0.4206345909099583, + -0.5048959582256487, + 0.11644365758719655, + -0.7616331154392442, + -0.385057424540592, + -0.05421440110168718, + -0.3039347291749237, + -0.03564144484200493, + 0.14322163991733383, + 0.10249670206987649, + 0.2503370318685302, + 0.1667374987425766, + 0.09158109665238234, + -0.23292160169810683, + -0.6668107536350723, + -0.02921977913526308, + 0.4371792340978159, + 0.25030027037366864, + -0.7706657878953296, + -0.6367801212124888, + 0.012296762729823496, + 0.06793562355662641, + -0.5312509685683455, + 0.46293772037488756, + -0.4705163772769122, + 0.3411213280765525, + 0.5816817728138665, + 0.40747616167158507, + 0.4675200904359472, + -0.3870721901702436, + -0.5692392637829481, + 0.5646686951746732, + -0.14827321765296175, + 0.546456646532591, + -0.2229604649500181, + 0.169204842152738, + -0.3377992127565802, + -0.02205900719360354, + -0.3086445772373722, + -0.0032734248240084973, + -0.7031518132592867, + -0.3633441166561335, + 0.30796629847499857, + -0.4501295908276126, + 0.4789005282591775, + 0.048144085753550114, + -0.7515869960115719, + -0.4592035836846476, + 0.10554508131375762, + 0.6219986789678481, + 0.18074448255193898, + -0.14828872344298394, + -0.7340898465411504, + 0.6325377674969103, + 0.016062478414879733, + 0.2662638422877036, + -0.07269910855832562, + 0.5312263981992437, + 0.05813480298122364, + 0.2996094807960613, + 0.5077112613091826, + -0.28875779072965846, + -0.010624340204780425, + 0.6424630767195517, + 0.02972887772764754, + 0.3902615004683644, + 0.5164778703856959, + 0.3808450915554088, + -0.32847041426235224, + -0.25687839076598074, + -0.5948489188927637, + 0.3905154542523729, + 0.496583347064819, + -0.4108782148913739, + 0.1102966154859566, + -0.09852630842295251, + 0.3766338058967863, + -0.31581110162850384, + 0.6074940493439084, + -0.5227059333490793, + -0.4481391325010981, + 0.6057965192088525, + -0.3457991728512884, + -0.1661947800390715, + -0.6145061286836195, + -0.4375990651842248, + -0.28493028704531276, + -0.28681930578165893, + -0.7875338477373468, + -0.5822703927090795, + -0.4483706753572492, + -0.6882227883881104, + -0.32085152493574415, + 0.05300779553214652, + -0.35762511099086247, + 0.04432643063724706, + -0.76710090954316, + -0.02008979343477546, + -0.09925449502312911, + 0.01615923682879361, + -3.84292953246157E-4, + 0.3744103449617059, + 0.4653227291294081, + -0.6737517263031698, + 0.26806314773068685, + -0.3977682765042444, + 0.3510407652116835, + 0.055655788360456815, + -0.6485614447559181, + -0.4096765967045531, + -0.011666566219017627, + 0.47848957367252554, + -0.019810828808782932, + -0.04893763320130973, + 0.04540009836257064, + -0.40657747530468563, + -0.17397608786662455, + -0.34165114145447256, + -0.5129039900329457, + -0.06285776289140177, + 0.4067582551668686, + -0.7911559135649868, + -0.45898038857247364, + -0.5318788021667122, + -0.016067441989082165, + 0.06668278345925216, + -0.6761692659809337, + -0.1316820472882516, + 0.3179920793353642, + -0.02576735568960664, + 0.09487790283475628, + -0.27576127552350727, + -0.4115486610781893, + 0.4625026840944758, + -0.5151110939553195, + -0.4681567769206848, + 0.1752662315282757, + -0.3928707832513811, + -0.17822961646736746, + 0.47528430832437973, + -0.5727222221067492, + 0.39449418502341704, + -0.3096462975975583, + 0.5788090463449639, + -0.7216747161469838, + 0.4035903749138755, + -0.018753002020948206, + 0.04899423128120595, + 0.4807700500047417, + -0.6451987444532765, + 0.27173487031159616, + 0.4556522039448866, + -0.1845182372948878, + 0.3761815743366207, + -0.03711451632155671, + -0.7582027275607442, + 0.1375918252266195, + -0.20088249476328968, + -0.4061914904491556, + 0.2503755455572715, + -0.2579248223687216, + -0.3957947440473678, + -0.31506403361056684, + -0.8033047905961724, + -0.2711920014558755, + 0.27857861112989546, + 0.6531027852813606, + 0.4328890928915078, + 0.13286062728341874, + -0.23902263585333028, + -0.047539206363181985, + -0.7228286915072749, + -0.3681353168127971, + -0.12922786050440305, + -0.11354681340861117, + -0.41477999918814873, + 0.3017136573840927, + -0.7020514061815917, + 0.23024267310305147, + 0.4908136165655762, + -0.16047801634380632, + 0.4820827014553689, + -0.30372624122586955, + -0.013783494090488402, + 0.286434444164538, + -0.5538134639312048, + 0.27460702634640455, + -0.16034716175405894, + 0.21751888486140747, + -0.07143352433549655, + -0.7982924741140436, + -0.34871401828643905, + 0.412651595010178, + 0.05196814018829288, + 0.07677058657919678, + -0.23160378605129817, + 0.22423817523253853, + -0.4935788021037541, + -0.644140738537462, + -0.5442756594074554, + 0.5689694534848947, + -0.03616855677422948, + -0.7608578963720046, + -0.12718615266904143, + -0.22525494130158163, + -0.5007284145786628, + 0.15962188124330245, + -0.22612215686609838, + 0.03574723207069708, + -0.21393852346361408, + 0.3094406304127356, + 0.14351824251389167, + -0.337833359361793, + -0.0923825008871858, + 0.6482842281946454, + -0.5860857905635386, + 0.23503266169522974, + -0.5747453417657562, + -0.47593470975067725, + 0.27169254433403334, + -0.634887922784036, + -0.5904654048629591, + 0.250559238149907, + 0.429585766320984, + 0.002354939753809626, + 0.21931557966717763, + -0.4492380326593739, + -0.003688565998311133, + -0.22120108737441235, + 0.1675975947566224, + 0.47225518213215134, + -0.5951342313672306, + 0.18507831415974374, + 0.2268585087417997, + 0.0649669912961307, + -0.08799367137767689, + -0.13231557536252514, + -0.25233968100175186, + 0.043641825939349954, + 0.14263190252529967, + 0.3482795780839626, + -0.052215252432331605, + -0.5413051129865929, + -0.3734645813704565, + 0.47526252918795164, + -0.27861495016947957, + -0.22160006197756488, + -0.7646183473538332, + -0.1031644482753904, + 0.09827816374495535, + -0.29531930805482975, + 0.6255213467053372, + -0.04399599460969583, + -0.07486868830180116, + -0.23663354299170536, + -0.0732091214498366, + -0.6530112208839414, + -0.17328945941096674, + -0.2859914993426761, + 0.5499533993993059, + -0.1327458758096388, + 0.04040412467909382, + -0.7388402868416095, + 0.05458853539324182, + -0.446252971244753, + -0.3695714604675427, + 0.5020098798418665, + 0.20466831653095674, + 0.28733508778879846, + 0.49774806645712666, + -0.7780747442364088, + -0.41674540690150796, + -0.6251350195347662, + 0.3036394152228822, + 0.1406259518329981, + -0.09498585066596965, + -0.13758760237542955, + -0.26010114738508283, + 0.07961951486810692, + -0.3517615221771556, + -0.1824607583292922, + -0.6902173437508929, + 0.38128012471776096, + -0.11151748914687498, + 0.05650053954515033, + -0.27824699061168756, + -0.6201657549222179, + -0.5096702807809413, + 0.09893101249001479, + -0.34212630770512403, + -0.6403777983229675, + 0.2593406288960919, + 0.4796154857665925, + 0.33848151659452885, + 0.47839362872509505, + -0.35112026987567874, + -0.021730314019288377, + 0.35189784049860984, + 0.4543225964450862, + 0.19820890252988688, + -0.16457447827818028, + -0.3960946139284449, + 0.20104111399679214, + 0.2685751293000095, + -0.7783415427072299, + 0.4812689772776867, + -0.0799016063887159, + 0.39547291696485687, + -0.25130010471380604, + -0.06250894633216442, + 0.0259324949532862, + -0.5818033284810613, + 0.6501147284922139, + -0.24909077098915688, + -0.19778003614416584, + -0.5448640876529343, + 0.6465275803536333, + 0.38581434193597997, + -0.20803654289023854, + -0.12657772770151143, + 0.3770374215836564, + -0.12014167504787909, + -0.18100048448566786, + -0.019302958143449844, + -0.46790974864401347, + -0.6459420838927248, + -0.4441396817927757, + 0.513580565906162, + 0.2435007990171204, + -0.36855505787816145, + 0.13797582100187655, + -0.11720523731838317, + -0.5961992817919994, + -0.6893813219619968, + -0.6261507010665444, + 0.03094779150331084, + -0.4088787892867179, + 0.49309210500610956, + -0.789383307632902, + -0.5813854143800014, + 0.03321513161067613, + -0.30753624520346023, + 0.08717866872860036, + 0.549398988090679, + -0.472996239819259, + -0.6852597845749782, + -0.7084134781312059, + 0.5019405850115558, + 0.5028257461100002, + 0.4825941565766224, + -0.7840040250831931, + -0.6643443659814826, + 0.47304681169578233, + -0.5563747503792138, + 0.6015167849130204, + 0.634123681001063, + -0.2876882300736481, + 0.37987553170271526, + -0.7561588200747223, + -0.7261067715079524, + -0.5525794341227355, + -0.1084671305495204, + 0.5018388076772736, + 0.3322750701262024, + 0.5823323759612024, + -0.6220949250130842, + 0.3173068381148666, + -0.7606765535701083, + -0.1408980869194657, + -0.2515098428780478, + -0.17014990080315073, + -0.21865147950191466, + -0.10955310295021636, + 0.25473002925287525, + -0.1414366690139176, + -0.2938411184946803, + -0.4051829268001682, + -0.40645184380462523, + 0.37071748584275677, + 0.1636666717317945, + 0.202883826629089, + -0.5633292487334121, + -0.12356752546457206, + -0.010297657414070072, + 0.058276907262778344, + -0.38503608179218274, + 0.5454025228690075, + -0.5012406565892418, + 6.358982668720481E-4, + -0.15115254526741062, + 0.4908187882737044, + -0.5874331083023581, + -0.6815901419274778, + 0.2292651560553266, + 0.21120957967234155, + -0.21643800877473252, + 0.20059976318838169, + -0.008703631223517472, + 0.6256459251589231, + 0.2439962505182015, + -0.1505646629259263, + -0.7647504864944921, + -0.6018663146014014, + -0.658959395683756, + -0.13594706732372086, + -0.19635528919596634, + -0.5157077128709818, + -0.12244999967407533, + -0.7071969586763651, + -0.29761410447721015, + -0.47679823404419064, + -0.1641765083580936, + 0.015866477836917525, + 0.47611422662299685, + 0.4316504689611643, + -0.5900202022153664, + -0.1058617471890525, + -0.49729583834165414, + -0.7944341653398069, + 0.08233940504574822, + 0.03444726779932461, + 0.35776421016102333, + -0.27465707498681435, + -0.5640555295771754, + -0.2161041094680839, + -0.7740884740724926, + 0.6469429261102336, + -0.16565299708867565, + 0.2653041093968799, + 0.6487096032980685, + 0.5804992916219939, + 0.22991725101215488, + -0.5871673344809126, + -0.6561114436646327, + 0.17462642248659754, + -0.27854925841251055, + -0.7180893540320731, + -0.3763699103110492, + 0.5311309919519652, + 0.4240941865848388, + 0.5925422160446184, + 0.14379776956464596, + -0.4462217620072601, + -0.6420734417385909, + -0.35327996463182415, + -0.6720819790958927, + 0.5407258174059183, + -0.4911046156286281, + 0.4416615977137849, + 0.17716949213842814, + 0.12240067479855621, + -0.462998676777076, + 0.6248726211302186, + -0.059201151555649756, + -0.13715052169228903, + 0.04778757368041109, + -0.44121911256137647, + -0.12187352020770248, + -0.6779719193065468, + -0.051196610996738334, + 0.35834137149128054, + -0.08824566194465244, + 0.2009119117227639, + 0.0695874911053439, + -0.46993219877071796, + -0.28268809751883184, + 0.19236249098560543, + -0.0871066530301019, + -0.2908525430164589, + -0.6179320015704317, + 0.36772923086137055, + -0.5676119202963917, + -0.46417565173356834, + -0.17255846911919026, + -0.70212740383717, + -0.08154451566333631, + -0.17259515021282223, + 0.4616350767522265, + 0.3667871085779312, + 0.15705463828981525, + -0.2605160080151754, + -0.5662997448051588, + -0.25733391989388266, + 0.5175697684209165, + 0.08677821467857982, + 0.25734125321795454, + 0.6341174306767378, + -0.624723474695883, + 0.4766692201088819, + -0.6996063794105876, + -0.18870257688490977, + 0.08344135116590468, + 0.4921652317818944, + 0.23279162011608967, + 0.5421892520566524, + -0.11927511076043429, + 0.32038969322820765, + -0.42985927093576654, + 0.6404563226937662, + 0.5623297701451456, + -0.3198963722020567, + 0.49312632220598684, + 0.005210489940187801, + 0.6158870795647674, + 0.21886695459399996, + -0.6868507455083444, + -0.46468672730641897, + 0.5332350945863468, + -0.42586357149905285, + 0.41626369547035014, + 0.2545244612576979, + 0.4762176775391126, + 0.5885646378650099, + -0.04602283501769444, + 0.15969385592599528, + -0.5706533569484542, + -0.2180717441762775, + 0.010330970073576085, + -0.06539117659519933, + -0.6799692860064859, + -0.6704922325019778, + -0.30238134248644677, + -0.48810632192022163, + -0.4268462012642522, + 0.4081642241753186, + 0.5111067715547432, + -0.3443292480701187, + -0.25804190408448346, + 0.30152262920380635, + -0.5197591722642758, + -0.2860198031957719, + -0.5203322197064101, + 0.00713866922173545, + 0.36403257556101865, + -0.4185143402796275, + -0.05286544494994527, + 0.6035894544763346, + 0.30205047999190204, + -0.5125123906605523, + 0.12503008577197328, + -0.3839948194930937, + 0.6241362834967074, + 0.03360616265368488, + -0.5728175337046969, + -0.49200568580989984, + -0.07254724029204085, + -0.6980349180276205, + -0.7810417796277431, + 0.06618821264465768, + -0.1929815478988618, + 0.6576298235457109, + -0.3446727835078697, + -0.2545967278695538, + -0.09508608416130737, + -0.19128274857918015, + 0.22089507041633183, + 0.6583794788193217, + -0.4687504076286029, + -0.20100220681356262, + 0.1665008341998223, + 0.04158220262517398, + -0.13771319796760106, + -0.696345981335666, + 0.3771534203283523, + -0.7606608055472872, + -0.22938953568574627, + -0.7414909853481235, + 0.3233965502332189, + -0.3071407810380742, + 0.26236429922619087, + -0.39447709872553655, + 0.10117998055341582, + -0.27234710268695717, + -0.351694978500746, + 0.5786968290154061, + 0.5652308170667414, + 0.11398502681711431, + 0.047459900714048486, + 0.34171712869925563, + 0.6497530077606487, + -0.4033195620667715, + -0.6852949269039126, + 0.40305520550609597, + -0.14672423870745765, + -0.4356035984469223, + 0.14449408079077697, + 0.5401321710829642, + 0.4093359253834362, + 0.07041087719569417, + -0.34389369859478014, + -0.6336640465143003, + 0.033905861582844254, + -0.1794434081159022, + -0.8025396676093631, + 0.3638972271044335, + -0.0608085418680584, + 0.03937313909918427, + -0.06706274874390172, + -0.6537422747080265, + -0.7645116892984779, + 0.0028405333918770648, + -0.41603671369968326, + -0.12499715210166029, + -0.3628559999512702, + 0.5026751236501744, + -0.2752883268862265, + -0.7490170954494364, + -0.07875644588247044, + -0.542359744009199, + 0.10155115001009585, + 0.5901735411437906, + -0.48136308555324414, + 0.0814989850233172, + -0.5368245726012406, + -0.20877561451254978, + -0.5259836760300832, + 0.29363217294762334, + -0.6390206936585567, + -0.7507393882888146, + -0.7197941734462263, + 0.3929711181157022, + -0.7488335223341571, + -0.6485998672571358, + -0.5709845416661388, + 0.15246052509428465, + -0.5260689838560584, + -0.5396124663372888, + 0.35626674214625964, + -0.7551181537259631, + -0.05037747861520803, + 0.646647455378471, + -0.30734037122739627, + -0.5673670809032723, + -0.09315822329500523, + 0.5115476351603402, + -0.11811811387340199, + 0.19200069524400354, + -0.7686133533413392, + -0.7160441910682316, + -0.005511596362955062, + -0.21981390130899114, + -0.07732277383237107, + 0.4631670299394016, + 0.6521206122986404, + -0.7728609960234203, + 0.6479679432837205, + -0.5260041215463299, + 0.6221781965033352, + -0.3845081166636261, + -0.47927745165154484, + 0.1302816913201189, + 0.60476079267881, + -0.5524282739984177, + -0.08949907162759152, + -0.49340820609503644, + 0.4441568077800774, + -0.271193185650732, + -0.1482323780704211, + 0.5544200298168774, + 0.5277495072256718, + 0.07936702026498765, + -0.39318258727702154, + -0.6382819043154127, + 0.22425143302397388, + -0.01555555976690004, + -0.7800466195529346, + -0.34896266335566645, + 0.26680084182273, + -0.627998514822952, + -0.2545684085772829, + -0.05361142229539073, + -0.6730519005073754, + 0.6502738222048788, + -0.7423725741588287, + 0.3216572880603289, + 0.034715448001506166, + 0.26868361153565223, + -0.6579679584801624, + 0.4865344472901002, + -0.43853711088939085, + -0.7179520624770424, + -0.17062574382853057, + -0.18031350871299023, + -0.5034382819618605, + -0.7815478938931262, + 0.26057988125388987, + -0.035805545098759106, + 0.03507833538683536, + -0.3291411824783992, + -0.491110632643905, + 0.5416950875680403, + -0.23687957036306506, + -0.38105091583761785, + 0.43317779826174896, + 0.5590104451780008, + 0.3072570947475882, + 0.5188576989313186, + -0.3320836431213031, + -0.22877833216653354, + -0.5736915793477346, + -0.02284181566456911, + -0.490180976841086, + -0.040374966315100624, + -0.32296332549603773, + -0.19077145588974032, + 0.1228293290600968, + 0.15364283994092387, + 0.06099772917684254, + -0.02626646530715404, + 0.36532834801476166, + -0.4463076658460345, + -0.7453895775769646, + 0.19705022854622, + 0.08083879618344159, + -0.2736471296519434, + -0.7494206375920643, + -0.12491643896617355, + -0.09357473861755716, + -0.29687311841755304, + -0.5118827484401121, + 0.3770801791321604, + -0.057498576326613704, + -0.22431394977740537, + 0.5549488971375353, + 0.3396452094359167, + 0.2980140702653423, + 0.48676991913087797, + -0.8058921538825761, + -0.30177589111746317, + -0.5768652871163142, + -0.5073692804042824, + 0.2064735326219821, + 0.10901599398503459, + 0.04002655192908655, + -0.6469724540512736, + -0.1292819643943275, + -0.6346233014931002, + -0.7181923971505246, + -0.4124279430684405, + 0.1938407412842421, + -0.753044582332224, + -0.1008191099657253, + -0.28828154042010545, + -0.050579956250949576, + -0.04093189857845614, + 0.6596669395240294, + -0.27374003714119133, + -0.18082312278895596, + -0.3803645430350544, + 0.037524841581399127, + -0.09828722976417681, + -0.5794859243706456, + -0.5204312945889483, + -0.7207166429887336, + -0.03420292852413964, + -0.0322026439139923, + -0.1621842563324819, + 0.5841985219460325, + 0.19292327622331407, + 0.1381846291304949, + 0.43356864561384023, + -0.4396682240660418, + -0.08594210760274834, + 0.5285879159008554, + -0.4409360347763883, + -0.24823019466534135, + 0.5715302507314511, + -0.5878282895797684, + -0.38369362374983995, + 0.1557525908707107, + -0.6211336785395483, + 0.5809845147044405, + 0.4145033270180566, + 0.19067621230528242, + 0.5939848906873252, + -0.5098306661977478, + 0.2702674496855283, + 0.23469662976640893, + -0.16580785151266775, + -0.5192781027811504, + 0.5498643171305387, + 0.19269269114067922, + 0.2923771796799587, + -0.07244184533824438, + -0.5570383432877962, + 0.13540261172134183, + -0.6719206622460434, + 0.14091894802181582, + 0.6145098655708053, + 0.28411288960610903, + -0.27816979500197525, + -0.6825160363124847, + 0.2116516214559968, + 0.44046132039818786, + -0.47280168671617184, + 0.5328438777881487, + -0.43382751154113314, + 0.566475292364483, + -0.5411540287620736, + 0.5565712310102441, + -0.1878200379081687, + -0.19118583913682574, + 0.05684538639322545, + 0.5885684731118942, + -0.341138378451432, + 0.1304895036205307, + -0.42913996323281495, + 0.09234701465883921, + 0.35200805488025144, + 0.3047438485422186, + -0.13599614879266286, + 0.30239168509216585, + -0.13689814902469488, + -0.7660094567498922, + 0.14708827513621447, + -0.6166221911030159, + 0.053804004572976516, + -0.7987372575742892, + -0.7701187726980423, + -0.6447816147462979, + -0.38300166656914003, + 0.3571807656301148, + 0.22931673383067464, + -0.2396451006504916, + -0.4511592650848374, + -0.1923113273840219, + -0.25645378661955476, + 0.4891645580292535, + 0.5787596056735381, + -0.03939776947588847, + -0.5971168890584722, + 0.38591421692019756, + -0.08621611538621188, + -0.554223430041066, + -0.7028480296743302, + 0.12347417889222623, + -0.0799105328743418, + -0.5581939547000261, + 0.05514504282284949, + -0.6871123299456376, + -0.6858409987511103, + -0.5366773884863272, + -0.49291143393301373, + -0.697081466559045, + 0.024200840527423217, + -0.6681468460308602, + 0.5153675415127211, + -0.569772392257886, + 0.638178863636304, + -0.1732440998661221, + -0.6881261406987114, + -0.4565002014438012, + 0.15030052937797878, + 0.49842760957711196, + -0.12139316318981519, + 0.2832725975147373, + 0.6221702503438565, + 0.5364142197037808, + 0.5117395981689018, + 0.023576828424494156, + 0.6313615053202563, + 0.3464034963417909, + 0.15542644608670408, + 0.3625099389631342, + -0.3026031344066993, + 0.4808560160178085, + -0.6090017416270597, + 0.24040628963217003, + -0.5466930459191077, + -0.4804814929925602, + 0.07617842611242098, + -0.49162845144313555, + 0.3837109857764648, + 0.4640152879207934, + 0.3792081928556813, + 0.3678771244008755, + 0.18212711070305987, + -0.7122425364273516, + 0.4931541268539946, + -0.10390127009013239, + -0.5829266683464185, + -0.5453689613503194, + 0.05430124479552423, + 0.15014822584374454, + -0.6188127752884489, + -0.5595686025266258, + -0.02832950404989354, + -0.6835301956112174, + 0.028938469611088258, + -0.3864681527628117, + 0.04737474434888267, + -0.02145336542809151, + 0.40433909325273054, + 0.03526353991727815, + -0.3287304553372438, + -0.44454562157216476, + -0.06650940900837954, + 0.5900824419152676, + -0.2521248155621312, + -0.47104938616463127, + 0.06488390025722623, + 0.033675230423510505, + 0.377522788424114, + 0.18010950615001076, + 0.2944214518868561, + 0.028090894084724982, + 0.3362788454845006, + -0.3975703161604195, + -0.5985825180415603, + 0.1609062002481657, + -0.4908948095533016, + -0.7966997854902905, + -0.12155964701089361, + -0.20824909797355773, + 0.24598333721518595, + 0.25169659178221104, + 0.16669547488663194, + 0.5044456156267955, + 0.17770931583060934, + 0.16746028941543234, + 0.4684945612376955, + 0.5431659718678646, + -0.14018790169112405, + -0.28914965956402783, + 0.6042351852190323, + -0.6861275646254885, + -0.07712352049624938, + -0.8061194305987844, + -0.7611358958875175, + -0.529982067375326, + -0.5902899669185762, + 0.3937901444274018, + -0.5870756758541636, + 0.4682454301874609, + 0.36186771901654324, + -0.24666992844718483, + -0.09929197964447245, + -0.7643183154531659, + -0.7455795548714144, + -0.3102846765134683, + -0.7805695916205673, + -0.7894749848337138, + 0.6000493223556304, + 0.41633632327015635, + 0.438358118615369, + -0.3456629963280855, + -0.06403979623837786, + 0.6379506686926245, + -0.6429641961412584, + 0.24592535714458863, + -0.3424583179308672, + -0.283801600407793, + -0.6964134672060953, + -0.7886654122725796, + -0.7455259569071568, + -0.6528856733120911, + 0.44707165223400425, + -0.08252325955720918, + 0.5564443691454505, + 0.19724428348080247, + 0.22093950567960963, + -0.7675498721895715, + -0.06513389051591134, + 0.655346486508848, + 0.3925934252025901, + -0.7463275216286362, + -0.15778150582362316, + -0.5437171166597929, + -0.5288074104757994, + -0.5668584928803923, + 0.5205788046145886, + -0.5328197364170364, + -0.04508060995978691, + -0.4798558475844048, + 0.17992366712863195, + 0.45844955946979893, + -0.5682782962453838, + -0.6479940920193865, + -0.5343096082712558, + 0.4445818025176108, + -0.002881190266623812, + -0.39400978478564014, + -0.7209069962519601, + -0.4047857612040021, + -0.29462104659850696, + -0.05415461266311994, + -0.2565617462149187, + -0.15876588736645492, + -0.45947237288757314, + -0.7219853031975798, + 0.623154494791394, + 0.3926683156172289, + -0.8021271017038238, + 0.07027374844419088, + 0.06283700179892693, + 0.1623949323447199, + -0.7276838377297602, + -0.2785336467463583, + -0.764846602134081, + -0.7188539108194337, + -0.027994959727934088, + 0.5242750684872873, + -0.6423211883530807, + 0.20306495218031928, + -0.4671986098215259, + 0.45034947297582006, + 0.3468115785664724, + 0.4538392283131766, + 0.28626793177506993, + -0.6020015971911781, + -0.7732623777580117, + -0.5100905025475306, + 0.06665797699586706, + -0.07750151326552146, + -0.6369812484223353, + 0.3947841308909995, + 0.5133832675638236, + -0.582202831969339, + -0.0014819862911967796, + -0.4992592089717931, + 0.22023220733644366, + -0.13911733754386857, + -0.24066751751130255, + 0.44664204987248823, + -0.2146417188988653, + -0.4216684760452698, + -0.1256914549578647, + 0.34703244597337457, + -0.2149364062072615, + -0.5370759345558423, + -0.18716710126646108, + -0.09156274812954235, + -0.5356754426792368, + -0.23958121936297871, + 0.3223367040266524, + -0.2597105897858145, + 0.12925749521891228, + -0.3827557186434801, + -0.3060188976764835, + 0.24832392989353214, + -0.6487576498405426, + -0.6735668328461681, + -0.5768613546183625, + -0.5932384638957386, + -0.02556312173797215, + -0.49940108298684677, + -0.5677752311513186, + 0.44534750478877794, + 0.4591664803614631, + 0.3036283246249075, + -0.15323620692440798, + -0.6009402184646137, + 0.3891369941570991, + 0.12921634998051768, + 0.5456711359488583, + 0.41438832666823433, + 0.6557674174097575, + 0.1451927330625129, + 0.578064957322913, + -0.6119095779751631, + 0.17350707205228777, + 0.14485713467580885, + 0.6561043713243292, + -0.0902134284122833, + 0.12014384287987845, + 0.14067380390467443, + -0.06237864045355601, + -0.16235106375075747, + -0.04113869370410017, + 0.20437618027882942, + 0.43166602699616774, + -0.3165428567032612, + -0.5018918158851545, + 0.008752844819528982, + -0.24169729911392424, + 0.11438018891353918, + -0.03682675357275045, + 0.17417291016522118, + -0.3428207026940877, + -0.09955364749738937, + 0.15291619488932484, + -0.1429808129221588, + 0.02794438033554314, + 0.6307694955338025, + -0.06669476067252955, + -0.011229891233047407, + -0.2602901231166136, + 0.30829778427513077, + 0.08875560025445561, + 0.3758830915252861, + 0.4551581063191231, + 0.3006253997474121, + 0.2739496374009526, + -0.04310280304221947, + -0.5517215517695002, + -0.29496205566656875, + 0.16390033438144014, + -0.4616353199834655, + -0.5433501958230103, + 0.27383958713916845, + -0.8062092970053814, + 0.5795042712564157, + 0.23864158719320072, + 0.44078937869356427, + -0.1938434617560726, + -0.06794443331651356, + 0.2909205472298445, + 0.3548106868027422, + 0.2849685357873294, + -0.021602910949522713, + -0.006591611361447258, + 0.17529400935313444, + 0.23394821126768683, + -0.6181714733074575, + -0.07173997051774184, + -0.5929755737910796, + 0.4184935215187263, + 0.34281601411147056, + -0.329380207444808, + 0.09171412249508737, + 0.09938799900326822, + -0.454787963778421, + -0.7228011039682143, + -0.6795226575614994, + 0.4086898098038839, + 0.31797813062189373, + -0.42791497091782754, + -0.26167351802510985, + -0.7942804043556155, + 0.19803040049264709, + 0.05895218019509241, + -0.5346181000531743, + 0.455406513658967, + -0.7388552298597753, + -0.7518002191141444, + -0.583693753973322, + -0.6967374501894266, + -0.4783334725673041, + -0.6012930373628805, + 0.5647001890714075, + 0.021499448523663478, + 0.10173905833287933, + 0.4730752165726152, + -0.6460746296413493, + -0.3214839646592592, + -0.06947809915828007, + 0.17742070261198684, + -0.14141166766212476, + -0.6943539358753308, + -0.74059878342635, + 0.10710850480208134, + 0.0966961128432392, + -0.7051536554839731, + -0.39816510790657667, + -0.17295352749627457, + 0.06293771972959572, + -0.6705462627557407, + -0.11500442090228191, + -0.1745814905068347, + -0.5858708286253742, + -0.4158930542185121, + 0.23439820616870388, + -0.7229819807023565, + -0.28831398455844937, + 0.48730661478967086, + -0.2985806676471524, + -0.6078162882997096, + -0.8043775277976544, + -0.11487891977159204, + 0.2565551748998153, + -0.5695365617384401, + -0.1733427997970809, + -0.4370089590448461, + 0.24405644287943484, + -0.06697518016406545, + 0.4583248047424756, + 0.156590262656077, + -0.7212566357025215, + 0.6449600869559419, + -0.7884540496829745, + 0.33187464250371124, + 0.4777799742034087, + 0.2969201152111903, + -0.6622295905191468, + 0.1572151184364029, + 0.08215614189557396, + 0.649830773896085, + -0.3759912569854739, + 0.3931650088659745, + -0.09279336161924978, + -0.07818090725755023, + -0.2465358871092843, + -0.5811297179175704, + -0.19821031625431107, + -0.7526915079234984, + -0.01831910131947323, + -0.2556279085496027, + -0.7638463298029728, + -0.6463742281594581, + -0.07440945552437783, + -0.0539984820297712, + -0.40995018521914967, + 0.2830877248390188, + -0.47950189737720234, + 0.6543096432369525, + -0.6519293064635766, + 0.11362865072708495, + -0.7081046820807619, + 0.3792411290406864, + -0.23161075829263267, + 0.020147517770772616, + -0.5225021814227514, + 0.6459802263172033, + 0.20626925421377373, + -0.7846536200628152, + 0.5363403898712374, + 0.2855439093153006, + 0.2511543558225774, + 0.45050125916660366, + 0.06770603401649944, + -0.011391229887946719, + -0.365082891096726, + -0.0902236296107134, + -0.5112183531963881, + -0.714634793072078, + -0.3622346750391128, + -0.4311311338692535, + -0.04137297833179421, + -0.7335315221313466, + -0.25130559199749114, + -0.5020530114924003, + 0.30800646893440564, + 0.19485652892222094, + -0.4224387288687082, + 0.15539587749837447, + 0.4741507903544103, + 0.28037655302613185, + -0.024940996598244447, + -0.7184641561654226, + 0.6272032064727803, + 0.611096228857252, + 0.12402740716838345, + -0.30022343449916444, + -0.44959891097972765, + 0.2142872825871046, + -0.2980392739952502, + -0.24402464274760172, + 0.33226138546768424, + 0.22947407365203165, + 0.32312588420611366, + -0.12610216323850965, + 0.02545538758745447, + 0.5551124464044744, + -0.6130435558815376, + 0.49482439819100954, + 0.6125335265088868, + -0.44122047517943286, + -0.3942097766083795, + 0.4484379010557006, + 0.02060412268121925, + -0.034738878822406116, + -0.17011524379119647, + -0.4539845098527266, + 0.582116717605245, + -0.6469513268061861, + -0.035353482036234785, + 0.3030429572135852, + -0.21576956022784233, + 0.09191682662546641, + 0.33266378710003874, + -0.14310638922217445, + 0.12891167607330345, + -0.17567324566179676, + -0.5687682962897211, + -0.3742082429575773, + -0.6998011595651977, + -0.6624677727180498, + -0.4187637889006174, + -0.048191273718307004, + 0.2550215599719613, + 0.4970259414025032, + 0.6073092097472897, + -0.6832900864437274, + -0.6416510316334518, + -0.5923467403377325, + 0.29566837299271975, + -0.6481933793897666, + 0.26162328560948633, + 0.4112615090854669, + -0.018793735346729346, + 0.3086377306646476, + -0.5454596420795541, + -0.5590615293529213, + 0.5730256474905852, + 0.14859354952160286, + 0.19226662547395357, + 0.49372644612265326, + 0.4169527022806384, + -0.31725031287461647, + 0.33741247854651657, + -0.07849354290444488, + -0.5134569353102165, + 0.16647301553160077, + -0.11453063945153563, + 0.2749351086738402, + -0.07691429600338784, + -0.6485956277975397, + 0.0752427595122871, + 0.24432459331024725, + -0.30528005730769203, + -0.19839063056826922, + 0.4428371900370104, + -0.07536185117114946, + 0.5910590259531819, + -0.6892451178748821, + -0.7961718512715653, + -0.4043744989289071, + 0.2045211095018883, + 0.15333148480058345, + -0.5212352651049144, + -0.06166214607487164, + -0.7111300973866727, + -0.680992496501588, + -0.3788548939916773, + 0.6566356747286773, + -0.5908812169661345, + -0.6004072735502931, + -0.5770412841006205, + -0.7624061246553594, + -0.12917169248135763, + 0.1187965750070955, + 0.3418793458222297, + 0.44597627283011676, + 0.6511111924273377, + 0.09496501030334481, + -0.6685744722248501, + -0.16457267629279004, + 0.2037681030141284, + -0.1250763061334762, + 0.6057406976668708, + -0.17764613831606102, + -0.717398648482511, + 0.11759013314816591, + -0.09316462926932989, + -0.4383396099837211, + 0.4966775275983494, + -0.4958977802594938, + -0.7819496865998974, + -0.33120336992781996, + -0.758321730591034, + -0.24819623316985018, + 0.6587756780109041, + 0.17258162213029782, + -0.5361705227411512, + -0.18091848403517952, + -0.4275439425106788, + 0.002303395659095653, + -0.4379691702839838, + 0.20958517773560914, + -0.1728058001723627, + 0.3476395106433555, + 0.6065794743370864, + -0.036130353158267625, + 0.6244848086552949, + -0.39586624455047964, + -0.1012211811858521, + -0.8013760986937704, + -0.13404190035783525, + -0.22934919984066693, + 0.33494637867015575, + 0.6584722859822741, + 0.2931933468572482, + 0.06304173500305332, + -0.7403099565126224, + 0.4694051072119233, + -0.4715847287808975, + -0.20916565897765738, + 0.1593453742335036, + 0.35245588429601826, + -0.4256954141403987, + -0.2546427326583136, + 0.13261757903445093, + -0.11762029465959367, + -0.5635314209527029, + -0.25155513715260125, + -0.13089408202192476, + -0.39338383297447405, + -0.26814149330434456, + 0.1078653663325364, + -0.7059114550475285, + 0.5642400801603115, + 0.1440705593606313, + -0.18254199021786432, + 0.14227837535927135, + -0.698789836440251, + 0.42761683030705255, + -0.2162059510688359, + 0.07979747457444542, + 0.38215578800584027, + 0.4227454921536761, + 0.5494257098932315, + 0.39105906698707227, + -0.7906870009806753, + -0.7065485651612173, + 0.5856521364976798, + 0.21505441837588501, + -0.6924949518721912, + 0.19954265678573024, + 0.1530030805922683, + -0.2473755353015391, + -0.5993566373175825, + -0.18900894820798053, + 0.22336073677098744, + 0.35977808309137116, + -0.457689070108717, + 0.0283846492175045, + -0.14409680009925363, + -0.1179077176061184, + -0.804846775711475, + -0.5412726651352204, + -0.48484513474541424, + -0.08928110020224012, + -0.5531679225141497, + 0.5672902998873827, + -0.4696040323248857, + 0.44354186086114755, + -0.49069508041117804, + 0.22147362657866554, + -0.6633334854907038, + 0.07261713207604892, + -0.40827923855680726, + -0.7409422943745428, + 0.3738773950897526, + 0.6316127602345717, + -0.37554755841275805, + -0.7741422801498835, + 0.4333630893291941, + 0.5600083132719788, + -0.5340173101854478, + -0.3709948807612897, + 0.05441112696144779, + 0.0324209543649191, + 0.2577406591110104, + 0.378167926248152, + 0.5256901013167977, + -0.17303882476816967, + 0.5014771260353198, + 0.36426287940555724, + -0.5385182548425401, + -0.15318244498364608, + -0.5990130802913043, + 0.44947217367879955, + -0.6740341790407641, + -0.15370781813809953, + 0.1242631872589256, + 0.04234960097655771, + -0.2771050599673748, + -0.1403052811091866, + 0.21718964752314018, + 0.018645665439582237, + -0.3258038899249863, + 0.16865251721434737, + 0.2913630621340778, + -0.22150088258538148, + -0.538077322005148, + -0.1518222736965592, + 0.22514956456373458, + 0.20034602475559582, + 0.6209130873238645, + 0.37695963532382526, + -0.5536989577627877, + -0.4789685748517423, + -0.7650866717409336, + -0.39711260363295164, + -0.18074691469387516, + -0.697537142908584, + -0.10989410641595654, + 0.6238313607321911, + -0.47469880375392937, + -0.6140027814887605, + 0.39636679993040913, + -0.13297571756275994, + 0.2393934060725037, + 0.6563508218833148, + -0.461735728432887, + -0.23147399097110988, + 0.322086661341599, + -0.5804190432660056, + 0.6501211497518055, + -0.4421193342240261, + -0.3084388950071989, + -0.12243081199224448, + 0.5129428858951649, + -0.15120703076717057, + -0.7457018033404521, + 0.5707496312598147, + -0.7791697603999492, + 0.0822757197332743, + -0.18364855776653477, + -0.44465238238123217, + -0.03923880355071596, + -0.5890583422742485, + -0.250432337220188, + -0.2853323279202201, + -0.735316647123334, + 0.15725247700991618, + 0.43225347593813523, + 0.47625143349720933, + -0.3698059391425, + 0.18571016074161684, + -0.09286557166175424, + -0.2108853129754128, + -0.007057212363940524, + 0.12065320828265591, + -0.14486344418943398, + -0.3321383167338205, + -0.31916915374349564, + -0.018457552137974842, + -0.05476526041686569, + -0.44381957782114906, + -0.22665821898675054, + -0.39294171356060975, + -0.3999263279751446, + -0.2929049797569181, + -0.23957262774701482, + -0.11439496413332884, + -0.7313910919331642, + 0.34835890264805347, + -0.10651908498662765, + 0.30992460730972426, + -0.10247398038888578, + 0.057188603798413506, + 0.23742491801084487, + 0.4324671132868, + -0.6432760591473135, + 0.5689559156039937, + -0.7299615360309006, + -0.5293463773080708, + -0.383827287644283, + 3.489665522491414E-4, + 0.516957787858502, + 0.14148796126078744, + -0.009063128185668012, + -0.2801080099012938, + 0.5552880451926568, + -0.3486704174287214, + 0.37953998244761367, + 0.6494052807114964, + -0.7439552733942555, + -0.07863690782887256, + 0.16620570568227477, + 0.3935820503349995, + 0.1982208804103559, + -0.14284543125901483, + -0.7447127298106225, + -0.7880513108481223, + -0.40131937791308175, + 0.15873892250273747, + -0.4857438431689295, + 0.2876576319319121, + 0.4121606147533744, + -0.3920781541017436, + -0.5945457807926509, + 0.42717551537843346, + 0.6322371473980694, + -0.27275316753436063, + 0.5509716859133528, + 0.5449927723692337, + -0.050933588493111914, + 0.645308431205878, + -0.418956582976123, + 0.2531928346324811, + 0.49849155808046375, + -0.4340275893383228, + 0.3009684225963071, + -0.25253308800558993, + -0.43985606029574004, + -0.5408259360508602, + -0.4750060427147276, + -0.7903517096917075, + -0.03198261219454723, + 0.08857569907460117, + 0.308802508666025, + 0.3133929637651446, + 0.4353320522640872, + 0.20135455811682312, + 0.047843411275943715, + -0.6854477514598053, + -0.3984518866400744, + -0.36442331212813417, + -0.5185880496861195, + -0.19968012684068281, + 0.07183924004273878, + -0.3895919411464669, + 0.5642871030209186, + -0.4019124306404551, + 0.5093978769207953, + 0.0916302343640999, + -0.48946421314627, + 0.2585415941241692, + -0.047499100979036424, + -0.029750136020231688, + -0.5476663542983422, + 0.4719399791059472, + -0.4147116985315758, + 0.5782171929177743, + -0.546240382604052, + 0.5955178155658544, + 0.4410308559096664, + 0.46592353895662975, + -0.45069554713565474, + 0.19471070567428617, + -0.5183478686840133, + -0.7188390628310186, + -0.15195342464696582, + -0.6298603604693966, + -0.7688939405452782, + -0.2915173485761844, + -0.5577916263304943, + -0.6175744263791462, + 0.27397128579012053, + 0.4924147898390224, + -0.11869555141571275, + -0.04181220864604995, + -0.41572041247918246, + 0.03076669603834481, + -0.30374588652093293, + 0.02720429466045926, + -0.2890651654390437, + -0.6630399372375513, + 0.1903540920310366, + -0.7812629436332862, + -0.7822649905071247, + -0.6849970006164158, + -0.3135357135928125, + 0.4563393277156268, + -0.4004889865743224, + 0.5636719053580873, + 0.6537530196494402, + -0.5492597480006722, + -0.6619726697033316, + -0.2252335822451803, + 0.5907788463600038, + -0.49112542766987977, + -0.2801863607542484, + 0.36559388329715403, + -0.5266323698102283, + -0.07018058378673453, + -0.27182573334780213, + -0.16643256966414255, + -0.13708415800309603, + 0.31559580359978134, + 0.6596891202515757, + 0.619596519453841, + -0.14679515409676103, + -0.764209337403673, + -0.32550576779307583, + 0.2687474110458926, + -0.2777576886639723, + -0.33095815460866806, + -0.4346428922586135, + 0.11206970904271707, + -0.2090255854292551, + -0.42820546474587784, + 0.29390161506883816, + -0.16218732954338566, + -0.12534853467959517, + -0.5882519317094842, + -0.42607253038460335, + 0.2235029641304428, + -0.5184130742731572, + 0.27208419075083634, + -0.17165584198054396, + -0.6322211653786036, + -0.4981077274826856, + -0.10104673458277835, + 0.3675069844839952, + -0.4016516961112953, + -0.3750164982178301, + -0.6554929621665988, + -0.7546363775042545, + -0.7136130410212439, + -0.07831221408153943, + 0.5559300732552656, + -0.2829557386707897, + -0.24418079533269044, + -0.1409850613890543, + 0.5470711821585842, + 0.6436844644656717, + 0.6580135041612128, + 0.5002440028407974, + -0.7630850831113428, + 0.556978936157661, + 0.353817864222168, + 0.02672516576528794, + -0.6623180829809002, + 0.13529926568464712, + -0.3572086006744279, + 0.4127613948190979, + 0.020570370447180242, + -0.6081958120019054, + -0.4656640920770424, + 0.6461246289457635, + -0.08747737189099569, + 0.23047141978521812, + -0.7518490070982412, + -0.286634537410683, + 0.3090554291927704, + 0.2350882426864872, + -0.25598615206529607, + -0.05301646381356151, + 0.23478650030344428, + -0.4354055519777422, + -0.6003080996550278, + -0.23817716644177267, + -0.11775131465800626, + 0.6301879733195598, + -0.23153588142628723, + 0.3367124266914231, + -0.6111924607365122, + -0.18050220562096309, + -0.01542466415202104, + -0.0744823392365409, + 0.08522622164916394, + 0.2376234546091628, + -0.24048512519419263, + -0.7679860119852437, + 0.2703714641460412, + 0.19393820523825067, + 0.2625597092641411, + 0.4280754087811728, + -0.1912934127790029, + 0.6393127285126817, + -0.4644076423534642, + 0.1758180133994427, + -0.1860763060823175, + -0.35464362590913917, + -0.21092409565635206, + 0.4191041920417299, + -0.6074006588689003, + -0.2599829011070044, + 0.10912420099069486, + 0.6216754583909107, + -0.5016650972583532, + 0.4227928549771419, + 0.32679911183696764, + -0.1996141929449723, + 0.35369935897509885, + -0.1455519706984415, + 0.3637206971738366, + -0.24094636810461056, + -0.3726057081144976, + 0.3485781946488863, + -0.6275670059032236, + 0.5620946653316868, + -0.49159229914314617, + -0.4148573407128447, + -0.3595730620019554, + 0.14291458973739257, + -0.25715585466744484, + -0.6878002780922624, + 0.5893534153026155, + -0.47169191735563704, + -0.2846069125562628, + -0.633637082416919, + 0.07662608566643403, + -0.43411070100489235, + -0.6784110241803933, + 0.15894308363303766, + -0.7218854329988644, + -0.48601948274227336, + 0.11655189835788882, + 0.48954363933569767, + -0.5373107700023895, + 0.4853454738555273, + 0.03490497294785866, + -0.6075291791689512, + -0.1260415800028054, + -0.3319469984137335, + 0.23371492769525248, + -0.16499548594364344, + 0.239533864108198, + -0.2872662557607891, + 0.38046234538701584, + -0.2233325908470558, + 0.1906072759884383, + -0.7871239564803718, + -0.13914173058763768, + -0.22570032305484755, + 0.2931442227807962, + 0.3010253588536277, + -0.6890201854693413, + 0.15682051252634666, + -0.3479946037385412, + 0.17085972883768286, + 0.3264859915088173, + -0.6485044485329514, + -0.7858537344132347, + -0.7388655358904551, + 0.6077476917066184, + 0.10117113725342974, + 0.11434340205814808, + -0.7854548282150726, + -0.6443796305984508, + -0.14031552356500399, + 0.4756695400906409, + -0.0705528640588362, + 0.40811653443368, + 0.5762618081818648, + -0.42852245512561743, + -0.18329340878919498, + 0.6379434258853015, + -0.02749093837689376, + -0.02379540104800515, + -0.31335467152245977, + -0.6879589278115915, + -0.07673485422854809, + -0.6949854652956844, + -0.3893555924415808, + 0.42356079321468576, + 0.4440714896510348, + -0.4443199261404352, + 0.4234233952647931, + 0.33114911719854845, + -0.4600540579330322, + 0.02860558517294609, + 0.2796804761323791, + -0.7059397207202179, + -0.2737563147239962, + 0.2576916409613613, + -0.24743642330620153, + 0.6071486392222868, + 0.2435020992829341, + 0.5610280991496505, + 0.1893132669980423, + -0.12178776821072534, + -0.21972788330389048, + -0.44695753988633824, + -0.8064603151664288, + 0.05728725295700732, + 0.4028943485739035, + 0.2796162900284759, + 0.35057649981286476, + -0.5255213627942343, + -0.2261135529501317, + 0.22371487455053873, + -0.19475569544865856, + -0.16584193907918143, + 0.2771650238021558, + -0.12269774715043469, + -0.04915023671464336, + -0.47509549908709453, + 0.5228896858049269, + -0.1378655925259591, + 0.563175636446328, + -0.7522526630706278, + 0.38136482484728773, + -0.7273306839576537, + 0.5827074150550297, + 0.044819766781123205, + 0.16258523510226097, + -0.7696344787530705, + -0.26243554223652643, + 0.360926337546689, + -0.09792140134501792, + -0.092442825308379, + 0.43724183512633596, + 0.09642810512636812, + -0.5927631343958448, + 0.15274492743875023, + -0.07662276849171412, + -0.5721389616003646, + 0.5223992328270651, + 0.0019067564662009762, + -0.5789687869420012, + 0.5356488646434449, + -0.06712018302173584, + -0.3520556066917814, + -0.36990876062473255, + -0.7244323133389152, + -0.1891123441229553, + -0.5094561471771903, + -0.16590736284718766, + -0.2167625930367787, + 0.5412584231442662, + -0.08090173166187564, + 0.17757347165216208, + -0.09806152756182662, + -0.13513737670140347, + 0.44292606364551135, + -0.27633725767475403, + -0.18617196137542724, + -0.570862503153996, + -0.17785662270744074, + -0.7703037502213489, + 0.30238613768878186, + 0.6415849572668816, + 0.18467318544569145, + 0.5990753966962027, + -0.3273275024807772, + -0.19604123248761163, + 0.2741097989266198, + 0.24211303774090143, + 0.049297130603915496, + 0.45437900923293395, + 0.4573826949549028, + -0.49742958507101126, + 0.3801428078203247, + 0.09826552006330813, + -0.7704501196863264, + -0.11166334231689912, + 0.5933967340620055, + -0.5462551305209202, + 0.16889599005313005, + 0.17570360768905458, + -0.36126964795316724, + -0.34747723220146237, + -0.3394817970173153, + 0.6073766469475784, + 0.22968702024674925, + -0.4395780286649338, + -0.07212462456782986, + 0.5402941467368366, + -0.7624908223580322, + 0.39766979136391634, + 0.15999426582577947, + 0.11983972386275099, + -0.22108630694916387, + 0.4231679755897456, + 0.2872896558469461, + -0.06642383819322406, + -0.08677695505844307, + 0.46350417581958314, + -0.7196306608569235, + 0.42935179771109755, + 0.6049965593181464, + -0.44957348592751384, + -0.2484432317600801, + -0.3512952024773546, + -0.6825886042887461, + 0.4071291465025558, + -0.545672796328168, + -0.5680431312560414, + -0.44555487050354026, + 0.47228841008354305, + 0.6059911647753998, + 0.16420697509475224, + -0.5461019282953853, + 0.1297984458311, + 0.5808747480484676, + 0.1137791782915224, + -0.296272873689541, + 0.24282017893593488, + -0.6730165268592578, + 0.6464773245119052, + -0.31619703330826493, + 0.2450766280294615, + -0.7777458680517833, + 0.03961599836688323, + -0.1770662877315461, + 0.6145328979664356, + -0.449125535171929, + 0.36378818177757, + 0.24039927199043076, + 0.6169378945826302, + -0.781395561637449, + -0.6142049208262468, + 0.07097620911475244, + 0.6537511801740478, + 0.333003622295862, + 0.4519810826660501, + -0.11455067723074286, + -0.5053209311394454, + -0.49304830490581397, + 0.535846565883804, + 0.4397245178236947, + 0.44059713975319326, + 0.052279721937768975, + -0.634707360002556, + -0.1443458933273526, + 0.6346799048029296, + -0.06533188075625873, + -0.30979545402568454, + -0.6244116566913303, + -0.024754734042513382, + 0.29281604385140414, + -0.6451111916765311, + 0.2875766003760979, + -0.5104080551860407, + -0.3281396142235741, + -0.37868471828251976, + 0.37081648873268225, + 0.2835418996544451, + -0.14939616173946957, + 0.10546274656058285, + -0.48364817236386154, + -0.4196054876214065, + 0.0293988332279691, + -0.11543621737646304, + -0.7475646204790569, + -0.7511667499186858, + -0.318495003333628, + -0.8016621824994196, + 0.3375777318907457, + -0.5364223052918953, + -0.38365719575218266, + 0.2631355403529222, + 0.5372542676634199, + 0.5261117037103816, + 0.4653481646757104, + -0.18680290022396784, + 0.4568373352300449, + -0.4143152441097675, + 0.6438272464534994, + -0.13661126636236487, + -0.08464392990897662, + -0.03216950958757803, + -0.3042558036135974, + 0.4211530243448952, + 0.3379714917077995, + -0.07367891869576537, + 0.10039182455413109, + 0.3974773281120446, + 0.5500282614447235, + -0.596622665386803, + 0.13310147059192234, + -0.6086933932011803, + -0.20920315330673533, + -0.46934041885712086, + 0.16244317660759489, + -0.2029108943910457, + 0.21433396206473765, + 0.4863860787626876, + 0.3250154889520781, + -0.5933746237693704, + -0.578064790732985, + -0.34189357760148126, + 0.4421256596517803, + 0.2360456362758815, + -0.30773133383169726, + 0.4313488070831427, + -0.0016402123638065147, + -0.6571033238799849, + -0.7589012613111812, + 0.14054915801696266, + -0.08757795976026062, + -0.019185667658988215, + 0.634721331820317, + -0.49116569021684126, + -0.7040652227414508, + -0.0489424268708929, + -0.5789846546165274, + -0.1425677091686608, + 0.6136968953571144, + -0.3494330071843723, + -0.2195093229961359, + 0.48275037843376734, + 0.37156005586409824, + -0.22863830746366964, + 0.5964108816171153, + -0.4607388529774117, + -0.48499653748263094, + -0.8017075432677383, + 0.2966856836359367, + 0.058116785693066886, + 0.13433744504734701, + 0.02226400571851206, + -0.39613208417553836, + 0.4742075224901351, + -0.6112670450985994, + -0.7626065650971836, + 0.3278300694460864, + -0.13038136043338178, + 0.6521956687461711, + -0.21365890716594715, + 0.5747807515695461, + -0.3384323873619546, + 0.3648272881807363, + 0.6318123155213166, + 0.5613255532331421, + -0.3701324993776148, + 0.19409522759312126, + -0.4455925285845459, + -0.5571246177896548, + 0.05181441074166171, + 0.5155372758219577, + 0.4104349797786152, + -0.46882920936735095, + -0.6545250163796552, + 0.06498660870328721, + 0.24264301616695383, + 0.5328406564966975, + -0.7355354477216262, + -0.7681824172028661, + -0.7982291251330176, + -0.06342191571336875, + -0.4381879972285131, + -5.272625313497148E-4, + -0.30533426538828834, + -0.07378563522302506, + -0.39699563037248325, + -0.034097128659171916, + -0.2215182151020566, + 0.5768930630857559, + -0.5843288173416714, + -0.5833044054930693, + 0.40360710343861605, + 0.056404482267563005, + 0.3870290746529458, + -0.6861243101828669, + 0.30512318675951466, + -0.3475268766231037, + 0.5794820261330934, + -0.6155475107807433, + 0.25020634785822515, + -0.6444696596064226, + 0.6159324285134659, + -0.6884420329673873, + 0.09559588737370217, + -0.5313132531462079, + -0.38332532009648485, + 0.3749571557878696, + 0.02568804505786204, + -0.14640083932890635, + -0.4780625455292372, + -0.7070885396376353, + 0.4791134544816712, + 0.015949364901207352, + 0.20967007662169157, + -0.7590266016101285, + -0.1591275503509978, + -0.3158703329214981, + -0.6731047020211391, + -0.14054689217485028, + 0.29263052736897877, + -0.3215116156847501, + 0.28475192488678525, + -0.5599808874599957, + -0.24813205668991667, + 0.27189667374479065, + -0.2569671131194081, + -0.09213695902544483, + 0.36367076762343087, + -0.17901633871624645, + -0.21853454769413472, + 0.2595050664716657, + 0.26522313331107916, + -0.093377667663335, + 0.057221768595800526, + -0.13901416070995143, + -0.38329987293830287, + -0.012465297825170918, + -0.6406562072094033, + -0.49344497478270777, + 0.2869683730275131, + -0.41867972621649174, + 0.5419417588109406, + -0.6483451109509896, + -0.6862404895199602, + 0.4565252357463444, + -0.6545613870992832, + -0.26308578410287453, + 0.3704839585984364, + 0.4431817142679576, + -0.6172004709239187, + 0.2780370501088473, + 0.31443643364382823, + -0.42209294610184744, + 0.49560479553240133, + -0.5183611884111812, + 0.0023808131709461833, + -0.10436803028282515, + -0.045533098275795325, + -0.48071324970256163, + -0.4922546949580315, + 0.23480234631120644, + -0.04848762756220226, + -0.07030344722801507, + -0.43476686446329216, + -0.016199562513141808, + 0.3833363297097424, + -0.6518076799416495, + -0.30871813598890857, + 0.5216244647390237, + -0.4282469525352093, + -0.6678094455052496, + -0.07728568144431014, + 0.345665486517856, + 0.2772049120326995, + 0.15576754526738845, + 0.0511798582777413, + -0.5058335717877028, + -0.6822047174007755, + 0.3255908683627343, + 0.19924081543637218, + 0.23260674575435802, + 0.4811201982923229, + -0.056973828712170715, + 0.3406215530835689, + -0.676729811500705, + -0.2768335961641082, + 0.3325643908822372, + 0.21530266766483852, + -0.09011565036275238, + -0.7063724359938347, + -0.2027720106024049, + -0.623620886518921, + 0.5834634460769083, + 0.14143399568676174, + 0.4945936100199312, + 0.0501524735243396, + 0.021529238773225434, + -0.041372277565856486, + 0.5853402051660138, + 0.5761426586185848, + 0.6252701852997756, + -0.5880868365950865, + -0.13925682358673463, + 0.25560765173495625, + -0.26119059778539466, + -0.5658422220723247, + 0.609048855864245, + -0.4957162445001212, + -0.38114776804000244, + 0.23702890674592958, + -0.6594288849844457, + 0.16082993939742074, + 0.05566383497783367, + 0.48262893216899594, + 0.45189243724651906, + -0.60944921611214, + -0.7752842969302915, + -0.6847529648643074, + 0.20434592754305048, + -0.4937260318470665, + 0.596728031076282, + -0.6105003765397399, + 0.16975566041068435, + -0.6323735441107764, + 0.11756082531925194, + -0.7462904901081653, + -0.4518105377564559, + -0.40696039150263014, + -0.3307722484180976, + -0.6065958533633384, + -0.21813186781950356, + -0.33398845673977584, + 0.5277638487004573, + -0.6030107287619146, + 0.17280402722846067, + -0.4521507405071168, + -0.5099931664646269, + -0.19307443802129476, + -0.5243799546894112, + -0.4187456937192324, + -0.6194080319174582, + -0.322824759046483, + 0.2771586788198618, + -0.6303536602647715, + -0.4298484775890825, + -0.7219335601815913, + -0.6651223232544611, + 0.6133846714205097, + -0.09269218600062812, + -0.7392215434593755, + 0.6072267318275181, + -0.24286649089037904, + -0.1049192663816022, + -0.41425577614283937, + 0.03624549561821255, + -0.5150366577041476, + -0.8070911843798446, + 0.5190995386251186, + 0.14773420129321269, + -0.28782228215676153, + 0.10396336731144828, + 0.1298663222133326, + 0.5853986759543989, + 0.5953639111868446, + -0.5513989609166443, + 0.4346632155622775, + 0.608915740227672, + -0.4691819688031788, + -0.05602665345554925, + 0.5951797490508718, + 0.05685020050989609, + -0.5469444393609125, + 0.12077653557428025, + -0.6314330603734797, + 0.4483899579653793, + 0.4387845078550424, + 0.5271092276734118, + -0.10219755361254779, + -0.143638150698563, + -0.14239372962172991, + -0.03232142427234008, + 0.21019537030684698, + -0.028806097937831066, + 0.32616260030100064, + 0.23115972990779532, + -0.315948816880258, + -0.115932807735879, + 0.2995663439746251, + 0.15674555963421122, + -0.512957411558172, + -0.2717971328736547, + -0.4745564527230994, + -0.6856466361751951, + 0.37403322487196033, + -0.4296776008699785, + 0.4455887447942869, + 0.5048987989512502, + 0.08498991119648514, + 0.08584012458346502, + 0.47834273292275487, + -0.40999732286413315, + -0.792447952327955, + -0.47520155567678324, + 0.2081451697025981, + -0.6472726248681079, + -0.6128105997738749, + -0.5671782477305843, + -0.6446327280904556, + 0.06682402455456249, + 0.6302591736191318, + 0.282092536091222, + -0.031580986621976725, + -0.5746314026128488, + 0.6119149564504737, + -0.2869270848606452, + -0.668492453743506, + -0.6601455349338472, + -0.6464660350838245, + -0.4520010596007811, + -0.573106066276517, + 0.4857625243030156, + 0.05956373927150138, + 0.3781572748164307, + 0.3919901974740242, + -0.2275530352398395, + 0.42519732373464303, + -0.3873066689152844, + -0.7320771963699112, + -0.06677737651152338, + -0.17030890683705147, + 0.29448471557298983, + -0.33272967434488976, + 0.4133553307311021, + -0.4258643505203045, + 0.03210822392984192, + -0.09081941365703117, + 0.5984825611983261, + -0.7668820805711029, + -0.2899689717920123, + -0.5956888675090151, + -0.4279052625975341, + -0.4952561306227633, + -0.619302503806852, + -0.7385574838983169, + -0.07473083948237325, + 0.43452870456133763, + 0.04860711378863192, + -0.7624636067130346, + 0.30352174015914624, + -0.5339353571106717, + 0.43505481260632484, + 0.32698507417043465, + -0.7268992149282426, + -0.5242656875297184, + 0.14800312511918634, + -0.5351806584432186, + 0.3347953872228161, + -0.41844778275401223, + -0.37955363254770047, + -0.679003287962176, + -0.3453811328595643, + 0.5126419371326779, + 0.04511666488626753, + 0.4346988899758363, + 0.1655669266268246, + 0.19944916634229315, + 0.34348302154700716, + -0.21901764452563044, + -0.4887796393213108, + 0.23498111657162657, + 0.3306344462217091, + -0.6763107091849968, + -0.6086036281531151, + 0.41645480746620656, + -0.6037531494613447, + -0.5016795952916151, + -0.7114435583517897, + 0.0039029227556299784, + -0.6610389965731106, + 0.31898743203290547, + -0.4360761194202551, + 0.5054925907668527, + 0.5848668320321432, + -0.20901692062678223, + 0.43418658735813154, + -0.2661398539867388, + -0.19023581594677974, + -0.1934074285025258, + -0.762723771432059, + -0.36825853606798964, + -0.3030405016440584, + 0.003968715611836204, + 0.3883586101290296, + 0.5640589408801572, + -0.5120880707666506, + -0.16183266822436382, + -0.6338942543330447, + -0.2072870880344293, + -0.3524479853393393, + 0.484822117782601, + -0.3970098308999166, + 0.020752064934937753, + -0.3736522570166894, + 0.02930200381700132, + -0.3147255089057666, + -0.13669469518065647, + -0.5781865353601949, + 0.4087052780526229, + -0.25959360759667827, + -0.31659678523105356, + -0.60032284404651, + 0.14849942062086652, + -0.6266805723031441, + 0.16840757648853577, + -0.6273303060076625, + -0.28488635158147557, + -0.3796920132742986, + -0.04613094327358158, + 0.5382994707243137, + 0.06905534735142649, + -0.2687204202723782, + -0.10311761436861244, + -0.31749482031910325, + 0.6398296384564169, + 0.40240632203183513, + -0.3881364840356789, + -0.7774645411219975, + 0.34507775392083107, + 0.29656457427487426, + -0.5973186062634928, + -0.0412182115630656, + -0.107951048350442, + 0.039410135601002705, + -0.012240815672958982, + 0.5333989776964768, + 0.1298217844124434, + -0.5888977748315523, + -0.25483125870080425, + -0.028485444654692382, + -0.3191099168435438, + 0.09718794214135573, + -0.21096294107412417, + -0.647683201670155, + -0.6579614361627779, + 0.2829082989230708, + 0.24885164602317078, + -0.16469472437445332, + -0.3156682734456504, + 0.46250431774352274, + -0.7085646116577633, + -0.6950180317172051, + -0.7693507266969231, + 0.11016080816441898, + -0.1972053332508289, + -0.2161965782469797, + -0.29117193937109953, + 0.6216812979916772, + 0.40973701227331605, + 0.2782552613114849, + 0.5927959709505118, + 0.27503606345874065, + 0.44465122912774746, + -0.3743275428753325, + -0.31468146011025677, + -0.48043302616873895, + -0.7425247654689627, + -0.5534281505923841, + 0.36601181998397225, + -0.10412380161243073, + 0.2905617019241419, + 0.3047484585932211, + 0.08837085717999393, + -0.605313212990369, + 0.42203424470294293, + -0.20429451003118315, + -0.7275610629195189, + -0.7944612732531514, + -0.29239373986328887, + -0.748449153158661, + 0.546272941581187, + -0.47026076221878665, + -0.07660560619747525, + -0.6339759770288204, + 0.22121008137763376, + 0.03928320465202373, + -0.4107224778714827, + 0.04351068611655329, + -0.7603534019036664, + -0.7374780282706126, + 0.5310042995538601, + -0.3758874595963632, + -0.22311856006401076, + -0.7672487697500769, + -0.6697381637904478, + -0.1469397896014164, + 0.5420590473307189, + -0.5413885446221547, + -0.742169218248693, + 0.43065483476653166, + 0.5511332678177859, + 0.45487970337394634, + -0.34169131928725316, + -0.1859718856227609, + -0.04971032885536708, + -0.4281993154846105, + 0.3834553766966421, + 0.28242232167914694, + -0.0337804846145332, + -0.23196841620957098, + -0.028358399376327226, + -0.027097115484516543, + -0.6094825635049942, + -0.15196766848849563, + 0.15707099629933685, + -0.2565469012646985, + -0.11810186729672756, + 0.05447345926195335, + 0.2746442035465849, + 0.5608738051120691, + -0.45142475265961984, + 0.2295535077052998, + 0.24900500204974196, + 0.1467952178859544, + 0.6498502226634119, + -0.14300302530508435, + -0.7654151041508478, + 0.2743391745192961, + 0.2178083249385897, + 0.5491273525460366, + 0.34334317721243235, + -0.7167876755209538, + 0.3440888016140712, + -0.2974660711926914, + -0.22077303044508234, + -0.5277998032904742, + 0.22888274626060368, + -0.5458846217065381, + 0.6370391965954857, + 0.3790686765825807, + 0.57724423322412, + -0.2447717231670904, + 0.1858436182229689, + 0.12697321479313295, + -0.11768249485803561, + -0.11266894139676598, + 0.22561742185499856, + -0.6448119069192132, + 0.3436835947140636, + 0.4943823049492039, + -0.7665629368681861, + -0.5029804019552119, + 0.008711093411475246, + -0.0479685700603244, + 0.45255336193700557, + -0.3501215660841333, + 0.3991082298920533, + -0.15157655200398712, + 0.04707049862470469, + 0.5012275342302687, + 0.10706858579257417, + -0.07249089963755861, + 0.16373543503095633, + -0.5882944641927912, + 0.024037723608245187, + -0.1261621880116246, + -0.32171984335963044, + 0.246571397936994, + -0.4415830983599709, + 0.07697929202916376, + -0.07860111654403013, + -0.48886714651232444, + -0.1737993300524462, + -0.5556418832153437, + 0.647776286857893, + 0.16632375663207832, + -0.2676923704002856, + 0.6453529950293045, + 0.4551605519279275, + 0.2113918423128195, + -0.673973591580999, + -0.5379237042483886, + 0.08676068423223926, + 0.4139066546066713, + 0.2514792189300593, + 0.10123361031153222, + -0.4721169636719314, + -0.1468048339054434, + 0.49869157254092855, + 0.5877157621181904, + -0.14774751433610755, + -0.6640190074254753, + -0.2506502152088541, + -0.42191534706553646, + -0.40371133177043045, + 0.6013112273890479, + 0.10426532446703674, + 0.22579981941130767, + 0.5016580524685265, + -0.24795980229542813, + -0.005977835543889309, + 0.3113330400407285, + 0.35165445678094487, + 0.3515650629587016, + 0.44340441237494577, + 0.050093060672196765, + -0.09818652675905681, + 0.3030494073987783, + -0.6807954715349905, + 0.06690045398285793, + -0.37766201984360803, + -0.6863013032805624, + -0.6514466724916301, + 0.3709729115298087, + 0.15787128253206828, + -0.5030464571476853, + -0.7601886469916431, + 0.14376087668348358, + 0.6306257743874807, + -0.3562024403309582, + -0.38121657164963374, + -0.0183492046883591, + -0.16460649133133365, + 0.015025465877131716, + -0.5123649087497062, + 0.30078585060723906, + 0.6496904191167124, + -0.5662028698215551, + 0.6457175300195374, + 0.2476397294969731, + -0.6307359464085665, + -0.5272296275132147, + -0.12328512583711526, + 0.5587779146260291, + -0.07967391651250699, + -0.29249921818412017, + 0.3205876439103922, + -0.5644203778438951, + -0.49382071767377994, + 0.022956251597104793, + 0.32654839139800484, + 0.5408860603386946, + 0.5234423362131476, + -0.02712094011333821, + 0.10062190364218848, + -0.41221396262898535, + 0.09904548999362761, + 0.6025827814641606, + -0.7297645803906876, + 0.5593764264199127, + -0.3474269905775726, + 0.44591057206134976, + 0.42602825496596364, + -0.1909707757312371, + -0.7148965181371334, + -0.48906350088061706, + 0.601271695024466, + -0.5111225557969638, + 0.35716036122721906, + 0.10644864765674189, + -0.8032058708053311, + 0.06702750734968443, + -0.23125043497684616, + -0.15017276148042868, + 0.06442248850282062, + -0.7075847346280602, + 0.33269004503020694, + 0.339108300714411, + 0.2161778758410916, + -0.05413400078178521, + -0.2741139173037964, + -0.7011880537946511, + -0.4778764733408317, + 0.15304191809559908, + 0.41371327962957183, + -0.7124865663188619, + -0.2518711444293955, + 0.43305767485845104, + 0.5771631533239184, + 0.3577008394749591, + -0.291903866969317, + 0.4218581225251298, + -0.0962650255599461, + -0.518143520520864, + 0.4399664086784544, + -0.374397390307636, + 0.30016804407348474, + -0.5111204705002461, + -0.5626306015255638, + -0.40348674418964237, + -0.223821173544956, + -0.16963600954680824, + -0.5438125252967427, + -0.4753517796390723, + -0.06910232549649953, + -0.1145449430402804, + -0.5506161596363226, + -0.3039554490097834, + -0.40378557598198184, + -0.6290579749492854, + -0.5807152599423446, + -0.5505668064018169, + 0.3834717726658713, + 0.029268204286494903, + -0.45966207246766555, + -0.31892773052870993, + -0.6139309379053899, + -0.666569902745708, + -0.06565991624352163, + 0.35705400897881046, + -0.618698362876988, + 0.2716441084840091, + 0.05480684802912983, + -0.6657435313564841, + -0.2952374718040744, + -0.5060481169272675, + -0.3414777446430581, + -0.29974765757487015, + -0.16966158703325518, + 0.23565597195568755, + -0.2005022737239862, + 0.029680072301348837, + 0.2908088729930346, + 0.044178490494024, + -0.6726256432684271, + 0.05766925167276915, + -0.251385387895399, + -0.21729828280827213, + -0.4804664633445809, + -0.25043569174990354, + -0.6919538012367027, + -0.43502103056063673, + 0.042440220699433984, + 0.16051055851646834, + -0.39237330553887356, + 0.10277100368740921, + 0.21509258541986986, + -0.5533277381111515, + 0.34824907165000896, + -0.3814249341776159, + 0.1412711076683384, + 0.3281097018336786, + 0.3067964267741795, + 0.20534788741403787, + -0.3447668059533813, + 0.23263116101853953, + 0.37542598488534284, + 0.25418025092967156, + -0.642095673497124, + 0.035565617869265265, + -0.11346643238792387, + 0.11090693428614717, + -0.6613912402971032, + -0.5749488880849057, + -0.4306470379061576, + -0.3757723419157717, + 0.05736158248391454, + -0.439806600594245, + -0.3049183462328256, + -0.4904022416915156, + 0.20704926974133753, + -0.6465599697057662, + 0.27123421441646633, + 0.07084942615641288, + -0.6382760663098755, + -0.4481811720420933, + -0.23044260437928105, + 0.3684200272020254, + -0.5662668152148167, + 0.24229677641926195, + -0.04863244434405012, + -0.5499417255226874, + -0.23224166614775343, + 0.16741851866590696, + -0.4769992585124413, + -0.6224671752377127, + -0.18812777092812982, + -0.6036168904277424, + -0.03931149112681398, + -0.5254030734139754, + -0.6672997591010223, + 0.41321153991367987, + -0.005585796812877519, + -0.4136515863614821, + -0.37888255205989224, + 0.1014372353825359, + 0.20520132504199506, + -0.013413085950512493, + -0.4006882127194604, + 0.18615761660364072, + -0.6727597463122881, + 0.11656905601923628, + -0.4886959759963456, + -0.10610191621435261, + -0.40420730635548385, + -0.5160927978279055, + -0.06540679603364297, + -0.4110517707252036, + -0.28492786250037905, + -0.09457661726323885, + 0.3332530547345768, + -0.3383556132952519, + 0.19468922135483324, + 0.2223431441743473, + 0.19546985507657988, + 0.3555363483552726, + 0.2622857204145772, + 0.1798476048803962, + -0.16331570807324847, + -0.6478386290893837, + -0.027594486640711957, + 0.38538932210508603, + -0.22453265876981476, + -0.09226571876123135, + -0.3841473447950011, + 0.2970788573608131, + 0.23579526322140254, + -0.17860865529242165, + -0.39078322378149183, + 0.29938149771589473, + -0.3403933503362614, + -0.37852903740052934, + -0.5836920650869215, + -0.6567882797633647, + -0.25731901221583187, + -0.0012916094791276533, + 0.20814548653413478, + -0.20628477344858764, + -0.24939152133392622, + -0.49627313705192105, + 0.13443812965591895, + -0.6323538010998289, + -0.21922052785472068, + -0.02249139560661606, + -0.07576364218686715, + 0.4094653832962841, + 0.336397703467575, + -0.6610317782942796, + -0.14889564902459496, + -0.2769473685295554, + 0.10409964234818003, + -0.06219458610872475, + -0.055895037435023553, + 0.3737402477085784, + -0.46430882545638075, + 0.22708495851983623, + 0.2921671359473401, + -0.042148762635346726, + -0.3321680855699135, + -0.3860133228193005, + -0.5370515785653112, + -0.6277705196046994, + -0.2927603007455466, + -0.4114394166962111, + -0.4337082441173345, + -0.13558711105632137, + 0.09217756461797055, + -0.0950466450021783, + -0.002182789634796789, + -0.2234269431860733, + 0.01736383379582418, + -0.4646867154685256, + -0.388425179439042, + 0.12574231349321852, + 0.022295169435080475, + -0.07997019502023439, + 0.15926975458250403, + 0.292711961206785, + -0.2526378311254434, + -0.08045092825779987, + 0.1718130022996912, + 0.08271041292729309, + -0.09673521417013431, + 0.2167472354777923, + -0.19778955101521323, + -0.12721835476808396, + 0.11757664012746627, + -0.3984646336103083, + -0.5496214393630088, + -0.2951393269872798, + 0.22269211728602367, + -0.03509818071039705, + -0.06269111552416295, + 0.14634102272478622, + 0.15992940265491562, + -0.646841186494364, + -0.2763709688846644, + -0.35052326903622233, + -0.260787061985676, + 0.18612069235327688, + 0.029585020246474247, + -0.17884297058838938, + -0.5132112127615365, + -0.07914600830001128, + 0.0076629576582506465, + -0.10497822777551391, + 0.08710321078486338, + 0.4173903825464337, + -0.4814516881347422, + -0.6365935641408897, + -0.04617617131637186, + 0.24933416103397477, + 0.1606586308247292, + 0.2527357847609881, + -0.15706920845935568, + -0.5275658817496144, + -0.625548989952024, + -0.008016867789646165, + 0.18427496596531578, + -0.5916608046290007, + 0.23993382506136007, + 0.32130367616131894, + -0.16020912647057584, + 0.17662660988557277, + -0.47567843634708484, + -0.3503657898365279, + 0.014914948883923418, + -0.12235397446958951, + 0.14208177906304065, + -0.05674607963657663, + 0.28201942750736375, + -0.37338547976538405, + 0.22314850587914126, + 0.2747114755951531, + 0.04481150149242019, + -0.10563529919637049, + -0.2681215128010285, + 0.21787550242907927, + -0.3509915294478531, + -0.13649507043478393, + -0.5587717694887512, + 0.2763855947476954, + -0.4007800042337766, + -0.23543519456979395, + -0.5011066355440068, + 0.26022809399301394, + -0.18963398423719802, + -0.12644011275917533, + -0.36914893342271454, + 0.40093350125505844, + -0.29649927856577984, + -0.27688781332362167, + -0.15620291766391525, + 0.04701558224050917, + 0.30340718264129596, + -0.2752776190591912, + 0.25280333671145694, + 0.2559549533357536, + 0.409002237322451, + -0.6152159757557758, + 0.1856505110838309, + -0.4268967884293784, + -0.14450469980951142, + -0.6941384479326512, + -0.019228784404156207, + -0.08137175726355672, + -0.5411243893238227, + 0.3203701408492142, + -0.028830634665453214, + -0.5001174022308519, + -0.30859323360863145, + -0.6755145802801938, + 0.25885176861158266, + -0.5891384615178488, + 0.11296705206672719, + 0.27228981016807974, + -0.6525127882433751, + -0.22696065226686102, + -0.181236424760989, + -0.2310628061996532, + -0.31543300170471383, + -0.5701553061237721, + -0.014178505606606495, + 0.001155768345724395, + -0.5711421314493408, + 0.17974419534309205, + -0.33451848837421244, + -0.3276752425845533, + -0.38128087119923304, + -0.6892478856563202, + -0.050684128238436044, + 0.2966048556869859, + 0.10970697071688651, + -0.4935981307248603, + -0.5220905404129272, + -0.15170399365589904, + 0.30385954656537295, + -0.08533327816617742, + -0.2721570397087962, + -0.5245926629820674, + 0.32499539894253393, + -0.44656508817109203, + -0.13399330782628127, + -0.17059184153621976, + 0.27243045807446364, + -0.20725761967198525, + -0.3024410520985826, + -0.4247117480090414, + -0.6381475935813584, + 0.20270053188453574, + 0.18299559121234277, + 0.04603998637176021, + -0.149731131583415, + -0.3991008356766455, + -0.09022204463800032, + 0.18976100006980912, + -0.18865262583769304, + 0.32025224590364154, + -0.3584889922228311, + -0.552981536109948, + -0.1830350647426907, + -0.42158660472133047, + 0.35406140726022717, + -0.3909155412360777, + 0.24235892173949525, + -0.3728619672490177, + 0.4111817863607262, + -0.5963127777439667, + -0.5269330133385521, + -0.03978572661409707, + -0.05413235723266885, + -0.3001982290254207, + 0.08528173224862057, + 0.1784611170796826, + 0.2215281001430489, + -0.43383579828328905, + -0.3947057168675825, + 0.3205480945068936, + 0.18096076278611473, + 0.33674197617467583, + -0.6538639610125849, + 0.2555663612328506, + 0.22565241379147272, + 0.0034667840759738944, + -0.1035309728764483, + -0.3754329461472683, + -0.4000746197479919, + -0.10116160354158299, + -0.18663637341992934, + 0.21516130715433135, + -0.254781841913168, + -0.5461833968746896, + -0.39040796146212653, + 0.021333449284632766, + -0.5770171539804299, + 0.01800577651693558, + 0.1635289936194032, + 0.415847181265916, + -0.4499067811267845, + -0.08772556686261135, + -0.04369279384223046, + -0.46121525476259556, + -0.1677592307894764, + -0.5919852893994225, + 0.39410637185330344, + 0.34542013067221544, + 0.3872214505591448, + -0.5120363217786197, + -0.4053172604026467, + -0.015349217091888079, + 0.003675820578928679, + 0.1810804533042647, + -0.07549794968786772, + 0.2435374463579587, + -0.3745443719104992, + 0.06984378416148762, + -0.0015356896453651014, + -0.631660152986536, + 0.09605047472892436, + -0.6523036618086911, + 0.0426558447049773, + -0.43198138602386865, + 0.3716128440681109, + 0.17596158309346843, + -0.43689795302522394, + 0.3780807766232722, + 0.15873650986532506, + -0.043617332620686455, + -0.11497066137413481, + 0.34275342187526514, + -0.4088639038009484, + -0.6480619156724277, + 0.25200336883048235, + 0.40496367459814875, + 0.3648887796832586, + -0.2630956390782151, + -0.2274200824337197, + 0.40300881319831794, + -0.13356562020093454, + 0.047905130376741045, + 0.3116538017188618, + -0.28405382557359105, + -0.2811804028617168, + -0.5278756566811791, + -0.49884206486601756, + 0.0200976790142261, + -0.22754874957043142, + -0.5726170571391738, + -0.5749138868639903, + 0.3653630964026572, + 0.26869731847248013, + -0.4204239958735741, + 0.10852002720658849, + -0.2539498022615469, + -0.5313364466785181, + -0.5879240876578267, + 0.2413362489807428, + 0.34387933929551895, + -0.6416572376762248, + -0.29341441394664225, + 0.07643589036838816, + -0.24039281732871365, + -0.21457119645037037, + -0.23458493837441952, + 0.29741761627041086, + 0.15547055154332545, + -0.47581606763544837, + 0.06927747479891988, + 0.1349853007253049, + 0.25836167847295033, + 0.20392263992088433, + 0.18988538936029398, + -0.1676230554474475, + -0.4502612111439514, + -0.5203744946699702, + 0.05965752299413518, + 0.37993586571213156, + 0.19677720999474568, + 0.1676932789182246, + 0.31888618768671784, + -0.02490643280755822, + 0.013766861093771565, + -0.028235705724191096, + 0.2838190305307855, + 0.14364340460929093, + -0.319731907583926, + -0.5457938527988482, + 0.022085683847610338, + -0.6759813492699921, + 0.4105152928188688, + 0.14358453295928253, + -0.009021595291106133, + -0.24917207201982622, + 0.11741804833801761, + -0.1182690070939948, + 0.07232743590071222, + 0.30280732731363746, + -0.6767976190059999, + -0.285807480702757, + -0.24535308798818567, + -0.19738134126689555, + 0.2634629839377549, + 0.06699581715084679, + -0.14386887812639515, + -0.2889742608026554, + 0.07046467474724505, + 0.248633227660087, + -0.026332131863720742, + 0.12094492479570074, + 0.23178170157388034, + -0.1699126976213733, + 0.06124239354639349, + -0.2267593331263329, + 0.0059078260855230935, + 0.21315737984056016, + -0.4471901574608582, + -0.19475160191459773, + -0.11831462192828501, + -0.22694553271542722, + -0.18534607383750934, + -0.6227495087712561, + -0.08738510962850266, + -0.14411269437231045, + -0.26657729086411475, + -0.36056601854627757, + 0.2858552718269344, + -0.4548404207867271, + -0.49480210116705425, + 0.33865195255253877, + -0.09113899542446957, + -0.12406632041227483, + -0.41430378834292275, + -0.09405261258956399, + 0.12171112419441066, + -0.5008336833338466, + 0.3939547905689672, + -0.5791517016952769, + 0.1120451565870314, + -0.0894229401345058, + -0.11399096343428472, + -0.1873463444075124, + -0.568826419299696, + -0.14530702488093172, + -0.38105367362362386, + -0.6996480830089274, + 0.4080425170377012, + -0.16608630683151893, + -0.5935446767100168, + -0.34049159638560916, + -0.44861492544816967, + -0.38425665097597805, + -0.4032192043461111, + -0.34523530247571743, + -0.4633456355860357, + 0.011489064467307686, + -0.0483356330073621, + -0.3094615462265505, + -0.13330689258801065, + -0.29559247689806406, + 0.29930621243554467, + -0.6363892977767205, + -0.440714315160433, + 0.39737327452523197, + 0.045783915018637655, + -0.020246350671528135, + 0.04028378136124289, + -0.316915104928069, + -0.37330480396736415, + 0.22430035614856214, + 0.18037131798444594, + -0.47864684193035434, + 0.3615981144806458, + 0.2130987603983442, + -0.08501087548508812, + -0.5403420131770174, + -0.5558499084520211, + -0.17173899376849833, + 0.22030841355945807, + 0.19957320807416912, + 0.19830016044889243, + -0.13906214919069737, + -0.5240253051159565, + -0.1094456386453716, + -0.10651080663313328, + -0.39812586802039546, + -0.6201083457409536, + -0.5401323989393012, + -0.4728360266352003, + -0.554017149010236, + -0.43216121922306994, + 0.12418729109324844, + -0.3402771946486799, + -0.20663778465383853, + -0.2604532370476781, + -0.13182524441070542, + -0.0399103864687812, + -0.1450267016587935, + 0.37378047808778414, + -0.3180168593554131, + 0.07905937898730575, + -0.48728968229779157, + -0.291267809916213, + 0.04893033148406911, + 0.026730612751951544, + -0.5509842369195045, + 0.05656212172082409, + 0.1648277193790536, + -0.6779935323912081, + -0.5408658055851551, + -0.36874584505842234, + -0.4670607344756499, + 0.05542097769210552, + -0.508484244283818, + -0.61977212214342, + -0.6549574958172303, + 0.34263331045164647, + -0.3831262390985364, + 0.04642080957526362, + -0.041184601795792974, + 0.40910521044993253, + -0.053209179150995434, + -0.1553290542643767, + -0.6227418387239141, + 0.2998434881838251, + -0.24994471191757106, + 0.0753639974678526, + -0.21721264175934812, + 0.0955446886577278, + 0.04630966206606679, + 0.3759992123060826, + -0.26109297667232223, + 0.2341393048076047, + -0.6457748124277681, + 0.4106949642528842, + -0.45434409928814834, + 0.01020715484166912, + -0.02245402256726936, + -0.04255656884314196, + -0.08105628241003526, + -0.5618229216573506, + -0.024617252535697576, + 0.1330892943147165, + -0.5637643226415225, + 0.23901106862442323, + 0.32147659174856635, + -0.4736307656403226, + -0.05896469357615597, + 0.12308500006122958, + -0.025874633945002, + -0.5935126580016412, + -0.2459112357374209, + 0.18541026322916276, + 0.19325340085531673, + -0.003777159934338803, + -0.07483984151224632, + -0.23595494809419038, + 0.24698409919385478, + 0.05751624671752542, + 0.37647196562920093, + -0.42540940778898667, + 0.09782289637624109, + -0.6911496814416684, + 0.13338215264500863, + 0.3897809538867464, + 0.35650377094651187, + -0.3114215293170992, + -0.25858836380894334, + -0.6211980999499416, + -0.5470792363604027, + -0.5888090557320296, + -0.21757415381812673, + 0.2001826695627852, + -0.3224972560538308, + -0.27211782069750273, + 0.119997246738905, + 0.11352255039942938, + -0.3642672674837499, + -0.3308233891672396, + -0.2054931896479329, + -0.2602147617611129, + -0.10352048346467912, + -0.45806781543636266, + 0.32033846919089004, + -0.07952911615730507, + 0.05587706903849665, + 0.3454867718532887, + -0.021610920520112264, + -0.3101199761257383, + 0.27383199431548644, + 0.21336618149615538, + 0.024872757020712233, + 0.3759184451533727, + -0.18045592205043115, + -0.07044529297506186, + 0.25107676631456777, + 0.18612335243600953, + 0.20614964796892488, + -0.19696506960646043, + 0.1575303068414564, + 0.041263384999260966, + -0.580373867765271, + -0.6652540535073357, + -0.30295944039902223, + -0.5373827300483375, + -0.09066443222842713, + 0.39648254222729895, + 0.3050508701957272, + 0.1229558106676889, + -0.07282467934386161, + -0.4465685918323448, + -0.6596494019542574, + 0.07664919913493995, + -0.2005485754868832, + 0.08574346724138326, + -0.6495236168435471, + -0.0019051870222935863, + 0.02663225155732385, + -0.6972190033890983, + 0.2853330617202038, + 0.23541626177743835, + -0.2795509863828774, + 0.2678115844187269, + -0.19387751544358556, + 0.2913089247095688, + 0.3987533569929341, + 0.39220908790358855, + -0.16544364529857103, + -0.07818953108029869, + -0.14339874697301025, + -0.09717077494765414, + -0.1451656269759004, + -0.05099853159166523, + -0.5411093669848995, + -0.5616656532215882, + 0.1285380678904443, + -0.5260133249154317, + 0.2941335668777658, + 0.40443400064439905, + 0.18189761414940375, + -0.3665034640485868, + 0.17656725986428445, + -0.1146201476288603, + -0.6360107094535021, + -0.4376142134731904, + 0.3206424310756987, + 0.17279081626549364, + -0.49979551797169625, + -0.07598237135822516, + 0.20764345692397956, + 0.1613211482410507, + 0.33759162894856465, + 0.2894042147299548, + 0.2748156819581019, + -0.3265044649512208, + -0.19747176911396003, + -0.1557487363014869, + -0.2360571325174421, + 0.0034331469169788242, + 0.041075503991554796, + 0.22082755595261638, + -0.08192849758012688, + 0.0509068645206423, + -0.6515950469938313, + 0.3436153757248156, + -0.07271448928714708, + 0.06371092308027415, + 0.11009566520390712, + -0.23264480976611296, + 0.15404741968283897, + 0.22949142422913216, + 0.15326286956537338, + -0.34279062695937884, + 0.2354172139854046, + -0.10071246356427954, + -0.6145416098246513, + 0.21316042394281576, + -0.28678783382476, + 0.026146850527199672, + -0.24665118745251624, + 0.38631290308770316, + 0.17482827816843605, + 0.3460416169037964, + -0.2959606680191245, + -0.4772246181186765, + 0.3419286362905448, + -0.21690704395230276, + -0.5778274508141121, + -0.21094133165382156, + 0.15427407415436178, + 0.17969051763552124, + -0.46423369653125146, + 0.032106740224706165, + -0.09897076893090617, + -0.1028960327088726, + -0.6594943345261891, + 0.05697201247149908, + -0.6840163007507484, + 0.2304267262702192, + -0.3718575947018205, + -0.3413936073644248, + -0.2313317615250125, + -0.623921750592965, + -0.23267819346905977, + 0.11365593949406883, + 0.019024192763240744, + 0.2649802128489045, + 0.3903522167368242, + -0.6203623642155469, + 0.2694314656785204, + -0.4588882906541262, + -0.24860406909856736, + 0.2757935617016457, + -0.5718460016596633, + 0.21776290070643245, + -0.13357302028371176, + -0.2508943132091021, + -0.5184423753736607, + 0.17309341178659166, + -0.544467791968306, + -0.3265647546279204, + -0.5835346870187648, + 0.10241592783672782, + -0.6206911405329482, + -0.30125968866173575, + -0.6337568450829592, + -0.10148051273774505, + -0.6650426159299978, + -0.23991494110366363, + -0.2296149051248782, + -0.19744646309698477, + -0.5094693480722075, + 0.16998956704446877, + -0.4982482140573036, + -0.43444926031004544, + -0.5387045387283642, + 0.04565163155361163, + -0.34253205741892256, + 0.24982194996233442, + 0.1514239616385492, + 0.05550276437242874, + 0.3298115670948464, + -0.25440796235642177, + -0.0024990480477787846, + -0.12442228481610706, + 0.3620647810614651, + -0.6171493235214381, + -0.26147032184442914, + -0.056808902890622015, + 0.1872370291667581, + 0.24980156099024575, + 0.16239811230914358, + -0.4139149301788422, + 0.1871920273503226, + 0.3143447818358328, + -0.2755170512555405, + -0.4782417335180831, + 0.31451870489080525, + -0.24777492183916133, + -0.08965234665990462, + -0.6921914970411689, + -0.11077108444373285, + -0.11232954656756022, + -0.23533036279975145, + -0.04911328057993769, + 0.27423865000260406, + 0.0847132959717265, + -0.32421053100148317, + -0.46409008566279664, + -0.14317664687541043, + -0.42648928886740767, + -0.4368873337720011, + -0.21574471159246889, + 0.11768748355991476, + 0.017481654576792294, + -0.35977944317332533, + -0.6107184286149726, + 0.32926245184627045, + 0.10630897458825128, + -0.13417366924446872, + 0.15040527162766082, + -0.3237122970709297, + -0.5492367091095269, + 0.3944503791905084, + 0.3290620009209734, + 0.3729194007950133, + 0.2234175648861576, + 0.017627634124435243, + -0.06126335378238701, + -0.6085433614182345, + 0.10362404423108984, + 0.12760054983052704, + 0.39777602147665914, + -0.661169209227987, + -0.6521204557040461, + -0.27848621414284824, + -0.2655841861319928, + -0.17619201238627558, + -0.6273145539170503, + 0.21960422267676116, + -0.4580249516146483, + 0.19388112250666512, + 0.011865186866219513, + -0.4503397530094397, + 0.04610455622331433, + -0.1141191380566906, + 0.2859562963164126, + -0.04429447478392212, + -0.2044465648913837, + 0.2570389591160471, + -0.2753119691856715, + -0.22131366453282048, + 0.22366608344607486, + 0.3242904951747819, + -0.30072148417736194, + 0.18331122904011987, + -0.5147984223919903, + -0.020849753613564448, + -0.12077943607548658, + 0.38946788506999586, + -0.19087582525468139, + -0.3609884155446149, + -0.12216217603163071, + 0.28886013690587664, + 0.025279497994258326, + 0.08254666525581233, + -0.5102191208547653, + 0.07197196213595558, + -0.24384945104984096, + -0.7009851414391722, + -0.6252699172804517, + 0.11873984208830368, + 0.01613209437649865, + 0.1283891469277907, + -0.05952686709854482, + -0.11819483998199731, + 0.008608448565376903, + -0.5812963233014652, + -0.5865959871234783, + 0.1713361578904723, + -0.47305693596154574, + -0.42936633257742046, + -0.39658838722777223, + 0.39728723922061315, + -0.5258169010176574, + -0.32713637361626896, + -0.12249009349920781, + 0.25305175074723985, + -0.42187515052413327, + -0.00915114149171603, + 0.08365996515421814, + -0.37332652580144776, + 0.3440111400282434, + -0.45291991264026543, + 0.16547343099820622, + -0.5383509097807867, + -0.2106945770362772, + 0.20478192188594535, + -0.6838953268588376, + 0.17237430936210318, + -0.004803717677004382, + -0.6589216406222613, + 0.03214992821654661, + -0.0899805770192611, + 0.14529760662012958, + -0.6369962405226597, + 0.1640236864368685, + 0.14123606018932633, + -0.5934369124330982, + -0.6416567890607894, + -0.4741389139854191, + -0.22419374333345182, + -0.06406593979856456, + 0.14890912541464585, + 0.30048803893202247, + 0.05990674358443593, + -0.47113395905332145, + -0.6275330675059889, + -0.08381949566943292, + -0.6649752723731811, + 0.3497175347111191, + 0.12451389060614859, + -0.4175519845617205, + -0.3210061814569436, + 0.2971603482075912, + 0.23773065114879288, + -0.622676941405624, + -0.5578476157388252, + -0.5210743951166458, + 0.0316005536395455, + -0.11679254364874359, + -0.2449413715948462, + 0.16966224025299792, + 0.32348225876061376, + -0.5866170459475738, + -0.3704121444600715, + 0.04575758483181547, + -0.21302158988415504, + 0.3852247602186504, + 0.07574934846186321, + -0.6172560749565591, + 0.1158628244125125, + -0.5683563874869924, + -0.6569491242360732, + -0.6066107672933807, + 0.08969282762038044, + -0.20482849337447456, + 0.009727061816361515, + 0.12593585685700803, + -0.06919574188043098, + -0.2661580319241996, + 0.2005748500259611, + -0.12930917409285514, + -0.3968361018601329, + 0.08720962720307235, + 0.3390702015980004, + -0.37037205169847787, + -0.19588590088234803, + 0.34043653405859875, + 0.23493310991755922, + -0.4404500846164749, + -0.5256729098901587, + 0.16367911175098893, + -0.3567572778746506, + -0.6155294445843643, + -0.6738374938608104, + -0.30964007183041903, + 0.2045836685346717, + -0.264846545519427, + 0.254638905457537, + 0.31818263306030803, + -0.04232141068019013, + 0.06680324495569645, + -0.043887485220784894, + 0.05723872591587775, + 0.11393918243242562, + 0.3182164982584329, + -0.23315234938237345, + 0.29860867741379826, + 0.3672004442748179, + 0.12135402749513324, + 0.3886939713393661, + -0.15270301468237768, + -0.11304962605391411, + -0.28766706591810204, + -0.13675657781553885, + -0.10728408881936713, + 0.10880849382191404, + 0.09011236356263386, + 0.34103799086732545, + 0.1783637173948961, + -0.0915675203878007, + -0.18522823278975542, + -0.35143477834920295, + -0.6962724296983454, + 0.2739252519634289, + 0.22064776724160762, + 0.07253593711565398, + -0.5996961243223382, + -0.3951891678863739, + 0.2497372290933091, + -0.09967348952773047, + -0.47093335327001384, + -0.5245172731248087, + 0.11241098601259647, + 0.31503264093297345, + -0.3828757407245425, + -0.18430373033861835, + -0.31925054642308026, + 0.22484034365136296, + -0.16230874311950438, + 0.3040454414977277, + -0.11828091620023795, + -0.4848673760692611, + 0.40108502108112154, + -0.6465561179277449, + 0.3070332981347682, + 0.04314869937982624, + -0.21113362158334287, + -0.20435014723213468, + -0.4592787903585677, + 0.13500893249553259, + 0.005329600947600044, + -0.0855494611781672, + 0.10353348761916759, + -0.07657117362458521, + -0.28580842010750673, + -0.46420384487255695, + 0.3204503822325996, + -0.578846114859754, + -0.46686873467336965, + 0.1711552147102573, + -0.5190988932379159, + -0.06415506513892932, + -0.34783111285835855, + 0.23056123831209274, + -0.15385013772698808, + -0.34979098309682627, + -0.15742267235312069, + -0.5326103324336655, + 0.14940891596222305, + -0.6547314938285037, + 0.3862088556454869, + -0.6368625834966648, + -0.45711769438592376, + -0.35822912019741426, + -0.46554056518816367, + -0.34740117732789483, + -0.559408238150501, + -0.20260426865600845, + -0.6782972872330755, + -0.2935828740410166, + -0.6965607476490742, + -0.5686740588738385, + 0.07078529128906774, + -0.0872960559883893, + -0.2401004132301715, + 0.03315585586036485, + -0.4889865650555344, + -0.3534338036020074, + -0.5516616770355063, + -0.43739780023310915, + 0.01151093822344873, + 0.3613507846443972, + 0.14952412079431554, + 0.39792384835650185, + 0.14980868840331918, + 0.12388883966968645, + 0.10741629481753323, + -0.1741706053044434, + -0.5606669707154054, + -0.11137851735977955, + -0.4218145658694839, + -0.4101302878251631, + -0.42842879328871525, + -0.07061727112685212, + 0.03940076436401707, + -0.14283305391223133, + 0.01000186428182881, + 0.22680970478659834, + -0.03908622781270721, + -0.27906587008630035, + 0.02608311447212086, + -0.05490319059243598, + -0.08783520494736696, + 0.11375390218318171, + -0.1559339919662467, + -0.3768873443941347, + 0.3223000507683703, + -0.07148951155649708, + 0.10827739330655017, + 0.1308382122448578, + 0.4135876389541445, + -0.0301817273058419, + 0.19154752780506124, + -0.6360912775650034, + -0.4618618144958348, + -0.5968473311362548, + -0.6541280455644194, + 0.07731697419631023, + -0.22730292570253086, + -0.2203774408622482, + 0.4005920547549643, + -0.3052937511308363, + -0.5874264960341173, + -0.27819662297174114, + -0.6948184570339313, + 0.08345303732513176, + 0.21911533273394723, + -0.6186280654628213, + 0.345549788909738, + 0.13303662024510743, + -0.2745451515132763, + -0.16029082875634482, + 0.2110568721281323, + 0.0670656467912365, + 0.40293838232818857, + 0.09040791485761968, + -0.6948103042194478, + -0.4852935567557928, + -0.39783124217264687, + 0.3093610853512053, + -0.6791126141761624, + -0.18889075592677684, + 0.10053376475880238, + 0.2755525754003266, + -0.5959042576221052, + -0.22665260556221006, + -0.2232646718012637, + 0.1269227168552327, + -0.2045514771271577, + -0.3862309253073136, + -0.379844719300621, + -0.5958573820484003, + -0.4861731209907654, + -0.23184159817666916, + -0.09542810494407672, + 0.20527696938232232, + 0.3872238830703648, + 0.027749177459926555, + -0.14288666094110347, + -0.302300928060849, + 0.3657185729632445, + 0.24193378588463998, + 0.30469290113314973, + 0.003110535108752144, + -0.3202601168521711, + 0.013181205478797087, + -0.48055790825622147, + -0.03296094469689359, + -0.4965356137210718, + 0.08170344364342641, + 0.2715038630909249, + -0.3064475521013764, + 0.24283807355759923, + -0.27438612582297534, + 0.3546878316987908, + -0.51289592413071, + 0.057416283448713634, + 0.22018850991744743, + 0.3933093352902214, + 0.4015303964118787, + -0.4774951132380443, + 0.26432613785409387, + -0.10270782571955528, + -0.32160131534140596, + -0.6649114106034167, + -0.13257152727522248, + -0.45893217951368426, + -0.18958709140757313, + -0.3700653072521123, + -0.5982688030522217, + 0.36631235094949977, + 0.05267973883841082, + -0.49238980862224635, + -0.6161537440190832, + 0.012676496945471682, + 0.08902359329176168, + -0.07797090646793436, + -0.49249755543218876, + -0.17320027113229752, + 0.10896550347735867, + -0.6857842400836531, + -0.3360196296363558, + 0.0300977379458911, + -0.05961270247359107, + 0.14336574561537496, + -0.6510847047047462, + -0.5734160525071198, + -0.5104270627453981, + 0.088163265426486, + 0.2844838671483686, + 0.3971243759594886, + 0.19514812247926927, + -0.6794025237075074, + 0.29455736633630125, + -0.3280161419731394, + -0.6944547533968399, + -0.5391079738772787, + 0.07719238699311326, + 0.3818631901873618, + -0.45017161100236047, + -0.19434744943181304, + 0.26360962870804183, + 0.030495246163896872, + 0.08988436447658044, + -0.11608775709870423, + -0.48815270749990125, + -0.10258702894428051, + -0.6292682365439597, + 0.061953231134804776, + -0.5582391222398491, + -0.2105867346729528, + -0.2975685442392724, + -0.5588779239117532, + -0.5789140338981503, + -0.1413083145473677, + -0.5992837910273031, + -0.22850602171263845, + 0.13009327170539675, + -0.4100621368968362, + -0.23598751895348724, + 0.2566616503556125, + 0.15425537015241209, + -0.6432655910105668, + -0.5634154172391994, + -0.31310327434819185, + -0.15288374710874508, + 0.31309377622501644, + 0.03946272589916422, + 0.1959986095061783, + -0.22750277162387333, + -0.08867101839050229, + -0.24203285277607334, + -0.010288225537806173, + 0.026184544971059043, + 0.2513815549592737, + -0.16465921056583577, + -0.04489536460983601, + -0.49926714020972, + 0.18712710164508395, + 0.19017957563778976, + -0.19178374156495293, + 0.16063180758888462, + -0.3051528296022699, + -0.5994401978733453, + -0.08822470620446121, + -0.5030305607730285, + -0.590363915439653, + -0.5014212174041723, + -0.1986198737082122, + 0.4674341763213764, + 0.5420539254124901, + 0.6592297266575421, + 0.5854804768496131, + 0.4814109231505225, + 0.5968451636416069, + 0.49724994961467, + 0.45393034879827526, + 0.46420408278652936, + 0.5786667059747963, + 0.5482856830996818, + 0.45311037699689055, + 0.6329551376367797, + 0.4503970606016457, + 0.4970653963144162, + 0.5473317764589749, + 0.437433663959741, + 0.6466785274965814, + 0.4387169203306303, + 0.5158488524542507, + 0.53834467537197, + 0.4237198871442378, + 0.5562653945485598, + 0.48234664138791855, + 0.4310140861443698, + 0.5161866451388599, + 0.6705797088465225, + 0.6635927109837054, + 0.5657025820459678, + 0.43990605064036437, + 0.5447922135671159, + 0.5128185932154441, + 0.6139164044922971, + 0.6295666084212204, + 0.6252293339229402, + 0.45805690578781, + 0.6728871939488039, + 0.6371982348459604, + 0.4325571584564463, + 0.5649773318188582, + 0.6066228428533091, + 0.4842970972681528, + 0.544325991396472, + 0.49035140711189273, + 0.4881521436673356, + 0.49951306927280253, + 0.553922728735075, + 0.5744456724886463, + 0.6457402089616897, + 0.6461266313983803, + 0.6071165634338314, + 0.4428488166561421, + 0.49097219162779027, + 0.5248129395584047, + 0.5609669936393582, + 0.6202585732635575, + 0.5549609951727332, + 0.6434968126163341, + 0.4717700910010644, + 0.4622894639969762, + 0.46596289541145924, + 0.4606328975354214, + 0.5871612878632104, + 0.5003142443693706, + 0.5699028167349656, + 0.5567525269586613, + 0.42032873675461446, + 0.5107086455953256, + 0.6418421234304174, + 0.5821544141926375, + 0.5998706978314299, + 0.6180767518367756, + 0.6204710319529498, + 0.5351407799565968, + 0.5945321660719296, + 0.47319540470538746, + 0.4768291388132557, + 0.4916087049839365, + 0.46270210890112107, + 0.6283933624108718, + 0.6455819248323083, + 0.600774144960079, + 0.6637616352190279, + 0.43567076458528214, + 0.6698077905323113, + 0.6272490780230322, + 0.6192515897705617, + 0.5751034647710036, + 0.5306808771696223, + 0.6341170923108062, + 0.48823873223823955, + 0.5553381069482131, + 0.5873864692352018, + 0.6137400023958357, + 0.6388798569829655, + 0.5268776181996615, + 0.5790273719927985, + 0.49859522613550966, + 0.541676872292598, + 0.5435862409332185, + 0.4322580337265353, + 0.6375096037115525, + 0.4913826363881254, + 0.6270851468393341, + 0.4713055797897616, + 0.6086388710755517, + 0.6738544758785563, + 0.6273834067799136, + 0.5299242359599197, + 0.4185170508297353, + 0.42629337297357256, + 0.6009538437943178, + 0.46343094614600383, + 0.480090753612673, + 0.6137292058244812, + 0.5238609273917348, + 0.5376337436426795, + 0.4903966607112131, + 0.5629602891382564, + 0.5344678607474925, + 0.6470802906438068, + 0.44145423874008993, + 0.5137751870198444, + 0.6071829567715165, + 0.5849688191484499, + 0.5134027979476665, + 0.6589815436306298, + 0.6181359242961386, + 0.46622850013023936, + 0.485660603603865, + 0.656837806785233, + 0.47129707118819175, + 0.5785014593256994, + 0.5829290204447165, + 0.6363068499710567, + 0.5516715474407697, + 0.49894813318551334, + 0.5364074264462153, + 0.5917885480902132, + 0.43206857612983, + 0.6619359755278256, + 0.4533190912626591, + 0.5431263405192199, + 0.4684189196812743, + 0.5084915713784353, + 0.6475651262767762, + 0.6652630971623619, + 0.5863526386546289, + 0.6423468283177979, + 0.6387400414784019, + 0.553544037358878, + 0.6373717298973551, + 0.598029654470537, + 0.6124620335032895, + 0.486265263537652, + 0.6276416994944343, + 0.4528997455854161, + 0.5303836096925258, + 0.5044821499958442, + 0.5092692358823151, + 0.5726805590580115, + 0.6335271290916902, + 0.4241148029465642, + 0.4780602779789711, + 0.5072332078915623, + 0.5191800771344939, + 0.5724648631142694, + 0.612863592602764, + 0.6277706863449661, + 0.6632572619091675, + 0.59693698069152, + 0.48264443024691134, + 0.6217871835245562, + 0.4603932297992795, + 0.6378757448159743, + 0.5708742127239732, + 0.5933162155407821, + 0.5312469616720906, + 0.5536957072885555, + 0.54739378068374, + 0.48445231689230145, + 0.5624147089672218, + 0.6078568365008923, + 0.4825955879780662, + 0.6693824134462376, + 0.47636603166118446, + 0.4484346637060803, + 0.6755027522673198, + 0.6177921169122649, + 0.6272692539896341, + 0.5987343924869968, + 0.5154118011137121, + 0.5983099014952165, + 0.6153692731627101, + 0.6557152967381263, + 0.5000312128320163, + 0.6652113904471284, + 0.6030795275788443, + 0.6141460927313582, + 0.5596860648756049, + 0.5986120659397449, + 0.4938560091402009, + 0.43611913108881867, + 0.4604517949176197, + 0.4831728469942052, + 0.4431966092629867, + 0.5939472825240782, + 0.4507265169883076, + 0.6093587427518725, + 0.5877218469912404, + 0.506862149538697, + 0.44875066157406884, + 0.45793502707155687, + 0.44018529949796653, + 0.5747793625136739, + 0.43780860214042805, + 0.5168085693089912, + 0.5177196288272081, + 0.5753105160022003, + 0.5550097232181904, + 0.658670668989513, + 0.6412177982605612, + 0.6363457484815642, + 0.5441510189587092, + 0.6391900608686572, + 0.6628996788158477, + 0.5092460055640639, + 0.4269143745623648, + 0.6196651356259205, + 0.6459335364176745, + 0.44829797076625866, + 0.5874476980210436, + 0.4355172928207225, + 0.5857464389304033, + 0.6257229477761885, + 0.5402125738029191, + 0.545033901184193, + 0.5789129866985342, + 0.5618542838145933, + 0.5650437496370394, + 0.649463024840668, + 0.5001375683699432, + 0.5644436729684134, + 0.6375428618366663, + 0.479873358716355, + 0.666690606763042, + 0.5586899761155781, + 0.5102896243213139, + 0.4871096235525132, + 0.6662316912678525, + 0.5867457709534064, + 0.5096122707420818, + 0.5716197095420408, + 0.5728833804978186, + 0.6234064657056231, + 0.632506733294896, + 0.5162603772324839, + 0.43240642629512893, + 0.5232507375925354, + 0.4413740695940175, + 0.47473683721702387, + 0.46260772811086376, + 0.5005001136640667, + 0.44466623412770256, + 0.5440041953792338, + 0.6349124654651287, + 0.5067243679449225, + 0.6079328908313011, + 0.6098422021380696, + 0.5203166339105789, + 0.47830199358630826, + 0.45774294798397025, + 0.4543537085994652, + 0.6192850808867276, + 0.6072018255973984, + 0.582415733264982, + 0.6591135687365302, + 0.43013296933404804, + 0.6611612798312771, + 0.4608300231577807, + 0.5302160104179617, + 0.5742828627181795, + 0.5114470451444928, + 0.47722002575039596, + 0.4548626274263117, + 0.6755338194513842, + 0.4808852534612501, + 0.5148757705475746, + 0.4618716651854826, + 0.45882295866173944, + 0.43901741592278787, + 0.4976841969086656, + 0.4969383729193578, + 0.5617863189905521, + 0.526147200553068, + 0.6746423409128466, + 0.637026250750818, + 0.5519024899065211, + 0.4621954487004976, + 0.4940214557858542, + 0.5567403779212075, + 0.6066172152983637, + 0.4469046398113415, + 0.6303672365409566, + 0.6242109158697227, + 0.43963584001535283, + 0.6073521735964696, + 0.6023206259789691, + 0.6198291620618346, + 0.47345742615969566, + 0.5808314407049127, + 0.543856035089381, + 0.4479777356959779, + 0.5582756281494973, + 0.5333009532395458, + 0.5392503750666627, + 0.6609673750274927, + 0.47222590900279227, + 0.49822181200771054, + 0.5246788981030743, + 0.4907467701990235, + 0.5344993101031748, + 0.5207077781790682, + 0.44820035088293625, + 0.6356289429921735, + 0.428794984633122, + 0.5092204756292538, + 0.5550165650600659, + 0.4878467897512861, + 0.5481512364533279, + 0.6490387208519751, + 0.6142522963459744, + 0.5681194759730086, + 0.6523598408438566, + 0.6162133672763177, + 0.5980931318354286, + 0.5300801427588163, + 0.4449509351319563, + 0.6495949224115514, + 0.624523581527455, + 0.4267829730087652, + 0.6739838427727136, + 0.537087567959511, + 0.5260912283935472, + 0.6580756308366497, + 0.49379574910455, + 0.5118671424057131, + 0.5143842695839108, + 0.5968359604979185, + 0.4903147619495039, + 0.426353220820696, + 0.48100389056871146, + 0.6412272748665911, + 0.5039418924416001, + 0.593059743805683, + 0.5172139896766281, + 0.41805614351155274, + 0.6668549030229215, + 0.5860977381158725, + 0.6193758666218552, + 0.6259995315491169, + 0.4945796260295595, + 0.47476218278318305, + 0.659340519794962, + 0.43794492472360436, + 0.6584120792430973, + 0.510278343279303, + 0.652383386428919, + 0.543194744166043, + 0.4378219580126148, + 0.5545379177842602, + 0.4509108812766529, + 0.5349174735624004, + 0.5590099771288486, + 0.4659969989812755, + 0.4512414902444197, + 0.5229388545205581, + 0.5522562967315601, + 0.4944579321542084, + 0.49954040175028336, + 0.42260084774210793, + 0.535478877603105, + 0.5654419149660532, + 0.637299695366859, + 0.44363237931573024, + 0.5367145887785808, + 0.6657175470221559, + 0.5559006083277793, + 0.45671693217298587, + 0.46072377246816243, + 0.5135420401415893, + 0.635449404650353, + 0.5284221266102663, + 0.5178584456800421, + 0.5725892351959766, + 0.5031541234669046, + 0.6660879707831288, + 0.6120825610936936, + 0.540279015316429, + 0.49698426958480535, + 0.5681084827292692, + 0.6242695470492894, + 0.5004299909380394, + 0.4911390948434139, + 0.6146715073487065, + 0.55831824583249, + 0.4530114202312831, + 0.6074640156675691, + 0.6154723334975585, + 0.5992437267567092, + 0.5118444927209195, + 0.6283648455708937, + 0.6065177420655278, + 0.46293005558901834, + 0.6079104676796193, + 0.4905071190629247, + 0.5809906722310887, + 0.5491141956813124, + 0.42693913508435594, + 0.5757808984693259, + 0.5933289293301643, + 0.5337690468070537, + 0.5029267749863433, + 0.49495197582147576, + 0.46932371621092445, + 0.5553520309874104, + 0.6479767893792774, + 0.5527798189064801, + 0.6580148650543524, + 0.6280504213483815, + 0.6040615507824502, + 0.59644808902457, + 0.582694170009862, + 0.5090873256690353, + 0.4400596334284925, + 0.4477188554731578, + 0.5054266040410771, + 0.5581628811547719, + 0.4972822158008782, + 0.6084524728223781, + 0.5739500047084555, + 0.49035666176462783, + 0.5529514783696118, + 0.5914075485909807, + 0.67538983994488, + 0.5085965980809788, + 0.6598147482933657, + 0.4323444705298839, + 0.6006428520722422, + 0.5104499544818366, + 0.6485151376015932, + 0.5430976610091469, + 0.6295449660364517, + 0.5160014050230306, + 0.5006802266816713, + 0.42694010608997185, + 0.6518422696735923, + 0.6178595319228681, + 0.574400546808636, + 0.5434669180298011, + 0.6348719999659375, + 0.6557729701444659, + 0.5308184761792736, + 0.5438604286220285, + 0.670718384776195, + 0.5648205975790153, + 0.4936802868389032, + 0.5345356453523964, + 0.5082343438184401, + 0.4256772287290611, + 0.42313292557439397, + 0.5534458900307653, + 0.4637613242904179, + 0.42245048697166454, + 0.6137144377265251, + 0.4443069326420005, + 0.4854204463696326, + 0.5548749924915477, + 0.5117667170937367, + 0.5520638033094771, + 0.6147898175442287, + 0.635558991637625, + 0.5638572141945352, + 0.5726952390369426, + 0.554019410858893, + 0.6660878663830436, + 0.49525214539391577, + 0.48122107825086635, + 0.5545453482986078, + 0.6699492737816963, + 0.46298672522318196, + 0.6181151958340659, + 0.47436316582025223, + 0.43190500387274167, + 0.49250479253910995, + 0.544271454701356, + 0.6522463641201073, + 0.6163910589755587, + 0.5147275692168303, + 0.49319296504151217, + 0.5826684057187235, + 0.6358197294702331, + 0.5416214821298686, + 0.48008651016909015, + 0.6492073439181617, + 0.42260679640309556, + 0.629989037448212, + 0.657301084041479, + 0.568209486180431, + 0.4414560414393055, + 0.5690979973178488, + 0.5960454510633756, + 0.6194414836411287, + 0.5996675085902231, + 0.5659518667321599, + 0.5920103853706724, + 0.4782864198700212, + 0.42433335482101275, + 0.48200220370967994, + 0.542006012436168, + 0.6528009301820393, + 0.5783767757057955, + 0.5844413306523676, + 0.4833647160938334, + 0.44802212903352523, + 0.49897850432777724, + 0.5591149050428208, + 0.46980832959847457, + 0.439571297950881, + 0.4425393646047051, + 0.5617388586522751, + 0.5606384545821183, + 0.5172761885184596, + 0.508167321155661, + 0.5879132274373654, + 0.5630636760015889, + 0.4324909571409352, + 0.6482877515917723, + 0.6485141465843491, + 0.5687386034094687, + 0.5963949691482113, + 0.5540623417330249, + 0.4913978077860422, + 0.6703478840071713, + 0.4239707351098261, + 0.5414781637621419, + 0.46200382199042805, + 0.46959732731481796, + 0.6682323587124259, + 0.47777509237291915, + 0.616197645822351, + 0.5234640937327312, + 0.5771979044100117, + 0.48296402334032085, + 0.6164329989352109, + 0.559319139680866, + 0.5308791411211339, + 0.515439663645697, + 0.5048692606389887, + 0.4629599611853106, + 0.45709006519684237, + 0.5863408436316522, + 0.5995111692390515, + 0.5325912025738845, + 0.46571514226584776, + 0.4645205022145728, + 0.6626921631154359, + 0.4956096452516222, + 0.6363658570803743, + 0.6259934689140431, + 0.4672119219842729, + 0.6354801934164509, + 0.4658848982233089, + 0.490143462549298, + 0.630832754206834, + 0.6295022271715566, + 0.4183133435139623, + 0.4394573718827477, + 0.6253256453736712, + 0.5066543444149957, + 0.5640987317517786, + 0.46459011771453634, + 0.5391808433292018, + 0.630317392074155, + 0.6127850156161817, + 0.6718477340803675, + 0.47369257588793445, + 0.671774511182929, + 0.6213649958364811, + 0.4977147230668319, + 0.43196644223391584, + 0.4539048669829134, + 0.5044513969340377, + 0.6223531856936368, + 0.5969851060213449, + 0.6387359682751598, + 0.5200566786879803, + 0.6741139580538985, + 0.5031870913222498, + 0.5977819975392813, + 0.45161147177961325, + 0.661539033866589, + 0.443463423655722, + 0.6665255594659715, + 0.5951801329211788, + 0.48991668043948833, + 0.447779161777201, + 0.4518130371510692, + 0.5771734806227231, + 0.5352156895484459, + 0.6529724505636997, + 0.609706311695312, + 0.6368094450169708, + 0.57061860671665, + 0.5363294529881435, + 0.5476732687367042, + 0.5049232879704582, + 0.5354317975718653, + 0.5969427210416507, + 0.515640823052235, + 0.41946604920977787, + 0.588414875139128, + 0.47778498623130344, + 0.45355246383195624, + 0.5174364529938532, + 0.5103880933737921, + 0.44219083044836777, + 0.666088145962821, + 0.6636074473146492, + 0.47692222799914374, + 0.5531799909043248, + 0.5892951974429909, + 0.5099706764790207, + 0.5019580338566951, + 0.496291300817115, + 0.6505870336262342, + 0.6303055002836201, + 0.5693481895682326, + 0.4879705337596449, + 0.6162250251297505, + 0.5060599454742185, + 0.6538239031658255, + 0.5294589090201278, + 0.596048650801392, + 0.46065211206608214, + 0.5064747000639123, + 0.519756707501114, + 0.5230382341445254, + 0.4265381017881242, + 0.5711022311577458, + 0.4580142332496942, + 0.6066429683197547, + 0.49988193691533445, + 0.6260095292394353, + 0.6519887232604787, + 0.5155227839390981, + 0.5684884589987342, + 0.4287088279202834, + 0.4430293232641885, + 0.42864910317231464, + 0.42049372693034714, + 0.6386880677726037, + 0.6481255254149257, + 0.6463798863001994, + 0.4823740068732457, + 0.43813463359681787, + 0.5601313373000347, + 0.5400181105609843, + 0.587949024132556, + 0.5196521931801825, + 0.6581302715139099, + 0.6271071806054245, + 0.5013887453467445, + 0.4632093410296341, + 0.46540538117004604, + 0.4914114598829813, + 0.6386123043736134, + 0.4339543722102577, + 0.461623257364374, + 0.5327916612677219, + 0.6638736222104763, + 0.44228600781562605, + 0.5291009279315599, + 0.6743111761160566, + 0.44154997114073724, + 0.5913732340101286, + 0.5484552104563477, + 0.48787862176150787, + 0.44242148419505, + 0.5435470815513115, + 0.6568735566958117, + 0.6659740812263231, + 0.6625704412419343, + 0.675531448570769, + 0.6180454610888914, + 0.6278516479889766, + 0.6551603866001334, + 0.4485778099331271 ], "y": [ - -0.21526389852559014, - -0.5668076639655169, - -0.5634771243075074, - -0.48026675530570584, - -0.6105894952396467, - -0.528834561488468, - -0.20427884154503073, - -0.5816803609518845, - -0.38153783025719773, - -0.26948606942401004, - -0.3688975289296914, - -0.6359853003634688, - -0.4273868730430644, - -0.5410618594727711, - -0.4822991775856031, - -0.6000760136419334, - -0.6770172204223297, - -0.5926089720797051, - -0.28325039167604055, - -0.683727001977012, - -0.6944325720112785, - -0.6365672449941226, - -0.43759186533026323, - -0.6873404885026364, - -0.352291894934858, - -0.6763138774698857, - -0.5344870490104631, - -0.4933794028262368, - -0.40168449364987546, - -0.4767620474605535, - -0.5820975451679147, - -0.3719557442925087, - -0.1920500774993632, - -0.48413852968543436, - -0.23319737468354235, - -0.4183797692069673, - -0.24198083019339367, - -0.5927015932220178, - -0.207306658457523, - -0.687267235706826, - -0.3615524586386805, - -0.47580236234233897, - -0.6482327195215988, - -0.452071335970582, - -0.6794329073406332, - -0.4821681731735029, - -0.3847862455731721, - -0.4585895152390683, - -0.45076666032736185, - -0.1991435229227715, - -0.48437694622178884, - -0.33567761675735586, - -0.16806080974870896, - -0.5854997920723012, - -0.2634266711000602, - -0.6938328365839215, - -0.22022443093669347, - -0.30228225474968207, - -0.473697779730351, - -0.58787501791053, - -0.5747254730815081, - -0.38661090618840144, - -0.4525455738154044, - -0.4852154042526807, - -0.23677108072346942, - -0.5797875050219646, - -0.18960332581143713, - -0.31879215386083337, - -0.2985985193227354, - -0.2479027929285229, - -0.5827320173700912, - -0.3999983089263434, - -0.4384505056865782, - -0.5340810194978354, - -0.14889848273296136, - -0.20716787374985596, - -0.2787442085683768, - -0.1563407697324456, - -0.49365811430562745, - -0.32840489438635656, - -0.4019233308894716, - -0.5800464504993721, - -0.5899015543940788, - -0.6767687635138475, - -0.631705445060666, - -0.3639690707391558, - -0.6283145227777176, - -0.6926201922318653, - -0.4047761496992247, - -0.29614722338752864, - -0.36597979137400555, - -0.6143579857897379, - -0.3592793920823914, - -0.32491271118632864, - -0.6196178613765617, - -0.4905221061569761, - -0.33380004107977485, - -0.34315763094612356, - -0.5730476283140317, - -0.6643791833063918, - -0.4264024723664032, - -0.33960041049174966, - -0.492063563260129, - -0.4518432963066661, - -0.2675590447170642, - -0.47652769182442584, - -0.404460528825577, - -0.40694422283870973, - -0.41866840777093767, - -0.25018158548965436, - -0.3357983193142373, - -0.5119608139525116, - -0.6681389534446313, - -0.4408080929682888, - -0.4296174160693305, - -0.2938403216717465, - -0.298562915938461, - -0.6317950609868391, - -0.4750925677047576, - -0.27754328064793027, - -0.586251582786329, - -0.4034006634826291, - -0.2085841995495269, - -0.2528736251079428, - -0.5484941371120031, - -0.30737080385583193, - -0.3636011409672178, - -0.2374230498058933, - -0.19262544839201212, - -0.2834610648409034, - -0.44176606352562237, - -0.1918394285970243, - -0.43286957130061177, - -0.4705464574790802, - -0.34202151998338487, - -0.2526122317428531, - -0.5101631075415498, - -0.35427361262068663, - -0.1967571490215113, - -0.3692962823049929, - -0.5881504015653899, - -0.3375595528846289, - -0.6708378352307791, - -0.401557770711446, - -0.41743562643710497, - -0.46038129349197976, - -0.5349823492938082, - -0.6874945543016642, - -0.6563036244778957, - -0.4758892941872483, - -0.526602158506708, - -0.4483941038098501, - -0.22575063111469196, - -0.6548952649401933, - -0.6819474994469957, - -0.6206292031472959, - -0.5278033730711778, - -0.3009303163088597, - -0.3912521604400618, - -0.35925670973255514, - -0.28785858027739386, - -0.24724224644536702, - -0.2865296059429153, - -0.196947494232949, - -0.589686853160144, - -0.4610229225374262, - -0.1736911509707474, - -0.27532794151000023, - -0.41935496010648254, - -0.40572664365236993, - -0.5692365980756601, - -0.33879866076302506, - -0.26272847800110677, - -0.5338147495225387, - -0.6803796477431132, - -0.47537211473008084, - -0.2620982128161942, - -0.22017891924789823, - -0.20771787547936782, - -0.43420924228466545, - -0.16498457157702218, - -0.2581621050228022, - -0.1454445829635055, - -0.40493163856591646, - -0.3497626222582684, - -0.6669387057337621, - -0.15332366397516117, - -0.20220118991697822, - -0.17140112395010654, - -0.5531206214097724, - -0.4643250645739929, - -0.6914924877765393, - -0.2666324881832466, - -0.5959941759254339, - -0.5723506226473106, - -0.4624695345383819, - -0.46968615143340775, - -0.6841776754148233, - -0.2929798291387249, - -0.45360084646137266, - -0.482107802843161, - -0.42115711210480716, - -0.523466443078983, - -0.16261207265513766, - -0.43269337370900274, - -0.44559732225615695, - -0.6422268164721529, - -0.4118222177369574, - -0.36665277110116895, - -0.39444379843191585, - -0.6897154325228744, - -0.34720576594930497, - -0.31688817089183186, - -0.5974254940932917, - -0.2597430646311647, - -0.6832730519739092, - -0.49558725060429604, - -0.2949628534445622, - -0.6383697934051112, - -0.35082587597742826, - -0.37721775122359696, - -0.32429790138762615, - -0.6628125503876823, - -0.6400778198389123, - -0.5022114859398216, - -0.44303844712049234, - -0.6576644623407387, - -0.14643411893318437, - -0.5831059084612487, - -0.4962425709841234, - -0.550623437500016, - -0.5682074709905698, - -0.16399640304854746, - -0.47648103205835934, - -0.2564289749333582, - -0.1528424140155097, - -0.19632199326509925, - -0.3976044499503634, - -0.3000757872859389, - -0.4107578923456179, - -0.572738964594816, - -0.4137846489198366, - -0.49387164585427157, - -0.25431908461016905, - -0.37945759300107357, - -0.693098142425255, - -0.6802386498566139, - -0.4185696274767257, - -0.6151313078157574, - -0.3442992009357707, - -0.4030051152553079, - -0.6901212175319289, - -0.1432716503561745, - -0.4023586104529854, - -0.5073081512616008, - -0.35117845702744693, - -0.5317604096148164, - -0.21362812206555531, - -0.16106013241149564, - -0.3916748011481499, - -0.3900175220355754, - -0.2523033776073218, - -0.2700412497278186, - -0.5719202029435765, - -0.4083922406429072, - -0.39934528507908995, - -0.6564849371063238, - -0.5244731471824519, - -0.6865079030405267, - -0.6114530030712465, - -0.25984795905333063, - -0.3625635055872547, - -0.31102676273905766, - -0.378114672750309, - -0.5980100394047524, - -0.5781949044547483, - -0.23618236160344075, - -0.3097239051191674, - -0.541084740831006, - -0.2413716542441447, - -0.5897441132680863, - -0.3799479184436683, - -0.216198339124007, - -0.15108867157946704, - -0.30216525116452847, - -0.5296672053871968, - -0.20349831867406676, - -0.37936016840960635, - -0.32665207102851174, - -0.44969887389629115, - -0.2986271739828252, - -0.5381940276659318, - -0.26557750923869133, - -0.27628547754246796, - -0.6014320866232739, - -0.6431930955560783, - -0.6853213826411336, - -0.46303948132452366, - -0.5236232061363543, - -0.2977564361734746, - -0.2740990260203191, - -0.6490405780222896, - -0.14547515666218225, - -0.6565079025063754, - -0.14247642138476835, - -0.4820530838780044, - -0.6079928653208734, - -0.24367860757577908, - -0.19663664761583544, - -0.2587054844934042, - -0.18568213399400135, - -0.5407509619013914, - -0.19673958479260067, - -0.6845981032143993, - -0.535469369259308, - -0.308640245974398, - -0.6308214673251213, - -0.15075025473135373, - -0.6629058962552222, - -0.2525126583250521, - -0.6255636274305838, - -0.602940233259621, - -0.3418837154564412, - -0.3599463767937384, - -0.2410442171870018, - -0.5071444799436968, - -0.42695210225660823, - -0.46128592074875596, - -0.5271420319114182, - -0.25846378480455856, - -0.338942269624897, - -0.3410116652248729, - -0.3553896458484627, - -0.2905759460828277, - -0.2926982777546428, - -0.19887449151002784, - -0.6320599378707857, - -0.5280739919311576, - -0.29214462801341473, - -0.2780356973323652, - -0.4275590819297849, - -0.6383307253418019, - -0.6466171747590481, - -0.3340031366504746, - -0.5702213103495449, - -0.22505303767576734, - -0.3671116484287669, - -0.6054207810510405, - -0.420031359589941, - -0.379499748649322, - -0.3081047412189693, - -0.5367505933316209, - -0.6971347623405126, - -0.5931303716057673, - -0.5494212591825566, - -0.589403643143711, - -0.22474388174047644, - -0.4191637979037389, - -0.21597748027543934, - -0.4750092056413736, - -0.41955106140438175, - -0.28732072278240217, - -0.5578950366143984, - -0.36594348195377946, - -0.4131531695321406, - -0.5811303548892564, - -0.49217742205479614, - -0.3165246826326464, - -0.6717172886595825, - -0.2611963199866791, - -0.6926435457508168, - -0.4051750988732216, - -0.5926098417255232, - -0.4426878066118041, - -0.3334004634194424, - -0.42771737580572067, - -0.3053665745407606, - -0.36657545409079845, - -0.6448359294437067, - -0.6048529242382151, - -0.628107984162322, - -0.6750159797002793, - -0.3465327301974543, - -0.25998653918392, - -0.44068846209810414, - -0.31195135490012665, - -0.5020058399583776, - -0.6916932996558096, - -0.26801417982607595, - -0.6183877741494541, - -0.24050080972555438, - -0.47586362833497076, - -0.31891178653915686, - -0.37898477353438, - -0.3032546180342803, - -0.27653832305023296, - -0.19026067562873505, - -0.26374549012894544, - -0.6709847769421702, - -0.411481688211929, - -0.15188551584887333, - -0.41950245942357034, - -0.5019243673085719, - -0.5383071043729578, - -0.278176251237267, - -0.2569335776212289, - -0.23012739525959736, - -0.5399787461366308, - -0.4954275622120159, - -0.3924111088882546, - -0.5951346892481899, - -0.15488924095825074, - -0.19894128785068793, - -0.14210967616625803, - -0.6634260585760954, - -0.1557644811268185, - -0.151780585935401, - -0.5715693788390369, - -0.6668129805632896, - -0.4927382836273416, - -0.5331560896806996, - -0.6207281938645495, - -0.40998616806129257, - -0.17575056963284885, - -0.29204455698832815, - -0.6801102390920798, - -0.2737623077672693, - -0.3829516130918535, - -0.5066789535277716, - -0.6284986498822265, - -0.613332798463113, - -0.3727848619225612, - -0.5360828788602103, - -0.4490936462622829, - -0.15821449622659067, - -0.24919460858885628, - -0.2569732847429945, - -0.3739783187753656, - -0.19274127292350862, - -0.29896275981677606, - -0.5505679134937247, - -0.318422153150009, - -0.524366108518497, - -0.2230685936911586, - -0.3516054129096772, - -0.34831479887740413, - -0.3931438743717756, - -0.4113838389039835, - -0.348481892020182, - -0.33116247273639243, - -0.27381404807534315, - -0.5231041249280255, - -0.5564338163207172, - -0.6299229800416154, - -0.2922572879880402, - -0.17951107736091687, - -0.6817545607759401, - -0.45363046831042203, - -0.34078262402305515, - -0.14018493367950546, - -0.4165475408770349, - -0.18873748677678193, - -0.26783974569270674, - -0.49420726147940586, - -0.312212040789134, - -0.3749342414123156, - -0.6680995949541044, - -0.5571183834801717, - -0.5638040325165967, - -0.36391604952451, - -0.37113579085632836, - -0.4739371783977352, - -0.4238631070281471, - -0.6298405328983244, - -0.1580918643272733, - -0.5753149932180412, - -0.3490117719432422, - -0.3354510961509358, - -0.41836152855434783, - -0.6114392830450794, - -0.5249928169409083, - -0.33359454931440413, - -0.14752755064153733, - -0.5801328064105491, - -0.389248755068303, - -0.1689831288211543, - -0.29095640960435865, - -0.3195706283820997, - -0.431114520827856, - -0.5342721929452461, - -0.212032651559186, - -0.15415603315203164, - -0.4898222892229926, - -0.6929628487747368, - -0.3275227033999748, - -0.5518848588283765, - -0.4754478579992858, - -0.5020859362097194, - -0.24970925422517426, - -0.5048822864759303, - -0.5997158603045283, - -0.6305810898323154, - -0.4710465525642499, - -0.3780801672457604, - -0.5642305935303451, - -0.6448248328873669, - -0.6509345385694514, - -0.5055738228527857, - -0.6759089308247426, - -0.4341376317972618, - -0.4979962938144452, - -0.5534335936913292, - -0.1695733300971587, - -0.20093503708074772, - -0.34973724354073754, - -0.6201102597774513, - -0.524894814213295, - -0.5142690771066138, - -0.1976347607106237, - -0.3436386377606183, - -0.3866708034375136, - -0.5917315449239026, - -0.3828862383122404, - -0.324807375216214, - -0.4481373261158089, - -0.5104181225913832, - -0.19612045861830396, - -0.6302298270444524, - -0.2851023471325862, - -0.42585487874073336, - -0.13903618515835525, - -0.28204117658772154, - -0.3232620217995583, - -0.4254402957536574, - -0.3574483949969366, - -0.5147631788946414, - -0.3671369834156951, - -0.6179457967823929, - -0.6820634912356419, - -0.25103464743381904, - -0.19429802640801896, - -0.2421148271217281, - -0.3074977294767069, - -0.14629914981937242, - -0.6461038231434193, - -0.5392657261795686, - -0.6856062608603823, - -0.248821232560411, - -0.6295447746878674, - -0.35855468871349994, - -0.32595118284877644, - -0.6916699430775799, - -0.31843118428171424, - -0.5644172444210394, - -0.5224745560563797, - -0.2551302854369139, - -0.20366263744983742, - -0.2082549425044497, - -0.6055900822903126, - -0.38543355085502956, - -0.39121457488468175, - -0.6030594430125832, - -0.409117903323125, - -0.5444583898331984, - -0.6426906800337345, - -0.2729108758988388, - -0.3287708441741195, - -0.32268395319595705, - -0.24712079063986447, - -0.3319436822747706, - -0.28352778180933413, - -0.3752771401361604, - -0.6640189769906387, - -0.6554988828800513, - -0.41924848059225134, - -0.3689669503124891, - -0.684838599502534, - -0.18266170276580773, - -0.3532130609014225, - -0.6281099366846545, - -0.58586419311318, - -0.3463672386541155, - -0.6414604528214005, - -0.39700693589001823, - -0.6543091181565703, - -0.3676360593828759, - -0.2477704579369866, - -0.6464569756610634, - -0.20587532476586778, - -0.30200044151963434, - -0.44537971266126536, - -0.3698468235780297, - -0.6882188724555194, - -0.31356744361539973, - -0.6081118682218483, - -0.6582168832181572, - -0.17262397240079597, - -0.1750482521519694, - -0.673946497685395, - -0.18589488472975912, - -0.6189946761778354, - -0.3024088544350932, - -0.1821447568945752, - -0.31657674430420524, - -0.42197323163587297, - -0.3284406211197238, - -0.16759427563415463, - -0.27623083502459955, - -0.16868971941792643, - -0.16111398401434684, - -0.27286211932555604, - -0.6496231085951973, - -0.23639958094232083, - -0.5750648539804049, - -0.6532529026682433, - -0.36443315213387634, - -0.6317755106686144, - -0.19334902506191098, - -0.43234580707985015, - -0.33384611403388126, - -0.6590782843644487, - -0.4051135429593617, - -0.3993802361211106, - -0.20934639120672438, - -0.26036343626390257, - -0.4076810880921705, - -0.5640494691387595, - -0.15824715281175705, - -0.19309555180754623, - -0.496603453608641, - -0.2923507989025627, - -0.4077229723263429, - -0.2493675651583599, - -0.5219057715068856, - -0.3984074696982834, - -0.6380185678661527, - -0.6786718833505176, - -0.5422095737954773, - -0.49649805976072786, - -0.6863874299624693, - -0.15312843660300157, - -0.637425883555342, - -0.4646234246420048, - -0.36026506850437656, - -0.46943738393646794, - -0.43378376990406453, - -0.20259938533527183, - -0.4167326708937919, - -0.31765362466908925, - -0.6036113094828982, - -0.6212501267960631, - -0.23795504276512536, - -0.48468728297261976, - -0.427154398538899, - -0.4909307055213845, - -0.5366833759211845, - -0.2058673896910716, - -0.23083859492270864, - -0.5099728089446275, - -0.4301558344491626, - -0.4146446251518383, - -0.1925017743841252, - -0.24201710340933313, - -0.3574754138529278, - -0.1474919127293639, - -0.15498479924438313, - -0.4970964139123859, - -0.26159445162449746, - -0.5533337425859597, - -0.39367904145520727, - -0.3081020121407764, - -0.22989463890251166, - -0.29228789418034157, - -0.5741926606813325, - -0.23848503902486212, - -0.4212099552155242, - -0.48175897074175833, - -0.2603089259201685, - -0.6385885971099798, - -0.6167554980087308, - -0.4011681840005041, - -0.3776057864487809, - -0.19203432692152755, - -0.1611579471981487, - -0.5211993539249601, - -0.5703327222715054, - -0.41056885119204856, - -0.6379065009877873, - -0.4802789227250636, - -0.45362926785667257, - -0.20872328966312526, - -0.15234613770825933, - -0.3525975187184175, - -0.5405421331967066, - -0.2562911294408811, - -0.19903650822664726, - -0.6186608074966065, - -0.1787547020944268, - -0.23999653023017808, - -0.6607564471790724, - -0.6493217435833661, - -0.4148776422042736, - -0.36511243265594706, - -0.5318361811539778, - -0.30556364302553884, - -0.40346773825976523, - -0.49206555682146147, - -0.43056469437672035, - -0.42969308595376426, - -0.1687413298608209, - -0.5814275438027134, - -0.2817088681167917, - -0.3185795449213315, - -0.41030893124033296, - -0.4737656195460803, - -0.3634732939773591, - -0.14066154524726016, - -0.4247196984871438, - -0.6395794009272529, - -0.3193985000343985, - -0.39707617881551643, - -0.605997808538345, - -0.24528775988578672, - -0.3727088453191906, - -0.32422722892552086, - -0.6645838817776732, - -0.33161077759657975, - -0.6943719086347901, - -0.42981396248402126, - -0.407833582234277, - -0.4394836641311708, - -0.5425111707727563, - -0.14313297257858215, - -0.25524889556378483, - -0.3274263901361544, - -0.5943483338024255, - -0.18698872997545357, - -0.45637114953864333, - -0.5472940817143578, - -0.6004294398598552, - -0.6877489319621786, - -0.16149455748478714, - -0.5689182207153135, - -0.31276026047126176, - -0.6215294534594782, - -0.39306245407709844, - -0.38186275225540034, - -0.1651611109583303, - -0.1886630404089047, - -0.21742310544091997, - -0.5072004869150573, - -0.5550007647882751, - -0.3437308618101009, - -0.4938856435608914, - -0.547192252153401, - -0.35913905497508064, - -0.46102959264702015, - -0.40400689920897387, - -0.6620770786357651, - -0.3779663918555969, - -0.3418658168616246, - -0.5643773419256306, - -0.15976561493144426, - -0.6600120640419861, - -0.22721365797485488, - -0.2919887261296891, - -0.45674696880441124, - -0.4527505821808961, - -0.5509143897075601, - -0.33021304364910364, - -0.5038678565118776, - -0.26138011655526394, - -0.3758899645519693, - -0.5969630015851606, - -0.5990197183395755, - -0.37393423495960654, - -0.16030890169055134, - -0.5224869663086269, - -0.17481967232448647, - -0.3288132768025028, - -0.5800334295985337, - -0.636423907226603, - -0.603776975348596, - -0.24451667937931937, - -0.21660673619134702, - -0.44738234802994187, - -0.43023322979045825, - -0.6565112758369289, - -0.218700527106941, - -0.5877579146051259, - -0.42942422395522306, - -0.4776278052460776, - -0.4303073132324879, - -0.6665369885419569, - -0.1998827934250999, - -0.5323620121184691, - -0.16483334326821109, - -0.5331134171275932, - -0.3478633663983045, - -0.5915921264450007, - -0.3918446006761166, - -0.5070608827373838, - -0.38176391402943194, - -0.34978649117433785, - -0.15048750074661676, - -0.1670575693618317, - -0.42297967118637864, - -0.448773692741142, - -0.24474150774745235, - -0.5662797342358559, - -0.3057846651107648, - -0.46442069644261363, - -0.34058230388727384, - -0.17722098994241198, - -0.21565914783149875, - -0.39449398725191087, - -0.5766924963679653, - -0.6072703165380339, - -0.6616638030800411, - -0.45405897265235085, - -0.6345923885971902, - -0.6454373514706581, - -0.4332339371350891, - -0.33785076059054625, - -0.23889285934169113, - -0.16603758340584973, - -0.22238761776917892, - -0.20931878921354335, - -0.6435112376811334, - -0.1601294235136086, - -0.38678975608968647, - -0.29930195314968827, - -0.4855172285717533, - -0.5062201318247195, - -0.19049300245542167, - -0.4122131612936806, - -0.6855047087147019, - -0.5897204765002811, - -0.4670440201143835, - -0.6501345746217382, - -0.145172362008674, - -0.5883179592781471, - -0.3315005839347792, - -0.5879832020318205, - -0.2516000901068127, - -0.5710036716898828, - -0.6610168977831631, - -0.6068987190955123, - -0.22794337001791992, - -0.6162085654799259, - -0.5199903702331581, - -0.309270015069063, - -0.45363458035925075, - -0.6378965880371203, - -0.619870201189144, - -0.3392629033452842, - -0.3843370697781562, - -0.20788753968801932, - -0.3393715073123067, - -0.6813537603604553, - -0.21611453966099303, - -0.23135490170645978, - -0.521883579525706, - -0.6109362101084262, - -0.6317542995329662, - -0.2988094044643175, - -0.5838307818787476, - -0.46646516450737907, - -0.18215708536891762, - -0.4091177984629728, - -0.5942358762847508, - -0.4695296825453138, - -0.5088503152812356, - -0.4846824291133835, - -0.35606078863593554, - -0.49034880492235733, - -0.24216789113609472, - -0.5267940047363043, - -0.5720268824888434, - -0.5629727731824936, - -0.2307347191073003, - -0.3247640788310153, - -0.24207537918923083, - -0.6344044166346695, - -0.4260055472641212, - -0.1672173884143625, - -0.32763137666812253, - -0.52847780619767, - -0.3285216761493629, - -0.47100443470121056, - -0.23171542269570367, - -0.4916085816865508, - -0.18012260758818754, - -0.2547668971935106, - -0.5256522130516823, - -0.21658955543872344, - -0.15515148509221133, - -0.673008132960371, - -0.4290525800299913, - -0.21815705523804108, - -0.3183595521862611, - -0.22857698243135538, - -0.5361420062067028, - -0.5795469660869162, - -0.6781155920441404, - -0.431298939601575, - -0.15846271715932614, - -0.5579777487733196, - -0.49373882704018235, - -0.5185901908881287, - -0.6744431400581559, - -0.26337336224887714, - -0.1389166059153163, - -0.4775685127431716, - -0.6197849510465211, - -0.2806412211320192, - -0.35513511482405435, - -0.6409971206782088, - -0.17411489888441123, - -0.5958233274455992, - -0.17820364085727114, - -0.15103183515091145, - -0.20352832806369958, - -0.21906159287509103, - -0.3110101540479724, - -0.3462623434848626, - -0.5249836086049872, - -0.3163999928725693, - -0.49887966605973344, - -0.33913302730982836, - -0.5433797598895835, - -0.32079382166807957, - -0.5631416946646925, - -0.5076312188601435, - -0.5436281677758499, - -0.2370448810778819, - -0.5531849494411669, - -0.605824058762398, - -0.690148528745593, - -0.6854564524032043, - -0.5911349566536584, - -0.2694367154385903, - -0.2128279556311598, - -0.33784712980067294, - -0.3794364513506489, - -0.36826837975864674, - -0.309057612940049, - -0.577147348817632, - -0.24712293721905215, - -0.6870360245398733, - -0.5177834975540944, - -0.6365032470447659, - -0.6207156967953997, - -0.2882512040062272, - -0.6614409938642822, - -0.2197885450891618, - -0.6632585816358073, - -0.3174426411758643, - -0.5764161736459391, - -0.6489475811320378, - -0.6155977068334704, - -0.5890434487251097, - -0.6376820791042556, - -0.6650287757058662, - -0.5086606388633312, - -0.27363491381257926, - -0.4868465555041333, - -0.2706026202835932, - -0.5416852608322711, - -0.22955220268697274, - -0.6709079826686762, - -0.19189817448769098, - -0.4964472761646024, - -0.2630524725797876, - -0.40394475492848253, - -0.6312625647311609, - -0.13920188867864758, - -0.6366884222800726, - -0.6010561776334165, - -0.6922465072496143, - -0.3389303873277529, - -0.6319337155677307, - -0.5301881410478368, - -0.3500876770072152, - -0.5259530608106358, - -0.301018944166795, - -0.21251279566437226, - -0.43877952874404574, - -0.6799608232001628, - -0.4037323181358194, - -0.41296411079854806, - -0.2674147176848378, - -0.6372020796732246, - -0.34667758467821297, - -0.27510527229675463, - -0.5018056193958246, - -0.24216433519213998, - -0.23306163008528769, - -0.2661498755326439, - -0.5465195840088859, - -0.4627437682169755, - -0.41251198727640437, - -0.546531631719278, - -0.5491969920320365, - -0.6848954930566342, - -0.20791801671965338, - -0.26864996171789796, - -0.20731892136724123, - -0.5216067517234599, - -0.5656367939081292, - -0.5228573837877217, - -0.6289808578824323, - -0.659457452128484, - -0.2567756428499711, - -0.37918273534034913, - -0.5201883080249954, - -0.4528968879286486, - -0.6201536875850585, - -0.14073364884846606, - -0.5200131104245055, - -0.19999043197316224, - -0.6792241878549735, - -0.4484015421953172, - -0.21290263324948455, - -0.18889147731470124, - -0.4029663466828609, - -0.35213351777867397, - -0.5848490127355591, - -0.6953667588773778, - -0.5094809697794198, - -0.5057564308673874, - -0.5448535620621764, - -0.32027178060208666, - -0.5871364908039626, - -0.3749714356257476, - -0.24763907707718752, - -0.3812648746068766, - -0.17696596245552065, - -0.5390103583067747, - -0.4365752500094183, - -0.6750962816467131, - -0.4236486584396144, - -0.6476461519011214, - -0.5691540641061743, - -0.17115979006176296, - -0.20704740305278624, - -0.3716207101215393, - -0.30434797948247805, - -0.6728443650712422, - -0.5282378022573591, - -0.576142207127544, - -0.4855475611428407, - -0.16577110933143846, - -0.6646284688062738, - -0.4664483483608729, - -0.6957869110310251, - -0.27072036079632117, - -0.61194679351218, - -0.6243008423659855, - -0.6445157870129281, - -0.6355208428482841, - -0.46824444204373217, - -0.4916250575439225, - -0.42685603243282255, - -0.6095681499856349, - -0.3618835279900705, - -0.20858534318720817, - -0.38684135815874654, - -0.1779221790580744, - -0.32641273194090364, - -0.6798636341977077, - -0.5722762325627617, - -0.1473040105296105, - -0.5106720895196006, - -0.2628762700365074, - -0.35583479013315034, - -0.2856696223305327, - -0.2206000135477279, - -0.47025443825181057, - -0.1425244770004851, - -0.23959637797649308, - -0.1579292150917998, - -0.6798600097409987, - -0.25144310636463535, - -0.5642693453922502, - -0.5770961175835305, - -0.488809657032539, - -0.4708841607187445, - -0.4950554824402147, - -0.543416829834997, - -0.600173603250946, - -0.2694676014170257, - -0.2851816847057024, - -0.18583543316704487, - -0.5596451938351696, - -0.559566621398417, - -0.5529141097938461, - -0.1400264953252427, - -0.6597776973915432, - -0.19586638678812673, - -0.3485328527034192, - -0.19206219757720377, - -0.41713726145124425, - -0.33010965981983925, - -0.5491230037779766, - -0.5457928707815324, - -0.4988555048263006, - -0.2051174412843369, - -0.6420185703413783, - -0.5366182788803779, - -0.4712681714310408, - -0.34606319274895825, - -0.665125733512121, - -0.17706210325360883, - -0.5432289571298126, - -0.6366102945345036, - -0.2761285145461653, - -0.23927415399451246, - -0.4425735558192965, - -0.3376030641195697, - -0.4522175090859325, - -0.5230036356346226, - -0.3514754785038397, - -0.19747360746088782, - -0.6359034942430931, - -0.17192703618849248, - -0.4032988692005489, - -0.5846927926531933, - -0.5636323470451706, - -0.26534582175869587, - -0.45496353074489504, - -0.22402521692910182, - -0.1421033310591726, - -0.4463748500386117, - -0.42000590269799887, - -0.3948021046023091, - -0.3542710509043312, - -0.6334048855418036, - -0.2435708108300148, - -0.5230203351656006, - -0.4877389439839657, - -0.4837905198393099, - -0.6601693604522773, - -0.2709178836827827, - -0.15092977821672926, - -0.2763166336255261, - -0.540311106690656, - -0.3360134546181453, - -0.6765426423030775, - -0.5329027200283063, - -0.3081169296503153, - -0.4708466772466252, - -0.5761958904876303, - -0.3003684717952377, - -0.3290518108082551, - -0.39158824041534723, - -0.23643601013373777, - -0.17488423592267033, - -0.5082464495135727, - -0.5789348758658969, - -0.1515407070692264, - -0.43891211865309976, - -0.28252264040724967, - -0.32457706731345864, - -0.6413121553527622, - -0.4325933667275931, - -0.480394826151045, - -0.5737925960675307, - -0.3662454962893023, - -0.4581270116110699, - -0.2615000680883083, - -0.25041087947807844, - -0.49672499714693436, - -0.3516271496493728, - -0.299256058000547, - -0.5728918345954431, - -0.5780084293196716, - -0.22507838732020136, - -0.41330645340893596, - -0.378819673922772, - -0.20829334626466567, - -0.6441883187190192, - -0.4015977184413567, - -0.5124560807944388, - -0.2650646525949979, - -0.25426799833062746, - -0.5136440755536551, - -0.3711219199025993, - -0.4777377981176927, - -0.5671923173094908, - -0.4956315920016685, - -0.5869394872673607, - -0.5681490475184714, - -0.5820773829974478, - -0.3345183618393055, - -0.5512252163292427, - -0.6173174520973145, - -0.1630119854748232, - -0.22346422116911668, - -0.5071871347101519, - -0.6214588277996623, - -0.2664257354379401, - -0.23132882815881362, - -0.16162449877498897, - -0.5516521940613478, - -0.6466023715653999, - -0.28820169042378263, - -0.5080915376939064, - -0.30901315735227297, - -0.4302926955699395, - -0.26115449052829764, - -0.35790200088519547, - -0.5751019066236143, - -0.6810664411407488, - -0.43185226844431995, - -0.5715769319741816, - -0.6726875937725952, - -0.31100796217137566, - -0.6374821992354888, - -0.2521575263218877, - -0.445865601966126, - -0.32052716370908346, - -0.5453898608402129, - -0.5860536133454833, - -0.6542712700210718, - -0.4092777500628785, - -0.3758062393550047, - -0.36049888615427833, - -0.46745441924850356, - -0.3095154399801217, - -0.5226727052134166, - -0.5834869680088853, - -0.5628853807204413, - -0.6858416280281106, - -0.6083143615948693, - -0.34890802058959025, - -0.5747751843791069, - -0.6654190811708101, - -0.36930078792627646, - -0.39984649815021656, - -0.14278671829731315, - -0.14602864936102566, - -0.64246655539994, - -0.3532441963707372, - -0.5086223182686922, - -0.563793912548815, - -0.6486358204343223, - -0.4598340302442543, - -0.40964959472987794, - -0.3028903079515562, - -0.2896887582218571, - -0.5493409309008694, - -0.27065715572547905, - -0.49685853677776737, - -0.3255020437444604, - -0.5683862244543183, - -0.38030867641270283, - -0.26448349821420036, - -0.39792724651422146, - -0.6362590153616359, - -0.20677768320293338, - -0.6803170499344696, - -0.32721742475720395, - -0.5952485212709959, - -0.49051856240672265, - -0.47461575861026223, - -0.3075101301860683, - -0.1974810238358603, - -0.5973307193546995, - -0.6537635577324735, - -0.38876849024912236, - -0.6427401485509792, - -0.3219492193016839, - -0.5741173215031125, - -0.39829370025825156, - -0.6798384440173624, - -0.42311314212646506, - -0.3227112648724906, - -0.5452902394889935, - -0.4239345237388259, - -0.4371726618455074, - -0.3732854107511463, - -0.6246631154841643, - -0.5567183721504283, - -0.3859132345916668, - -0.18591022880924757, - -0.3461091701772223, - -0.6933193804241445, - -0.3585930560193854, - -0.1973710567717999, - -0.5451247811360121, - -0.42347470670928755, - -0.6208232956077193, - -0.2221447541795043, - -0.31407318055465683, - -0.3248324760841366, - -0.6542444516751447, - -0.40063424901395867, - -0.4091456248920296, - -0.43455316604012134, - -0.3192151213329015, - -0.20797882929167877, - -0.5977039318794102, - -0.5014431507348712, - -0.3105281477461295, - -0.18218471146070525, - -0.48013162960773714, - -0.2134328196005455, - -0.2042352254180793, - -0.2681635361050539, - -0.6913882918386877, - -0.33634466251132084, - -0.4327837711850377, - -0.46548693334259983, - -0.2149800049214754, - -0.5010580218635079, - -0.5951448259262342, - -0.26188447558482264, - -0.6793165124754584, - -0.6007892516907923, - -0.46620693674063635, - -0.6544342536418858, - -0.4024932312046266, - -0.46306140763121284, - -0.5425001763952984, - -0.39334639247796266, - -0.15984056293009585, - -0.3651123761009211, - -0.4347204844213041, - -0.5091335395997476, - -0.5203937149025698, - -0.6524453674905765, - -0.36494057437793676, - -0.5895833815776289, - -0.185505372788216, - -0.43652074926379547, - -0.6112078378137746, - -0.645479820895079, - -0.6605150207998587, - -0.14537303541520585, - -0.3479154310526881, - -0.2040977807984684, - -0.338866230196779, - -0.5932890032720595, - -0.6170861656540959, - -0.47307497675208365, - -0.44085691346669875, - -0.5852757091698442, - -0.6531845028561505, - -0.6257025838539781, - -0.6089035800358523, - -0.6888475982684314, - -0.20667408939924165, - -0.5199177790162743, - -0.1757443536167892, - -0.5540501130860035, - -0.6269310194028649, - -0.2554042150477362, - -0.5646704607546071, - -0.5707390223721852, - -0.20795064738027347, - -0.6178246812286269, - -0.32752314215172007, - -0.20244711789193992, - -0.5441848912909222, - -0.4839432943254509, - -0.6767054806919113, - -0.575335865712735, - -0.6112461300658194, - -0.480959458297723, - -0.5147976300746403, - -0.5724528786415712, - -0.6835883935954271, - -0.5948093995897389, - -0.6775144420334458, - -0.15637811340671226, - -0.206640184960815, - -0.4704432132860136, - -0.3279448339948115, - -0.4700561815381603, - -0.25543287913628326, - -0.4701512304254388, - -0.48005518721602547, - -0.37355420358435654, - -0.37030763461352706, - -0.5563379029249987, - -0.2796732486113857, - -0.6729736693682975, - -0.28175686450548626, - -0.5875665779949952, - -0.16709121770777313, - -0.6958370311440657, - -0.5042417910738668, - -0.46499559783661876, - -0.35744647512221717, - -0.4366997047223364, - -0.32730583154086157, - -0.2304831285041405, - -0.5969643710554366, - -0.5447979253911532, - -0.4690673443202007, - -0.5315041152743916, - -0.2768372365373985, - -0.2923866785771651, - -0.62611633476065, - -0.24024782823618923, - -0.6885114259693106, - -0.25692902473325446, - -0.30399913673956896, - -0.676692518551268, - -0.24625875713293782, - -0.6828848323375688, - -0.2038487535641929, - -0.35237391058286194, - -0.6712010283061537, - -0.3396109178272301, - -0.3504086486105214, - -0.2784274309417097, - -0.4377148760469887, - -0.17499560339938225, - -0.2489502568749763, - -0.20036112753631424, - -0.3690316859672872, - -0.5326199373418314, - -0.4459464032133973, - -0.6404364498190347, - -0.4427769245192088, - -0.5528483509876833, - -0.6337724781137672, - -0.22851263803991873, - -0.6083504841100206, - -0.18005412577340585, - -0.6642543902232526, - -0.5301104895352735, - -0.6132650894860749, - -0.34569223153609857, - -0.2692534102178566, - -0.5226887011782291, - -0.29050023987049933, - -0.4432878550558108, - -0.6954039945388211, - -0.3266839099539974, - -0.6172510313683279, - -0.28990928645333275, - -0.6128994142374098, - -0.4030669145127096, - -0.4847555208128077, - -0.49397019489313176, - -0.6876424384957432, - -0.2176149720205699, - -0.457711232686981, - -0.6829276398447659, - -0.18445092614427705, - -0.36566650516933347, - -0.23661531076753284, - -0.45358124248036635, - -0.5499294271804935, - -0.27369745645782034, - -0.2525946622806068, - -0.24472032307609126, - -0.2871026731409007, - -0.4452070618499339, - -0.5092935257546303, - -0.2793745061535638, - -0.34712097020685906, - -0.6331284890402562, - -0.25185697588116085, - -0.4414550023002522, - -0.3685027242747063, - -0.1925372982149527, - -0.49166406270657337, - -0.38083782112590336, - -0.15819562426943712, - -0.26159033732166087, - -0.3599157149430414, - -0.35211484451006825, - -0.5038417426698936, - -0.46673328906528594, - -0.5771099118968721, - -0.6499791386421792, - -0.504898654436543, - -0.20132390957024032, - -0.5205220256812462, - -0.44442259494483877, - -0.6457979270567963, - -0.4068771463769635, - -0.5990812066230154, - -0.1939386401864165, - -0.24785826292081642, - -0.659688053274931, - -0.3503029412467906, - -0.6103911814398588, - -0.6615368824306248, - -0.29916414599043684, - -0.5546026170507871, - -0.49063264901166126, - -0.1613701431265233, - -0.318393487281109, - -0.3702135160898773, - -0.6652913363954305, - -0.17599507838769013, - -0.2062058867058879, - -0.19098120502527816, - -0.14986981266320565, - -0.24451365242666656, - -0.4464990791037207, - -0.5589274876127035, - -0.473819870411187, - -0.20309060748424124, - -0.17854883824119894, - -0.33072767427783106, - -0.5702785773367993, - -0.2764642907556683, - -0.1913801906967456, - -0.606695522713022, - -0.16460365948093703, - -0.29920110633427494, - -0.335882258457198, - -0.2971807567366492, - -0.3464239264324735, - -0.6634602762063748, - -0.37166436151446686, - -0.2195118973244451, - -0.35701591706475067, - -0.2510968401235121, - -0.31301291516190294, - -0.39374805970018417, - -0.4927253248211211, - -0.28912361137683273, - -0.28480058855268864, - -0.256665872714921, - -0.37053521844241144, - -0.45891856890758886, - -0.4721875597602352, - -0.6131197960338974, - -0.5497723693271369, - -0.6193277685493983, - -0.5582907149347597, - -0.26336931579672584, - -0.4649351955775263, - -0.2382910311153405, - -0.6659055901618779, - -0.6016683783767849, - -0.2976449070445156, - -0.43110591085128924, - -0.5493943738233544, - -0.6104319849814906, - -0.23044567801555188, - -0.47906953089167237, - -0.5665360334166081, - -0.5143951246322324, - -0.19861769281692265, - -0.281491549439199, - -0.6427418381066213, - -0.24258782843318755, - -0.5674999965749665, - -0.26380149025138716, - -0.30425513166090284, - -0.4449856022834919, - -0.47252615804592135, - -0.5863281015586471, - -0.2637140874955335, - -0.5524944347156457, - -0.5614879067817715, - -0.37723762478405015, - -0.4123526834109719, - -0.5236920184134457, - -0.2106899970383742, - -0.6232835904176042, - -0.6071085355492997, - -0.5618604279280952, - -0.5383710591759534, - -0.2183382695492676, - -0.4391878114625851, - -0.19968271354072092, - -0.15143518883488083, - -0.6809576867295536, - -0.4538879806515417, - -0.661627658926051, - -0.40002226600215535, - -0.14137634905154361, - -0.6280772609260765, - -0.3519468924826479, - -0.6602829514281162, - -0.5242972309816744, - -0.17715203745727237, - -0.16482449522280207, - -0.47496824179462827, - -0.48886942459939026, - -0.6048701701069119, - -0.26215189493399527, - -0.46468103113969284, - -0.39694731534934347, - -0.23932647045613759, - -0.5824552487326311, - -0.24789316210574158, - -0.35571966275125794, - -0.3322086596003916, - -0.1667768493955082, - -0.36962001758323765, - -0.6398363850628803, - -0.6851781210512011, - -0.24101967311878242, - -0.547021674085395, - -0.15999667386322225, - -0.3584946869471607, - -0.5060924989758122, - -0.5078183226137214, - -0.6010371309238934, - -0.14237428118492734, - -0.4072061932265358, - -0.4483457925159152, - -0.31829989356706595, - -0.35335181752461103, - -0.38788246107390434, - -0.5140740416187094, - -0.21674514408886186, - -0.5150597557635429, - -0.3120930176253676, - -0.14831541327081943, - -0.4924750089772758, - -0.6409640361972363, - -0.4181090797658274, - -0.42704024159519816, - -0.2230220998688185, - -0.26284211470215574, - -0.15007246621671955, - -0.48336557846715056, - -0.30606782232296786, - -0.26262293661324604, - -0.4741019922201169, - -0.17305723240536386, - -0.49560375563932935, - -0.22500873743061972, - -0.2206583117198877, - -0.23132542867023426, - -0.2429837279940481, - -0.47290508182070223, - -0.42099107532476976, - -0.20391843269768256, - -0.23360583888988523, - -0.5008686870489761, - -0.33538996161588547, - -0.45169842531099824, - -0.46433324461154557, - -0.5202076296697377, - -0.3516063909375081, - -0.4952383399722584, - -0.5970411981989927, - -0.6058215820753883, - -0.6440434843266442, - -0.6549804843132141, - -0.5185652733559724, - -0.493125789365923, - -0.6245716863224056, - -0.20276216074162184, - -0.6716708016430682, - -0.4084254389881276, - -0.1484007520995556, - -0.2562610513524352, - -0.5118967959460913, - -0.512617386744373, - -0.6281198390835462, - -0.4686224088848978, - -0.5976610709457401, - -0.4465639349911592, - -0.6623084473240427, - -0.3819473084220606, - -0.19011409712229344, - -0.6700085530962366, - -0.1982361719379751, - -0.16291335719890532, - -0.6826241351020838, - -0.5905108583722953, - -0.4132517198820203, - -0.3468577473324062, - -0.6334715045530952, - -0.18061702291267867, - -0.6586417977139849, - -0.1611346703077826, - -0.6231794722000895, - -0.37978208049100165, - -0.30277878866665353, - -0.40425394447493096, - -0.18406924968686567, - -0.5596571007612955, - -0.6911426860359801, - -0.5554219653515412, - -0.28372801501263983, - -0.5550046290705444, - -0.15438361144734436, - -0.640601816767616, - -0.28726929810155416, - -0.2975066849968765, - -0.23120880851170228, - -0.4966658649853423, - -0.23920910830948833, - -0.48331286218301944, - -0.27855690726679094, - -0.6836886169200802, - -0.23652791340621337, - -0.4490985172954747, - -0.3002182153434357, - -0.6859517635987836, - -0.4559358679802987, - -0.6077336359088016, - -0.6237451633032918, - -0.3539234758849741, - -0.40047181842537277, - -0.6255253501587413, - -0.5153133024569541, - -0.6907479372899143, - -0.23248087600153272, - -0.3255161582405629, - -0.3759957933968195, - -0.45643703835163885, - -0.40570481968773575, - -0.2709154972077781, - -0.23053714995392643, - -0.5257692644378991, - -0.5113271970192942, - -0.21083053377038896, - -0.48348825071571533, - -0.5147793004514327, - -0.26518597593565774, - -0.5768937474209381, - -0.4560982071279885, - -0.6066079687956367, - -0.3050598229948321, - -0.6789487928005676, - -0.22044695144029458, - -0.6710674958689865, - -0.2477641726760927, - -0.24181817642614944, - -0.2926499661472735, - -0.5257791365314693, - -0.27876751074066214, - -0.38901736014229554, - -0.21608254298448704, - -0.4196812595457911, - -0.6652178908814388, - -0.36073865289591506, - -0.5000365012092429, - -0.5134555896992783, - -0.3878854857062946, - -0.48633851641207115, - -0.33854706809039525, - -0.49154267042299127, - -0.29217181511676094, - -0.24336091850755237, - -0.2972162637998068, - -0.36850526642536463, - -0.5070725086498591, - -0.3353157855757429, - -0.6057830394746879, - -0.37364605314534044, - -0.46701476349258414, - -0.5495645209025496, - -0.6968961067002706, - -0.5770204828454361, - -0.3447090632770464, - -0.2705725872911198, - -0.49373653394554917, - -0.37896069791118075, - -0.35348152334457295, - -0.3330044587394067, - -0.16348983989369892, - -0.1584136542547715, - -0.3383040097161813, - -0.5288369970901275, - -0.40143651474418623, - -0.439738541338844, - -0.21492902338300135, - -0.39551960105401107, - -0.3646009450570318, - -0.6454181378306835, - -0.6039025361001463, - -0.5531924473557872, - -0.32311959905069204, - -0.33358077650093876, - -0.18089879019184318, - -0.6667170209554392, - -0.4420008472848867, - -0.36259773725537225, - -0.5087441036761549, - -0.6869465490860167, - -0.47356421441533736, - -0.22671349032692784, - -0.295393695447094, - -0.4820591672933282, - -0.21892520912088764, - -0.663814313184951, - -0.5589280392766172, - -0.6377644904114556, - -0.4870631751102631, - -0.3645917703544555, - -0.17287098515103605, - -0.33755682912397844, - -0.29797680690644873, - -0.1634963895678263, - -0.46523109624308934, - -0.6430579832217895, - -0.3227719497396982, - -0.5435070482870433, - -0.5107332211754593, - -0.1702861423744092, - -0.20588296697792308, - -0.34843028310762303, - -0.16837675379293704, - -0.6390948723254801, - -0.4885766907848265, - -0.5751234827483215, - -0.24443073785119074, - -0.4236102636871647, - -0.4680391505543416, - -0.15893373057325, - -0.5819706499584286, - -0.20630801291940543, - -0.47954342419684237, - -0.25473276315901544, - -0.2733954113923092, - -0.16597234714666576, - -0.2873949101757904, - -0.26680785302798715, - -0.6016678343454654, - -0.5970580213161133, - -0.5378796720817348, - -0.6969762402895971, - -0.4263373740161499, - -0.1749930845831713, - -0.38760108310601227, - -0.40711598125417087, - -0.49785582153023306, - -0.5295030416014236, - -0.314170864931736, - -0.1536359706918493, - -0.23941049248721624, - -0.5665972749899315, - -0.6287367478371023, - -0.5844480020038801, - -0.625665882799165, - -0.33054376336696445, - -0.1576644709302777, - -0.624931455520598, - -0.5679218416889156, - -0.539873268103978, - -0.356495704103858, - -0.5409555394599159, - -0.2570190927490823, - -0.3304027956602548, - -0.3796657857624455, - -0.34343034134164474, - -0.6172467547181834, - -0.4660251034674804, - -0.21242197404921315, - -0.4903082265417735, - -0.19577386172997102, - -0.5828917353042345, - -0.3159382804008806, - -0.4031858131525055, - -0.2058827472068317, - -0.5689717050627853, - -0.3052542005603106, - -0.2750625185905648, - -0.48386364073180294, - -0.6580328455229698, - -0.22661000003808995, - -0.4627455950072892, - -0.42593529404832026, - -0.5688876407458247, - -0.15264885835703546, - -0.6825128612606827, - -0.17288830242293107, - -0.6415254806024369, - -0.30213428792756003, - -0.6209053684552044, - -0.6462200335825122, - -0.4663645387545592, - -0.2792126843322692, - -0.4543222227911812, - -0.5374522383498594, - -0.6808516018006979, - -0.4849320096845968, - -0.5721804914149684, - -0.18921114235416592, - -0.5424581156370087, - -0.35228040536358435, - -0.2107779679164722, - -0.35979618134084757, - -0.19023244092054237, - -0.34748649223632977, - -0.6407199774224873, - -0.3156857068713596, - -0.1411971567691488, - -0.47835257939553655, - -0.2061742221020922, - -0.21164678765954364, - -0.6737565883388463, - -0.26193665893493917, - -0.3102018465203943, - -0.34979936850149324, - -0.46608487401677223, - -0.2238550615369425, - -0.1783494665331552, - -0.5675649615906753, - -0.47009720364373575, - -0.20830983706662942, - -0.2046091921343302, - -0.3736574686056042, - -0.5675117554943652, - -0.6349303576241387, - -0.43883508251214565, - -0.6183632085204468, - -0.25143629771329423, - -0.4634378445002818, - -0.5014394721426256, - -0.22132587056099184, - -0.24256004497791056, - -0.2402424921413565, - -0.21584044855674295, - -0.48096611496833436, - -0.30762686442623777, - -0.31536023387846956, - -0.2080533190044177, - -0.25872852673856883, - -0.4850024175607818, - -0.22741753613656007, - -0.4418320783760565, - -0.47222426557807357, - -0.44146684363647776, - -0.42663416714770486, - -0.454374796472328, - -0.14227207536891773, - -0.4849061891136409, - -0.2275518599374569, - -0.5552932507697677, - -0.26139184908798585, - -0.6621206641905439, - -0.5359387566283387, - -0.3508471719127619, - -0.5380902654853653, - -0.25437675899498596, - -0.4046309216730565, - -0.5344643292175854, - -0.1712799585067345, - -0.5228525676085944, - -0.2992373052559397, - -0.6563053053810255, - -0.6520132315686499, - -0.6778010160190175, - -0.4471075555283985, - -0.2993859232233131, - -0.34381946348075987, - -0.5140914882428028, - -0.4288799481350359, - -0.430462997219822, - -0.3938189938432971, - -0.6868159464421992, - -0.21357915320182141, - -0.5501292801677248, - -0.46660630035728534, - -0.47858992928958977, - -0.47447319068640537, - -0.4436006647060263, - -0.5257241176353348, - -0.6469687070277422, - -0.6012894529671902, - -0.4010163168843008, - -0.6815530862089391, - -0.43969028203696525, - -0.2396778261314213, - -0.14962928015967036, - -0.21970528525103844, - -0.2636349806489746, - -0.28082182514959947, - -0.1579144662321028, - -0.5187255126715082, - -0.14766464774019028, - -0.20587352264808872, - -0.6637387949975775, - -0.41805221184711977, - -0.42192282763998096, - -0.43649966250463984, - -0.3053917108693551, - -0.14680189865457727, - -0.6720380491430138, - -0.32703654455336245, - -0.3151345284333896, - -0.6172957662605544, - -0.32677928155855074, - -0.30265924355803336, - -0.6910019202910792, - -0.2753246971038279, - -0.17359221848477246, - -0.6907027336082538, - -0.436556294011129, - -0.2367730171557753, - -0.514197263033976, - -0.6150501714099212, - -0.41803437780142516, - -0.6691290274037455, - -0.5210547595576934, - -0.46814446893917894, - -0.4396458283630313, - -0.4680235294869731, - -0.6827883302742399, - -0.5961812977843441, - -0.5268569950795859, - -0.30884385315897417, - -0.14426642924393573, - -0.2773077136510659, - -0.28961328980490525, - -0.28736931875437516, - -0.3499713571614286, - -0.22460898716811456, - -0.1986450801388775, - -0.5926547427926874, - -0.4523493421278899, - -0.5714748701861464, - -0.1887325029972936, - -0.5235360805120632, - -0.5805108957333345, - -0.2272566012337286, - -0.345696995478531, - -0.6182554225080709, - -0.4315560754133858, - -0.2590769421585908, - -0.37811037815872733, - -0.538190798983518, - -0.6459663006940373, - -0.17232994615385455, - -0.6855592572286049, - -0.27816399220775173, - -0.3498403374555076, - -0.5390408300952667, - -0.5579530435051643, - -0.32271014076766313, - -0.3765465695809104, - -0.41094663585130725, - -0.5607487070835331, - -0.6938395983947996, - -0.3988519274003659, - -0.5059251247105391, - -0.477496397474565, - -0.2703425472634014, - -0.4547910015375742, - -0.6131800256743482, - -0.40891029232427384, - -0.4462490063391778, - -0.1445463831214162, - -0.23572270931534295, - -0.4487036117852111, - -0.4871801347788639, - -0.601640182367128, - -0.3581504176288492, - -0.535544043367207, - -0.16745624118802627, - -0.2869966573648924, - -0.418571992721151, - -0.49316308123261726, - -0.2944953678501513, - -0.6222259268918033, - -0.2227808235586754, - -0.6087423228533239, - -0.3447455236770971, - -0.23760640228738494, - -0.4007508026125178, - -0.3502579897699632, - -0.2559877681561005, - -0.6932243247924073, - -0.45977186322213354, - -0.16502638350649323, - -0.30258472503407746, - -0.31459633597824876, - -0.47220592930142147, - -0.1650825558567014, - -0.49417784807214427, - -0.6831555309241946, - -0.2746696652588833, - -0.3355454869853901, - -0.46825831862327494, - -0.684135417152865, - -0.29166947938128795, - -0.33498473881460294, - -0.39559500778244977, - -0.3100734126374124, - -0.5819837157810551, - -0.5481803968758564, - -0.6962514515224557, - -0.5546999644965561, - -0.6358206804822168, - -0.3812398986814836, - -0.218044084312417, - -0.5428667281197248, - -0.3324329630998251, - -0.22783673838619217, - -0.4908827710827772, - -0.34515426063892846, - -0.6786375478439451, - -0.3635267386012745, - -0.3510287441799869, - -0.62759940029181, - -0.4708490667524717, - -0.29835428857473123, - -0.5765331967885178, - -0.616441578767649, - -0.596055055363337, - -0.38976251464724126, - -0.5462362866650496, - -0.2400959602905548, - -0.6123111975171991, - -0.5885346045659614, - -0.4915929392645513, - -0.30593862937079824, - -0.3313299923953876, - -0.6228794083100686, - -0.2889610808604691, - -0.43589988681658604, - -0.360679598691643, - -0.5973637515046298, - -0.4096218023684683, - -0.28191319108233304, - -0.4550228489020458, - -0.6713245520089431, - -0.3939153930246734, - -0.6157680531728147, - -0.14263703062953703, - -0.1903586693300392, - -0.5633330081394394, - -0.20714168371016783, - -0.4997792995221596, - -0.5237620153921917, - -0.5368472796148128, - -0.554966157529462, - -0.5307015524388787, - -0.22501472012557194, - -0.5963171915332275, - -0.22334960965379713, - -0.15480337568362967, - -0.5906181417710783, - -0.3156912092494582, - -0.6098489156276501, - -0.3601333477173675, - -0.5933066332798518, - -0.6947293340417288, - -0.2938641697715465, - -0.52498887766831, - -0.364741340727469, - -0.6034593668108267, - -0.16238972466524348, - -0.29223602062326554, - -0.5144274683484572, - -0.46241653139985395, - -0.4023137867341873, - -0.24874471582922786, - -0.36191444178766125, - -0.4348725922514744, - -0.5700293119808684, - -0.6884830075525666, - -0.5081887473466097, - -0.2509760684770025, - -0.24273938494774328, - -0.21666707468260538, - -0.45693707552087615, - -0.537743859610006, - -0.4458554402136453, - -0.3000547546152809, - -0.6127834084129812, - -0.1793891396715238, - -0.29608092489374366, - -0.17432287022307846, - -0.6447987899349, - -0.4167561348254531, - -0.19728520540474082, - -0.6457533655792365, - -0.32049320486254856, - -0.6208328576568976, - -0.21462942871342205, - -0.6625240006764958, - -0.44995707255919765, - -0.21658819080693814, - -0.3355883334642532, - -0.28967871700013276, - -0.21685189246423814, - -0.34877277377160726, - -0.552126770353246, - -0.4850236435838392, - -0.37720096073449827, - -0.4447218926706864, - -0.5695504131527556, - -0.4056823082551809, - -0.5254630076284528, - -0.1566972161020539, - -0.29937498238515226, - -0.6210529584425715, - -0.1501565376063675, - -0.1561775921511297, - -0.5043793050598048, - -0.6144088872729624, - -0.4436516182607864, - -0.5760466537661907, - -0.2952919510195779, - -0.47024854484405265, - -0.302466804789149, - -0.17159407917750735, - -0.285323176343367, - -0.6897461221621296, - -0.19729015174800335, - -0.5669856482832573, - -0.481674165665547, - -0.6447013377400417, - -0.37478193005412014, - -0.6732370392629002, - -0.25846595021474067, - -0.3107713284794074, - -0.34363472003769685, - -0.45050018714693474, - -0.1430540160539967, - -0.5002052213981034, - -0.28112786527663114, - -0.3886606189039532, - -0.5971780549304747, - -0.29788778341486244, - -0.5811294065693272, - -0.22788573740732504, - -0.5909582552758298, - -0.22783980194109704, - -0.20808002624990363, - -0.6298174694581868, - -0.6227029662175054, - -0.6142914618814894, - -0.508501654346083, - -0.19308891007954143, - -0.4765832727416601, - -0.4426230929633969, - -0.533462228085103, - -0.4649664013468523, - -0.5130592991990818, - -0.3705385174670819, - -0.19691867105555438, - -0.31355681045985484, - -0.3097415339422854, - -0.528488159414436, - -0.3688295420640026, - -0.40514962342543, - -0.27891410758602875, - -0.34958305179830235, - -0.6718744172931909, - -0.5695277069674688, - -0.262282007213443, - -0.6249991488809882, - -0.38389777911688633, - -0.3418002196794364, - -0.44675314265867105, - -0.45255963671145966, - -0.5982609304706917, - -0.63114180136123, - -0.40320699070631916, - -0.4399360645451375, - -0.6197406821776819, - -0.14954472497695004, - -0.38503055945224846, - -0.15837459044369073, - -0.20696053322800173, - -0.6730501269800848, - -0.6794889527301838, - -0.5682696634217249, - -0.557545115184297, - -0.3610322217762479, - -0.32812959927363444, - -0.1802040638051805, - -0.2584221288356995, - -0.27113855695860356, - -0.5860399906501059, - -0.30843146787177705, - -0.48333457180246997, - -0.3330262684062325, - -0.6972582993358418, - -0.408166773623477, - -0.5233911682545934, - -0.34039989230505735, - -0.30543316742770793, - -0.5878038900861462, - -0.46485172644415695, - -0.25858831977165625, - -0.27130987310027904, - -0.3692267222254641, - -0.3095023212342885, - -0.627032340080248, - -0.4111711088877481, - -0.6327731897848936, - -0.48573360180759717, - -0.14800872756079586, - -0.3778424763903071, - -0.608385871859984, - -0.5367918823342233, - -0.3600133749117479, - -0.1907469846521488, - -0.5380380293115128, - -0.5771215964799928, - -0.6270619360627895, - -0.4622388884588364, - -0.22787883194419462, - -0.4208915990709243, - -0.18636016334170613, - -0.4816936431767215, - -0.4056989278599296, - -0.4647801603204605, - -0.2999643535032726, - -0.6382598285606598, - -0.375441323746701, - -0.24864158754283627, - -0.6808982900636589, - -0.23309872254778713, - -0.515444773700059, - -0.4523857533843107, - -0.6335894950175873, - -0.5389206588936817, - -0.5461704759547342, - -0.2898404689950254, - -0.19645039751936055, - -0.5689155952842265, - -0.5662635637017702, - -0.5607823219209065, - -0.5419926855129759, - -0.41662010119445114, - -0.152326464827635, - -0.558866885986063, - -0.22123750849959306, - -0.5524933279365088, - -0.5670266426000203, - -0.2899255895624541, - -0.2798812217905355, - -0.515212252632532, - -0.6315017619078307, - -0.2251696867520085, - -0.29996013648254516, - -0.29559999242975266, - -0.5071087744530316, - -0.5429861180395336, - -0.6726097084583905, - -0.21849201579947802, - -0.49642499873584733, - -0.29728910916715556, - -0.35195139169612805, - -0.640029063783447, - -0.6703597638831219, - -0.26743355832033877, - -0.32444889781763664, - -0.30486405201036687, - -0.43360902047320865, - -0.4176329750824126, - -0.5799104193021158, - -0.21603383363973117, - -0.6860993500204704, - -0.2741936915476106, - -0.16385126835271813, - -0.20976522122343078, - -0.41149452129775277, - -0.31172142225997523, - -0.38645131996270243, - -0.5450371398183422, - -0.15733037567426045, - -0.43763536640748174, - -0.48821064249474144, - -0.24037098645442462, - -0.22957979031675796, - -0.5962377540980696, - -0.2655193728045078, - -0.30369129329149946, - -0.46146560125937675, - -0.43334133033815697, - -0.5017270681823127, - -0.39987551335387406, - -0.2897757309759858, - -0.19530864766531608, - -0.5957758486459863, - -0.38005628072741754, - -0.3950606000334997, - -0.6192055558887066, - -0.6138524522635403, - -0.3189143891316185, - -0.49436555509468977, - -0.6625574525508934, - -0.5510327649303648, - -0.4320790022857521, - -0.6359934992434723, - -0.14531953383205032, - -0.3130652300186997, - -0.15156119907569088, - -0.34979566049430394, - -0.5923391655016566, - -0.5918889092833239, - -0.4766432329469643, - -0.4706861247619064, - -0.6226062355924186, - -0.2724317373576457, - -0.44682397628943366, - -0.18898173866808143, - -0.6758046700168059, - -0.5455004404481654, - -0.5798809967756733, - -0.16350757404560767, - -0.1477215425752415, - -0.6869161421873478, - -0.2124797024076242, - -0.5231152858327419, - -0.5607658840834397, - -0.5132075324655035, - -0.5547323133238043, - -0.3685122127282173, - -0.21059627525888486, - -0.3102250677005998, - -0.2836862111587277, - -0.4388347008787322, - -0.5384089784051138, - -0.1885911316630846, - -0.4743032028260534, - -0.25430306631768695, - -0.6654170232670378, - -0.37820581901869815, - -0.6652434474724773, - -0.6038102382993106, - -0.33139031452884066, - -0.6681317462813369, - -0.4810600150989025, - -0.46972954087340213, - -0.5542215083569058, - -0.3205187263835013, - -0.1986742215818213, - -0.5135756700575111, - -0.15353258851615248, - -0.6736755696731032, - -0.646144797243887, - -0.19524629462212406, - -0.5126058825969538, - -0.409761801117589, - -0.5219042216269343, - -0.1432720822504282, - -0.5450245893644031, - -0.18628407374534228, - -0.6217474373758298, - -0.5001197240403761, - -0.175527172343673, - -0.30275802853411016, - -0.6521096989687373, - -0.1955810236065918, - -0.6582459501782433, - -0.6052019933916629, - -0.2673259871346996, - -0.6161417473163971, - -0.6037639038844814, - -0.6068682275850261, - -0.672976079322892, - -0.33992381970200963, - -0.5681006977067995, - -0.6722048712609971, - -0.4265590758057028, - -0.24818199362946747, - -0.16528279266541712, - -0.635114576161567, - -0.26247913201668593, - -0.3966114944855676, - -0.15880042072555067, - -0.6782131998621612, - -0.5813557751804872, - -0.404220011707522, - -0.2383045088096425, - -0.6000914260519458, - -0.4611235620297337, - -0.582074085388447, - -0.4171272630219391, - -0.22152735751549762, - -0.38485474344075765, - -0.27407817409922863, - -0.6186271667191646, - -0.2142922488436783, - -0.5662329791179925, - -0.5114883613846072, - -0.197882566759298, - -0.5977616653217308, - -0.1663884862738796, - -0.6364944087654472, - -0.27894915163766787, - -0.5325941003420076, - -0.6147452765069357, - -0.5865692697023576, - -0.5835057373528144, - -0.35272134449788795, - -0.599707598199983, - -0.3160377876365414, - -0.32738270617949605, - -0.2029367934803636, - -0.30267431052784133, - -0.16132883109056362, - -0.615307804478529, - -0.3661240839611725, - -0.6767427648374674, - -0.2715231387304312, - -0.5231715381228065, - -0.49720376109213515, - -0.5419399056494152, - -0.5454260230712198, - -0.30730872899529044, - -0.5431090873485983, - -0.5155273239393956, - -0.1851462145148891, - -0.4201032100954105, - -0.2713041114493992, - -0.20382997768490696, - -0.4092080374489499, - -0.656900975804509, - -0.5560218266828364, - -0.20883408353796568, - -0.32389230508173666, - -0.394592704826462, - -0.5351280619099864, - -0.32832757320523265, - -0.400301676892984, - -0.21732845052429206, - 0.2849156155200059, - 0.2745484650647288, - 0.18842729251404416, - 0.23389898101046774, - 0.059139629753226564, - 0.26103734021579394, - 0.146934144224512, - -0.1260038068545996, - 0.4132671089891746, - 0.3391310751474464, - 0.36087941597401935, - 0.4555777025304648, - 0.048453676661123185, - -0.08877484319903489, - 0.3139161788202603, - 0.26790861039514524, - -0.04355959511900656, - 0.3725056062161528, - 0.3383930801268272, - 0.3890281087659214, - 0.40745050318833453, - 0.22508456792779574, - -0.0994489110978676, - 0.3853588872258765, - 0.09355870996673918, - 0.35196702019950277, - 0.48378215530981916, - 0.43224902339090976, - 0.31017413910325536, - 0.008104690472674064, - 0.1746171975277494, - 0.18052195799806087, - 0.3565566966740598, - 0.1392248949883167, - 0.35187599366947653, - -0.1170602598782324, - 0.35252121297272904, - 0.29442647253686105, - 0.42582563152543174, - 0.45677927625933945, - 0.469005682374955, - -0.08095924651895098, - 0.23927981098972206, - 0.030659917784301965, - -0.06338198280744164, - 0.40882701421620105, - -0.08581974002080342, - 0.2643507897623555, - 0.4340229232330608, - 0.49777037573893856, - 0.016360188754554916, - 0.4203369505865856, - 0.06405118853807432, - -0.055440033939089695, - 0.2832881023847097, - 0.6099410560782216, - 0.4982552400575312, - 0.22992439496911032, - 0.3636039745282408, - 0.24695969961328096, - 0.21429253219573774, - 0.14613519399147795, - 0.02319215482061604, - 0.5740889376304266, - 0.13433288728003195, - 0.25718951516310934, - 0.33604309181217995, - 0.4307777827340561, - 0.15856900336617202, - 0.36231524394994935, - -0.08668395608816676, - 0.349974789292997, - 0.5159841675245991, - 0.21795826175783578, - 0.4817684692857238, - 0.5859596764669456, - 0.07217332079940306, - 0.13837034195867576, - 0.528655321023558, - 0.519482988857115, - 0.0255512083584567, - 0.09703380665506744, - 0.5306634270979409, - 0.03367991747574875, - 0.2921579588362706, - 0.34647624355466533, - 0.3691400574119712, - 0.34777020483736204, - 0.006501834754100766, - -0.0583574175524955, - 0.5825475491738455, - 0.2955951885897046, - 0.5868730714609514, - 0.3359590258487897, - 0.057398774141872, - 0.42548897934538776, - 0.5986419984555654, - 0.564105573139245, - 0.3842903806577904, - -0.08025111749719982, - 0.4076846818582329, - 0.43583657757854344, - 0.40121157698965126, - 0.4947852632587768, - 0.5590059568130376, - -0.08398981265032726, - 0.1495313536143597, - -0.07293827869646001, - 0.308796058538076, - 0.5662297480124795, - 0.5448738296420313, - -0.10364925273152148, - 0.2783962518726758, - 0.39354590804525547, - -0.022911898602104894, - 0.5134707444702444, - 0.3210517662632041, - -0.07702668031958343, - -0.056888905637410614, - 0.30330312680732074, - 0.17525993631708475, - 0.054202396078386256, - -0.03818945062933869, - -0.10527095356430338, - 0.042004348314507806, - -0.06186345863608793, - 0.15207407142774226, - 0.34291521487159876, - -0.07606178134957764, - 0.09128352788318508, - 0.2987907039723255, - 0.006287263328451448, - 0.38008135284509614, - -0.01623126360169712, - 0.26924064724022273, - 0.4413481936490401, - -0.10781177137153707, - 0.2969527591467414, - 0.05157339004519515, - -0.0013160525572026294, - 0.4469860083577696, - 0.33637333179152407, - 0.5559838821906932, - 0.3985949468766449, - 0.4765479713052805, - 0.5943895032260813, - 0.38734121131778243, - -0.00736238486615981, - 0.4680038330716887, - 0.5213517544628326, - 0.1885362065411692, - -0.11873581913103744, - 0.107124434134072, - -0.08601410080587202, - 0.13440372129767192, - 0.007228152745858252, - 0.3776668793857759, - -0.0010321947016824762, - 0.3308649666569675, - 0.39215261042289107, - 7.435875510353185E-4, - -0.06738970288181614, - 0.09043864142653527, - 0.2416154677099337, - 0.4468666209917054, - 0.1929156955409459, - -0.005773418149675441, - 0.22850131533591872, - 0.01011857346556172, - -0.008990567701987029, - -0.05986996973191806, - 0.3228567534666069, - 0.07893559823933102, - 0.3483962298816882, - -0.045034909005189694, - -0.05073215040508748, - 0.547716636200296, - 0.32448369770609337, - 0.30427808141385243, - 0.5476479702371895, - 0.16293589370898776, - -0.13021976787425812, - 0.6046958931962637, - 0.2559922824501306, - 0.35552228489039783, - -0.0735575463533325, - 0.5831996083657951, - 0.28747385130496234, - -0.09667094344969843, - 0.24430524560686007, - 0.43866636243849755, - 0.2845969245181767, - -8.082964707982199E-4, - 0.5822683505879419, - 0.06425209119504613, - -0.03482236184495023, - 0.37112999907193633, - 0.32638640471418345, - -0.04951736855141772, - -0.13578174814346367, - -0.027988248692111126, - 0.603050371562814, - 0.06363560630601267, - 0.09320584307659788, - 0.33856936352632583, - 0.3335755156056493, - 0.4389803158016695, - 0.5637082854749179, - -0.05034278636454184, - 0.03086035455137895, - 0.1546570757010468, - 0.15380947716917176, - 0.5771292693155335, - 0.3765334567299139, - 0.5798487943636943, - -0.05457877676264848, - -0.13211946656365878, - 0.47019711713888757, - -0.09484160013148701, - 0.1079080351994055, - 0.32138854076950474, - 0.5921135156180827, - 0.5477827561593789, - 0.029707757564824716, - 0.4454188063112997, - -0.009523445163245436, - -0.09723318215284055, - 0.2600319900094897, - -0.10158568032256088, - 0.27383911198987004, - 0.08900461862357023, - 0.04322094544159988, - 0.39635930702050315, - 0.5374097779145798, - 0.009251684229416801, - 0.3209273676586467, - 0.4191917358169943, - -0.027472638678185585, - 0.1873594160341155, - -0.09791546557571117, - 0.002410326032637994, - -0.020041713139368852, - 0.2579226049355678, - 0.5995270883901519, - 0.32511236236201174, - 0.5445950363854037, - 0.1565003976486249, - 0.3226219610482225, - 0.5966789174563414, - 0.4495939054770407, - 0.5805846280543914, - 0.35530343638670703, - 0.0037348685295767736, - 0.6077219619060661, - 0.32876133853525563, - 0.16785518683443051, - 0.3581733289991417, - 0.4763860390980921, - -0.12182572483055172, - 0.20776832232868708, - 0.4384585688345457, - 0.388424473380408, - -0.04729931830595385, - -0.008498582186939246, - 0.29826748039313167, - 0.4291028797240304, - 0.4786441562989161, - 0.06240184824385295, - 0.09401821905757105, - 0.23600084613549738, - -0.10584459442424154, - 0.02173622138447362, - 0.08034970822215545, - 0.04879743786655236, - 0.5057877215453551, - 0.00748715268138056, - 0.1960149263440124, - -0.09893217537691103, - -0.06333345827301802, - 0.4372434930538278, - 0.030375644503818522, - 0.4902541343889415, - 0.5374757079384904, - 0.4595059285227332, - 0.432218048349412, - 0.3385712600895077, - 0.533224685105739, - 0.5990079886437947, - -0.09666992439780277, - 0.49152899802980876, - 0.5592128793963373, - 0.5458450929453263, - 0.43159783272460783, - 0.41583498420906995, - 0.20794219184741863, - 0.17092157104573014, - 0.4427223251825948, - 0.04263007609492711, - 0.3821184081601182, - 0.3089916842129298, - 0.03570790882893937, - 0.007875192834767897, - 0.37278767135935365, - 0.5221175583371449, - 0.11529087796565374, - 0.08566461469880027, - 0.2434917379464901, - 0.023830934553561445, - 0.36461270690468295, - 0.12645757480537917, - 0.37621600751945317, - 0.03850538523281233, - 0.043639097169954705, - -0.05726686658387292, - 0.07096334678718705, - 0.24241212566352643, - 0.2045064311446126, - -9.564384180251462E-4, - -0.10097227530639255, - 0.3311049762589248, - 0.25531514949895784, - 0.384171490857913, - 0.4336737785795167, - 0.3109549905836186, - 0.17136103200326724, - -0.052252399149696274, - 0.573414239869844, - -0.1084832286244233, - 0.4373380089303436, - -0.07589692393417992, - -0.0055077103292068, - -0.02433058598772199, - 0.3491373880399051, - 0.3614724360204149, - 0.0010033048765082375, - 0.567011489943491, - 0.07752422432465539, - 0.002445637079249885, - 0.04655312399072159, - 0.34461500544150137, - 0.4851597897874129, - -0.11252636485589695, - 0.47864497837566167, - 0.45625008497916153, - 0.2622235953019627, - 0.13020126598435944, - -0.10393629680536193, - 0.22567972563293054, - 0.43444407958586084, - 0.38594301224863503, - 0.10621864625295954, - 0.4699808436726788, - 0.300275835961705, - 0.4489681496001352, - -0.019310474104897737, - 0.09399141713898149, - 0.3005932393053402, - 0.601984559208396, - 0.06117822774386725, - 0.1420733257531815, - 0.3478296998824416, - 0.08322994707692277, - 0.4787760490547994, - 0.5572993233967954, - 0.30367097310383123, - 0.39819286838468393, - 0.18280157899733723, - 0.05713349134721621, - 0.12007793507130321, - 6.482444022171685E-4, - -0.01613258613486497, - 0.46139231217828214, - 0.16677951889806014, - 0.2955650524467677, - 0.15972307192237095, - -0.029363345573152094, - 0.48715474044548723, - 0.40791807868645735, - 0.24620534350662177, - 0.16231001525198951, - 0.36602662132037556, - 0.4057668122351713, - 0.22904244366120707, - 0.4787500905956793, - 0.21482052366251242, - 0.08694575227771864, - 0.1718321571444545, - 0.4404816010442266, - 0.3005939172512869, - 0.5510095809557758, - 0.24551977160965183, - 0.5349778216270228, - 0.5379542772465458, - 0.40436953930088537, - -0.09876695188973426, - 0.36762038257401575, - 0.33974073376286285, - 0.38619048208639595, - -0.03207607971655742, - 0.5495225470343728, - -0.0032159554484535724, - 0.024075852791693386, - 0.4692727671496034, - 0.5564200649795921, - 0.32621985549990784, - 0.3266215992770526, - -0.018751864651470385, - 0.30645265551268236, - -0.056557886055166096, - 0.30883440209283247, - 0.44877184122210234, - 0.1834582575742429, - 0.02032141667967194, - 0.5527366852334301, - -0.12352836009533809, - 0.47889889568140376, - 0.287023289435428, - 0.1281730860847704, - 0.3614698299064607, - 0.43559336648660085, - 0.07131979052167389, - 0.5803517131852739, - 0.2991595627241803, - -0.008567794509189597, - 0.01443390158656016, - 0.5108308253192952, - 0.26243102272490043, - 0.09437395659294595, - 0.5679619243511373, - 0.2800040253292118, - 0.09752919069782359, - -0.059744185417086676, - -0.04546748836567614, - 0.272158957788079, - 0.03941460496267807, - -0.03591992197988071, - 0.04005333653979659, - -0.12586176993870962, - 0.30955093940289186, - 0.5864172211934798, - 0.5082862919371623, - 0.19788089234919048, - 0.6072538378083695, - 0.10139006116294155, - -0.051171294823884966, - 0.4489848638732571, - -0.06793493300700244, - 0.15876822814474945, - 0.4004941944590009, - -0.06019455728127765, - 0.20689082787026425, - 0.3720877557909652, - 0.37550893636718063, - 0.50965695474686, - 0.19589250124760565, - 0.21748766896647953, - 0.5975163026536937, - 0.33799764158447704, - -0.1032435414525366, - 0.03042716274800697, - 0.3962761791614303, - 0.3777262940151799, - -0.030801011685378257, - 0.4028267150213406, - 0.5168463175162874, - 0.33021938087785574, - 0.3912936484280226, - 0.07340219628482716, - 0.09839482115990891, - 0.45878358216215653, - 0.400680720977754, - 0.5798503259469574, - 0.2141611276241106, - 0.5817563415022372, - 0.22041679893963106, - 0.252485744104776, - 0.5647344909530482, - 0.34305175969815604, - 0.5011531398683854, - 0.47868211489261536, - 0.46692682474334357, - 0.4425623824615956, - 0.17529275502689134, - -0.05530060199054264, - -0.11725931790594721, - 0.5159246496850274, - 0.10268931915053567, - 0.06299899057478991, - 0.02509051792637379, - 0.35754150688943165, - 0.12047833175106376, - -0.13182090648415926, - 0.011155852851660625, - 0.1191322420006447, - 0.5643649236223088, - 0.035938803183220513, - 0.4425431184001982, - 0.40983832259562536, - 0.4904822673717578, - 0.010720853132296093, - 0.16334348345643557, - 0.5306581142936577, - 0.3360615938281325, - 0.5756307930431407, - 0.0018393728421626787, - 0.5887891968746345, - 0.12315923341737939, - 0.2732496442318268, - -0.08223719685505851, - 0.08713838253666681, - 0.18008036742151767, - 0.08870257100786844, - 8.80279335122025E-5, - 0.027661432212370357, - 0.5741038249207425, - 0.031825345942632255, - 0.22537199633629107, - -0.12007592133427843, - -0.030082421642590562, - 0.32669334923457943, - -0.08769261061074583, - 0.2013038375246768, - 0.1060045587427039, - 0.5136705354167161, - 0.287464781166839, - 0.2399664979585162, - 0.3555681432055978, - 0.04809984873308293, - 0.3861708508833208, - 0.026363567618576556, - 0.369122272264651, - 0.0010025855526971938, - 0.2669987755890048, - 0.07416291825242785, - 0.28455458668317807, - 0.32909563220155513, - 0.12252236655861981, - 0.12589238107112538, - 0.041552139748876754, - -0.05199055394421587, - 0.4892717491763283, - 0.3768143398020084, - -0.03392221168805487, - -0.006604096075923299, - 0.07573098226432012, - 0.24616891804435903, - 0.20233067941156424, - 0.09670635480630771, - 0.4356471021205556, - -0.10281386565292819, - 0.3879595670413799, - 0.11003436403599096, - 0.44436651758018864, - 0.564669514394151, - 0.5081173072283133, - 0.5669398642844283, - 0.20697853407006067, - 0.4102650390107724, - -0.03781914423965685, - 0.45963138121509295, - -0.006027739328479997, - 0.17360194072713364, - 0.13500995381185527, - 0.3509728435983288, - 0.34718853600686167, - 0.2231880046194326, - 0.09459867220967647, - 0.4599779710442504, - 0.23322403286215482, - -0.008666914890640143, - 0.09590782116752877, - 0.5359198773427284, - 0.2898357166286284, - 0.28039903967943147, - 0.20868175916060444, - -0.07527825210500781, - -0.07317078673227656, - 0.35902864546025315, - 0.21772988927858838, - 0.1892383013856943, - 0.48499906467063914, - 0.5735298640788726, - 0.541980077828332, - 0.5239687851873776, - 0.4202511868498465, - 0.23870376874251792, - 0.180398046415071, - 0.4132727160659496, - 0.4247904476714134, - 0.27407216140244917, - 0.49971484675299105, - 0.444074433667315, - 0.1161637076702281, - 0.1850302507246394, - 0.47605673687453764, - 0.38773966623538814, - 0.24821301603163431, - 0.04789548283331385, - 0.3775268333902636, - 0.12300333952202519, - 0.2632117919293015, - 0.3861414737519073, - 0.4245470336837698, - -0.07097765227118442, - -0.10067099556761834, - -0.04016582270249154, - 0.38054918996224407, - 0.4884757271663962, - 0.5970834004167795, - 0.2576092636586318, - -0.04789136234701323, - -0.04721595258927366, - 0.5123104844916347, - 0.5349530654057932, - 0.2955335202273747, - 0.07599695123606603, - 0.0636406902362209, - -0.098260805497389, - -0.1324816558033198, - -0.034680761475278654, - 0.21412315102777513, - 0.4663976234476336, - 0.004796612610709128, - 0.5663587072371962, - 0.2400753084815907, - 0.5525293016552281, - 0.09729776480882268, - 0.326291868525764, - 0.06059839176393039, - 0.45083488069343514, - 0.07293278399610131, - -0.011780271540754061, - 0.4918189776483055, - 0.46194123295529144, - -0.11884134397834804, - 0.22820385384687447, - 0.5209360589427369, - 0.12456593889924406, - 0.4542349605466416, - 0.07279273950265602, - 0.03319350899654405, - 0.33162580153837645, - 0.4742929352241789, - 0.3931127225955695, - 0.431017625272883, - 0.2717479111107357, - 0.19974970056081404, - -0.10241360989441053, - 0.26399916087288683, - 0.48315849896810725, - 0.11773927146210184, - 0.28589542768483583, - 0.2419313214120783, - 0.2842187843228923, - 0.5301321995136463, - 0.18769082156871902, - -0.06788011508795169, - -0.0844958843252415, - 0.3253282138948535, - -0.02011798913437357, - 0.30839264553362605, - 0.1986860509997153, - 0.542621094690184, - 0.1486777268336481, - -0.03965456470511593, - 0.4037829791000591, - 0.5219895076630919, - 0.5597647554583675, - 0.030937229326242238, - 0.17281917082875514, - 0.4864731270770538, - -0.03199373999110189, - 0.3834202924560811, - 0.1680075360528286, - 0.2400776412688973, - 0.2502413708212283, - 0.31866255777901425, - 0.27497660908691907, - 0.2585381041688748, - 0.3007697216220945, - -0.08983547585762416, - 0.1453030016971137, - 0.44909993127216796, - 0.5436836442228341, - 0.41150526197146564, - 0.24943236255540485, - 0.07311363994287282, - 0.03100654523350524, - 0.2024725754290273, - 0.11874367544225684, - 0.30792778071781124, - 0.34466876196222673, - -0.09860785015495933, - 0.37326974900471677, - -0.1013827008169667, - 0.2697930844592585, - 0.43313365306607277, - 0.10260441274289306, - 0.3912259906457657, - -0.08449486599516033, - 0.5457426654613766, - -0.03250692873361155, - 0.32548877279899374, - -0.03357926450475829, - 0.3097346144278502, - 0.09999877340024654, - 0.19356111304481344, - 0.31177419781371346, - 0.21169827197048963, - 0.21442467933253134, - 0.029970815834074904, - -0.04153608328948431, - -0.1011831000709752, - 0.35999343172606757, - 0.16806845522415792, - 0.05846905707417188, - 0.2537798144399031, - 0.48786813730182477, - -0.0557719174951397, - 0.20543862098706328, - 0.5104559682361097, - -0.056804481009986765, - 0.45804725737051455, - 0.35779827880881865, - 0.31189222825439666, - 0.2389449888417412, - -0.05762893173051174, - 0.036501117606941885, - 0.5480746264598942, - -0.040466170129530216, - 0.23915110608728718, - 0.0707390968951471, - 0.5381163926298617, - 0.30066744785009636, - 0.11963787183448482, - 0.13028611979956406, - 0.25814025783388506, - 0.5335248019926252, - 0.5939957579788535, - 0.037381834554104265, - 0.2883195591607639, - 0.10267376501972789, - 0.17207867842765567, - 0.0013501392755145836, - 0.15360377016010124, - 0.08862787865144034, - 0.4781254669103847, - -0.033811203842210175, - -0.08117526801776592, - 0.44457557899552247, - 0.17854921153157066, - 0.06196061680265508, - 0.5969712439776793, - 0.3712179022782157, - -0.04819571669316862, - 0.5089497092294548, - 0.3156680890886033, - -0.051088823627788674, - 0.24695560375857128, - 0.014353703144775298, - 0.5430547412676965, - 0.3809020495842206, - 0.4853388492578474, - 0.2469571550904769, - 0.4294335422362361, - 0.31798601604322096, - 0.11015260924858578, - 0.33976055433198205, - -0.10515888805532468, - 0.12067510836789552, - -0.10423806497551438, - 0.4780207572656081, - 0.11040345030352755, - 0.36366376298921765, - 0.10133762400526461, - 0.34666800988318314, - -0.032843766756216544, - 0.3655154532330258, - 0.40198563448216784, - -0.006898334535042738, - 0.05000796154347073, - 0.07850957844974507, - 0.3420471420039598, - -0.07630381952972336, - 0.2368411856009615, - -0.019311710079764927, - 0.3730430982377876, - -0.04721521166376638, - 0.01103458781158434, - 0.5865647226336216, - -0.11655331250382871, - -0.09907169643712593, - 0.5968079385420917, - 0.3595905369343171, - 0.08772053986883527, - 0.30406375145494835, - 0.1648234384131746, - -0.04687290523203094, - 0.05829436379707628, - 0.13529769000273228, - 0.019065329237039602, - 0.5106067998588489, - 0.3278448016501918, - 0.3829501596413648, - 0.02638707157125139, - -0.008173612459713125, - 0.5770464200926431, - 0.5631989494208489, - 0.5733941406502303, - 0.2744992263628912, - 0.14867909553260922, - 0.03690369078407571, - 0.0467727974021927, - 0.507685874213534, - 0.17830592988291488, - 0.5081492018309156, - 0.11697287661450162, - 0.5076185376161517, - 0.5420481363496006, - 0.06894001374446568, - -0.04095636962371926, - -0.11271991788377315, - 0.3928567443223464, - 0.16687417354245088, - 0.47359376436914213, - 0.12372391734222049, - 0.46576471291313826, - -0.011693116128684039, - 0.2185122205022763, - 0.00872040082792458, - 0.43958815123779504, - 0.4896364828284675, - 0.1625193979519316, - 0.07832695760449668, - 0.19681155992718674, - 0.2621430210945579, - 0.41289336371984997, - 0.1685660059895151, - 0.2116192014235061, - 0.10723318743943577, - 0.5279831932756827, - 0.012438937830508645, - 0.5275276661792178, - 0.00763170680283759, - 0.04106771043963872, - 0.6038669702377336, - 0.31350438793989427, - 0.48982050154951906, - 0.5314542921441644, - 0.4259771063808113, - 0.4229598703337428, - 0.04224114988976527, - 0.5908789445887701, - 0.14011424543050638, - 0.3578417650182568, - -0.0168103542753128, - 0.2071802422627705, - 0.4370806286125598, - -0.10753844839169883, - 0.28587986080502575, - 0.07396891933070149, - 0.5407377783355061, - -0.11793617976449762, - 0.4079618814509085, - -0.06719868115503459, - 0.5616253566321366, - 0.38131796668228757, - 0.5325614157948347, - -0.11114710083946588, - 0.4139624949224374, - 0.5040868554128566, - 0.5754020159833199, - -0.05816948545794025, - 0.20867339913109378, - -0.03713535547967463, - 0.18607962881042722, - -0.008941936386503924, - 0.23937101189263155, - 0.509619958126795, - 0.40559888217933704, - 0.2632968648236435, - 0.00877722657893834, - 0.1801134827224023, - 0.08501564566680347, - 0.5892092485594413, - 0.19035121118315873, - 0.5218499664746921, - 0.18891410170799727, - 0.4890585667494789, - 0.308751013136418, - 0.08565977117453985, - 0.08336751527005479, - 0.27817622458308616, - 0.48936772307488174, - 0.5032406388186458, - 0.38116911665060627, - 0.1955527477166069, - 0.03506816913844246, - 0.15961516937896458, - 0.2133245204304689, - 0.605837730765285, - 0.13494923219160998, - 0.3673791296661141, - 0.08853980421618246, - 0.4263715206375662, - -0.03507503124196251, - 0.2785314534182315, - 0.08564051491861469, - 0.2804194050646434, - 0.048008420850683964, - 0.41306273081983325, - 0.5622688117935581, - 0.6014934989929339, - -0.004378375501769116, - -0.06382099616252393, - 0.0077471590559417824, - 0.15446070458097083, - 0.5031750680955398, - 0.15464789414582458, - -0.031191399527904687, - -0.08523688325623449, - 0.11136342135421434, - 0.08349020508852456, - 0.34813907873644934, - 0.20664614045433227, - 0.05446025824880238, - 0.213987650984028, - 0.474658487115899, - 0.4391099346332985, - 0.37759910282882725, - 0.5720689156722212, - 0.02932089011483488, - 0.04503641499198366, - -0.08621969108947343, - 0.4305168839983913, - 0.003286588556969866, - 0.33089945767470413, - 0.17727458524929102, - 0.042357486300031666, - -0.12378211021733347, - -0.04906034431238861, - 0.5697449970331907, - 0.2243723515872626, - 0.24790878129755728, - 0.03647356946870964, - 0.5428334712461519, - 0.4301178126496903, - 0.23360319848606176, - 0.06906100138961865, - 0.07604566731263016, - 7.451225592357003E-4, - 0.601307177436081, - 0.33505650254620734, - 0.2953308477020174, - -0.11471397679690545, - 0.0799366175924828, - -0.06737550558101442, - 0.45541215749730846, - -0.009696861887847935, - -0.01562937055299174, - 0.16955819462167365, - 0.11115364156500962, - 0.37756328347679946, - -0.06509707820486078, - 0.03596393631182196, - 0.5401312965314807, - 0.3879060730755777, - 0.47831146137164005, - 0.4155631183361911, - 0.4113730740688335, - 0.4669705413307166, - 0.2642771952705223, - 0.3106367179372098, - 0.06521929697264708, - 0.13527971445469417, - 0.5953182475742416, - 0.3853032193131899, - 0.2182273364738896, - 0.2092063745731873, - -0.1059386641604404, - 0.3430252156732625, - 0.2987990301327319, - 0.4219863873691446, - 0.3774736696925979, - 0.2620688274858473, - -0.06559857549619662, - 0.18743960476879534, - -0.11491218181086396, - 0.4362971479217944, - 0.5639241061407931, - 0.12483993149918049, - 0.41762057998714996, - 0.20795972955392783, - 0.16855763023314885, - 0.045097021893975964, - 0.3594226700342587, - 0.38450300751985733, - 0.5078299629272672, - 0.0849717009044931, - 0.28906829728871086, - 0.13301955784607722, - 0.00493329157088232, - 0.5431776239152531, - 0.12784529562440872, - -0.051921542985894215, - 0.23302915715216138, - 0.2910256312403452, - 0.1647145037352606, - 0.30346599283637193, - 0.36545959157453867, - 0.1078340678443104, - 0.5288699111819102, - -0.063297685359017, - 0.5324803039673852, - 0.1587340733615824, - 0.5539342983971275, - -0.04652024132819313, - -0.13617398532318686, - 0.3978278378092549, - 0.5616288433342479, - 0.21901535386529813, - 0.5154066292619706, - 0.021037130428710776, - 0.2596468187669036, - 0.015553081197571678, - -0.04601791178463539, - 0.17450858261383467, - 0.47683218877354705, - 0.0748264221302461, - 0.13393885016564372, - 0.1756678419763819, - 0.46018315403095866, - 0.06865735949761509, - 0.21107796852887667, - -0.13642316227771042, - 0.46781195284350885, - 0.07011932850820313, - 0.0618374179630464, - 0.49874130306973674, - 0.43937483159068524, - 0.08051294037982687, - 0.14827878384302046, - 0.007984243101085364, - 0.16787968425168304, - 0.19416600386247884, - 0.4068082635482605, - 0.009219998571200372, - 0.25772726230216986, - 0.2076038749778853, - 0.1321003812720234, - 0.3155160697830066, - 0.1771561235702539, - -0.09181583848505716, - 0.5932464275169883, - 0.5458550295051966, - 0.15876601672302537, - 0.1439015099931275, - 0.4342467468360526, - 0.5119856024076237, - 0.28199486044522437, - 0.4805746639655737, - 0.08849426411957367, - 0.37754475380860597, - 0.34186681686016834, - -0.03333215120836833, - -0.0521418273625265, - 0.39299681306974066, - -0.10605900059008931, - 0.5939697724977784, - 0.24174662003622088, - 0.425171386912401, - -0.06239814157019029, - 0.4606177127380148, - 0.36336208393375535, - 0.052561414412505975, - -0.12376685992029929, - 0.47170084560849146, - 0.5571261626809199, - 0.3794311203633952, - 0.5284050858320153, - 0.47147182505381247, - 0.4724737090514879, - 0.5271988319046087, - 0.2652711482267518, - 0.41294053303765343, - 0.06632643893586002, - -0.09519152661893673, - -0.12962521988272663, - -0.11879480980850382, - 0.4702298573041346, - 0.26723283921506713, - 0.3426962422667663, - 0.10389379690926565, - 0.3769588244372314, - 0.2826515204298474, - 0.33591842123093196, - 0.4742371593152288, - 0.5020246999641065, - 0.27501891201348766, - 0.42689779126276695, - 0.5470543603608736, - 0.017664166590103614, - 0.01965425616784877, - 0.07324358077413981, - 0.09380163101548539, - 0.40958513207539604, - 0.590880754339729, - 0.5475613082258823, - 0.46341605057754776, - 0.3669013701013115, - 0.6081499794365001, - 0.10832009972682316, - 0.23317363443799177, - 0.32980334484739726, - 0.24861153055409824, - 0.29893017507113423, - 0.3320144058769098, - 0.40450441792362646, - 0.24633985489379717, - -0.0582084042761684, - -0.09324640198161233, - 0.4624132419106527, - 0.558317876912098, - 0.07923284312284237, - 0.09727230669404074, - 0.5568741997865939, - 0.4186857452227717, - 0.06026670975883869, - 0.28733535776446945, - 0.16262176877261875, - -0.11127341175764274, - 0.5218377016596556, - 0.34087723938196657, - 0.5056989684454853, - -0.10250416264485297, - -0.12069771485833863, - 0.22907585814261056, - 0.17106966680507651, - 0.4503590264867898, - 0.35156712094617204, - 0.48722653109197056, - 0.0777945269061236, - 0.19480296121119123, - 0.4255350992136133, - 0.42604293695515394, - 0.5603512098674337, - 0.5712542208586365, - 0.49903925306021346, - -0.11635536063511696, - 0.36092555502797324, - 0.3049035942585415, - 0.17669523507276014, - 0.24432536641548375, - 0.34110901807824856, - 0.6058504793215178, - -0.047985320358963066, - 0.09574049284834887, - 0.03371250246469354, - 0.31051392462150673, - 0.28705434676207614, - 0.06218191308787244, - 0.5296753915076353, - 0.2135574273641373, - 0.11339105710246233, - -0.13109467777291928, - 0.14583574831165574, - 0.4947532784643136, - 0.39937463393812256, - -0.10808462910602794, - 0.49323694441849586, - 0.2903047520632139, - 0.018088333774633036, - 0.33538177888905646, - 0.5558103701638045, - -0.07715456270121145, - 0.35791299134494925, - 0.24551446199479066, - 0.03438608638856597, - 0.35027727513944984, - 0.170670666261866, - 0.07711312176863391, - 0.4502099140433855, - 0.16152289620312327, - 0.04031825924265128, - 0.06271048538012533, - 0.4657145880653778, - 0.21340754916859994, - 0.13385462300911982, - 0.35843183125363404, - 0.13741137895609062, - 0.2181810104903959, - 0.26160359459951327, - 0.2907104270380823, - 0.5302994647950594, - 0.35242063264073603, - 0.3818836301133287, - -0.10449330211947595, - 0.521350625092338, - -0.01818252181807893, - 0.32659080622728304, - -0.09231960816089692, - 0.014929712709634335, - 0.4247624445029342, - 0.13520834536174864, - 0.02909039561061308, - 0.24376019195789794, - 0.20615376695788679, - 0.3907196796934338, - 0.509666199358883, - 0.21863223734330822, - 0.5422824832501394, - 0.36358566355731714, - -0.11130792714886703, - 0.515855959510218, - 0.03501132952172528, - 0.6063961987523858, - 0.3730755462515284, - 0.3663545725446862, - 0.23178227885847286, - 0.4974255571444166, - 0.5121920790082954, - -0.01964598317397534, - 0.21396448917117727, - -0.1299057415053938, - 0.31220276699989497, - -0.034700520064310916, - 0.5600261687482246, - 0.08553333109906397, - 0.1935914963790199, - 0.4564535476370074, - 0.2832194184954982, - 0.3693083690741459, - 0.5876733588791899, - 0.49759301733030603, - -0.005375647962556518, - 0.5387994069659269, - -0.03037587742209584, - 0.08863029539898101, - -0.03993550927598433, - 0.24144444797098674, - -0.07726371119515768, - 0.3798710033545446, - 0.5323014966613353, - 0.09782600353320794, - 0.18475370773874156, - -0.1132759855117247, - 0.22243336519851137, - 0.1734187860079059, - 0.31754277966223404, - 0.37313411761950876, - 0.13782329004531985, - -0.08199512191393035, - 0.5873103663235255, - -0.11685024545025001, - 0.3116383981906192, - 0.29444109523567547, - 0.018690661006848602, - 0.2949217938144738, - 0.044320146601283306, - -0.06918086155081093, - 0.350986307522645, - 0.28208413407462235, - 0.1907961676391905, - 0.5605777133757651, - -0.012798176653691234, - 0.6101751811031405, - 0.1733448565331861, - 0.5044556397276262, - -0.06904722948503196, - 0.5125659035458706, - 0.3978792554740732, - 0.529708153791676, - -0.11828833055651958, - 0.030961488235874163, - 0.5982171403154051, - 0.4989471148475666, - 0.5302668584585334, - 0.10353947506888028, - 0.077021620745989, - 0.5427016807307125, - 0.19916895449803462, - 0.04094695316158578, - 0.5666798492975195, - -0.05781288630597964, - 0.509163939274034, - -0.07005905564928616, - 0.017299001107875633, - -0.12656975827973888, - 0.28692545248725754, - -0.05198500055662979, - 0.17594708428262912, - 0.060637000530194135, - 0.40168779898683715, - 0.45628798952812266, - 0.1301494213040627, - 0.4560468735165978, - 0.3895083632639115, - 0.1563032917050844, - 0.14247851468490458, - 0.5181438265020908, - 0.0389832672957201, - 0.5077563424545192, - 0.29158418880408066, - 0.14904165774548445, - -0.03216289784637959, - 0.2600400888781981, - -0.04107352827662698, - -0.0998654042691377, - 0.44354721235346783, - 0.29131528574911636, - 0.1447290893532887, - 0.10931795763769925, - 0.5901489338435535, - 0.5099286156088593, - 0.11926850233328168, - -0.11978510926391527, - 0.5891416567396948, - 0.5737096722852831, - 0.20871233120867738, - 0.3378393950169729, - 0.29040354740050855, - 0.20636455839475, - 0.5175577727365355, - 0.5019683714295622, - 0.16684762155165195, - 0.5165470209576121, - 0.26587903062026086, - 0.0913754807626137, - -0.13638496175350634, - 0.10485944057755514, - 0.20504718063301242, - 0.3867839352937483, - 0.17813953558703383, - 0.4286087109520117, - -0.015325407358874762, - 0.274167609699956, - 0.1814557811838437, - -0.030440695017037167, - 0.1863928330414869, - 0.37269990919119966, - 0.01829809477152916, - -0.01647178448843467, - 0.5615110524123887, - -0.07580563290719808, - 0.13403539208273957, - -0.06977479894311228, - 0.10728693971956679, - 0.3346722727334178, - 0.1436244162491429, - 0.20622636920356885, - 0.1991128657138896, - 0.4913420113935215, - 0.0584333540962618, - 0.3338445742668825, - -0.09739185832876976, - 0.04559042464415192, - 0.044381816980617994, - 0.23218322508945083, - 0.5830765344428624, - 0.44926591390237813, - 0.1897806022479931, - 0.183507362207469, - -0.10359501028777501, - 0.14213924493845564, - 0.2350094349504004, - 0.14316848330535398, - -0.09608320700650735, - 0.5864233691253916, - 0.5455014940299413, - 0.5131851277478383, - -0.11790900045903212, - 0.17340146422774827, - 0.28147944181549756, - 0.0016754225702281245, - 0.12469199016603949, - 0.4372836507272324, - 0.0885888718772459, - -0.12363922527420093, - -0.09546674359291321, - 0.45855883374247064, - 0.41026976315075325, - 0.40713320660926133, - 0.4213361199168507, - 0.2986203137106599, - 0.5857262942091473, - 0.21599477404994977, - 0.06701230856349419, - 0.15634355110443915, - 0.4030989667243613, - 0.19702538593917662, - 0.17882777856540055, - -0.08768613857202469, - -0.03754185883248726, - 0.09424374854812942, - 0.136788506294229, - 0.5311104234652526, - 0.5267365899357813, - 0.5955459719970032, - 0.4953345608793839, - 0.5366580465025078, - -0.07523651006545697, - 0.1692293562533611, - -0.13168243320808135, - 0.4082775917771908, - 0.5241210980831327, - 0.1951867008121907, - 0.357733417978717, - 0.33653439333552043, - 0.49680478811550255, - 0.23997711402055827, - 0.44499475461289106, - 0.4790156711911491, - 0.3135174473020175, - 0.23482633852398316, - 0.17371621043199703, - 0.2499326442309377, - 0.43076965294135716, - -0.07060108172859778, - 0.3933761297101219, - 0.13463607704537056, - 0.04164067381008599, - 0.06488841766572317, - 0.4582967357752873, - 0.2783127991402629, - 0.5269536849367987, - 0.420246163662399, - 0.47911144382044213, - 0.44265314067049, - 0.20256019062964176, - 0.2195041952454561, - 0.381179481335314, - -0.02103383615560382, - 0.46136407896742493, - 0.2571481441072441, - -0.01814865855819807, - 0.2878753438717705, - 0.4429251609784035, - 0.47002098910284096, - 0.019194983059636156, - -0.07883486880719617, - -0.05328587784285334, - 0.37964741394476387, - 0.14836907812025446, - 0.35418802494376, - 0.2763978830014891, - -0.034050921535329584, - 0.08560518417859903, - 0.184527123155992, - 0.5731721503083054, - 0.5610157643319746, - 0.3324774228728021, - 0.513403612150063, - 0.07150127645884394, - 0.07589944939590207, - -0.0657407858406643, - 0.17386273618665932, - 0.01411242572589158, - -0.13361282740730507, - 0.582833983533426, - -0.10703231148268286, - -0.08621175979722495, - 0.04550781452263225, - 0.4022125483045982, - 0.46223595652706884, - 0.440792148956781, - -0.1341541051287397, - 0.12241833940631652, - 0.22206873046189646, - -0.12569550773459562, - -0.017410001681002665, - 0.4353518663632291, - 0.18158620727929242, - 0.20121799044338595, - -0.12625153996230193, - 0.11422396194223039, - 0.4859556702252862, - 0.4920702581071148, - 0.22056078626666464, - 0.12890806784809244, - 0.570004159009124, - 0.056566470860971746, - 0.02219159595384096, - -0.08625091411140307, - 0.35867814874279513, - 0.366527212510404, - 0.6079621510523775, - -0.0318293782026734, - 0.28919395086548305, - 0.13353098084755888, - 0.12418357791232892, - 0.053816857545839036, - 0.5083193699920053, - -0.12903558258043307, - 0.225704884569082, - -0.06436910151485649, - 0.5884326284517606, - 0.3837292050783979, - -0.00795902708002355, - -0.016155000923047044, - 0.4563057296898787, - 0.10265505927327634, - 0.5680747146422992, - 0.2674643599255288, - 0.5620601763388975, - 0.304422599979637, - 0.13877665306442288, - 0.0017357308191860987, - -0.06504037668764703, - 0.2811514651838732, - 0.33406554812894296, - 0.1565025242300615, - 0.5246935162784946, - 0.006269742271678508, - 0.08397410507669917, - 0.10368600054879054, - -0.016903394490193818, - 0.0642756152983458, - 0.6053014581645829, - 0.17547024552839036, - 0.16281867969041958, - 0.49331902947411066, - 0.39603849627963317, - 0.1364542144387057, - 0.0498840520560454, - 0.3094972108439458, - 0.1839670572516548, - 0.47135518729239445, - 0.5599950131202732, - 0.1717805846596483, - -0.03142197785521013, - 0.27898761813557293, - 0.3729658132451563, - 0.5711069527754332, - 0.09271847283530865, - 0.4644109824000494, - 0.15978771336393394, - 0.44829270072179117, - 0.46065398238562727, - 0.05972347444545062, - -0.12156810039600807, - 0.44353001857455177, - 0.5417460719856291, - 0.25272067780585933, - 0.02935049240098192, - 0.47497626521087233, - -0.06790172323928578, - 0.4208379875739999, - 0.3941029866222727, - 0.10474737233029546, - 0.26142216528040496, - -0.001498820857415234, - 0.45433940656938687, - 0.45054769897275193, - 0.5749740855846787, - 0.001270267111346951, - 0.4678597371372888, - 0.350364004737489, - 0.2985078129188371, - 0.3928362533162062, - 0.46290378419487666, - 0.09395946240663774, - 0.19652035519081335, - 0.06510735633815729, - 0.3329491948839812, - -0.1162348574849493, - 0.21150056711207038, - 0.5013044010402365, - 0.47516787779925995, - 0.17600170727646236, - -0.055131853807697195, - 0.46126777025266685, - 0.19671045336072196, - 0.18148998449626408, - 0.24886635591340617, - 0.5358104908695159, - 0.5053400723663876, - 0.012278923555058163, - 0.21268809897590257, - 0.5445057534172204, - -0.02630704157874554, - 0.5090475085267308, - 0.05310853559128226, - -0.11886108879688342, - 0.31974103009962823, - 0.16005414013088726, - -0.10200221948840638, - 0.11731269119232296, - 0.007561389733247381, - -0.13658096180572457, - 0.20743321323019398, - 0.33780127858890496, - 0.20431613792322428, - 0.4646259645495585, - 0.543315386109017, - 0.41202833666737515, - 0.10251401872135704, - 0.23002237384450508, - 0.4318895285807387, - 0.1389224130779108, - 0.3012859297404203, - 0.6108857078123269, - -0.08079429551978991, - 0.5356322754110534, - 0.10981506303591826, - 0.5401525006638617, - -0.13722581929412075, - 0.5080022607043287, - 0.2854943201675218, - 0.15435403641751488, - 0.5371491474018089, - 0.5280289772743961, - 0.3848405215558731, - 0.1511960231053387, - 0.043473063101350184, - 0.4927858476553836, - -0.09255840140924018, - 0.09130904113612603, - 0.5042219459889767, - 0.4807026822627354, - 0.3351965421728467, - 0.013341110638871445, - 0.3543019442789457, - -0.11602760893111702, - 0.15993081451049085, - -0.08540640072258043, - -0.11994470378508972, - -0.0841415224661956, - 0.46424457288549537, - 0.09803032308140222, - 0.415771671065578, - 0.16768683030455622, - -0.07862579333400874, - 0.4007683576726574, - 0.10146794592407254, - 0.45604273200927625, - 0.04692927525939569, - -0.03650007595186314, - 0.14567524239498897, - 0.1065795479895941, - 0.5245771057178611, - 0.02722056945226156, - -0.008352907645996582, - 0.33703188771904774, - 0.23311014409865688, - 0.002648215816281191, - -0.054977842675595384, - 0.16682026992677124, - 0.11002226412540045, - 0.5368448888191316, - 0.17351048830174598, - 0.5464428911862212, - 0.3214064829516144, - 0.16575959194834416, - 0.15584801091072814, - 0.026728554897296447, - 0.12465932681477199, - 0.43142449730457144, - 0.2539708185260728, - 0.24104734229275582, - 0.23443011819095594, - 0.16530582213763922, - 0.49776977865430383, - 0.5192380916440791, - -0.012588664123298884, - 0.5889960087027716, - 0.5779535392896441, - 0.5886367906935551, - 0.33216839487439376, - 0.3128242014284931, - 0.1964585082741665, - -0.11843368093370428, - 0.590765299329787, - 0.4715455835211658, - 0.17800012172141966, - 0.18767392280508383, - 0.34408122794854346, - 0.16095095143888455, - 0.43425572238246424, - -0.05496938372464663, - 0.03536400839651169, - 0.3983444123366797, - 0.3716562543359919, - 0.45635937874765076, - 0.2394812245387274, - 0.20681591436872943, - 0.5027457237984714, - 0.47602084803415057, - 0.42886701190939114, - 0.22823018917308735, - 0.3750086193409138, - 0.33964228900732313, - 0.2617822226934168, - 0.34861236357592224, - 0.13374179820793586, - -0.0945151785416155, - 0.18475330797415213, - 0.5553497339861103, - 0.4947218050121034, - -0.10674027652778292, - 0.547701230480717, - 0.04697214497665195, - 0.11035980338397133, - 0.07596977737775132, - 0.460765717131577, - 0.08754331262051723, - 0.214530034911323, - -0.09625218249786924, - 0.5553058236002155, - 0.22755979956784123, - 0.5081080882681417, - 0.3789056923506824, - 0.5886800017970186, - 0.03138095605243199, - 0.10083512843761502, - 0.4697269856028534, - 0.06505447201935469, - 0.48998785956081214, - 0.40468617903763715, - 0.3706836684471285, - -0.05089087097422074, - -0.04340136793189686, - 0.6028692717322057, - -0.08261955931202575, - 0.3322831215749198, - 0.098378127707859, - 0.14495062666407293, - 0.34837682379399976, - 0.3195843661047258, - 0.3347449226156885, - 0.5449880664826039, - 0.2596177207533336, - 0.04907629591552268, - 0.020903616416014487, - 0.28408059317069145, - 0.1661295020046628, - 0.027016453421143144, - 0.08543667642517586, - 0.33093401880765333, - 0.11191698280563556, - 0.36790528479485973, - -0.09252248032185577, - 0.16641056352259775, - 0.2989340897391913, - 0.48965486041702566, - 0.08319398427965696, - 0.1559707046521575, - 0.47875412328499567, - 0.42419617516295216, - 0.044654824555711486, - 0.1286761741259706, - 0.46185564854594574, - 0.23639702299870213, - -0.016722419334566876, - -0.055342059986317485, - 0.3734777488925518, - 0.5475532417503912, - -0.05863942102367539, - 0.5258050995644387, - 0.13275088453695072, - 0.3415347591427909, - 0.39048521461312247, - 0.5723609954486547, - 0.008833317900245607, - 0.29578504938897293, - 0.08721284871952753, - 0.39394811335260516, - 0.3271483842036204, - 0.05994814004447288, - 0.15291136186202436, - 0.0982290411162127, - 0.24149958388606624, - 0.5649688238809005, - 0.4445538226832815, - 0.14838077067402816, - -0.018070966033271033, - -0.011221420748540545, - -0.019053931504857943, - -0.1330476997023332, - 0.027661285190812845, - 0.5959834433264459, - 0.04335637775533155, - -0.05309907034788386, - 0.26438689367806306, - 0.43440270358122146, - 0.2695897446785602, - 0.2903908837570677, - 0.49804376621844193, - 0.38353725902602676, - 0.5068305960618386, - 0.3557937396557838, - 0.4930835521461938, - 0.2688293211039796, - 0.4535645082435287, - 0.40784743164406667, - -0.0433685383362345, - 0.564985579887999, - 0.06835730827358025, - 0.08818663462474471, - 0.25657718998758167, - 0.31962222074350816, - 0.10176780924448428, - 0.5639197035263348, - 0.22453704930433493, - 0.4360169591489049, - -0.13041963619879457, - 0.46387851488612775, - 0.2825357407625872, - 0.3053764353589386, - 0.3930501296625045, - 0.5427892295855158, - 0.03001427074914792, - 0.20408131032457688, - -0.04424764436747583, - 0.4712056952439774, - 0.11829359721950233, - 0.26438450278286924, - 0.0070376926607536305, - -0.05066775512331165, - 0.5234557897712531, - 0.3514471260497967, - 0.5264718743796712, - 0.06636589091256095, - 0.405536405277686, - 0.24487003456779632, - 0.5230540890276063, - 0.3447715893751539, - 0.6017269148948841, - 0.07011191504558617, - 0.439993753746599, - -0.017063735852688208, - 0.49666804475079607, - 0.05862739986720519, - -0.01619362804507765, - 0.039849319136113226, - 0.30716196757578124, - 0.0011772310715257306, - -0.13368034541730608, - 0.03913628846768308, - 0.03357464222548315, - -0.07946864236367886, - 0.21395029960229706, - 0.22163478636218636, - 0.2057246703696481, - 0.33091791771546847, - 0.48306157184709, - 0.24778707853943188, - 0.2748453731522442, - 0.3470205190093743, - 0.2701015813100718, - 0.5176887929112499, - -0.05987149896920292, - 0.5738470427357055, - 0.3498467568550912, - 0.6105345700100769, - 0.17438303729127413, - 0.15582112200349008, - -0.08383462506608992, - 0.342435957809375, - 0.48601669332898845, - 0.12229770522282846, - -0.009782252983123046, - 0.6077375014246559, - 0.06646143285350772, - 0.6097079820568975, - -0.013714053953991334, - 0.5666544748265586, - 0.4129012916384299, - 0.27840291554499863, - 0.28403485052388744, - 0.39171715531172, - 0.33511456082930074, - -0.12735251440837153, - 0.5090145077177612, - 0.36639825202292375, - 0.0918527382344145, - 0.012099169017364741, - 0.34184826854528677, - 0.14908694900736047, - 0.33977717779363314, - 0.18937923178873212, - 0.384637998054858, - 0.29058071199110425, - 0.15947556286005654, - 0.38834458664401184, - 0.5043560049327878, - 0.2803905411365618, - 0.3824253204879484, - 0.14046907907612827, - 0.5013317915679459, - -0.05039278415510014, - 0.1325093581761091, - 0.5270738649053709, - 0.23863435964109242, - 0.05189177397858796, - -0.0978902986922896, - 0.5575904264901255, - 0.30818164840101564, - -0.010115472561209787, - 0.1638552829586838, - 0.21429630965907948, - 0.4635953442920926, - 0.0219473624159581, - -0.06303289997283744, - 0.5243390679649493, - 0.47421514836978484, - 0.2479561838763959, - 0.25579376800309916, - 0.4506449696716974, - 0.006326852486399165, - 0.22998320117531224, - 0.16731154932341225, - 0.45510211156537217, - -0.09457211170450916, - 0.3193812968583997, - 0.32626513738267815, - 0.0412327923082004, - 0.25610477453653885, - 0.5299042885569305, - 0.3496589434401481, - 0.13675782467064562, - -0.002027768533363866, - 0.2860730255563419, - 0.4287001884799374, - 0.5412602578604806, - 0.24391202924927263, - 0.5019766825070419, - 0.3188042241716155, - -0.07465408744345883, - 0.2940728176041355, - 0.580906388402356, - 0.2898957349081792, - 0.20498891294859883, - 0.1344584037438568, - -0.02499442508294633, - -0.11968778787113794, - 0.357092305454376, - 0.42926679170663173, - 0.37469365574572366, - -0.11365971458714319, - 0.055632238096841286, - 0.10832153340351042, - -0.031188978893107816, - 0.5726690106657937, - 0.15975992009313272, - -0.024323506217155594, - 0.5676252856758184, - 0.3612059551026381, - 0.07598093871258502, - 0.44804603943587973, - 0.2959658829219815, - 0.17219153945639426, - 0.08565310505929036, - 0.4655100641526698, - 0.38228249566759687, - 0.07144969711311233, - 0.23990192977507713, - 0.5412829616555621, - -0.1366702671936378, - 0.36149303384040216, - 0.07113534247241268, - 0.5120537904358765, - 0.31616362852288954, - 0.08760843550249772, - 0.5134660526546866, - 0.5953594039140859, - 0.4636361608331526, - 0.1220910115969775, - 0.06864272765916585, - 0.5123315282013203, - 0.47535683809039786, - 0.1772412156277705, - 0.46872550921826184, - 0.15833600243258766, - 0.5817708247877559, - 0.4149348983141157, - 0.2652589503453975, - 0.2789544197896485, - 0.556758108953402, - -0.09658920425854041, - 0.300705234736655, - 0.5340476492461189, - 0.46453726909215176, - 0.12367695884544838, - 0.11120415899972041, - 0.4180808886968237, - 0.0739617579031133, - -0.012035275933706818, - 0.35154848187032145, - 0.14176607282065157, - 0.289095192977237, - -0.061862578976675756, - 0.17100242134595994, - 0.401426353373427, - 0.07801785490443253, - 0.2885244981608636, - -0.08889615901403727, - 0.23669476300017006, - -0.011784281939218127, - 0.10307366985782493, - 0.11309728597965996, - 0.43667105817058527, - 0.4174682693303158, - 0.4559319508057894, - 0.3228691751958065, - 0.056021138674065746, - 0.41979381662949655, - 0.0376393704964442, - 0.42948402246352424, - 0.4321638197017563, - 0.5160654825982508, - 0.022552584009734422, - 0.5722339247786029, - 0.380302006971336, - 0.25732159525621334, - 0.45862838871212197, - 0.15828953442360483, - 0.5427784564279414, - 0.5984595581181332, - 0.420564934340507, - 0.21098860640150047, - -0.027688480418103636, - 0.5817474668448536, - -0.12157667570440414, - 0.3192621276504468, - 0.3276831384405841, - 0.4314510842279419, - -0.06893547203978874, - -0.04125429272051297, - 0.3992362534381022, - 0.0421260075481672, - 0.2904313002747567, - 0.1781869888467557, - 0.5004020186930568, - 0.4687704781563473, - 0.3128322180605871, - 0.02101083058875497, - 0.5513014492629587, - 0.08388354520908983, - 0.4684215863073101, - 0.019922856903197117, - -0.07183564521506192, - 0.027191298797716007, - 0.1748595977743982, - 0.11313359301653092, - 0.10820260398781523, - -0.11528209556588238, - 0.33318121327589084, - 0.2841498064641219, - 0.4005532137254745, - -0.09089473571129283, - 0.1748062172415541, - 0.0375278464600024, - 0.11802506739267676, - 0.273812367743249, - 0.3292816654917191, - -0.13045978022221516, - 0.5082286386010959, - 0.3326447547215549, - 0.4422874829996629, - 0.3571137844254819, - 0.35359095464355766, - 0.4037018936842366, - -0.10522217762475083, - 0.2154292693097944, - 0.5696393173020513, - -0.04625597716886151, - 0.212287150671228, - 0.4326580399294315, - 0.5292053415103407, - 0.14197994443419926, - 0.2085593607879186, - -0.003926657952371598, - 0.42475977158169154, - 0.4657071459381641, - 0.24173615699284356, - 0.40192097987804665, - 0.45866441383791823, - -0.10560249065022348, - 0.5692105174335332, - 0.06907665319393022, - 0.35058299227477413, - 0.5816519091445227, - -0.08812857923064357, - 0.38829483817737, - 0.2939650794983963, - 0.5379716163410015, - -0.07049989735964841, - 0.49871031229516405, - 0.2133527913290918, - 0.5483341334541701, - 0.1366120840368385, - 0.5084426369937696, - 0.11745514076662689, - 0.08117714667206602, - 0.27345194623813696, - -0.045820174551937265, - 0.6106956342979503, - -0.1293993873613253, - 0.11465386255791504, - 0.1713150903206152, - 0.06774589460443503, - 0.2804546876279884, - 0.566975721333123, - 0.5996773535118601, - 0.08726149544635195, - -0.11264701063509472, - 0.2029050660304097, - 0.12995431225754017, - 0.5314328270460583, - 0.27795804495366516, - 0.43477053874550453, - 0.14571563838052004, - -0.1289779248346495, - 0.009431741511017305, - 0.1604200894375412, - -0.055099496603256484, - 0.26106049479269317, - 0.609637358732483, - 0.07801410501102768, - 0.4803005449936134, - 0.0685859694468487, - 0.5346075542649379, - 0.09988546456547248, - 0.027673644061704444, - 0.606357655606873, - 0.015248878158076795, - 0.27032439228189775, - 0.2620379235474418, - 0.5921419607391434, - 0.17327955894184766, - 0.1292104236729908, - 0.22887175499617785, - 0.2111852627365095, - -0.06878456291299821, - 0.22874245725736625, - 0.47165729088449004, - 0.38555395789661584, - 0.19353410666257248, - 0.0807245893926945, - -0.06803229149715546, - -0.03249647418034536, - 0.16833412193451602, - 0.4855235442075285, - -0.11644786655877945, - 0.4612883840822457, - 0.5273133821956026, - 0.3292301720955355, - 0.06984780732731966, - 0.46323224730059287, - 0.25017639015742604, - 0.49504997684504437, - -0.051333356679210684, - 0.0522683950101791, - 0.38996408780070146, - 0.39394638913412305, - 0.24901368387863143, - 0.4031886914465266, - -0.009430245560946765, - -0.04975743466242938, - 0.30952980331673835, - 0.412441383411027, - 0.35132447568334857, - 0.29930988777500417, - 0.20272126429401577, - 0.24617760672823025, - -0.06688514755411883, - -0.06347183701424323, - -0.05652335890316039, - -0.011954423303128792, - 0.5743695980025744, - 0.37596961298952736, - 0.12015436722903067, - 0.2792031365138131, - 0.6090496335776785, - 0.34734317652437185, - -0.053002764010896194, - -0.13497531553030223, - 0.5599421832607909, - 0.39899997559046174, - 0.5438829136506539, - 0.06769260652620124, - 0.3578628040657533, - 0.6014654074338454, - 0.4791098308505851, - 0.439668085651142, - 0.4928180627944123, - -0.13697130824027512, - -0.007027462752235841, - 0.536571765012766, - 0.31841428670134475, - -0.09223147565190931, - 0.1314896237222018, - 0.49086789703009537, - -0.06768011598058715, - 0.12138438615729719, - -0.033234668974533976, - 0.3427091007030372, - 0.43299250886999907, - 0.34142052240691617, - 0.1876426799408395, - 0.058302610432529156, - -0.03810817569184789, - 0.13204798118401773, - -0.0857517064659218, - 0.4983642459418629, - 0.5943099630800691, - 0.4134309477867322, - 0.13402101772071529, - 0.49713305726315604, - 0.22229032315080544, - 0.5283168758009137, - 0.21883448442543396, - 0.5734200521907824, - 0.325336832146613, - 0.41073489686319986, - 0.06743034529622746, - -0.03526567964632697, - 0.5620438481876545, - 0.24353548224043142, - 0.561179365687331, - 0.4982295942294799, - -0.04253958542651988, - 0.5488405138187095, - 0.23082404732400325, - 0.31254503650997606, - 0.17861518879439875, - 0.46619571060126996, - -0.059493860447461355, - 0.22595736312244502, - 0.11641647157869095, - 0.15427726540345627, - 0.20983320170638203, - 0.402782877124659, - 0.14231962982336682, - -0.03767029963085697, - -0.0672142973658382, - -0.11108756834258565, - 0.23063996005874843, - 0.49217730078679134, - 0.5799476123394505, - 0.23215272078489302, - 0.5977832178446759, - 0.48915170404012875, - 0.09566590682051893, - 0.456541345693971, - -0.040302505128512786, - -0.06969034009609738, - 0.4050539849434295, - 0.21645669756165564, - 0.22008263372981257, - 0.028982631347593074, - 0.10256650104993989, - 0.5141861008931137, - 0.06179669378564409, - 0.42465335361674406, - -0.12056007783777771, - 0.1289518710745169, - -0.12707214179591417, - 0.4557072695620039, - 0.4084485583342917, - 0.214315040534737, - 0.2619856435364618, - 0.2246197102669072, - 0.5512721970726222, - -0.006915741433568684, - -0.0020713598982188275, - 0.007676449338899716, - 0.31105072623999946, - 0.44025473820886574, - 0.4019055624520166, - -0.10456356175710856, - 0.08120765028836066, - 0.5306265981100581, - 0.5687504841831893, - 0.4466064606546978, - 0.43324216578419317, - 0.25646594485764346, - 0.33776666324603116, - 0.2952367483123858, - 0.21230500437750865, - 0.5747246795795716, - -0.022499834367122384, - 0.4582153647837274, - 0.46341152054949786, - 0.1842354774533917, - 0.5953283576245592, - -0.1226127546827244, - -0.07053368541491231, - -0.029986092019773702, - -0.07716063723949343, - 0.34221893066992026, - 0.41957018298204496, - -0.023087222248670186, - -0.033618402715360304, - 0.3544651828434022, - -0.10513516466916387, - 0.47063017371853877, - 0.2962116323233484, - 0.19292620299287394, - 0.05489669696638061, - 0.31670148513769175, - 0.23909649375974756, - 0.09909804832990946, - 0.24250600837119712, - -0.03972621619554746, - 0.5559503153322273, - 0.09416139561675854, - 0.4568725934615411, - 0.59206877379263, - 0.20996925663688398, - 0.52784379013855, - 0.3380533930140957, - 0.23853645505485815, - 0.48978499794809194, - 0.036500719182886054, - 0.5361302384377497, - 0.2761340269468837, - 0.5669834633070224, - 0.3295616870891309, - -0.04689108991587135, - 0.04019649567557412, - 0.08825054289387294, - -0.061401144294815246, - -0.028596853748023274, - -0.09992412776344498, - 0.04634787500442494, - 0.2976043619106587, - 0.15255232174396804, - -0.00626475449741376, - -0.04105263459797817, - 0.22754519799762252, - -0.0506288533916604, - 0.0676344157977962, - 0.09681074844699966, - 0.05060987566448455, - -0.005302963106987357, - -0.07559726896520359, - 0.2245271650096281, - 0.41960763670575096, - 0.56972791385477, - 0.36623690160820777, - 0.42378863252971766, - 0.186698168612572, - 0.3433792554751624, - 0.2434544972968778, - 0.0629546207157001, - -0.039789261165297074, - 0.44641469148720747, - 0.3842661974735788, - -0.05418096888010085, - 0.08355968529995678, - 0.6013609700080208, - 0.2078367889766516, - 0.4600449952694903, - 0.020806325153794075, - 0.439818842681455, - 0.5568413413909061, - 0.512654980047776, - 0.2802821007562825, - 0.17008083203313323, - -0.03397225281088122, - -0.04223650170185503, - 0.5633404439640026, - 0.28686181311577724, - 0.029717167507109926, - 0.37447832139413695, - 0.19862432298661892, - 0.5552751161352054, - -0.09652442004072939, - -0.03616493518984773, - 0.1303298390841578, - 0.5893146935471523, - 0.2705448764444133, - 0.1985143303196814, - 0.22115654547649433, - 0.3541765968620121, - 0.22760105084197257, - 0.007719840924440391, - 0.312491318074978, - 0.3765214220301687, - 0.27556837065419904, - 0.5040312534605088, - -0.0027710430834536615, - 0.04826362779674237, - 0.06366647708920287, - -0.011411632728584337, - -0.06915004354045885, - 0.3642924183350651, - 0.1191344285972874, - 0.02827178468180025, - 0.35571247651025467, - 0.4181615994303476, - -0.0739022283546181, - 0.3274287239641861, - 0.3575597290916101, - -0.0674751772491435, - 0.4223608124974567, - 0.29274274203896894, - -0.10068689594402859, - 0.21196290895759118, - 0.26677886307412174, - 0.5750909844488384, - 0.05002283345082778, - -0.10753858934774543, - 0.23550925201706702, - 0.23904483612620597, - 0.5258639994579777, - 0.2934839155012105, - -0.03684751401478893, - 0.1319006246450305, - 0.2809803337865945, - 0.16052983123502607, - 0.37704077898886423, - 0.24891344487352884, - 0.47507661962861825, - 0.48901686063001437, - 0.5843777443389644, - 0.435772179524616, - -0.030217939178573586, - 0.4988073522451071, - 0.3413984030306078, - 0.28132261503859085, - -0.07861796838094673, - 0.15304216813178112, - -0.06458921250951682, - 0.35038141013635843, - 0.1248162989614151, - 0.2352644875516261, - 0.38064548934811404, - 0.043762068600872644, - -0.014067866030171669, - 0.31178601388138816, - 0.07389909392900973, - 0.5458806054334431, - 0.25816114854381556, - 0.032640709727340095, - 0.33543559985680976, - 0.13982637457883973, - 0.5987904142344431, - 0.5832102329337365, - -0.08831888260570372, - 0.13172216844195395, - -0.012211969409191281, - 0.020929225655425515, - 0.4150107002952005, - -0.12713916376959, - -0.011579969784716149, - 0.03176524578790879, - 0.16945372566595374, - 0.5452841012070294, - -0.09851715571128893, - 0.17738854226902329, - -0.04693921595273655, - 0.32406729635670817, - 0.532486533300872, - 0.5281732101058886, - 0.022961095183551217, - 0.49754366660665605, - -0.11139885651130502, - 0.2748759368657001, - 0.2592721503664618, - 0.5462167699752926, - 0.04439726113188022, - 0.25649498800802784, - -0.021497528670672353, - -0.05360925615769917, - -0.055939153687247486, - 0.1796410517048524, - 0.2320002793134991, - 0.6043340381556147, - 0.44208895184520447, - 0.5842468816446799, - 0.5439441756279866, - 0.6007951315006198, - 0.585154483544518, - 0.029569868235943764, - -0.03931176887805356, - 0.36358854786208616, - -0.0694208301952309, - 0.506496751201539 + -0.3019206158563271, + -0.24029538829620556, + -0.4104350583063272, + -0.11194905596738192, + -0.28675296427848873, + -0.33388779216947617, + -0.502561248703489, + -0.3590285468107309, + -0.12951887599911405, + -0.4236884720513067, + -0.6861339538819354, + -0.8044427835894766, + -0.8447203087103776, + -0.5004991333326907, + -0.0905940402868538, + -0.290870075998122, + -0.8439447892163728, + -0.6652911670361107, + -0.08536673762904468, + -0.5885509017264076, + -0.2323360413889609, + -0.14267053816441255, + -0.7888800764228404, + -0.48674276392909666, + -0.7651249654746298, + -0.577257410667545, + -0.6373297464706759, + -0.03513549834606344, + -0.4451133910909785, + -0.5536559678209119, + 0.12066508330088299, + -0.8345888312794106, + -0.6253006042249872, + -0.403776300613717, + -0.5749149199346111, + -0.8014090701254156, + -0.3280409131884785, + -0.6812987960457341, + -0.5993399239835153, + 0.06872219665679091, + -0.6653186867883145, + -0.3310507387178855, + -0.7080161614765277, + 0.11651497757840856, + -0.3135328185340063, + -0.8233999990337626, + -0.6804106358259828, + 0.02074875035955559, + -0.7077090993542903, + -0.7295729066229115, + -0.12869996303419662, + -0.026022641727327267, + -0.3273520292588272, + -0.7551716066823252, + -0.7127481310579561, + -0.22474050157174796, + -0.5929618669727159, + -0.24252555616139593, + 0.13395823017981556, + -0.6641403690862195, + -0.6253286242711257, + -0.7329169191336551, + 0.10153407326180541, + -0.6955391964593025, + -0.4729183044879709, + -0.35103620041871725, + -0.7910153841698907, + -0.4939408022529764, + -0.3658055551045795, + -0.4139382788777219, + -0.33849092109899126, + -0.15445744107923853, + -0.1722315596501398, + -0.4545634377882526, + -0.3232710530248516, + -0.02445435851517097, + -0.4339703697957739, + -0.8045281134265647, + -0.4902878874844662, + -0.7911328579710526, + -0.20981364503915434, + 0.12189300817948812, + 0.1414060270470474, + -0.4121443043693007, + -0.014528743647285847, + -0.3020776798925976, + -0.8153258291656453, + -0.7853942048482316, + -0.1369736002742522, + -0.6869306183279017, + -0.1189855077427967, + 0.11883463713954712, + 0.008975665115476983, + -0.41643082467691117, + -0.3528553940700092, + -0.6151949260887447, + -0.0055666455833842665, + 0.026036387739130196, + -0.4356812025437315, + -0.5714030147544904, + -0.7881127395664698, + 0.003752901688906407, + -0.03268453710290731, + -0.14468848959523806, + -0.14668303996064636, + -0.4941785133508498, + -0.3713064547822425, + -0.32592388125249216, + -0.04236402224351421, + -0.28672756574071556, + -0.7810068792673688, + -0.5877576009828969, + -0.8124123456461233, + -0.34206993770028393, + 0.07483428533832304, + -0.7243453231716422, + -0.41068651885248053, + -0.03089620831445994, + -0.26500275301563436, + 0.06069487649890326, + -0.4108865643458476, + -0.0020170050187191535, + -0.1958272900936403, + -0.7787082612231075, + -0.29246863868067574, + -0.7093791522209527, + -0.12506242484989893, + 0.012168902090948674, + -0.7542753301430588, + -0.6395571409482722, + -0.7539481911246094, + -0.13406740524155125, + -0.2837496144675905, + -0.14317975253253568, + -0.13644428595207791, + -0.6410400237861441, + -0.02659486334979544, + -0.4427883806461398, + 0.00100758553533975, + -0.15464884134246593, + -0.7320903773077101, + -0.5216181024312827, + -0.691132451112203, + -0.5037351317846002, + -0.5693641751568121, + -0.5261975651832421, + -0.2730693585255223, + -0.6790852547871076, + -0.7392768171552241, + -0.10731648080392597, + -0.3081452807401952, + -0.7907125367239902, + -0.05253953383835752, + -0.5246468475900261, + 0.06254414160889643, + -0.8266864644889987, + 0.13091783303642013, + -0.5311229980442896, + -0.6844175524533894, + -0.18607995890933804, + -0.3015493496508719, + -0.3427730030933325, + -7.387503299738363E-5, + -0.6786643458374989, + -0.49561673514587223, + -0.30650501147296905, + -0.40347486430812507, + -0.23158063072737378, + -0.6024180234871837, + -0.022851874581586107, + -0.5107974317562934, + -0.13370062140006522, + -0.4003851750406516, + 0.07695357086977461, + -0.3195237210541163, + -0.6384769911811228, + 0.011825771893622772, + -0.02168028171443681, + -0.3518946513982119, + 0.06347750882114456, + -0.44253753711769006, + -0.5871681493750158, + -0.4123258779916201, + -0.7220353236579247, + -0.38910356403333396, + -0.8468241224631576, + -0.5533632147614586, + -0.6361446872916885, + -0.13405114010979413, + -0.6164377671078372, + -0.1300893481755946, + 0.041353847548780576, + -0.20653081209677526, + -0.12138336991220233, + -0.20549510803536397, + -0.7675932374120435, + -0.2781919855718239, + -0.04317614429471839, + -0.6990915803634082, + -0.6596065616483919, + -0.31048580221527244, + -0.67232307262819, + -0.5111501046988629, + -0.057065580745847666, + 0.10543795191599703, + 0.11075085741575696, + -0.015687840685359444, + -0.484230946034494, + -0.06357123043829971, + -0.3011163357235568, + -0.3075126776454249, + -0.0968511145262484, + -0.10692110031122759, + -0.7876158315886781, + 0.04173501045038486, + -0.8422642663053052, + -0.5312291231660929, + -0.14075646944992004, + -0.003268768817987766, + -0.4426992963914935, + -0.07462604990977817, + -0.8003722524372144, + -0.6252900044589962, + 0.06777385114450996, + -0.6120320681809844, + 0.032320967535321876, + -0.40318865019227695, + -0.2493894820581063, + 0.012873739291651809, + -0.6530812073292599, + -0.3169051990964875, + -0.7332224249705159, + -0.03557068595956536, + -0.3634670947157423, + -0.20633194189148463, + -0.5828194350177982, + -0.5734524551232754, + -0.4783485545593289, + -0.5365998274637276, + -0.11707737817622366, + -0.42206618289985653, + -0.25223509950658807, + -0.043244351001962666, + -0.3982838908760174, + -0.2474590262042613, + -0.147884136679015, + -0.6154879734266302, + -0.7844840755416899, + -0.04036451182739176, + 0.03191102835939896, + -0.7926975675245336, + -0.16085666379792474, + -0.3205090778869114, + -0.6309262937690303, + -0.35509819712577134, + 0.06462900842615948, + -0.19026709295390853, + -0.03373470078591834, + -0.7500586187657658, + 0.14084845438208538, + -0.30792573230980025, + -0.32151492712422036, + -0.42871942010941233, + -0.2889845819531537, + 0.06948469242919553, + 0.07421016836868888, + -0.34357501247859645, + -0.39777226331623944, + -0.41307837825748084, + -0.7794389401662412, + -0.07206397714771495, + -0.34056869517597566, + 0.11516093119270598, + 0.07458555629811414, + 0.02560351005376793, + -0.5172522247921765, + -0.7966303405857731, + -0.258766816562076, + -0.11841497871582063, + -0.09243731814898348, + -0.08285780729106762, + -0.11033736917499126, + -0.6665668209206359, + -0.13145148925947592, + -0.7763205500367013, + -0.4799698754057183, + -0.10784805856357293, + -0.8256654938190828, + 0.09417523021432161, + -0.37553387502879354, + 0.013581754808739466, + -0.2951371104055236, + -0.8348148598317777, + -0.39212846379393096, + -0.7332334416962244, + -0.27697681943146524, + -0.3795870895006155, + -0.2197404819832781, + -0.4719643373115875, + -0.7976190684863508, + 0.13797423121576047, + -0.35692472273694437, + -0.5988303580293383, + -0.5440254561785839, + -0.47222812348367904, + -0.4616806912111848, + -0.3272886012280566, + -0.6035515149211043, + -0.677981687823321, + 0.027267328129898627, + -0.07392250478737528, + 0.015753693385874512, + -0.5671322438220683, + 0.1261591904867989, + -0.28200222774191885, + -0.0653032685717515, + -0.1877196093707757, + 0.12626016153921737, + -0.736497050426341, + -0.43907946694456157, + -0.2942007230577226, + 0.14060793331303967, + -0.05985729765821779, + -0.038298277563881045, + -0.6118874754173794, + -0.8432778580691387, + -0.056284661988129314, + 0.10589751883308018, + -0.24876894810036176, + -0.7713637211833729, + -0.18379814470203104, + -0.5886465561570111, + -0.7675601954621817, + 0.008223368735022496, + -0.033738645138336576, + -0.6312858480508405, + -0.364256884461925, + -0.026059350430216677, + -0.4405540421635755, + -0.2601227612475626, + -0.8006328006007146, + -0.6678901435772696, + -0.3993851667563473, + -0.4642642048918721, + -0.263578289382423, + -0.37378728916315423, + -0.3561526648134157, + -0.34144170006244523, + -0.7719956807791075, + -0.23622887378559887, + -0.3288656999950442, + -0.15983642267329035, + -0.5716683388094201, + -0.5995681984300414, + -0.12486680403943606, + -0.26526730983467206, + -0.6913133178651389, + -0.19741373188227995, + -0.06947948336973553, + -0.5201991577163816, + -0.68246850664103, + -0.7086623798518858, + -0.621030623101355, + -0.27293630924597323, + -0.36503632431735583, + -0.4274076635436187, + -0.1955031244607096, + -0.766750106258492, + -0.8395633474697407, + -0.10951618143856834, + -0.46494659359633733, + -0.7358156831420093, + -0.5304063309617023, + -0.07006023383376825, + -0.5985383578901089, + -0.1092906730965928, + -0.2895272231063025, + -0.2857474713306122, + 0.1198834596914441, + -0.7911424620206795, + -0.6348716915071664, + -0.5359818838357595, + -0.3153334513570757, + 0.06473771708454779, + -0.8337349006185866, + 0.038088278106538476, + -0.23259570111429062, + -0.320417863807939, + -0.16949911532869777, + 0.12539930854958603, + -0.22466563891963165, + -0.5719704009904378, + -0.633236518588157, + -0.4812033844968486, + -0.16406224735270858, + -0.5988838435863235, + -0.010888893665929045, + -0.597381181363704, + -0.22633358268094217, + -0.7252542100074826, + 0.09218581582690011, + -0.6899344966713549, + -0.10175217851888063, + -0.19936198443601305, + -0.2538876521097192, + -0.4451176398780864, + -0.24942730570547678, + -0.7667281908352902, + -0.5345295919384763, + -0.8324451863616595, + -0.15721687406327023, + -0.46991999209223445, + -0.31445080758590593, + -0.07989859970041302, + -0.7138218255492095, + 0.026807782009240277, + -0.06838873297677428, + -0.48942533448811765, + -0.4284381944490085, + -0.8041838421624408, + -0.6837509198906335, + -0.12632723015109948, + 0.07084383244164916, + -0.1781920152708264, + 0.04855931080945852, + -0.6542246680244214, + -0.21322839804980243, + -0.4965500814672857, + -0.09994859853736782, + -0.24308037273641725, + -0.3049792592112286, + 0.14207626642249027, + -0.7262120426542414, + -0.7912552340041835, + -0.40240466419603566, + -0.0422651309953892, + -0.7631787798035434, + -0.5945752013806738, + -0.4782284119258057, + 0.00535881504546909, + -0.14703454779354597, + -0.1318022317676225, + -0.8197095849256179, + -0.4666256671363412, + -0.46659620681029784, + -0.7559005610019474, + -0.5387741641265954, + -0.24552502181524338, + -0.3270066441276043, + -0.6558793892038501, + -0.22391167098611897, + -0.46336440564879566, + -0.7813015576483144, + -0.7659894457975032, + 0.0862707526898614, + -0.772334290174396, + -0.5972008891016825, + -0.15730406683063947, + -0.464015000554423, + -0.12242366292860485, + -0.793897979553216, + -0.004504870564016827, + -0.7768231557994807, + -0.21999869845280262, + -0.2896683616741095, + -0.029404650793943166, + -0.15687888128857663, + -0.8212372108381625, + -0.5970989185189699, + 0.12295132096467487, + -0.5330029618139487, + 0.060534825914406176, + -0.4823488823546643, + -0.2721192810347596, + -0.330090078555081, + -0.42606060007892876, + -0.746907965024118, + -0.14324436378538552, + -0.10153560285882135, + 0.044198863079441875, + -0.2329359639285863, + 0.0011783736388916166, + -0.2729206177347715, + -0.6967358505955813, + 0.1390440937197851, + -0.4635514461647531, + -0.03188575556885287, + 0.09152609546873236, + -0.6370368557399252, + -0.4647808735192591, + 0.07518922008563111, + -0.19577386627971338, + -0.13955967121913693, + -0.21161672437761958, + -0.35766505409586563, + -0.5479227601357953, + 0.10398124210208515, + 0.03725481110278095, + -0.6913684623883065, + -0.5565548027009699, + -0.10118826769499667, + -0.2677008391414163, + -0.7964646135635467, + -0.8425830348559068, + 0.013398001259963488, + -0.8001024019433812, + -0.1662669608414593, + -0.2848373316797299, + -0.6739149289723965, + -0.5121500176377971, + -0.010878376142872903, + -0.03227969553547927, + -0.4422559238750806, + -0.6200987660983125, + -0.14962542078130214, + -0.825981975906717, + -0.06029849459562675, + -0.8182093660754096, + -0.5325862314054216, + -0.16712738695072304, + -0.8377816136123128, + -0.18575296830599797, + -0.13611078215124028, + -0.3262342624691339, + -0.13921265167391494, + -0.25707981782409206, + -0.68454346719881, + -0.02320304250227312, + -0.09399564717664632, + -0.3464976406415191, + -0.4052211345786861, + -0.29207790218028096, + -0.28541584000192366, + -0.09015375531723879, + -0.7340566395499846, + -0.7722362418346068, + -0.18415274266988912, + 0.07575483599490285, + -0.7618438192524644, + 0.07768471698963775, + -0.7380571673010498, + -0.02893672660709301, + -0.23750459750537112, + -0.8178718105780413, + -0.03525923742788262, + -0.02830507367127455, + 0.14793498667693117, + -0.05164876646561578, + 0.12481947538851423, + -0.5660753013204936, + -0.6481145428242595, + -0.25489928015488483, + -0.7886785482912128, + -0.6565277626539164, + -0.3200468890266598, + -0.8476224520689007, + -0.5360792030047432, + -0.2114005830319997, + -0.48698157275932025, + -0.46498387419042936, + -0.7779933187729363, + -0.7464533390917486, + -0.09823073077144495, + -0.3893201647723724, + -0.7176215756541844, + -0.6378029537907333, + -0.8182262378898993, + -0.03553092464719532, + -0.8070341043294519, + -0.08440024058411677, + 0.0206672580236692, + 0.004803169044695466, + -0.7721660234615064, + -0.1838087150292338, + -0.8061846049600427, + -0.7675996166701515, + -0.4083563121902581, + -0.4056113440767318, + -0.47850249103095643, + 0.056535372154187025, + -0.6290988763806039, + 0.09628002341923902, + -0.025631896251515407, + 0.12094465365253027, + -0.3255776741383052, + -0.7775519912507989, + -0.07548124245990284, + -0.5526353441154349, + -0.6725549626943086, + 0.010501047873605285, + 0.07412972937076234, + -0.7372352080256045, + -0.6910626961865021, + -0.11969479322990995, + -0.7063471144379584, + 0.11171046752950042, + -0.7748333180988143, + -0.7981028041922568, + -0.8340321600975533, + 1.9817303926750185E-6, + -0.6460087984408905, + -0.18798167090784335, + -0.08678452267098025, + -0.2645820160013689, + -0.08443932280822508, + -0.5432788258664776, + -0.4291863163711236, + -0.4668293300894127, + 0.06975362104866845, + -0.7913633732213361, + -0.39310048450524043, + -0.43400204212452914, + -0.006443519598113068, + -0.36793492980687265, + -0.39231001383113157, + -0.7821443891369544, + -0.8180666036519835, + -0.435932866492759, + -0.759128866703909, + -0.29451479894377675, + -0.5790859092308791, + -0.7036695526052428, + -0.4828513897459386, + -0.06859820029932895, + -0.19381877994194752, + -0.4985030987519077, + -0.0667406943287876, + -0.7964417691608827, + -0.6580531235102529, + -0.20630596430503656, + -0.5499148011641923, + -0.8321568297239953, + -0.20459582181896685, + 0.10816177809921257, + -0.6497706315996574, + 0.03139212606399411, + 0.017553484756794524, + -0.6500942743144074, + -0.42573290608656256, + -0.31209153655068556, + -0.14884775497362612, + -0.7664029475476646, + -0.3749029694904059, + -0.21290239078378093, + -0.39141917420356453, + -0.282512616547957, + -0.22058372863506692, + -0.44312552089976787, + -0.03685861332647855, + -0.4182535222279854, + 0.105531517963106, + 0.002215348053244637, + 0.1306833112738658, + -0.7291826856825019, + -0.5638331896887403, + -0.4197474666550544, + -0.41011318546219716, + -0.17043502739491623, + -0.32302680215507973, + -0.6633415520334458, + -0.14695968937289283, + -0.21259500076726334, + -0.5832938010135595, + -0.3927385965016538, + -0.26287986140412023, + -0.615304744586685, + -0.23849354818480684, + -0.15199370350245045, + -0.32818979567101925, + 0.0867095752281638, + -0.6483473265262197, + -0.42019465790956206, + -0.05156177335446632, + -0.18185515594584023, + 0.06097979591102287, + -0.7124284132877458, + -0.6283087389810598, + -0.7340534413353811, + -0.7962733699085153, + -0.501260642570776, + -0.08849588117176277, + -0.2689147743494208, + -0.4137202064284185, + -0.5174184698030477, + -0.6287075856760904, + -0.8013090466359133, + -0.6193946668376745, + -0.17772174760163906, + -0.22273482510826514, + -0.28229809035285425, + -0.13504782346596256, + -0.45381791226512086, + -0.13737408411695262, + -0.8346041551103125, + -0.34844879532721384, + -0.7487650525679168, + -0.04738216187025701, + 0.1376506129354873, + -0.7788506645452752, + -0.12197276614909103, + -0.7533625439880225, + -0.010938596760964314, + -0.5300139060656252, + -0.845911206604644, + -0.45870295854390913, + -0.21203587007148028, + -0.14423074317330242, + -0.4509518847229287, + 0.007381607046920147, + -0.7645730153172249, + -0.32359581960889927, + -0.42713806046205954, + 0.12759587827558372, + -0.636444090449328, + 0.0874033447695084, + -0.680313445554408, + -0.571292555065462, + -0.027284212830381516, + -0.4666262488694789, + -0.5138092087387993, + -0.7496414114964285, + -0.7780773147584747, + 0.024853143737346484, + 0.07042785866503842, + -0.6323057592815293, + -0.24557963116450476, + -0.684201482962148, + -0.7073978149728637, + -0.6384618746454511, + -0.3508413261245608, + -0.6920512751126708, + -0.23952448791158476, + -0.41051266734758785, + -0.37540531334489163, + -0.30484930343692795, + 0.0334560617910723, + -0.7906603021243453, + 0.08453204252898494, + -0.3203016644959904, + -0.18666119336717202, + -0.2831503559182649, + -0.6761677389729743, + -0.5191742399234496, + 0.05587639231267605, + -0.7483014161019178, + -0.30898261206110567, + -0.38127516120870025, + 0.1384076616889497, + -0.6846955096967098, + -0.0066530170357733676, + -0.8252185765403234, + -0.7582631551842692, + -0.512598412424636, + 0.041862200682142525, + -0.4737933503372272, + -0.7810149373993973, + -0.7042850298400287, + 0.12415719422643745, + -0.7042846980069655, + -0.6278101551448355, + 0.05665944309564752, + -0.5643561329005747, + -0.15897167632631692, + 0.0021023148356213994, + -0.1494705251166778, + -0.8459273803838706, + -0.41614262066744423, + -0.3877091515881323, + -0.42574891329222797, + -0.6277996332377597, + 0.040926325587696044, + -0.07760763145788119, + -0.31052476430653553, + -0.47778435423368937, + -0.11003828411238004, + -0.48482787275681527, + -0.4007649329563858, + -0.03622157497118972, + -0.46392361865340215, + -0.6900529388724768, + -0.20102045416729641, + -0.0214733504564093, + -0.4535088436521152, + -0.7964541588989047, + -0.5562223540635491, + 0.0254479171045372, + -0.4327906512116241, + -0.7439354676668881, + -0.554508842704198, + -0.8208351352942359, + -0.20652716766540646, + -0.005670276129035479, + -0.0086180221187242, + -0.1823339324086769, + -0.2058461772247896, + -0.22289182958526277, + -0.19270972872320014, + -0.3044924661300934, + -0.7977149034222819, + -0.2809589640252136, + 0.09467745590921317, + -0.3481207021692667, + 0.02426849051628832, + -0.5698453088926798, + -0.2996550267891729, + -0.5614259580833327, + -0.7978568016557627, + -0.4767702722234425, + -0.3551501621896636, + -0.08564452734116479, + 0.07580920975073169, + -0.6476609294785125, + -0.4096093391060578, + -0.38799796559263455, + -0.7119973009560867, + 0.12829817517564146, + -0.001868236132009149, + -0.28438289667895156, + -0.512848646985654, + -0.025614702733640193, + -0.5112396992878936, + 0.0042052579452538374, + -0.7392913683818817, + 0.06763586680743272, + 0.0450211175782238, + -0.26869056294759175, + -0.4441771001031307, + 0.12238512677126301, + -0.5290719500302239, + 0.07022684671410329, + -0.659767655033643, + -0.47547484764407805, + -0.7493925907840071, + -0.044251521623627554, + -0.5281178164548923, + -0.635896760240295, + -0.04422972456248242, + -0.16010833965638593, + -0.7485150994430243, + -0.012539568823251912, + -0.8259507352672489, + -0.5733854983632278, + -0.20297344719068688, + -0.3190397181610155, + -0.06361348936100619, + -0.3789647065621272, + -0.024092594001647982, + -0.20418738658948732, + -0.1032362254290673, + 0.08086805654967577, + -0.7411037347238599, + -0.6588426656659186, + -0.21295675559909122, + -0.8437790643144572, + -0.2404975236971998, + -0.46955746226789713, + -0.649479296744897, + -0.7048558087206263, + 0.022759303823558952, + 0.036734741759096634, + -0.5788648329242216, + -0.3291892174474902, + -0.2622459058229688, + -0.5346053374524959, + -0.7689803342079593, + -0.18746721679500655, + -0.514266759739652, + -0.08442097046069774, + -0.6439615855350065, + 0.026735058060245565, + -0.4500790915791221, + -0.6622638185167377, + -0.06941930774236915, + -0.6206026338846571, + -0.6396115876782917, + 0.08452881064115003, + -0.04859986678203976, + -0.023304172095511277, + 0.13252657321252004, + -0.5920834245443387, + -0.5276504366956309, + -0.5835385616267452, + -0.40359215988349556, + -0.309611369711704, + 0.03644858941713991, + -0.08532699963190693, + -0.665410253383367, + -0.4838645079130032, + -0.08809811970822934, + -0.6943471419552241, + -0.7898527393184713, + -0.10497692891662147, + -0.03231755938591607, + -0.3937791236959808, + -0.7036862681276121, + -0.2295844473871117, + -0.28879445210431887, + -0.5391194971922031, + -0.22459460791175845, + -0.5737097699505598, + -0.4348796175153112, + 0.14890718721023843, + 0.1373321142058156, + -0.3798556208545622, + -0.627488702015807, + -0.7351097480329533, + -0.13840067666399436, + -0.7050640137108345, + -0.1359247389350312, + -0.06453872939278915, + -0.7845744192396136, + -0.17960571367687983, + -0.26963016760606096, + 0.1399296744983336, + -0.1990121191123605, + -0.44191330478432694, + -0.31652183769294995, + -0.8476601150622617, + -0.27799154563754647, + 0.061478915640619025, + -0.7667478220659502, + -0.5220489780940574, + -0.04209286031202231, + 0.12881352433676463, + -0.6481925964088606, + -0.5598324017873102, + -0.6668765680425398, + -0.45024387350774153, + -0.17313118411969997, + -0.8307873143426076, + -0.7111828168226819, + -0.3386629660458539, + -0.3676566127996546, + -0.4222223490517127, + -0.29753804053855315, + -0.031433832038533116, + -0.5589594133647668, + -0.7433347880565434, + -0.6432385907632963, + -0.5177969114896206, + -0.07666981137857654, + -0.07309502160110493, + -0.018952741003969598, + -0.29435414967646145, + -0.18305669104603262, + 0.09678302378672543, + -0.5436710669286654, + -0.2676063090122345, + -0.08370794308503104, + -0.6396983199832795, + -0.7719544149203189, + -0.5352822894378475, + -0.027913845031854234, + -0.7963398750394229, + -0.1470028887012369, + -0.8166642196953232, + -0.015680693767361253, + -0.7699399728408527, + -0.10369306911188803, + 0.0956505745647872, + 0.13202442333156428, + -0.2176389004693765, + -0.27510757767035, + -0.3009303523487603, + 0.07912720065594192, + -0.5238621660578985, + -0.5300506582728346, + 0.012093640188585497, + -0.33926763728443676, + -0.7385392533235702, + 0.08740779654328645, + -0.09059460883107862, + -0.08206729738853946, + -0.06674259618931955, + -0.5690441751713298, + -0.7594653127070853, + -0.46123474715118323, + -0.648990315584158, + -0.6436100754683359, + 0.14881221208549278, + -0.650103790089194, + -0.47601892350879704, + -0.006606058638064294, + -0.4589902556904866, + -0.6021795732536218, + -0.44861390535200885, + -0.6553181084342916, + -0.5930101995459298, + -0.846081052749962, + 0.01255910670899274, + -0.7843148519445523, + -0.25710917378728204, + -0.6003818930777116, + -0.013018134550032312, + 0.07396237305354747, + -0.6899448667367232, + -0.8352649666979453, + -0.4802371833341508, + -0.5470035057398736, + -0.8125878771478832, + -0.09934898883379273, + -0.06695876094941577, + -0.5531246898126702, + -0.6368475164982538, + -0.8271745068471846, + -0.06842906548720706, + -0.05433351350312143, + 0.12966590694306324, + -0.4653336106593741, + -0.3787507892536875, + -0.7050541947173378, + -0.644490245484276, + -0.5791720145652703, + -0.7260637394440659, + -0.017153079812861072, + -0.8111671749108853, + -0.1318339064872842, + -0.497535096951834, + -0.2818447413945271, + -0.44160145929499756, + -0.048888610373689634, + 0.04909378907771855, + -0.5053567232388085, + -0.0028077483930766256, + -0.26302340639094346, + 0.06381110042571836, + -0.5920149993870298, + -0.5372499328953867, + 0.10051616610083092, + 0.04828398710840731, + -0.7882882952901339, + -0.6183133403359931, + 0.06814254414873389, + -0.5960511027067538, + -0.5727654138438911, + -0.6410911502512967, + -0.13925410563537755, + 0.04959186801682858, + -0.5965346134364087, + -0.05400679102188677, + -0.30989525348732805, + -0.8432711460651909, + 0.13422567359114457, + -0.25056690001049553, + -0.08552486406144377, + -0.5616100224025868, + -0.7077280439406898, + -0.421153365591828, + -0.7633025734088207, + -0.26928961364843484, + -0.7929975333132713, + 0.004762074642306824, + -0.7406201465387858, + -0.7255902085876781, + -0.23369415068668675, + -0.21421650309848728, + -0.025938609080174757, + -0.5772292406676616, + -0.0560059650892184, + -0.15019202791378883, + -0.13281248557966352, + -0.015541606069033764, + -0.3219434757091444, + -0.8101132712629177, + -0.46085157703395124, + -0.4037581068807684, + -0.7083295258180194, + -0.46446720508099876, + -0.0031538946220697195, + -0.19890727606010628, + -0.2846070175189398, + -0.05276046432685921, + -0.3313311286880769, + -0.5041203355353365, + -0.16601386028629384, + -0.15551199793339587, + -0.6396431567972218, + -0.29633027791300715, + -0.46637741290808243, + -0.3229370251367458, + 0.02876548749115393, + -0.2662917424396969, + -0.021388554396503556, + -0.1716014015787164, + -0.6139713659417467, + 0.09616815840724191, + -0.5510794836573921, + 0.07487267148198906, + 0.09729574409449993, + -0.47358033383235737, + 0.035165092508285145, + -0.4686367021160306, + -0.21570965131331998, + -0.41278556565631563, + -0.609252011957097, + -0.6560676229234221, + 0.11435786146037141, + -0.21146058357851816, + -0.7457824180421856, + -0.4588073093456174, + -0.13365970234513247, + -0.6878142253234552, + -0.330087822927422, + -0.7164017903685913, + -0.6091981236625836, + -0.7749796194045582, + -0.23325210144974284, + -0.5200334254837455, + -0.15140181862231994, + -0.7367380528357261, + -0.7449258113072891, + -0.29828892982213806, + -0.029160333984465048, + -0.5456087031331589, + -0.8149733361536505, + -0.34751820770177266, + -0.057508775102902865, + -0.5497351165951102, + -0.22525449195576275, + -0.387378300434677, + -0.0933147138224878, + -0.4037134528856269, + -0.3391206437646985, + 0.003213567721257915, + -0.42651765658720564, + 0.07092362443486355, + -0.789450743238046, + 0.03368460112622551, + -0.7089612918561675, + -0.3029070788931363, + -0.48887654290684507, + 0.06424352190866267, + -0.24874396476659777, + -0.05609706480101462, + -0.8449484985740997, + -0.337952412171585, + -0.6084634066579231, + -0.3437042365785069, + -0.6956568966276263, + -0.00621760863633225, + -0.2195517354117159, + -0.5206980547646531, + 0.10621946087823664, + -0.026186900333075247, + -0.42114187418290233, + -0.11137599171634693, + -0.6213156849138275, + -0.8172962158927544, + -0.73280903437772, + -0.3207457208260899, + -0.40859739573418935, + -0.6468201494181701, + 0.13253916929677678, + -0.17092681347804228, + -0.39713921627007037, + -0.10934842031287029, + -0.4589545221584603, + -0.8465092652103895, + -0.22026537354790543, + -0.48483521552839065, + -0.7618021421138951, + -0.11843846332707686, + -0.7629809294883945, + -0.6252041515481269, + -0.3627724632412581, + 0.1280612743690991, + -0.7492961036506448, + -0.5104693012324315, + -0.6372409873420348, + -0.5578714200385235, + -0.3831646174494506, + -0.5390587145520969, + -0.5255384733152249, + -0.7931274396991327, + -0.6909092551407551, + -0.053814358004333984, + -0.4400697363702087, + -0.2488895767653977, + -0.38038792049549075, + -0.5657638409064298, + -0.389011196621876, + 0.1255430283438702, + -0.5690328479847301, + -0.49946680984345865, + -0.2511588385790745, + -0.7537580148451498, + -0.002410598964414312, + -0.8208830951384792, + -0.10897111363102696, + -0.7593646233473362, + -0.32549536426848613, + -0.04080449767404215, + -0.2178517836254954, + -0.014943274892397995, + -0.1647602266274414, + -0.6631319602492703, + -0.5937151481174295, + -0.4482803287721322, + 0.07639233645142585, + -0.8283341646552983, + -0.03510549886506742, + -0.28770372827084034, + -0.7247932162499249, + -0.34537288113569753, + -0.7081335067175998, + -0.5512689753780169, + -0.33851333759944324, + -0.3405141524333236, + -0.5746920416554218, + 0.05690870726389052, + -0.42170461182965685, + -0.2447825401652517, + -0.40671169019605025, + -0.20770613662801451, + -0.10793055309784971, + -0.04461042385749814, + -0.7803715904214588, + -0.2366124899588965, + -0.5521041254181203, + -0.21709356484677111, + -0.10355989002576382, + -0.3026556182271989, + -0.8383637406173768, + -0.5912251216850485, + -0.6580180630357222, + -0.30045007072206065, + 0.12809548153876593, + 0.07723892270633115, + -0.7920922807876208, + -0.12690656900294517, + -0.4773627030646605, + -0.03158619649316341, + -0.2221978446655687, + 0.08304843480480928, + -0.17123496003544814, + -0.3623073839899417, + -0.1472606645122706, + -0.5052348229529262, + -0.2440921317868734, + -0.8182637415612889, + -0.11766350405689907, + -0.6783491479599522, + -0.7867983159504365, + -0.15328214135404394, + -0.6702293221202954, + -0.7460098731200677, + -0.38825448046469485, + 0.04700934801911172, + -0.6138590183943237, + -0.2676736668549684, + -0.2004836928617122, + -0.07325196275113266, + -0.3481754235344867, + -0.19172184009941273, + -0.3739245144096042, + -0.08971162335042304, + -0.034702273020176255, + 0.13781493556267888, + -0.1377885317023544, + -0.40285984813377973, + -0.031116810443313048, + -0.6500973326642018, + -0.6404628277267048, + -0.6410461810041546, + -0.3397698574608752, + -0.5798382097503316, + -0.5271966303901419, + -0.20899030089093162, + -0.7489515573018204, + -0.41740133424163833, + 0.03588534149414002, + -0.3687973294746385, + 0.07753881653774553, + -0.1896868017050617, + -0.30520817295673675, + -0.5561514575920767, + -0.8416043693032593, + -0.5271841353842509, + 0.14588716721864015, + -0.6934023143372368, + -0.7655007956315892, + -0.09251276580520307, + 0.13470197459017164, + -0.40721588751596255, + -0.1639485432455876, + -0.4321469021422221, + -0.7021914345803248, + -0.426207300761075, + -0.06527682208317043, + -0.7088804647335767, + -0.8252879905191866, + -0.3835121739472214, + -0.1639395825087323, + -0.16627222054627844, + 0.05642726114182184, + 0.033660287176471404, + -0.452136774248968, + -0.3542671145718839, + -0.18793288621644366, + -0.8270671301942581, + -0.04214570466803813, + 0.010232224874266005, + -0.18697111024356894, + -0.30559220920272456, + -0.18007459338970533, + -0.24798601785987318, + -0.8386904018759503, + -0.6851460151768203, + -0.014249800337294283, + -0.848574457505962, + 0.03261505838259682, + -0.19168047234195384, + -0.7286136471988861, + -0.5605155047522887, + -0.4961041158923565, + -0.7085078080059258, + -0.7816845893389932, + -0.4299882207672856, + 0.14555888104699866, + -0.800825939725097, + -0.7429374083367221, + 0.04871935058955634, + -0.06599830867327339, + 0.127282718125717, + -0.7215326151247802, + 0.01887765710185252, + 0.06871003485863647, + -0.5185101457097361, + -0.5319254465875851, + -0.27086515554116575, + -0.00907740097950649, + -0.09685980897250546, + -0.5451396091231656, + -0.06466684177438564, + -0.5150847472739152, + -0.08338981304987159, + 0.05593965086015229, + -0.14325737341339462, + -0.5008823074305239, + -0.16031694919455242, + -0.5506086866012467, + -0.7053012480080276, + -0.05685057635865376, + -0.3452943402716794, + -0.6878756730647484, + -0.19294876727496568, + -0.508817660367662, + -0.10405915202833516, + -0.03144050489509398, + -0.8355114366396881, + -0.234697547068057, + -0.08446643820957955, + -0.6898596747176593, + -0.26252039688780426, + -0.2591338032314453, + -0.7538214880858057, + -0.8062554343372281, + -0.762121971332669, + -0.13710915515699884, + -0.7273357815415075, + -0.4215543701336737, + -0.6180312825419068, + -0.24535559690723652, + -0.8189151600589551, + -0.5096317235700988, + -0.8179787371700491, + -0.7839768279960235, + 0.053335800893766105, + -0.7695583040339846, + -0.7603522133506345, + -0.42875797194530346, + -0.24511758876196332, + -0.6024953665725995, + 0.08255990360718202, + -0.26704546352813296, + -0.33834991629187505, + -0.7963537130879973, + -0.6465373336325747, + -0.673923720836377, + -0.049834886511425314, + -0.16620402196442907, + -0.21113499604065544, + -0.7284870931911087, + -0.28047390935381666, + -0.4799078375270466, + -0.8118175921254746, + -0.4552709995525979, + -0.46030430671943856, + -0.6094630640270903, + -0.7377136732273095, + -0.10489718100280432, + -0.17349661401405236, + 0.08807456152824988, + -0.43100631230585834, + -0.6919576371273333, + -0.1638896195326972, + -0.760277828644637, + 0.135901837574943, + -0.6140748111525609, + -0.08621295968521858, + -0.18538059796032258, + -0.5875972120016548, + -0.0037870097367251887, + -0.12528193428568524, + -0.44837609571915055, + -0.65686418515102, + -0.4486021845839369, + -0.18617741013269318, + -0.42250362681657766, + -0.7053707871062632, + -0.12462599341330427, + -0.48645220322574784, + -0.05449139571074835, + -0.5302103002103483, + -0.7942225708116162, + -0.2871914938833664, + 0.14303010479749467, + -0.022049092128240466, + 0.12064502616714212, + 0.03632986390981208, + -0.4739584744295363, + -0.5851816199473117, + -0.7652367783084646, + 0.025941009645057966, + -0.30673336750841074, + -0.08711096681139596, + -0.7257712234125795, + -0.6235248349410235, + -0.11475596653730136, + -0.5241756252305891, + -0.6672756247014158, + 0.08883298324368771, + -0.8479201342726029, + -0.02745436685984548, + -0.18404192800039887, + -0.4666611196256666, + -0.4451698691812669, + -0.45245130162494585, + -0.14889175034329294, + -0.40736557684676267, + -0.6713254911817345, + 0.030238414559122018, + -0.32249659200483605, + -0.6216483627516272, + -0.40475144382394523, + -0.3531021977904353, + 0.004188573993917255, + 0.09344756008953126, + -0.5189976643405417, + -0.5546938284304412, + -0.565370765693646, + -0.4557291074421335, + -0.5114439618108366, + -0.8309561243143669, + -0.4825253915225112, + -0.41776936111018537, + -0.3660301921879076, + -0.6739306088850735, + -0.03675027067039549, + -0.05958447346969298, + -0.0852883097504672, + -0.8299356778064536, + -0.35788797476165707, + -0.6670620210318243, + -0.7559043399783024, + 0.0927296099699868, + -0.7450412248650483, + -0.17652778008503944, + -0.2853610291287719, + 0.04287911068080874, + 0.08471044241890835, + -0.7760328954285296, + -0.1662629073496651, + -0.35045531785823264, + -0.45940688650925826, + -0.07993747490909275, + -0.09666910750025481, + -0.8334041036903945, + -0.704468869294401, + -0.48996404302315194, + -0.252832642713822, + 0.013403691591858724, + 0.13335335359931944, + -0.03511850066155542, + -0.823471675939736, + -0.5119597780537479, + 0.07342921648829359, + -0.7850095721230085, + -0.47796768216191093, + -0.11584335025269477, + -0.844575866955248, + -0.6157362696977748, + -0.5752401349462111, + -0.3944279741106689, + -0.4910634039747076, + -0.651660247511469, + -0.3659574097344896, + 0.13881486727624703, + -0.5076917172463307, + -0.027417560175299616, + -0.5021346700829972, + -0.7116775166336897, + -0.7215273381659064, + -0.363147961726689, + 0.038531222574965884, + -0.7466777936030135, + 0.11321309115076439, + -0.22374394805384834, + -0.12725554219979862, + -0.826937882289624, + 0.11790869898196332, + 0.1063372263686938, + -0.7263231875244002, + -0.5914775832729688, + -0.7930284633795608, + -0.4114428784456813, + 0.131608637519387, + -0.34999043029042304, + -0.14717099517327703, + -0.07344998638864841, + -0.5777606225357896, + -0.31365040459516524, + -0.08426809808795921, + -0.6144380728461057, + 0.051287305832439234, + -0.6020145668290948, + -0.05996729957138014, + -0.622584284157689, + -0.380070349314803, + -0.051739941979250914, + -0.8005710947388317, + -0.5215787880662368, + -0.8363396676854308, + -0.022816795988159222, + 0.06669046512995991, + -0.6742837719138217, + 0.08819563642532169, + -0.5426230538231573, + 0.14006706116234202, + -0.511992613928357, + 0.007247461919215881, + -0.8059802504662161, + -0.7164827632306237, + -0.13194612866300137, + -0.30765766485577983, + -0.07263003935253298, + -0.5524514524939899, + -0.735158899771241, + -0.24483908538070553, + 0.1418166797630993, + -0.19309454199743004, + -0.008331569899094338, + -0.5823626923630354, + -0.4942471502473691, + 0.10687204390322047, + -0.790535035989626, + 0.06733455005317956, + -0.08232221382660887, + 0.1475344890799425, + -0.5884291846395933, + 0.1423569925224757, + 0.12090778940284375, + -0.3112345677044428, + -0.4496664852518209, + 0.028412037630291764, + -0.30152415634958607, + 0.012978799566959576, + 0.052747850862691514, + -0.6466342472530312, + -0.7643590459710212, + -0.29767282690409613, + -0.4686037174662641, + 0.10962304995752226, + -0.02060560225301311, + -0.8163857921345572, + -0.20724388987880404, + -0.8171147823993462, + -0.7316489794739773, + 0.10716038241458015, + -0.434589749878943, + 0.05744965534475566, + -0.5780802175477215, + -0.7905363794605688, + 0.10470502352040523, + -0.293167294106948, + -0.5665546359630905, + -0.2834694410684405, + -0.7354323491862764, + -0.7983537003036734, + -0.31195294548559105, + -0.8040535959441045, + -0.1210491528052825, + -0.709098794527709, + -0.15551667033943062, + -0.5608126975519843, + -0.24008775303446883, + -0.615788590097244, + -0.0333328980470986, + -0.5348604746034185, + -0.25379004748656364, + 0.09713214044662222, + 0.04221403091188802, + -0.20900334068532045, + -0.007961860183882563, + -0.5691641861780663, + -0.7744171600220252, + -0.597088509742645, + -0.16520041449761502, + -0.8293673557517216, + -0.822022373677012, + 0.004874525288066089, + 0.11036351197767946, + -0.5515867295765986, + -0.31082861523375305, + -0.03151698192726926, + -0.6691258940610982, + 0.0059017657359209386, + -0.6620641753378309, + -0.33604826740990956, + -0.6560684768676777, + -0.12839875698772263, + -0.8438018618817815, + -0.5468842987903371, + -0.01325390151845729, + -0.34161232507591743, + -0.4383171266473295, + -0.5872625003769556, + -0.5141020441644966, + -0.49956692993031543, + -0.6551696096527613, + -0.5004474588679907, + -0.6713115918745693, + -0.020498097795519477, + -0.1868235190241503, + -0.8200857974031592, + -0.6188454851331009, + -0.5351456005108004, + -0.14829108678335634, + -0.34433861146934763, + -0.7200558795593922, + -0.01258075428155514, + -0.5790203363730331, + -0.6716302977279233, + -0.5710898547170644, + -0.2644081316954021, + 0.06652058350460088, + -0.01975085781251751, + -0.41868849633733596, + -0.4935100841260877, + -0.014863275508144369, + 0.0012246697887526858, + -0.8179710735848532, + -0.12960101411755054, + 0.021198903309533224, + -0.4451376951479787, + -0.11392139214450436, + -0.3950241770593913, + -0.790623310144062, + -0.052415958412048824, + -0.2893383193598362, + -0.7334765925215342, + -0.29679139164392865, + -0.718618885128444, + -0.8202033992957426, + -0.05946171299098202, + -0.45304210884516305, + -0.23546529550428996, + -0.5859385488636518, + -0.41913448621934474, + -0.7928228007477428, + -0.40628202034657535, + -0.6785281007178732, + -0.6056850997296036, + 0.06661785149480826, + -0.45622101982404484, + -0.641168621995304, + -0.7108135174935292, + -0.1407442733291362, + -0.6354858347691159, + -0.003264128225762608, + -0.22273705145281286, + -0.020888704267435942, + -0.7319517838979761, + -0.1955154628346828, + -0.7758540420289459, + -0.7180176371466986, + 0.0685345641423698, + -0.5258876751677419, + -0.40064128593172826, + -0.7812155837789798, + -0.39804236948338273, + -0.6123510347716297, + -0.45339482969405487, + 0.0853974045325464, + -0.7306844457266825, + 0.06611473987127181, + -0.6966577486363884, + -0.3246509815937496, + -0.8067794966082463, + -0.8436830633665008, + -0.8148695663183029, + -0.011803216679459605, + 0.12606280022466743, + -0.35236899061725585, + -0.3817718932916437, + -0.37347844868821367, + 0.12181259468255223, + 0.13631786196582774, + -0.16246846379119995, + -0.4534986956565576, + -0.4564445725482233, + -0.46834848159370257, + -0.23584322931041424, + -0.12015840200162164, + -0.2093020121552115, + -0.4279396133495658, + -0.5455112774601025, + 0.0517781207548107, + -0.333586425969185, + -0.014442785901263688, + -0.3538724127527733, + -0.6651496045751568, + -0.40532551640395764, + 0.02137302357280324, + -0.09962523414079216, + 0.05172042498231999, + 0.09269521855378438, + -0.43373361277752703, + -0.5757819703715841, + 0.10632914953376615, + -0.8303501017206283, + -0.5417549442270488, + -0.3154696230933651, + -0.5071065643790316, + -0.4538216364880756, + -0.6146296928455786, + -0.8169697372528096, + -0.8244670577371055, + -0.8045971989116854, + -0.7800390844867973, + -0.038188446535404985, + 0.014938516215409647, + -0.5774579786021958, + -0.7092138371855301, + -0.16808515831512005, + 0.010459715211356357, + 0.1324467582322275, + -0.17278311406665825, + -0.2114655565897442, + 0.07582088342339244, + -0.24327049165979386, + -0.5756900896625693, + -0.6696348748769024, + -0.2660155286816519, + -0.09456084994643521, + -0.5142947662570606, + 0.046329916933946946, + -0.8207296421174183, + -0.33793564789148256, + -0.1871741308124505, + -1.370803584761493E-4, + -0.7507567508878064, + 0.019101710165524532, + -0.10755831756842782, + -0.6058596742441995, + -0.731601993476434, + 0.04062191945345117, + -0.48490297961960366, + 0.024833634758797518, + -0.561061053032622, + -0.021236448305992695, + -0.41111836116268113, + -0.6062751386529784, + -0.36624471961457555, + -0.725759319271607, + -3.3361567873946285E-4, + -0.28644928116551527, + -0.8069617963963943, + -0.03452485686437057, + -0.22883599687852763, + -0.7217145440965572, + -0.3731096688368431, + -0.7446957542876048, + -0.39777337747705754, + 0.13617700110751596, + -0.011019859693170875, + -0.7979997225592075, + -0.5262516216531778, + -0.13971548660953448, + -0.36040328340530764, + -0.02807167220666007, + -0.4365906864799928, + -0.5506507647860757, + -0.682662270865762, + -0.13399886235644243, + -0.33037945633208476, + -0.1757084421115983, + -0.2611086021217387, + -0.06213651285241617, + -0.11345752098490114, + 0.11739734345226827, + -0.5456106683082704, + -0.07813269272285817, + -0.3269018149783177, + -0.7696231508383642, + -0.638651021352351, + -0.5491933668725989, + 0.11326405933917638, + 0.07407082323578473, + -0.3574703324479202, + -0.0510168823875935, + -0.4757369036202991, + -0.6541094872471194, + -0.09252341744393244, + -0.551240432714712, + 0.03595026605184781, + -0.8234114930563482, + 0.140794576038207, + -0.8000135690215013, + -0.5309130545637473, + 0.14795693023624212, + -0.17463682325380236, + 0.11587162756792002, + -0.21110142423412614, + 0.05747833304638239, + -0.2372522990686491, + -0.13409273367999175, + -0.21073696536567843, + -0.5427797756867125, + -0.4421354561999952, + -0.10416822527844705, + -0.2587329211789926, + -0.2256621938379424, + -0.25678458542191995, + -0.7115834116185196, + 0.07414812616565558, + -0.7593382071508293, + -0.39082985143205934, + -0.5088908565794483, + -0.7897339427475455, + -0.19448981397183984, + -0.6215423046916588, + -0.05739129789595898, + -0.2359691668397048, + -0.5775494289374067, + -0.2142220641541973, + 0.07418152967735947, + -0.45625745424351727, + -0.1516637694274915, + 0.14238083149901204, + -0.31007335343587694, + -0.25872228163352773, + -0.3227085356910221, + -0.02257331693002007, + -0.3519352052811994, + -0.20978354439537017, + -0.6853753499630378, + -0.03971765728643473, + -0.21272268571568786, + -0.18875250239017738, + -0.04542616771673835, + -0.5419957949872758, + -0.7170587491599227, + -0.0199372033722669, + -0.5483825959571704, + -0.09003421203817197, + -0.49834375147298166, + -0.4842411163988252, + -0.20924974913373606, + -0.04388420182315522, + -0.5583905713849984, + -0.4656368424960388, + -0.3516067543753549, + -0.324432855998403, + -0.5745508338441114, + -0.25185485928866513, + -0.2148520348857873, + -0.44596374869291955, + -0.11776094292960526, + -0.42186671690116767, + -0.3166099992500174, + -0.5668246107149165, + -0.6186403101429789, + -0.6852236425056784, + -0.653121683633545, + -0.5664545173150556, + -0.3603036296532961, + -0.4377188889456651, + -0.8442449595840767, + -0.7463053973984138, + -0.35876161910807475, + -0.1910138927471785, + -0.7420416023899871, + -0.5068786051271127, + 0.05833911919959933, + -0.1526096609239389, + -0.8028534131075656, + -0.15790535271221118, + -0.7959160761258292, + -0.4843105346580133, + 0.06865406263016272, + -0.1267308353099441, + -0.4582573479882136, + -0.0513917244250327, + -0.030084499743815662, + -0.13377692022253285, + -0.09394479461240646, + -0.5715749306056475, + 0.13257420431764988, + -0.6471871926838013, + -0.4570559939478359, + -0.4261997546079012, + -0.2241185417565128, + -0.3665291071710453, + -0.24142811486510452, + -0.04451005172034683, + -0.28115247148930167, + -0.3993711052260507, + -0.3389930771416255, + -0.4549492227948993, + 0.025344593748166, + -0.11594006717775607, + -0.3484507814164882, + -0.541160974428831, + -0.5509584981920645, + -0.43077764974915994, + -0.22137414610707162, + -0.32237529452228153, + -0.46693162554783263, + -0.1820191835738746, + -0.7372759724982146, + -0.7604302570419565, + -0.1953019939035162, + -0.39166017961752236, + -0.07375579219532358, + -0.7189756930453275, + -0.3121401170501944, + -0.7020749616247733, + -0.15573058797882566, + -0.6012390855301183, + -0.6135798004389081, + -0.7113739264524611, + 0.009062336990413367, + -0.7108249714155999, + -0.17876056654210626, + -0.21805790212193787, + -0.805831546364164, + -0.4537288626533897, + -0.24023330049029712, + -0.7145039263127103, + 0.09116810621594928, + -0.2975683533696428, + -0.686692969658746, + 0.12942506967258405, + -0.18163676213671132, + -0.2898128861108151, + -0.812992022687894, + -0.5715878455346186, + 0.01174080024903501, + -0.36484696925834686, + 0.13985918203601522, + -0.073246862895611, + -0.18843197197695405, + -0.8115334282852075, + -0.6758597077816675, + -0.2207319388359208, + -0.06019314638620821, + -0.20144590512640925, + -0.8374644702132786, + 0.06704188342215767, + -0.13237009851168635, + -0.4480888380077049, + -0.1348604603423027, + -0.4362840372184023, + -0.8436039812113784, + -0.4488771487921988, + -0.69274914033107, + -0.18243351585428824, + -0.32965884612094665, + -0.010247647107463953, + -0.6774965178251602, + -0.06857305574662453, + 0.09734094229876455, + -0.42671895335967297, + -0.506679762428502, + -0.08354604297025348, + -0.5125573312826506, + -0.02664545339933777, + -0.5128074450270317, + 0.0899563340887739, + -0.6432531564192443, + -0.1616350599356815, + -0.6866951163795185, + -0.038361669132507936, + -0.0275046264198473, + -0.7449335628033285, + -0.5447974382718317, + -0.10633344299907987, + -0.684889608300245, + -0.05217595260890717, + -0.01862675035967043, + -0.10915181398056062, + -0.6866120210331597, + -0.753825567760996, + -0.22416561486476194, + -0.8424977791995467, + -0.6133813675340988, + -0.561452085863205, + 0.11004838953478491, + -0.35620103992070323, + 0.029233899534198637, + -0.49969339376422933, + -0.18146582536645084, + 0.03587740943023865, + -0.2217951970171853, + -0.4955512601773771, + 0.04294732803241863, + -0.5618886885605009, + -0.435891567098577, + -0.15359490938171783, + -0.5866680876249675, + -0.019262997871530185, + -0.2868383386254453, + -0.6518506540528158, + -0.721241619794722, + -0.15446509642370687, + -0.7872814034795778, + -0.7365936793194702, + -0.7815038486869323, + -0.7776479408701114, + -0.16568481622642617, + -0.2668758333232446, + -0.6921274311395799, + -0.07699273225087733, + -0.06996324594937431, + -0.04073818377339433, + -0.5498512690813413, + -0.7547971305396316, + -0.09295766040497355, + 0.061786357144993254, + 0.12071567661861093, + -0.7098078125676034, + -0.06781877822705085, + -0.3358779909477607, + -0.3573509651609519, + -0.7548795823885651, + -0.5450765089762177, + -0.35877227298151226, + -0.5648879810368126, + 0.09099856219248659, + -0.02274342639486604, + -0.009552211183050163, + -0.4675390698949948, + 0.13394530604619226, + -0.44976595868115643, + -0.08842939699705687, + -0.487046940861376, + -0.8346214560474606, + 0.013228169241433774, + -0.4654275560219344, + -0.2721489331041985, + -0.303674655399374, + -0.13347714508973185, + -0.3283949554360778, + -0.4738694614930589, + -0.07902053858435654, + -0.029086614353259654, + -0.32250233015138796, + 0.13275824626485122, + 0.14824526787056158, + -0.7371431964290068, + -0.27450343659653653, + -0.7587597613935473, + -0.38747730293624366, + -0.02130674041334113, + -0.022646182964598305, + -0.4528614969875032, + -0.007317637084846118, + 0.08745120964656727, + 0.08411362435613245, + 0.039936384113322565, + -0.3848207855519852, + -0.4287877194130679, + -0.8186891754477776, + 0.13133250333791557, + -0.6842845609970276, + -0.41555648250055927, + -0.40241835531686027, + -0.09999828405761835, + 0.01430438079768237, + -0.7894288353787453, + -0.45210096467230965, + -0.06025053124661073, + -0.3550208961182564, + -0.2933057928928351, + -0.32196607584553216, + -0.2526483755944813, + -0.5575698452824486, + -0.5617136791870398, + 0.09646435598320258, + -0.5904364471374752, + -0.6375984378399646, + -0.5534753596195094, + -0.1672568074406111, + 0.10618340699540518, + -0.7404704942424649, + -0.2913665556539289, + -0.5250498413774909, + 0.1191946274177369, + 0.09830153656120055, + -0.8394920301032467, + -0.4413680383268956, + -0.5902050992617089, + -0.09139996366110847, + 0.014236349574259677, + -0.03144101546275424, + -0.17738577464961325, + -0.46136104877778616, + -0.7040920770532524, + -0.8181333398738032, + -0.7108770549992763, + -0.12484550883572343, + -0.14347176587007815, + -0.7432923909176044, + -0.08685884875928018, + -0.6516855600601485, + -0.2177793655677116, + -0.08107295961321337, + -0.27533365166323587, + -0.031126011689453392, + -0.22198789112771045, + -0.6394447860162924, + -0.737611734438143, + -0.4081288018103943, + -0.3910296192042468, + -0.12210388194327026, + -0.15234476121225504, + -0.17022560050893054, + -0.14801389089940054, + -0.8160923963357939, + 0.05700455493834222, + -0.12456341798847037, + -0.014572164776100904, + -0.3849844458009629, + -0.5991491301175329, + -0.172145475908968, + -0.6728934344721609, + -0.5403455655176642, + -0.726751231845886, + -0.14278459221623496, + -0.7105802977106512, + -0.7256786962374377, + -0.6875155082287787, + -0.20680480129541845, + -0.5893020376146376, + -0.7314211791556621, + -0.34108796753694015, + -0.03166824789814682, + -0.28704859615057554, + -0.011459845803236446, + -0.6011018831716665, + -0.7458672750152878, + -0.5404246112650026, + -0.6926929429652446, + -0.6834495649630311, + -0.3860170633636394, + 0.027327096226133385, + -0.12149714017541802, + -0.25306412992219374, + -0.48123878981176477, + 0.007153152213729919, + -0.5998013833152619, + -0.34158048926538265, + 0.08972038089107448, + 0.14090389006197668, + -0.790793267769254, + -0.40453963465316867, + -0.3682803329895669, + -0.7799167111781504, + -0.07723810597990632, + -0.6629015231131091, + -0.5867542429087744, + -0.6096568119986024, + -0.3904362150530842, + 0.13907398957281414, + -0.735746748477629, + -0.771297279064437, + 0.00956923886668759, + -0.3832213054222678, + -0.4824601102772278, + -0.395417348041383, + 0.11666278351958304, + -0.7079871084176744, + -0.5792576267662071, + -0.18446050268549496, + -0.6333108195420066, + -0.00861200472225343, + -0.49320536202035337, + -0.02233340123570693, + -0.19438421175864884, + -0.7728711371778177, + -0.53203616710262, + -0.5395997782311741, + 0.11430137039517019, + -0.37673171544568923, + 0.11482755756493379, + -0.28567624807371284, + -0.30238002914310336, + -0.001378129353615809, + -0.6613546384669706, + 0.1257419206092123, + -0.646085917586712, + -0.600308132977752, + -0.6049560125328914, + -0.14829369065021247, + -0.8248694979303236, + 0.08729189272716464, + -0.3985793790343806, + -0.2761296861993341, + -0.47990624052859254, + -0.6006524342422027, + -0.5346302383460289, + -0.10559427783450825, + -0.48154152376383397, + -0.25839605135000254, + -0.31271004280214076, + -0.4741833796004684, + -0.7783137719824098, + -0.5317826171219443, + -0.4626347250446876, + -0.804307860120471, + -0.009683453033165201, + -0.7039670831192059, + 0.019593383862373415, + 0.08951970321356673, + -0.4863275185031955, + -0.05944367815271545, + 0.11159280292308715, + 0.06384634622445162, + -0.7055208957134884, + -0.6252940367255091, + -0.5402431791279767, + -0.36180811654091255, + -0.06466661128502516, + -0.5210708444214565, + -0.6063983986034045, + -0.5148096472687445, + -0.8254955435724608, + -0.5562460738784742, + -0.5527384657236577, + -0.6794448772755408, + -0.06878209921439593, + 0.11490576143745002, + -0.7811811879685576, + -0.7371081839269985, + -0.38067982113639365, + 0.1349741266886918, + 0.042658984245109055, + -0.20376493588450506, + -0.7511552901391932, + -0.7622348141271974, + -0.46141041403946753, + -0.5586839143925982, + -0.6982382851525933, + 0.10512293350449498, + 0.10713085944266953, + -0.7403209599964571, + -0.5409891998400567, + 0.05787649709818443, + 0.12954886514734576, + -0.5459894223964528, + -0.7625217005416427, + -0.010449209739158527, + -0.5438964680418108, + -0.6446190881929027, + 0.050490450606430426, + -0.20190234046210986, + -0.42434569379085224, + -0.2499724821866468, + -0.5660067031594205, + 0.08871881482787725, + -0.7427763279956137, + -0.7792747209653929, + -0.5719438763399189, + -0.5139848982107309, + -0.2500813264399986, + 0.06347856911932614, + -0.6061955729630908, + 0.060966506045741164, + 0.1131249910002542, + -0.7707325711782395, + -0.8191513518252921, + -0.6830931030497223, + 0.08304732195172337, + 0.06493811925449755, + -0.7182611367086063, + -0.04157318308383817, + -0.040497434284640366, + -0.8036888458788831, + -0.5136667194601926, + 0.03620289162264567, + -0.6817275369508067, + -0.7229343804033475, + -0.18973517728143963, + -0.5639218334072011, + -0.49259068251360066, + 0.13321916051342297, + 0.060301077509808954, + 0.10368020891437024, + 0.12416243840678443, + 0.07096113606742638, + -0.259030517584913, + -0.21244089300875335, + -0.16673910110449308, + -0.43617908413706497, + -0.4134988937597147, + -0.3483309106934872, + -0.4621684020416495, + -0.39043253273520556, + -0.836215169111008, + -0.6140696044379537, + -0.581554315449601, + -0.24198111260775246, + -0.7477736414288231, + -0.6259866661295068, + -0.08384043792165319, + -0.8457597821393579, + 0.10911174879587393, + -0.25246138735747237, + -0.6480566638388183, + -0.3455521694887279, + 0.09309187253512619, + 0.07178651005113479, + -0.33237287102745317, + -0.19218993002712037, + 0.07285045873558194, + 0.06069593532632234, + -0.6586405679029468, + -0.8248334503185251, + -0.49886915063871523, + -0.6950142248224251, + -0.13941684325444392, + -0.7632375755222683, + -0.5344641196994839, + -0.4548693904556227, + -0.7646418466018976, + -0.6867395181054123, + -0.7178157447369866, + -0.49833649581691547, + -0.2434389134005549, + -0.4114507351045054, + -0.5190701547490941, + -0.26398730903055434, + -0.5372379532358971, + -0.7097736238554092, + -0.012130468658065219, + 0.033251039048525, + 0.022650794160036014, + -0.1214783995925226, + -0.00881428279722185, + -0.339834367007842, + -0.8305571702784037, + -0.2613963303572322, + -0.7215431504434134, + -0.11848655955245657, + -0.40635610565369445, + -0.4245014781112325, + -0.6035430381768007, + -0.25686522687338464, + -0.3826076646533661, + -0.737670770165095, + -0.05036594386420801, + -0.21218330052082413, + -0.7666849802091891, + -0.7928213602405175, + 0.11641792285841757, + -0.5591097317055462, + 0.05953684919668478, + 0.07249114080978303, + -0.4364023683993647, + 0.08334465107065758, + -0.35137401835128973, + -0.21278713265842175, + 0.1192001487115435, + -0.020428093378631162, + -0.07453918010878724, + -0.6079514561189273, + -0.5965847749997446, + -0.06967477750673612, + -0.43577846579375706, + 0.009530104682703988, + -0.4186249658450219, + 0.10158709571211144, + -0.44075460418593665, + -0.1174694590842853, + -0.6625779548844737, + 0.045271639581597634, + -0.8105129971915445, + -0.1256869002691453, + -0.5238705107235324, + -0.3758899119485618, + -0.33982995645360503, + -0.7044501147523017, + 0.08735301122653238, + -0.26360347216585067, + -0.8394184834464322, + -0.22976001659347123, + -0.8431822109145138, + -0.8367234467472716, + -0.11202241810823754, + -0.19345560762217673, + 0.0394590262192126, + -0.6557932865962279, + -0.8401617874605308, + -0.8157515804644225, + -0.23436852016328913, + -0.7296636088164483, + -0.27950614059467227, + -0.1653022173657297, + -0.22750266831797983, + 0.10199399151813382, + -0.512078436771016, + -0.5201665361587978, + 0.07036568793471476, + -0.09143362386745979, + -0.13028727387844563, + -0.1583165942894571, + -0.5614344779340368, + -0.014861968889119836, + -0.6789568544182149, + -0.08820834486597695, + -0.2667534655134981, + -0.8342453860594117, + -0.8416809313259449, + -0.5575966784633575, + -0.3077071214923254, + 0.06580923596328103, + 0.09623422064965925, + -0.16749066893411213, + -0.7318914595149553, + -0.15226636810670025, + -0.10946517774704989, + -0.6799077116691321, + -0.42814458704174724, + 0.0615657755092851, + -0.4823253474868203, + -0.5730868519664607, + -0.6971845302456492, + 0.03434162473300051, + -0.8381375366856353, + 0.028984832766633106, + -0.7039446452877294, + 0.13771131154902994, + -0.5059788554316972, + -0.1655501492815752, + -0.479869653903777, + -0.24065552945869872, + -0.6468364478054471, + -0.4464640687893331, + -0.05325462956874949, + -0.16572823205818044, + -0.6713667262964597, + -0.21548381431461938, + 0.028330590247098497, + -0.8040662438095418, + 0.08488790730963702, + -0.25826276344501076, + -0.7850244501445635, + -0.19729877209062052, + -0.5922207878589839, + -0.26360979443928745, + -0.08661866641229199, + -0.410587648552383, + -0.4456031209796055, + 0.053123822743864735, + -0.23513373370289836, + -0.28825442899861464, + -0.5476326633957609, + -0.17587883477517097, + -0.6397921417384711, + -0.4671864874275845, + -0.47726689008419, + 0.12668593459935706, + -0.14596123610749734, + -0.2603129825081175, + 0.14304072809791224, + -0.08525184187524759, + 0.07317593223011021, + -0.5606386330476233, + -0.6112221007565715, + -0.5845974654618251, + -0.07936619937404377, + -0.497433063212586, + -0.6373177647833437, + -0.5514959221636608, + -0.25425884258679066, + -0.19586720632180132, + 0.014365176375894184, + -0.3998828278893345, + 0.0684697451155718, + -0.18601581514847731, + -0.4581606470987425, + 0.14552396442128757, + -0.7353604230486853, + -0.5897473132683665, + -0.26063394658810546, + -0.6094342434963518, + -0.46209206111383005, + -0.7512115498955577, + -0.02420453101886233, + -0.22849604483479957, + 0.05631271918731773, + -0.6663834466676604, + -0.24293184248843736, + -0.1455702348660971, + -0.09511975311000553, + -0.07650763398392812, + -0.11694469413479225, + -0.09507804542483222, + -0.06622122282467346, + -0.31159481225580576, + -0.022460936117562724, + -0.24086388785749924, + -0.0589776052764619, + -0.7004346822662008, + -0.46516033159340353, + -0.33774985297941673, + -0.6446370578033792, + -0.630596672291325, + -0.7091613665695211, + 0.001698186826467274, + -0.764831819488286, + -0.4015289468875701, + -0.760601062913259, + -0.5850286224556219, + 0.09990056816863047, + -0.6096654460910842, + 0.11462721736104309, + 0.07362670909665758, + -0.5896663597009957, + -0.2519672976449715, + -0.4936272358812964, + 0.1018093509373198, + -0.7057944335586028, + -0.3140222550775611, + -0.3884758034738091, + -0.35598923782468966, + -0.41130065898694884, + 0.04601423395219573, + -0.11382708770097394, + 0.07966202114042586, + -0.7548182997118895, + -0.26765733917094925, + -0.7426825946463317, + -0.19992621349655193, + -0.7381441955733827, + 0.14778200574601807, + 0.08239828874215371, + -0.08791856552605581, + 0.029627858196889845, + -0.7828328535160877, + 0.13499052508943854, + -0.6443183994670953, + -0.8471926676403393, + -0.7620089820488648, + 0.010616101699315372, + -0.8163964668132246, + -0.5262145834208285, + -0.7562560351794051, + -0.1454039520689011, + 0.1177782691017738, + -0.45686268295749205, + -0.8115710586781629, + -0.6685475629547735, + -0.10592549248899885, + -0.7806331778976032, + -0.4267855305904955, + -0.04251045445051449, + -0.6999542022879169, + -0.15632130904334585, + 0.1430244868482351, + -0.486780735144221, + -0.2116621386509796, + -0.4006454296330085, + -0.3453867812882978, + -0.8465059110972414, + 0.04557214417464839, + -0.6151434491298724, + -0.8341287376951476, + -0.8411475653866254, + -0.26758318973050355, + -0.03967129234001965, + -0.7044482768610028, + -0.5599301010154336, + -0.16272765527127986, + -0.5754124319288938, + -0.3941620912633658, + -0.14921216227780332, + -0.39675997581060807, + 0.13379160085784247, + -0.8153832973600399, + -0.7663125800264707, + -0.16156661945789808, + -0.1561129854411526, + -0.42476327388424495, + -0.6300574965609091, + -0.7546648716893902, + -0.3338553506630988, + -0.6443281138048568, + -0.2640039278414953, + -0.8154046142236521, + -0.21097172910051565, + 0.08645477384926203, + -0.8233225829190104, + -0.2790484921269831, + -0.4934517982115191, + -0.5765186324998103, + -0.708992584292502, + -0.027847994761468375, + -0.03615907480787506, + -0.5911518427532086, + -0.6004538985384019, + 0.025741455666073332, + -0.08599770220753244, + -0.8402160183975699, + -0.0020729994868786683, + -0.5016494071515282, + -0.5994095736849591, + 0.08811049463105958, + -0.1543749765216722, + 0.13088962447928587, + -0.724472309963842, + 0.1339112237508321, + 0.10571260791654524, + -0.1850674799943559, + -0.7318414844487512, + -0.45262301455584564, + -0.35637422394929796, + -0.7510528642918922, + -0.5327425894188464, + -0.7979934996601319, + -0.7105345733236132, + -0.7629982380561049, + -0.4716801031413181, + -0.09783653757232802, + -0.5296626542118763, + -0.7645985273741487, + 0.11147729380614546, + -0.0564125294735508, + 0.016100867300311794, + -0.549982163667659, + -0.10584374208899294, + 0.05692264069770747, + -0.7903558769698892, + -0.05962772009590567, + -0.7432476676268545, + -0.7215565064134919, + 0.12813757304645368, + -0.7459012186775017, + -0.5439887472557825, + -0.6196599973601047, + -0.22401719204106096, + -0.13618735112676827, + 0.1260475997488265, + -0.1707610667217213, + -0.5618926771414059, + -0.638456338267137, + -0.7257315347921492, + -0.06314461945282179, + -0.03407745362753922, + -0.7567606960638991, + -0.30742874194315484, + -0.7128909742315269, + -0.565388987809532, + -0.6957611929314043, + -0.5649190365646761, + -0.7778697101222972, + 0.044953646273666936, + -0.16376490980996716, + -0.2596363690524197, + -0.21301611019770494, + -0.19281345248998893, + -0.8140355530318959, + -0.49402332715911523, + -0.26667141122351357, + 0.09405666322459949, + 0.11023294138301176, + -0.22428676235800082, + 0.1108489445988502, + -0.3837074902896295, + -0.8297915889201728, + -0.7236695212572007, + -0.6098825958813295, + -0.6942738448935586, + -0.8264306169193244, + -0.43337543854983285, + -0.7207370453117754, + -0.33910395343401434, + -0.49823780022565034, + 0.017830769419314496, + -0.13907292709404773, + -0.3253087505693789, + -0.010367818817144991, + -0.30002206219635263, + -0.5262584852122381, + -0.747627027437171, + -0.30621319425037086, + -0.032388975013188936, + -0.788867955961087, + -0.41443332913749703, + -0.2036698896752538, + -0.4081516909566061, + -0.7216983680367342, + 0.044320869897609416, + -0.5896240729692588, + -0.5479484664602784, + -0.6439948667203302, + -0.5092008995942954, + -0.6852098065782177, + -0.6462815749572087, + 0.11115583069717594, + -0.1327332384993758, + -0.7660112770317332, + -0.6072696001623632, + -0.14890060743041333, + -0.7247624311584059, + -0.6744196986238772, + -0.23590829938822766, + -0.07629025619540741, + 0.132876014415357, + -0.31335751882243235, + -0.002119078337986746, + -0.28184264511057255, + -0.38798523595527973, + -0.3239694708256132, + -0.21199062787196488, + -0.1693462917736137, + 0.0978740019875648, + -0.7954398539135575, + -0.7613174273161751, + 0.022523429784235938, + -0.35769257135888, + 0.055303437579446335, + -0.24123013667408721, + -0.718117504436348, + -0.6896151889797716, + -0.12076307598986691, + -0.08378951740288021, + 0.11881457350066671, + -0.14286936364381775, + -0.6405684350895153, + -0.06819938294024819, + -0.04969469225995571, + -0.4525516192787929, + -0.6771823928253558, + -0.42605106074769694, + -0.41347621628254705, + -0.13705624787738913, + 0.12647245730985668, + -0.6910404298955457, + -0.5613031779607206, + 0.07494328956964935, + -0.31390829410071674, + -0.034411529015852205, + -0.24492143521970122, + -0.7208530364883412, + -0.25754436164722194, + -0.7912312488972137, + -0.24485803636496672, + 0.07980333634579162, + 0.1371031527528993, + -0.7810710560580519, + -0.051771552125837283, + -0.06170739596325525, + -0.3749807881205755, + -0.34123476958572063, + -0.06781933980917032, + -0.6624765538024586, + -0.43130379789632595, + 0.026605104645656907, + -0.8334038300688695, + -0.645922826658075, + -0.06808048887773, + -0.28363663868237377, + 0.11840660046688745, + -0.48928919584777325, + -0.13199908663714222, + -0.7698267239074283, + -0.07929544304580993, + 0.015487019297333537, + -0.8240298911794627, + -0.4511551754502782, + -0.3872250285375081, + -0.26300663628132137, + -0.6796654587759705, + 0.1470609034411967, + -0.6668747000021784, + 0.04192771716451427, + 0.0900677454466644, + -0.6468807554126357, + -0.17960361329688945, + -0.20501716701668582, + -0.6611555664955064, + 0.11820780372457429, + -0.3391621660707391, + -0.324993760547697, + -0.15613549000749338, + -0.43999785036448696, + 0.05533839219255976, + -0.1449207440013649, + -0.5185379581960289, + -0.024524595691169715, + 0.12200962235133306, + 0.14066232539236323, + -0.37856326167708293, + -0.6827141967811251, + -0.4110266337659714, + -0.6235009999173949, + -0.14776976162252264, + -0.06863230472931059, + -0.425350355714703, + 0.052009877878367416, + 0.13352782626785709, + -0.7580937931673688, + -0.1000403873196245, + -0.7676012755620084, + -0.1719753771751108, + -0.28894082292743084, + -0.47210202553302555, + -0.14246904664654325, + -0.8218487497296638, + -0.38950427542634614, + -0.09640153494705239, + -0.46225801105279685, + -0.8396487649312496, + -0.4613405444880971, + -0.1637033993151087, + -0.5907800946736814, + -0.6392853057470445, + -0.694387459182861, + -0.44958737047422603, + -0.6706886045774327, + -0.322279465697604, + -0.6640983390410274, + -0.2109084355580534, + -0.03593238958776612, + -0.8357962101063471, + -0.6871355877373803, + -0.3469553773629426, + -0.7968007139469614, + -0.47949115535223524, + -0.5187553050660125, + -0.4007876445730666, + -0.31535132338498684, + -0.4656175751759803, + -0.16829399692155877, + -0.16012403583360424, + -0.2706069448693095, + -0.3576068341965196, + -0.7530394548596495, + 0.011091003134092281, + -0.5645264600678942, + -0.5081506639121449, + 0.14054090101961225, + -0.19269829702408325, + -0.11198995187068117, + -0.3455913090949587, + -0.7880808963371141, + -0.042883516773028596, + -0.1254592147812864, + -0.3225734757955726, + -0.704453476648089, + -0.5832641707006783, + -0.29370939290321607, + -0.7081469117892201, + -0.348774510301878, + -0.1095832388037623, + -0.10165246317688104, + -0.5933279562674358, + 0.10259227640501278, + -0.2534637900412715, + 0.09574253000815491, + -0.8062107613096181, + -0.45022996781334124, + 0.003006715105799418, + -0.5887561810814508, + -0.33402650387167887, + 0.08728494217424909, + -0.7324141691309681, + -0.7865022264079372, + -0.16887158945066894, + -0.575702743467742, + -0.3404280606636344, + -0.11580781554181196, + -0.46529778192166704, + -0.7401729178843749, + 0.12361609038431087, + -0.6595648978711037, + -0.3169893442876517, + -0.6913089275155561, + -0.30498777983614533, + -0.2566061149432295, + 0.11615843802657877, + -0.7979312320989742, + -0.485524039122827, + -0.23868038465443664, + 0.08419962179885998, + -0.7368297591116282, + -0.18700765705943811, + -0.40406418272319206, + -0.5518150475962704, + 0.03564726908656035, + -0.3692826224913574, + -0.30335722892706607, + -0.4799168007904334, + 0.09162731001744173, + -0.4520659317502891, + -0.03435813648833275, + -0.7903069541679378, + -0.3652073910803582, + -0.6283699411324891, + -0.09493728192669104, + -0.7398866046070998, + -0.014261845425675324, + -0.05001596847156309, + -0.16463474406925516, + 0.09143652162054061, + -0.18745612710790893, + -0.18322730662195474, + -0.2738173375753403, + -0.3046295949134783, + -0.7632312993287245, + -0.35720896003700114, + -0.0864337306733054, + 0.051003116489354405, + -0.6823175026067885, + -0.7863317354969619, + -0.5491551872570006, + -0.454007310208359, + -0.025226654490876466, + -0.2706381961279354, + -0.26092753569061056, + 0.14398295961803487, + -0.4805838422452572, + -0.09640388471075312, + -0.8401514903651967, + -0.10669570091334202, + -0.605153191807206, + -0.023134459868028423, + 0.09621467824535601, + -0.6650002399932019, + -0.563272221570889, + -0.2712188547850367, + -0.7894838865495343, + -0.6390735900688029, + -0.775331560299311, + -0.6703354448972931, + -0.7467466005136397, + -0.4886586682511007, + -0.07925000156715645, + -0.5896080569526752, + -0.7201841275109333, + 0.06224179565618193, + -0.6825836938350704, + -0.3569299677937749, + -6.511655751192391E-4, + -0.4505179190908886, + -0.7384923763479453, + -0.3818349544938944, + -0.4875306197432897, + -0.3767684359935405, + -0.00461715057733858, + -0.09885626585097995, + -0.5562517246403841, + -0.7540624673497726, + -0.7885175588535478, + 0.02951549828230171, + -0.09055152235725017, + -0.5942956264071688, + -0.5100716735168618, + -0.6084348887151015, + -0.44960860823882953, + -0.05907535984405399, + -0.43719669308402487, + -0.10457042473415146, + 0.002277075891920166, + -0.4383393330599022, + -0.059698247082315414, + -0.19860796364575695, + -0.39869927759475415, + -0.5986076945182844, + 0.06011639751134312, + -0.4432340074889703, + 0.02253838514761164, + -0.06426672531483546, + -0.04874976263041597, + -0.3110514644131399, + -0.5607827660481912, + 0.07365968648640897, + -0.18057797089557925, + -0.25410114175334786, + 0.07613544821163931, + -0.3915988273851112, + 0.02145793158887932, + -0.603180258427089, + 0.007136508072049463, + -0.4517646055226151, + -0.14919793030778172, + -0.5592884487030715, + -0.6284098126931291, + -0.1657335182483194, + 0.12481277236502841, + -0.6814272821902093, + 0.026386511679098112, + -0.073824104699582, + -0.4602507768937408, + -0.2569977430791972, + -0.7629214270663875, + -0.5108455964214582, + -0.3721491043884083, + 0.10431277710942088, + -0.3087061134638379, + -0.8473441576253655, + -0.377562650787423, + -0.7673201079270252, + -0.48902956720857044, + -0.19272817059892478, + -0.4091719149151085, + 0.33288531829803436, + 0.3629286703597931, + 0.2910746675569327, + 0.2226325089400876, + 0.2584597419940906, + 0.19126151234317437, + 0.36947879948273604, + 0.27247155314550353, + 0.30503079661118365, + 0.33214209554261886, + 0.22441172634768214, + 0.3017841511861197, + 0.2450321729097969, + 0.2936140787633801, + 0.31378610529009876, + 0.3876015977394321, + 0.191280894928234, + 0.38919305317879443, + 0.370669008234327, + 0.24377416429187293, + 0.2545937471290731, + 0.1919451967977488, + 0.3523724752377951, + 0.3745262154423385, + 0.3752100757939677, + 0.2904968115442954, + 0.2233857652583412, + 0.28309208233251615, + 0.22747489812167326, + 0.3907519288833179, + 0.26929431353940025, + 0.15744062080909996, + 0.2222512374284867, + 0.24340750790914406, + 0.3352104494924313, + 0.15879432435797156, + 0.2884488607696033, + 0.3085193909729911, + 0.2990649242943647, + 0.3791547766401123, + 0.3500379337502231, + 0.21162338507066492, + 0.3888114374561874, + 0.21816821138944076, + 0.15945716913117197, + 0.3801175895674762, + 0.25531090361948017, + 0.20189769738452001, + 0.3534537302141323, + 0.20240602734712027, + 0.2395163693301302, + 0.35310802120799545, + 0.3367101600182637, + 0.18020908588993573, + 0.2746054602012085, + 0.23444786337879958, + 0.265761974138884, + 0.29832844200609177, + 0.18790244430622977, + 0.29620081755175764, + 0.24708828451478568, + 0.3539152728863227, + 0.2586888815463895, + 0.37020054607713726, + 0.22147318849638015, + 0.1909970793648769, + 0.2773683980448505, + 0.34599285169216404, + 0.19028887867487454, + 0.21465362205316502, + 0.16364529463228414, + 0.25007659858061004, + 0.3930631421126117, + 0.3344988445925851, + 0.20510232206370266, + 0.3225116210938555, + 0.3055953381852895, + 0.293275587497446, + 0.3378455109998041, + 0.2918428423282332, + 0.2624049518417111, + 0.21713830971866613, + 0.2488104749689804, + 0.15897509426736967, + 0.1895396235613656, + 0.3837649944492826, + 0.3065853714631418, + 0.3495827895497702, + 0.20590068687240787, + 0.2638595653478804, + 0.16651808723787076, + 0.3330550612389311, + 0.3321448352448013, + 0.24035506765921383, + 0.3829586235725929, + 0.18262050948105768, + 0.2705408481846833, + 0.2905630690400639, + 0.35613931336019355, + 0.3327331759288391, + 0.2585831310153775, + 0.2851290803609542, + 0.3720286189359454, + 0.17613578505698105, + 0.3601110965464137, + 0.3116208192585087, + 0.32365672175836857, + 0.22141350589578807, + 0.38769419977292524, + 0.34031594209719795, + 0.34059931172021146, + 0.18388218300972206, + 0.39171633362840264, + 0.1861515675493362, + 0.349285440948783, + 0.30378283921075144, + 0.28742546473993213, + 0.3876054540605461, + 0.32005639297212735, + 0.17300900456970802, + 0.33171040041499456, + 0.32778479006771744, + 0.18262560010543283, + 0.36694366383621124, + 0.18692065187491846, + 0.29238296666105357, + 0.3461981457323575, + 0.21413136003524894, + 0.3127959242903239, + 0.3236523191681422, + 0.16915579894760116, + 0.3558732297780055, + 0.22504174682409528, + 0.21684458914426394, + 0.3154722945498639, + 0.1733912968800546, + 0.2513621920719988, + 0.30750106310628356, + 0.26118520073946044, + 0.33025100905483606, + 0.24719862993977382, + 0.19812963422446164, + 0.38957917671579945, + 0.245360944381246, + 0.18053509432480103, + 0.3065958871074205, + 0.3437221872384325, + 0.2731109153349983, + 0.3138266302928929, + 0.3020909159060373, + 0.3498401249016879, + 0.2950669118391113, + 0.2361119043481667, + 0.2934612167462601, + 0.1826226072577807, + 0.18263115910834635, + 0.26601311007947637, + 0.29334088502443895, + 0.2921507424238837, + 0.3292015361686298, + 0.16281494802163612, + 0.32694806987308705, + 0.3354277807932308, + 0.25634118323943467, + 0.22862475781954356, + 0.3132974406974953, + 0.18370588924796816, + 0.34531470747797083, + 0.3718793718845167, + 0.21167348156632806, + 0.294302010697481, + 0.32110011574904973, + 0.3906950977501217, + 0.18862261074310965, + 0.1933805568369104, + 0.245671173476349, + 0.18864281216843734, + 0.18956964029954224, + 0.23182429054679904, + 0.1998276486395059, + 0.3148600627430186, + 0.3866833185021545, + 0.25041335901779715, + 0.3862372236310889, + 0.3772477629892025, + 0.17020891476941838, + 0.33784601668541414, + 0.3043226492203259, + 0.38497546596922577, + 0.3292701443752366, + 0.23322328509853907, + 0.35446731730847236, + 0.33563300915969985, + 0.2450922273156224, + 0.17067403768202166, + 0.28377230974525586, + 0.37077128491189126, + 0.3428972668194087, + 0.2204575412817677, + 0.36561081777630144, + 0.16341549473772235, + 0.3380829780993035, + 0.3594657839854464, + 0.33867543006937284, + 0.30189264438755503, + 0.31940673339310266, + 0.1813268409445076, + 0.2480562953653812, + 0.3748375785288682, + 0.33710024015151613, + 0.18517990162118098, + 0.31765262544901873, + 0.16094509405524493, + 0.34676339269255363, + 0.22892916840598862, + 0.20050364409822125, + 0.35823972396209847, + 0.37309920379822903, + 0.16173869306988534, + 0.2331213198588744, + 0.3677526237592415, + 0.34016419404692855, + 0.3052746445371931, + 0.2595151185409911, + 0.26121310562348865, + 0.24614756691454304, + 0.1744279925194831, + 0.35138076213034847, + 0.27932051977014116, + 0.3239055855197936, + 0.29237161893090735, + 0.20178878436252612, + 0.24280331767947447, + 0.24840091367075134, + 0.16313036247191168, + 0.37508521644674064, + 0.2395820028205048, + 0.3369565354671313, + 0.2920980711680885, + 0.2308435772619175, + 0.2644762389994788, + 0.17300191140985238, + 0.33238252468020146, + 0.3664013486747786, + 0.2046055704896378, + 0.30843427144818925, + 0.32233750260316346, + 0.3129719989861467, + 0.22819439516866824, + 0.27790731650387324, + 0.28273363059756784, + 0.3900254064479578, + 0.35954238963643204, + 0.19842828421382086, + 0.26170071547335216, + 0.35895264953527867, + 0.2571895456674769, + 0.19465110698077406, + 0.22738779434173323, + 0.31630091373230684, + 0.3059750618057477, + 0.1887266223373313, + 0.3403097674169625, + 0.26159660721371913, + 0.3602820348601319, + 0.16794934448292012, + 0.1957772325450346, + 0.1841200879751084, + 0.3318297670920174, + 0.2843097378490181, + 0.324955878916917, + 0.18747391205626027, + 0.2909684604654066, + 0.32053566584137183, + 0.23916272766032226, + 0.1901325546212159, + 0.19504882061198864, + 0.38795679322687704, + 0.3098743473706641, + 0.3044393791460347, + 0.22241977010617253, + 0.38720891239278277, + 0.35790510928178754, + 0.3827806153495041, + 0.22612600240042846, + 0.2001076259882078, + 0.1863020235585202, + 0.317756802699095, + 0.3309734197343955, + 0.30963226245153386, + 0.20669096718030422, + 0.25802866009371517, + 0.2054393478854231, + 0.227494674172448, + 0.31347875370162265, + 0.17915248317045868, + 0.3056464171291706, + 0.28105865172168876, + 0.32514328127174896, + 0.2775707780169534, + 0.25263545430935885, + 0.32557382999355, + 0.18595208853281875, + 0.2707397645339559, + 0.1671848602529643, + 0.25157442966435584, + 0.3035941447987015, + 0.27921811152086384, + 0.1664281785927656, + 0.22504921390095894, + 0.306286429129939, + 0.3131487057800044, + 0.35746194221214195, + 0.36985638242191377, + 0.23425891595460724, + 0.3808067472336579, + 0.19028789738626534, + 0.27024756005611683, + 0.17199631203619045, + 0.3544367780558191, + 0.22650637570343257, + 0.3491849831403287, + 0.3821109013765165, + 0.2419120077619477, + 0.3404419410887143, + 0.20073657608483442, + 0.15754953549927686, + 0.19668995388013777, + 0.3374480661094934, + 0.17994390243572103, + 0.20706730352753, + 0.2944692520708462, + 0.2019486828569929, + 0.21985309367648673, + 0.25655487705577207, + 0.34788278985270904, + 0.3359452983919349, + 0.1830507968687668, + 0.2838365333528516, + 0.1796695889870939, + 0.1657979288344047, + 0.34159598647950595, + 0.34687073124263385, + 0.19829014589753485, + 0.17586176011322152, + 0.23670444422427253, + 0.2529995855923483, + 0.27708944983101297, + 0.2846759115805809, + 0.16900511786858932, + 0.2939764209716046, + 0.15789763467975473, + 0.31698077283216886, + 0.2670800002101581, + 0.22685620325618616, + 0.22416824955030057, + 0.18385952524831523, + 0.2140800849534531, + 0.2863039636369986, + 0.3375906405004009, + 0.3472265329727795, + 0.3549010780472907, + 0.2856212831103767, + 0.20567775479679956, + 0.22839372843180894, + 0.1890627147547544, + 0.23613977427719537, + 0.16231053369521725, + 0.30208433193325634, + 0.16969114648557682, + 0.2227142859839426, + 0.33783419240911894, + 0.2318066217343087, + 0.15991387148328487, + 0.26818030805365023, + 0.191857718580482, + 0.18380021387559545, + 0.3879749882253115, + 0.20190441075144003, + 0.32413683856537334, + 0.17180092700560573, + 0.2874244741223908, + 0.18739115071915188, + 0.20351141885308552, + 0.2036769282106759, + 0.33129824163889093, + 0.26743752640317453, + 0.3567916460525067, + 0.27444650942871374, + 0.3110747704887714, + 0.2504911871058474, + 0.1800657316116275, + 0.2802876478929305, + 0.3691552020677661, + 0.2699103436128567, + 0.36636565212929845, + 0.21709957892160475, + 0.28469787357245446, + 0.1603924316715406, + 0.16389344062410877, + 0.3709739675370358, + 0.22657027649614564, + 0.2074187440197422, + 0.2461643955796122, + 0.35246769333734934, + 0.3259016854819131, + 0.26166280089147553, + 0.32268498685694624, + 0.3919585387572492, + 0.1706296036222894, + 0.18690450096734965, + 0.25128718135255135, + 0.3221235909270169, + 0.37838967879409324, + 0.3678644888775105, + 0.3717484465764792, + 0.38530108629688176, + 0.27550022346955155, + 0.3781948397788808, + 0.3168407993760249, + 0.3800782255246498, + 0.27737574512876845, + 0.32958619534878797, + 0.3224626896612857, + 0.16868142656625543, + 0.2558107235816207, + 0.21407932484375947, + 0.17329778423995695, + 0.2839962851222443, + 0.33654482770705557, + 0.18151049746054745, + 0.1947845254798386, + 0.26201613158897086, + 0.2508357978548754, + 0.31436033036417455, + 0.24096085625712327, + 0.16500054858790253, + 0.3010842468811892, + 0.27840596913388516, + 0.15927412414859973, + 0.2635372203798688, + 0.1765746832819311, + 0.3754692572758717, + 0.35290978912877846, + 0.2664343385410827, + 0.17940276154410473, + 0.3699087835196041, + 0.17718045388647446, + 0.2736332900886356, + 0.24378083979108217, + 0.36668805454014974, + 0.2500129614828406, + 0.28462831468534816, + 0.34013715528123567, + 0.26250212619948804, + 0.20908851906866727, + 0.36670091590870757, + 0.22999102728820686, + 0.2953885063422226, + 0.2247153851917787, + 0.26631592921631325, + 0.2316996349939403, + 0.20956433636525756, + 0.3094759325538009, + 0.3743449391328719, + 0.22265641611491616, + 0.23233097280899043, + 0.1821615192650474, + 0.210585443010182, + 0.33071805730810566, + 0.17106012296980086, + 0.3303527465468861, + 0.2644574743292889, + 0.384342377139818, + 0.21873554505482107, + 0.17114556562800887, + 0.2997040167733328, + 0.24708316558775936, + 0.21090893884151116, + 0.2113377543501145, + 0.2680227578963739, + 0.2725742595771713, + 0.3854003764467397, + 0.232625339189572, + 0.36270065944572805, + 0.2980688612106321, + 0.21610261747137738, + 0.17457058380690402, + 0.16227388883301314, + 0.18439932292994146, + 0.1585525683323727, + 0.27840083916058245, + 0.35239204346493147, + 0.1665088859829911, + 0.32131730848051476, + 0.20994203090367763, + 0.16720696603502902, + 0.3601242834427202, + 0.2766688893241144, + 0.34369048141271574, + 0.34300780066689707, + 0.31136893328309717, + 0.2217925472150467, + 0.24399646479672898, + 0.35623787485027647, + 0.37136545189331976, + 0.1953779367786251, + 0.28489676598216473, + 0.23189854516117284, + 0.27332731450588443, + 0.23964922300833066, + 0.32106850161675365, + 0.22520011269705478, + 0.3285650413546131, + 0.18196420511119266, + 0.24659684446175695, + 0.3816653411806935, + 0.3667187546548343, + 0.3741409760121793, + 0.25539802827584684, + 0.22912870265233942, + 0.34672562407556456, + 0.3867889859013066, + 0.26939762231481074, + 0.2614474915428801, + 0.30781398551972383, + 0.2554587574963724, + 0.3319830366915749, + 0.3334635526057331, + 0.3760709319929566, + 0.27340331480795693, + 0.17286815737275865, + 0.3430620162748491, + 0.3091543036694889, + 0.32728942731747357, + 0.21635568416701384, + 0.35479394882139625, + 0.28657334029937137, + 0.21573762454127837, + 0.15673637993322684, + 0.2766049852910793, + 0.19531526673565272, + 0.3851986768187283, + 0.29525763107695047, + 0.19709624082505223, + 0.2754762676845658, + 0.33419503824786123, + 0.36331069615264583, + 0.2769595118597787, + 0.3049882748413163, + 0.3119516371427201, + 0.33797654148202483, + 0.28203838887986155, + 0.20202619354414927, + 0.3120822168004662, + 0.3594859913812871, + 0.32306426083708806, + 0.21005391714271263, + 0.17589879977392406, + 0.20701963677326615, + 0.20097989167597236, + 0.3867068822151123, + 0.17896393110631859, + 0.3082131873126314, + 0.20755065812150364, + 0.2650011859708591, + 0.3394654303260627, + 0.2568282076635378, + 0.22927141994115996, + 0.3059787057431702, + 0.31042351481399866, + 0.2045316334462267, + 0.2197069160178313, + 0.29197107205197886, + 0.26117840278708904, + 0.23595822164583508, + 0.2258142560951194, + 0.24748396162213715, + 0.2533825035964394, + 0.30472877822801897, + 0.2046993747541642, + 0.16100093738007085, + 0.22871542354623778, + 0.31088774150785425, + 0.32909873087810315, + 0.24689971570769909, + 0.34155452246087503, + 0.23926314184116887, + 0.3522133447009098, + 0.25695224805559613, + 0.316307306644992, + 0.19906348726347278, + 0.3909997583400951, + 0.19314281997897742, + 0.18187837462967024, + 0.30903890369082804, + 0.3401390508381703, + 0.22444056611295382, + 0.19666973120981007, + 0.1665854956815436, + 0.16091286720169448, + 0.37988538717827747, + 0.23165185576216923, + 0.37139431878743945, + 0.15972575136556613, + 0.35889587002851775, + 0.19191584699269001, + 0.2855102622800583, + 0.288459004220751, + 0.20902968980529596, + 0.35679803794371645, + 0.22176877660529776, + 0.2038189695722869, + 0.374485126996847, + 0.2650978862432348, + 0.30386039489065386, + 0.17141475175976525, + 0.26729146085865474, + 0.3469790866185735, + 0.29006593055272034, + 0.20392501089147996, + 0.15836113270106847, + 0.38962417846849584, + 0.3096752597558837, + 0.2088129617599482, + 0.17624441513512223, + 0.1786374005403201, + 0.19687108614190235, + 0.2002227048871624, + 0.27783010163815186, + 0.25544758066900813, + 0.34734764586457745, + 0.38452352763735803, + 0.23784891359848293, + 0.3845598420582931, + 0.2765568607601283, + 0.2743925705387655, + 0.23819962969007527, + 0.15943057528897672, + 0.3217003831463537, + 0.16968623248950637, + 0.27507383262124585, + 0.16083055051246364, + 0.23102833308357226, + 0.1704637324206094, + 0.36012870216644244, + 0.33232779836480386, + 0.2401970704258608, + 0.38308579764766126, + 0.2683530832131124, + 0.3215572980825614, + 0.3375101369492418, + 0.20883562659319557, + 0.27442186816376557, + 0.2369726451003643, + 0.3419757229876672, + 0.3375793174115297, + 0.22993027355964762, + 0.17294975748970856, + 0.22034304773271188, + 0.3542473215093517, + 0.2927761594555422, + 0.2600800531302299, + 0.23936081300585724, + 0.28093575333798765, + 0.17846724951178172, + 0.34852878223704403, + 0.20486347425529672, + 0.314924794107485, + 0.36302791148506713, + 0.16630876071400313, + 0.3724162560478447, + 0.281517648624513, + 0.21156595590715155, + 0.30496834091989267, + 0.2522411097141949, + 0.27298393311366953, + 0.18166903314552507, + 0.23423831403593393, + 0.29680042034454257, + 0.23152229186596024, + 0.3536791363815566, + 0.24712723064988812, + 0.2014112197686514, + 0.373666762344427, + 0.2896259458903345, + 0.32322977458984103, + 0.246665260393016, + 0.2427138401048477, + 0.24791203960570785, + 0.2228526671079799, + 0.3307388094514038, + 0.3744413293757576, + 0.3134610766090955, + 0.38338177646451177, + 0.347139939264822, + 0.19896797465193838, + 0.3638980267425432, + 0.30659921695220665, + 0.3419387222332637, + 0.3102483637140835, + 0.1979864749677814, + 0.25127644991068127, + 0.31952092343038174, + 0.38096308949551805, + 0.36653797461585114, + 0.38284149242423415, + 0.19998049108453492, + 0.23344386145452944, + 0.21861075142614264, + 0.301554099905725, + 0.23128435656351917, + 0.26100659831931405, + 0.3330834910978939, + 0.20760198211407432, + 0.3125972061274651, + 0.346390758657915, + 0.3364546555773802, + 0.35412847698999905, + 0.17151609964616643, + 0.31965665970310264, + 0.18531782370056826, + 0.23485702429334354, + 0.16657993948246053, + 0.35730239525413476, + 0.3540976324687102, + 0.22216138363879995, + 0.18713111968473004, + 0.21549794329868538, + 0.3716194616965382, + 0.38112941247967813, + 0.16156600326056328, + 0.37864839863686583, + 0.2303059395337329, + 0.2179324216522916, + 0.2861705380634221, + 0.31611080345011716, + 0.2285210514465391, + 0.30354783585395195, + 0.3870988040228115, + 0.2902101019210589, + 0.31748170410823356, + 0.22431228069952705, + 0.3105923921660677, + 0.29591998617804827, + 0.36230860361539274, + 0.21985535796598288, + 0.3167160440891663, + 0.38221655118493975, + 0.18931705811732785, + 0.32485948505775364, + 0.33654656483128365, + 0.15758325616239394, + 0.2563866250227581, + 0.16185726812228102, + 0.24913294631409943, + 0.28974369232955344, + 0.31018181725784394, + 0.25805917177695836, + 0.1906122312078531, + 0.16443519302646858, + 0.22475305134949491, + 0.2980033610509564, + 0.31264956349479167, + 0.3309727839545904, + 0.19984875011583858, + 0.3607202723606603, + 0.2123102404009605, + 0.2925350217328436, + 0.3469234618730049, + 0.3500919136723278, + 0.18105884280989115, + 0.2579426392205184, + 0.21337498647016795, + 0.17164423120255334, + 0.21484315982396496, + 0.26928829938645693, + 0.15872481417638865, + 0.22585035539734388, + 0.22676135464074787, + 0.18030936362070576, + 0.3421497880007615, + 0.28354780200625157, + 0.21092015567239253, + 0.2587412229393668, + 0.27378660026061413, + 0.28018732012692654, + 0.18837596737439735, + 0.3110234131884213, + 0.2192915806799715, + 0.32247418946141293, + 0.33166473197864105, + 0.39188783002811356, + 0.24902810487753813, + 0.30615613155633564, + 0.28638438159515883, + 0.370850265521949, + 0.3246375277967968, + 0.16413558181471954, + 0.29766445695742255, + 0.2986577684997527, + 0.30461363430369853, + 0.363302300003694, + 0.2728761164205874, + 0.2453658724904938, + 0.1599342838302852, + 0.22352747260245387, + 0.3833797673967728, + 0.20550869990344425, + 0.17951545989979845, + 0.24932964435671467, + 0.28079334143175994, + 0.3000275604478565, + 0.21593055592218646, + 0.1639189467867669, + 0.32584307686701797, + 0.1995208300053603, + 0.15635247926476534, + 0.3882339082397337, + 0.25782738730304755, + 0.1690350719588774, + 0.27286125335992545, + 0.32299893931818463, + 0.3569850719214934, + 0.3023458457145054, + 0.1567887823623163, + 0.23937791547708923, + 0.2554603165767533, + 0.33899418796005043, + 0.2197490952315614, + 0.33114742040631095, + 0.16973562510920226, + 0.3362310445421881, + 0.2325610436508163, + 0.20086677756368432, + 0.278978345349684, + 0.18552932724905388, + 0.18195774870778697, + 0.24028674130327246, + 0.334147963226481, + 0.35210805300044157, + 0.377122000643672, + 0.2510880449471356, + 0.3445767548838383, + 0.3928996354227484, + 0.3780699725015382, + 0.20697305671733202, + 0.3421431382475642, + 0.20322519257493832, + 0.361017511872229, + 0.3209042928478836, + 0.20369928857214942, + 0.2738335239324092, + 0.21759181953029127, + 0.33651169410978843, + 0.3237971308971055, + 0.27873126518970726, + 0.27655111569181146, + 0.2098867574763108, + 0.3034575704198119, + 0.22499163191501875, + 0.22495738480878152, + 0.25936871968027486, + 0.25534276848314214, + 0.2854119525839556, + 0.28789660491765856, + 0.25020703309430203, + 0.18180144334390608, + 0.38372709966005997, + 0.16193403643729173, + 0.38216802812251194, + 0.24366010962118578, + 0.3213637719181024, + 0.1812511485853306, + 0.3744581744327359, + 0.250431960747303, + 0.22040410792675247, + 0.33231207355264636, + 0.32361107911463194, + 0.212611451553475, + 0.258714318221374, + 0.32522043045936144, + 0.17388117467130848, + 0.34269041693736296, + 0.22089198876842134, + 0.2049294432571317, + 0.1646717441530672, + 0.3612819959530861, + 0.38087591877222493, + 0.1625243890010497, + 0.1616283859422514, + 0.1690496983404732, + 0.31170472258705484, + 0.34346322010515784, + 0.3922899079195595, + 0.2729304275246889, + 0.3406656484160182, + 0.33737315510505217, + 0.3299996871936842, + 0.3470412909355368, + 0.3713850052014913, + 0.33433841911277035, + 0.17167307715787322, + 0.3063960606408901, + 0.37721075025753537, + 0.19933402577810314, + 0.32112395609117467, + 0.3228717930159145, + 0.15933237966269576, + 0.32314338206595766, + 0.21850929662219468, + 0.2960952030096131, + 0.29490140324736774, + 0.1669150489190163, + 0.15977398942428453, + 0.16520724464216674, + 0.20999506622795386, + 0.3030921374638552, + 0.1624761691576162, + 0.39071095783497534, + 0.26346645581355665, + 0.36275311978766145, + 0.28855634611283737, + 0.15898604934918398, + 0.2215903151788709, + 0.28232694175544437, + 0.20786495470571947, + 0.2600360650792442, + 0.2623247903680965, + 0.35526822900674826, + 0.2536890679842517, + 0.2040580991024453, + 0.15954164180117597, + 0.2150976612539738, + 0.176834085668601, + 0.30766994596873376, + 0.34906910633409083, + 0.17835129166148825, + 0.2913125634171028, + 0.3685936496334523, + 0.19825531997018153, + 0.20160214441204188, + 0.342448369839383, + 0.3298152462893825, + 0.2416637382494273, + 0.36718431842413224, + 0.3375317272562821, + 0.28878168951567373, + 0.32505409326859674, + 0.2641329475629084, + 0.16712184034344443, + 0.3085167696988518, + 0.25425299968967985, + 0.2636839086115449, + 0.15808567989371855, + 0.3391220496298898, + 0.2302794441598655, + 0.36985153436012463, + 0.2597562641000296, + 0.32962266509870597, + 0.16813738875588732, + 0.24907013579558385, + 0.3125691092529753, + 0.2827650847434341, + 0.3395854508931584, + 0.17300693115536822, + 0.20909431474187137, + 0.24145221142731782, + 0.3371317599223618, + 0.3490038273848107, + 0.18906561377000947, + 0.3208036973022932, + 0.3478602993140292, + 0.3685211998979978, + 0.23176667825037633, + 0.2703835476821061, + 0.3876768574901536, + 0.3411880665244067, + 0.15756439406599673, + 0.3245670156646313, + 0.3457194534993958, + 0.33055791975502163, + 0.29964077741748063, + 0.17574174642721566, + 0.2844471680085757, + 0.3373250783977023, + 0.3803098049483746, + 0.38124402830024184, + 0.3763823196999188, + 0.2227877885907737, + 0.25112369562195175, + 0.2605519409529533, + 0.18225139353925066, + 0.25911102460073615, + 0.2268819047331277, + 0.3176019819361257, + 0.3166787613195896, + 0.31419747205932913, + 0.2568270036586938, + 0.2360187744832128, + 0.31353473989431213, + 0.3341224854062669, + 0.2402856340105824, + 0.313616485436558, + 0.1749408133235469, + 0.38925294138866756, + 0.21517513121807325, + 0.2613690458405954, + 0.297621810446433, + 0.20886149032601364, + 0.34978468871980184, + 0.37993484926818455, + 0.17540950839412114, + 0.2656388134926074, + 0.22487073723683362, + 0.2706664282222022, + 0.38392668833356636, + 0.3690917931034483, + 0.3250807771044665, + 0.262259434442094, + 0.2072253637689141, + 0.38567958103355415, + 0.23439353623606785, + 0.19602385536045377, + 0.3816816843163101, + 0.17431118774870322, + 0.20605919987265842, + 0.25795839690759165, + 0.23770071623111222, + 0.2595897402531093, + 0.3600159179161327, + 0.2384316396725346, + 0.23759043890288656, + 0.197683723116204, + 0.309236590616469, + 0.3865567885606607, + 0.2990384965496337, + 0.18124567233460423, + 0.3801884161574739, + 0.21186274353149273, + 0.28471196522587217, + 0.19274732905717606, + 0.1980218519727238, + 0.21036423153034314, + 0.36707116954085506, + 0.21722683127018758, + 0.2747640323448014, + 0.2635265932255566, + 0.2049978509232255, + 0.3489716331286511, + 0.28830885178740073, + 0.29310556482976013, + 0.21024323103617323, + 0.28221817019690193, + 0.35714068262233245, + 0.22642459213927335, + 0.36471523597040945, + 0.30998597673362777, + 0.3013436532538536, + 0.18106096970640903, + 0.36336917933270985, + 0.3194181180133497, + 0.2512162423593105, + 0.17442205750350995, + 0.20300446108828699, + 0.30511948281414825, + 0.3377615806314142, + 0.26025385251306404, + 0.22636194676258373, + 0.2849001759396748, + 0.2732801487142511, + 0.3057887385204294, + 0.3744884704259264, + 0.3589824675668154, + 0.3075244214851665, + 0.25848904978912524, + 0.24888254704515617, + 0.21644917955198625, + 0.15919680475106107, + 0.18025073248562545, + 0.17265207807002494, + 0.16529883649598034, + 0.17091067551345365, + 0.3705914897610353, + 0.22987149564556647, + 0.306660374629493, + 0.3617313596767935, + 0.3081085732120116, + 0.27988640260689585, + 0.36988521442195654, + 0.2639362967024421, + 0.17114738309933486, + 0.34047634075368494, + 0.1921246368413383, + 0.3691396570670953, + 0.21892751675651762, + 0.18314203808047858, + 0.2556721283096398, + 0.15915980629538845, + 0.2054675292059784, + 0.34122767352169786, + 0.20049481548053533, + 0.20962931687659186, + 0.38502591981612505, + 0.37196194348897244, + 0.30565012223787813, + 0.17550427936086396, + 0.3482540011002835, + 0.28718408432357667, + 0.2599545220796856, + 0.24974112736184484, + 0.2414127082329286, + 0.2704013376374203, + 0.28787328963038994, + 0.26805281586949636, + 0.16218566966835837, + 0.2122471749387947, + 0.1923166749319442, + 0.35476743699430024, + 0.23262276269092164, + 0.297523567548474, + 0.32450482740683595, + 0.2655962617222965, + 0.3641458273356165, + 0.3194648817774677, + 0.22510313794695808, + 0.3908152083134241, + 0.19878432237605148, + 0.3184566792681097, + 0.2817465239400596, + 0.3020593809459228, + 0.2709925025278503, + 0.19442779340001468, + 0.3056321383099548, + 0.29551040483846575, + 0.1898920858585783, + 0.28423104099269475, + 0.2749055800437824, + 0.37012659751356825, + 0.23785182413022105, + 0.18591236257705357, + 0.3680677617694722, + 0.22313467405677645, + 0.29821861420519147, + 0.26814625529032915, + 0.1837660072472653, + 0.34194411974033967, + 0.2798433830673088, + 0.22587367190312818, + 0.35694617220113367, + 0.2732973041572152, + 0.3727544601317957, + 0.36176106122466267, + 0.16169587971875268, + 0.32566464658168076, + 0.18110905629383195, + 0.27610847808999883, + 0.2552640277955585, + 0.30521934844347637, + 0.2898661981974684, + 0.2558560076327301, + 0.3671408247257842, + 0.20320977021159803, + 0.15639692521336188, + 0.34364114558429487, + 0.2909056212242975, + 0.37239518864512167, + 0.38711268986379965, + 0.39200899645367937, + 0.33788005740923566, + 0.293677697738445, + 0.35766972841142464, + 0.1957070146386231, + 0.3609374608615601, + 0.254033725018495, + 0.3205426540115345, + 0.24591853749800952, + 0.18556379155749572, + 0.18695502222050822, + 0.16216117351544984, + 0.2822912098005027, + 0.29098526676327874, + 0.3764282486923618, + 0.26944235347102813, + 0.34376453757724135, + 0.3001789018357971, + 0.35985795565193457, + 0.35593925716267055, + 0.2522782141081335, + 0.2720723332790289, + 0.21532092605407177, + 0.30779664685932895, + 0.23008692223361898, + 0.28007048543436164, + 0.16626154110121907, + 0.18663546063853656, + 0.18407996959890813, + 0.24874818668040144, + 0.3294404337760405, + 0.3314008423904745, + 0.3459170624752518, + 0.3144166655290106, + 0.3897887096933214, + 0.3003972794817231, + 0.26255948187658246, + 0.2889019052995359, + 0.281868732784616, + 0.2648500855080853, + 0.20332382738359947, + 0.2789963690809069, + 0.370586954128846, + 0.30613234895175234, + 0.16194384389935693, + 0.31848969891266377, + 0.2562931192944611, + 0.2601317953901532, + 0.28289089837000403, + 0.22337447711781455, + 0.3359478707869946, + 0.20201789410514692, + 0.20183061986320122, + 0.17411851290169447, + 0.2383212188912046, + 0.2642839333159894, + 0.2642039932822236, + 0.2821480035804618, + 0.18111175153774528, + 0.2718818272816601, + 0.3868531299371094, + 0.20184483789750615, + 0.34099306032698684, + 0.2115822441013294, + 0.2872062492746774, + 0.35650151774425043, + 0.37624231879264664, + 0.3473971308221102, + 0.16500506543035603, + 0.21061278046309573, + 0.18100981168447977, + 0.2093731206554089, + 0.31390555836586564, + 0.2192424876577403, + 0.3213429468441852, + 0.24736039659308784, + 0.17480689797393323, + 0.33064140166566314, + 0.28966816395709016, + 0.20024827076603655, + 0.24944595727560023, + 0.16155038774330346, + 0.3832612682269897, + 0.26917349941002194, + 0.3851676637522658, + 0.20649302846276674, + 0.26767569976307715, + 0.31150920991539943, + 0.30982624040843854, + 0.37521225518619195, + 0.2603482229503168, + 0.32510069838217026, + 0.3038229187490501, + 0.20821131748951466, + 0.3331277599850423, + 0.2515949048241026, + 0.1582246062100083, + 0.27109297696003576, + 0.40154187055563445, + 0.4017722051165212, + 0.6916571185461309, + 0.5701242136841256, + 0.6169901659911019, + 0.4706872464612293, + 0.39968404971400495, + 0.5250723499420871, + 0.4169778388994203, + 0.5358554680377727, + 0.5630581281370561, + 0.6230876491204002, + 0.6674043773579551, + 0.4806241656664044, + 0.5134566720637297, + 0.6312557497859931, + 0.698249720767383, + 0.6822306469470472, + 0.39459664900519814, + 0.6688531981974466, + 0.5960278380766652, + 0.5184739627766535, + 0.40765392272526246, + 0.501893517488013, + 0.48501083044444404, + 0.7075375220072565, + 0.46709537091635434, + 0.5801048894449206, + 0.7008212297766756, + 0.6365935295020563, + 0.5914566988131947, + 0.6159021182039635, + 0.5876596767579818, + 0.65281095049877, + 0.41738647136241014, + 0.7052037244907183, + 0.4916593021397012, + 0.6507125838330737, + 0.40245183542003016, + 0.46944425655170435, + 0.7037251816515895, + 0.47195547432534235, + 0.5057071371150839, + 0.4539476530035231, + 0.6421634476620144, + 0.5169099494804125, + 0.515243577415043, + 0.5301780151396196, + 0.5057948002069986, + 0.43608287219776065, + 0.3950877571834391, + 0.5220511059099926, + 0.677310945814692, + 0.4442658448349917, + 0.41639286587220425, + 0.648350495937503, + 0.4305103640836245, + 0.6262678344233075, + 0.4116650566284098, + 0.5871734079650871, + 0.5283673344898289, + 0.6405365762885427, + 0.4673214902296362, + 0.6688438867840596, + 0.66085731327718, + 0.6675015370266495, + 0.6822571494539108, + 0.4131805405271625, + 0.41997144360967154, + 0.605421726410147, + 0.7050168889012589, + 0.653093144602046, + 0.4248840440884856, + 0.666886804279991, + 0.6544456870959641, + 0.5993014764982849, + 0.44093626676770176, + 0.44520751061245745, + 0.7155179208144785, + 0.6273018464476734, + 0.4572809796962145, + 0.4032671733823702, + 0.4408354435741126, + 0.6046044049973651, + 0.7157681482926844, + 0.592278402932372, + 0.42786328759494147, + 0.603577649324597, + 0.6440822603012338, + 0.5145687091132335, + 0.5226677732708489, + 0.5282596131520243, + 0.555894659525025, + 0.5364738285204318, + 0.4711656243461399, + 0.4464810537172559, + 0.7064903043053322, + 0.5137751127678041, + 0.6969662632137319, + 0.4540267477337116, + 0.460714264785641, + 0.5027387310238904, + 0.6499880464547083, + 0.5613320747154835, + 0.48132306425563287, + 0.5573855261415734, + 0.41773948220922086, + 0.5126607446177696, + 0.4953782702524792, + 0.5640593309085433, + 0.39825880716200496, + 0.4425750572455854, + 0.5666241358042949, + 0.4503867205672676, + 0.5061622648208324, + 0.5766754127919094, + 0.46279047476529445, + 0.6885004408640818, + 0.7098653030982474, + 0.5155770942213084, + 0.41819027755964455, + 0.6178323224208955, + 0.5586169059747785, + 0.7059406593439119, + 0.5069669270460841, + 0.5394119083094847, + 0.6902332418721471, + 0.6748386757427622, + 0.6773296926931041, + 0.5801924264286119, + 0.66924753523923, + 0.3939388815074583, + 0.6043781364676322, + 0.605910117502007, + 0.4914386964479722, + 0.48196301187606383, + 0.5121127017476146, + 0.6477388239901842, + 0.6085493399718112, + 0.5776594727972111, + 0.4585572736199431, + 0.5006002927403831, + 0.4859728091294991, + 0.4680158710850781, + 0.5004408237214906, + 0.5979502494342562, + 0.45029984321037325, + 0.40707462241894393, + 0.6619769364842552, + 0.5232885655683437, + 0.46330695577060915, + 0.6646448337689268, + 0.40662192150506526, + 0.6453570408645554, + 0.6009046130559909, + 0.47360765171165436, + 0.6121036939393069, + 0.5177464857200167, + 0.5605287284170222, + 0.4946975275247769, + 0.5116839172315124, + 0.478585401527148, + 0.5404066373557996, + 0.639515853309392, + 0.7081596241211222, + 0.5323071100000086, + 0.5503739568272014, + 0.5437155780385701, + 0.4846698329339714, + 0.6637645323921548, + 0.6564530369820671, + 0.6672518817581623, + 0.43894817626592897, + 0.4890321124071386, + 0.4840353839326377, + 0.6311451603017477, + 0.5940939548617449, + 0.5889364011631264, + 0.6489246772679219, + 0.44725188122319487, + 0.6600775345037945, + 0.45345045448814586, + 0.539611385488604, + 0.5430739848380541, + 0.6187209581140614, + 0.4117418087490544, + 0.6053631832994046, + 0.5267975854508586, + 0.4131380248736253, + 0.7114764999826562, + 0.701125715070204, + 0.43734094515257693, + 0.5930423474972547, + 0.40805885695406197, + 0.7108553592924252, + 0.4450444965204674, + 0.5541614961678432, + 0.5888333563829715, + 0.4999719329353569, + 0.6607623242053204, + 0.6053446736987091, + 0.5307227958921157, + 0.45824915209559014, + 0.42988173487393455, + 0.5330823558440034, + 0.5921514892096896, + 0.427112254789851, + 0.6231124882144121, + 0.5811292533021727, + 0.6278316337248238, + 0.5484014332260563, + 0.511526819698542, + 0.41842021184986916, + 0.5320848222523042, + 0.6199536789338235, + 0.4850240397326074, + 0.6366001345612674, + 0.4122279543978098, + 0.4849187035549003, + 0.5884208791332232, + 0.6504975717454324, + 0.4401624412678399, + 0.5136497769194297, + 0.6400241861072402, + 0.4505990531238212, + 0.5066709926933601, + 0.5852090465668155, + 0.464966163927616, + 0.4262591341848537, + 0.5923537757594188, + 0.6323436114926096, + 0.6827821881279262, + 0.6568698755765476, + 0.6070933001576094, + 0.4559687478066684, + 0.47926564831370433, + 0.4303045499313133, + 0.43651408498532374, + 0.5863320008321209, + 0.42574626033139873, + 0.5666362848489452, + 0.6079426759528365, + 0.6162960235767307, + 0.6094952407594316, + 0.4531297041971685, + 0.5139775262895722, + 0.4930518311427469, + 0.555540520333925, + 0.5822370427762927, + 0.4991890411130875, + 0.6191243721841259, + 0.46395838368522235, + 0.6320459957776895, + 0.5812507243738417, + 0.44461287437765484, + 0.6702681082171105, + 0.6405208298523595, + 0.5340773018029276, + 0.7088649415715338, + 0.42596302898296, + 0.4100492265626279, + 0.553038239414026, + 0.6889935031713913, + 0.5816596135674122, + 0.6906367171418526, + 0.5223058601716376, + 0.5033836320421325, + 0.42253037719068265, + 0.408770490523704, + 0.49677054698231254, + 0.6547179914569122, + 0.6892120658942333, + 0.4609529344734653, + 0.4110972262811929, + 0.4671986001951752, + 0.4257500485947016, + 0.6443746186835169, + 0.45433906106225874, + 0.7118691926815527, + 0.5848493831863735, + 0.48401270193397594, + 0.5475566204499002, + 0.48707829713841816, + 0.39378514618487076, + 0.5343651291242395, + 0.6351249991413007, + 0.5948772321746578, + 0.3945081247659844, + 0.4591795688054529, + 0.6854578877489432, + 0.6626651056086819, + 0.6589875236972915, + 0.5961145057574432, + 0.5224034842683754, + 0.5050296215664786, + 0.670274213330784, + 0.4581706421206367, + 0.5076616125485874, + 0.6185521850935248, + 0.5323610113158226, + 0.4658291889029201, + 0.43019344002413573, + 0.7117411817991492, + 0.6447781849656943, + 0.5249599567827521, + 0.5487879584336013, + 0.6641759284030988, + 0.6962010590386708, + 0.6641992177678657, + 0.599030093608008, + 0.4952115979311617, + 0.5283349413380637, + 0.682723274930856, + 0.6226529382557275, + 0.6495846470310351, + 0.5695834565200765, + 0.4032616525915888, + 0.7134989027701221, + 0.4217448276833253, + 0.51145323308957, + 0.40136769783415943, + 0.4894076532561119, + 0.5580916056120575, + 0.6485885509451936, + 0.4106965326936936, + 0.6446472510934458, + 0.4673510482494977, + 0.39406648345200795, + 0.6423874771462855, + 0.6761786558340641, + 0.4385113439028285, + 0.4676346308195621, + 0.5925070197682611, + 0.44892483804258965, + 0.6405852645185593, + 0.5652733259129074, + 0.6998842040306115, + 0.5638670483173848, + 0.481979342873229, + 0.4046755417448317, + 0.6846887979367473, + 0.5792278730066671, + 0.6596425969046801, + 0.4151497323575476, + 0.6596571575218719, + 0.4364064090262114, + 0.5751060557601836, + 0.5359668596341719, + 0.5665202979008935, + 0.7049248036395264, + 0.5126899812737657, + 0.6247013006767026, + 0.6940919393391642, + 0.6312703081099512, + 0.6209608375781136, + 0.5250191331381071, + 0.6811603881339178, + 0.6012772240778049, + 0.5240705363958756, + 0.5428275577913633, + 0.6278616837976532, + 0.6094376197543869, + 0.664413273587193, + 0.5327978810037328, + 0.5081904082264597, + 0.5879185440144283, + 0.585134181789603, + 0.69841199801268, + 0.6380218894631005, + 0.4313041260930196, + 0.5612681368785195, + 0.4138321830673763, + 0.5878771294676932, + 0.5098797185612908, + 0.5592526382944856, + 0.6176230476188015, + 0.45282711332647135, + 0.42211738007870586, + 0.5792285332552183, + 0.7076279584663456, + 0.5132164689447851, + 0.4016151985625877, + 0.5005768790101279, + 0.5377959771658304, + 0.673057721234926, + 0.6065864872032398, + 0.4391610804901898, + 0.40850817437123, + 0.39446820023944196, + 0.45425620949987333, + 0.4985874177791048, + 0.4829372931939674, + 0.5514862469204134, + 0.4206242253851943, + 0.5603212990032334, + 0.6974934023928568, + 0.4288000031205262, + 0.39879540428154014, + 0.3983914441773548, + 0.44503724400750494, + 0.4362484868418247, + 0.5464577473336911, + 0.6386354700698925, + 0.6964360490258216, + 0.6074255178648731, + 0.4889255879648373, + 0.3934865795908067, + 0.40546136240004793, + 0.4694791632738844, + 0.41325872314812406, + 0.4469091086747741, + 0.4260294766766455, + 0.588165405581004, + 0.5416814561602862, + 0.6283709186026429, + 0.5236609948728579, + 0.4708195061900129, + 0.5790343691265639, + 0.7150104209183179, + 0.5441991803345833, + 0.5869566798610268, + 0.528878339354435, + 0.5672384326922854, + 0.6470639293015009, + 0.48184159350299094, + 0.6723555539381239, + 0.6684037014410424, + 0.7014351471492428, + 0.6570415567811738, + 0.6937392055566047, + 0.5468629323504164, + 0.6032049009900234, + 0.65399066773744, + 0.4278210246523501, + 0.560952774050389, + 0.43559484368022805, + 0.604153545803851, + 0.6463494808969634, + 0.4280945454000952, + 0.42623824425752127, + 0.5263752768004069, + 0.6495556606751474, + 0.6079491167840757, + 0.4592774102625227, + 0.39363311546516283, + 0.4403889709103802, + 0.39452411273797156, + 0.5320644315514407, + 0.7095865556218699, + 0.45031882013899127, + 0.49049465768292244, + 0.5825939028884322, + 0.5172782086775894, + 0.6038268139231213, + 0.6511217183113365, + 0.5651893223333359, + 0.40687306412608626, + 0.6765126047069006, + 0.5471072333163356, + 0.5284893426095343, + 0.4940247572433484, + 0.544245625771729, + 0.5208865118876215, + 0.5687816791532816, + 0.6356987615509171, + 0.4441040566252022, + 0.5828037684704762, + 0.4566041667253928, + 0.6584170780907639, + 0.5807587813329892, + 0.6679508018501403, + 0.5748337311880901, + 0.4459497575648414, + 0.43660702544867913, + 0.5320573843588869, + 0.5060681164284243, + 0.5934269143622088, + 0.6486763355614453, + 0.5264476321366137, + 0.5130671626174765, + 0.6336537918009872, + 0.4411128926119485, + 0.49436674110978585, + 0.41289815974124217, + 0.6972725394716452, + 0.6412957348528412, + 0.6758141756751737, + 0.6772136263959277, + 0.6634581557758649, + 0.4336025287141016, + 0.5393126049983168, + 0.6313854940431948, + 0.6980031803670094, + 0.6209955883427614, + 0.6424396833726045, + 0.47787300970116237, + 0.504466648515734, + 0.5394270777075578, + 0.525043421417757, + 0.7073667050865478, + 0.5367630077432356, + 0.7065011969700665, + 0.5670941169229409, + 0.4219836902928154, + 0.6322683054066398, + 0.6324770443535082, + 0.611089804535338, + 0.5200107570202483, + 0.6273077281518118, + 0.4717522173672615, + 0.5520433189359997, + 0.6167768192853258, + 0.5364042499960491, + 0.6179086197333079, + 0.7098424703994268, + 0.5838418314836293, + 0.5959736545923319, + 0.4853270098949111, + 0.4206022133129632, + 0.519159623591922, + 0.5475679535238369, + 0.6307073543308682, + 0.6831658139214447, + 0.4523002243227902, + 0.4563433871498846, + 0.5360966086330026, + 0.6915524469367444, + 0.44409411169573754, + 0.41402797160812355, + 0.6733587185238037, + 0.4510086271313907, + 0.47613037440818085, + 0.6999684229851524, + 0.516502041185436, + 0.41136584639365076, + 0.43044006833760456, + 0.45307618394591437, + 0.447409188832478, + 0.48299139047502126, + 0.5284183307825878, + 0.7119717923196682, + 0.5606853971863706, + 0.6096195050579132, + 0.4862086567418617, + 0.4605482266344224, + 0.49709931236369753, + 0.4432377421368927, + 0.7132611903778745, + 0.44822647818255984, + 0.41600779021575574, + 0.45746817335712375, + 0.5825304313067328, + 0.632836728287099, + 0.5983454878921033, + 0.4726685096685376, + 0.7049351479064989, + 0.6689957927368715, + 0.432599501935786, + 0.5248017260223407, + 0.5678126234206614, + 0.700432363623254, + 0.4745561015580358, + 0.4235507793185908, + 0.5154872399868501, + 0.6945633942493479, + 0.43817102324772633, + 0.6156795375194772, + 0.5472072173013496, + 0.7004069987187196, + 0.41196843343417894, + 0.6209583786565034, + 0.4873519943723665, + 0.4707098417272138, + 0.5043181105400858, + 0.43863939508241884, + 0.6845432418502742, + 0.4592011284641393, + 0.43168614804939615, + 0.48044038398942795, + 0.4845685251344588, + 0.5246574324022515, + 0.5953138057840592, + 0.5373533169710921, + 0.692784889485674, + 0.5109811949805377, + 0.46162198178378655, + 0.41688910252946515, + 0.4333177193474465, + 0.416001490724772, + 0.598419174457079, + 0.4771103642034885, + 0.6634043045077194, + 0.6434566717242465, + 0.6108015738826118, + 0.4728634263096049, + 0.6163189699448949, + 0.4042776049245752, + 0.6434119171100962, + 0.4700744996368002, + 0.7077827030986106, + 0.43245340449390046, + 0.6267837218832019, + 0.6944811477539081, + 0.6741662463863684, + 0.6993261963219768, + 0.5559378365400114, + 0.44949983138465116, + 0.5755946351184864, + 0.5093088039178515, + 0.39731303444802885, + 0.45498028025659304, + 0.6423225761921545, + 0.6849023191180699, + 0.702100332003754, + 0.6589851998369463, + 0.5895304012453122, + 0.6881967425705677, + 0.5012963500587777, + 0.6159561153437214, + 0.6971882432829583, + 0.4274603972733564, + 0.6104200170886455, + 0.5309762848750194, + 0.4194104779341083, + 0.5831691664919242, + 0.5609940752015927, + 0.5528258668661005, + 0.4409244046990854, + 0.5234028484754637, + 0.6341570172378744, + 0.6979611715835525, + 0.4823280715897249, + 0.491996069663828, + 0.6985831324852219, + 0.5952680204555105, + 0.5413931812016325, + 0.43900133915257566, + 0.7118104223109781, + 0.420306849795229, + 0.5926656038081533, + 0.6938601163915135, + 0.6251047544619236, + 0.4538994839271886, + 0.49244027139102375, + 0.43669593795478656, + 0.4893460875118337, + 0.7003354566695694, + 0.42535721588409164, + 0.6854609317881247, + 0.7129640013160813, + 0.4062625856237518, + 0.4245339045636707, + 0.546359979896188, + 0.4504071387455426, + 0.6256778518256001, + 0.5850404240391318, + 0.5670278448795742, + 0.5457890301927284, + 0.5887512845201848, + 0.673195546338485, + 0.4878367875573539, + 0.4505555447119997, + 0.4429016349712387, + 0.5879000971621142, + 0.5237948099969321, + 0.5147737994762814, + 0.397445268718361, + 0.5685371827429901, + 0.48035665039027686, + 0.5762762860425734, + 0.6253835009409578, + 0.7079825310757033, + 0.6891492421687659, + 0.48082038904147784, + 0.6728385368145728, + 0.4759800237299206, + 0.45492729112905805, + 0.5273536905930523, + 0.6620832786552793, + 0.6082271530183876, + 0.5174435926111037, + 0.48427943702362763, + 0.48176700722059596, + 0.5763753922998038, + 0.48415730377895316, + 0.4916221563925771, + 0.6561295488164942, + 0.6346916291223746, + 0.6654819564056859, + 0.5560834962322355, + 0.6154880565837786, + 0.49282670500316966, + 0.5380100672098375, + 0.4753338562936456, + 0.4470403100182614, + 0.6107993057745476, + 0.6334375162162126, + 0.6466720459078152, + 0.45912809507568, + 0.4816739361194806, + 0.4870054973835549, + 0.6005759223212919, + 0.6679754980820636, + 0.4141615269687212, + 0.5112880972778483, + 0.698397140457399 ], "type": "scatter" }, @@ -41338,44 +41296,30 @@ "mode": "markers", "name": "Expectation", "x": [ - -0.10024653371663643 + -0.006128662258061308 ], "y": [ - -0.08188011319811177 + -0.061285758701568493 ], "type": "scatter" }, { "fill": "toself", - "mode": "lines+markers", + "mode": "lines", "name": "Mode", "x": [ - -0.7666139110834805, - 0.6633025782322575, - 0.6633025782322575, - -0.7666139110834805, - -0.7666139110834805, - null, - -0.7666139110834805, - 0.6633025782322575, - 0.6633025782322575, - -0.7666139110834805, - -0.7666139110834805, - null + 0.4178483805738874, + 0.4178483805738874, + 0.6762126815500766, + 0.6762126815500766, + 0.4178483805738874 ], "y": [ - -0.697788532493164, - -0.697788532493164, - -0.1388998086540928, - -0.1388998086540928, - -0.697788532493164, - null, - -0.697788532493164, - -0.697788532493164, - -0.1388998086540928, - -0.1388998086540928, - -0.697788532493164, - null + 0.15624896603640903, + 0.393362968645088, + 0.393362968645088, + 0.15624896603640903, + 0.15624896603640903 ], "type": "scatter" } @@ -42224,7 +42168,7 @@ "plotlyServerURL": "https://plot.ly" } }, - "text/html": "
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" @@ -42240,12 +42184,12 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:17:08.248386Z", - "start_time": "2024-03-13T13:17:07.484957Z" + "end_time": "2024-03-21T13:48:50.379158Z", + "start_time": "2024-03-21T13:48:49.463290Z" } }, "id": "825dceb35326faf7", - "execution_count": 22 + "execution_count": 9 }, { "cell_type": "markdown", @@ -42264,7 +42208,7 @@ "name": "stderr", "output_type": "stream", "text": [ - "100%|██████████| 100/100 [00:15<00:00, 6.66it/s, Success Probability=0.53]\n" + "100%|██████████| 100/100 [00:06<00:00, 14.76it/s, Success Probability=0.31]\n" ] } ], @@ -42277,12 +42221,12 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:17:25.859550Z", - "start_time": "2024-03-13T13:17:10.842375Z" + "end_time": "2024-03-21T13:48:57.163741Z", + "start_time": "2024-03-21T13:48:50.380442Z" } }, "id": "6bfc00e5d93a19af", - "execution_count": 23 + "execution_count": 10 }, { "cell_type": "markdown", @@ -42318,30 +42262,21 @@ ], "source": [ "kitchen = Object(\"kitchen\", ObjectType.ENVIRONMENT, \"apartment.urdf\")\n", + "\n", "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", "milk_description = ObjectDesignatorDescription(types=[ObjectType.MILK]).ground()\n", "fpa = MoveAndPickUp(milk_description, arms=[Arms.LEFT.value, Arms.RIGHT.value, Arms.BOTH.value], grasps=[Grasp.FRONT.value, Grasp.LEFT.value, Grasp.RIGHT.value, Grasp.TOP.value], policy=model)\n", - "fpa.sample_amount = 200" + "fpa.sample_amount = 200\n" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:17:30.641037Z", - "start_time": "2024-03-13T13:17:28.025570Z" + "end_time": "2024-03-21T13:48:59.559168Z", + "start_time": "2024-03-21T13:48:57.164442Z" } }, "id": "90d7cb5e1e1cc7fd", - "execution_count": 24 - }, - { - "cell_type": "markdown", - "source": [ - "Let's look at the density of the relative x and y position of the robot with respect to the milk. We can see that he would like to access the object from the right front area." - ], - "metadata": { - "collapsed": false - }, - "id": "eaaf99db302255e0" + "execution_count": 11 }, { "cell_type": "code", @@ -42352,20016 +42287,20016 @@ "data": [ { "hovertext": [ - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 30.091528326798986", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 48.02373812816365", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 44.64846346790239", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566", - "Likelihood: 22.828118667793277", - "Likelihood: 67.47658213569566" + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5965905556432232", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 1.1238803101090267", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.18575458686579954", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.22169828773924782", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.40745287460504737", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.5965905556432232", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.15893704976288248", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.344691636628682", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.36292570780171296", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124", + "Likelihood: 0.5486802946675124" ], "marker": { "color": [ - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 30.091528326798986, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 48.02373812816365, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 44.64846346790239, - 67.47658213569566, - 44.64846346790239, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566, - 67.47658213569566, - 22.828118667793277, - 22.828118667793277, - 22.828118667793277, - 67.47658213569566, - 22.828118667793277, - 67.47658213569566 + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.344691636628682, + 0.5486802946675124, + 0.344691636628682, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.5486802946675124, + 0.18575458686579954, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.18575458686579954, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.18575458686579954, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 1.1238803101090267, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 1.1238803101090267, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.5965905556432232, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.18575458686579954, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.5486802946675124, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.5965905556432232, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.18575458686579954, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 1.1238803101090267, + 0.5486802946675124, + 0.5965905556432232, + 0.344691636628682, + 1.1238803101090267, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.5486802946675124, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 1.1238803101090267, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.5486802946675124, + 0.5486802946675124, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.40745287460504737, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 1.1238803101090267, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5486802946675124, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.18575458686579954, + 0.18575458686579954, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5486802946675124, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 1.1238803101090267, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.5486802946675124, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.18575458686579954, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.5965905556432232, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.18575458686579954, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5486802946675124, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.18575458686579954, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 1.1238803101090267, + 0.40745287460504737, + 0.40745287460504737, + 0.344691636628682, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.5486802946675124, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.18575458686579954, + 0.40745287460504737, + 0.344691636628682, + 0.344691636628682, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.22169828773924782, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.22169828773924782, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.40745287460504737, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.5965905556432232, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.15893704976288248, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.344691636628682, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.36292570780171296, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124, + 0.5486802946675124 ] }, "mode": "markers", "name": "Samples", "x": [ - 0.4905591618699666, - 0.5516717616766008, - 0.4790742675747113, - 0.480645760625706, - 0.5432644053176138, - 0.5312480726488219, - 0.46803891731613156, - 0.43565338893117883, - 0.4215833909281689, - 0.4428606237063729, - 0.4973339306971872, - 0.43501729528375643, - 0.49409614858853107, - 0.43626095058543557, - 0.5570138846496575, - 0.4467076142209238, - 0.43820595942077367, - 0.4818910799475662, - 0.4991522355419699, - 0.5040113775498051, - 0.48394403960496185, - 0.5457881061457825, - 0.4553876727381054, - 0.507106251523887, - 0.43504953951425435, - 0.5087395445647241, - 0.4614453304374614, - 0.4871352467805301, - 0.5034182376027745, - 0.541897302640506, - 0.5166700038252846, - 0.43197292112412905, - 0.5244349057659807, - 0.47229352785711975, - 0.49545451597337736, - 0.4351632305082429, - 0.4204530923461802, - 0.5014815436528849, - 0.5597087754286846, - 0.5153402893418058, - 0.4241838688365221, - 0.4428547420351033, - 0.49512895882765934, - 0.5278258597727286, - 0.5373097550051186, - 0.48716980585872766, - 0.5261363222839406, - 0.5149289450815936, - 0.4601743627885638, - 0.559732644994293, - 0.5494482312676707, - 0.5280078802383266, - 0.5359802363005264, - 0.46321752299367236, - 0.43158147519649553, - 0.5165475001267693, - 0.5383362241681406, - 0.528744468853051, - 0.5419829726846053, - 0.44617142047073677, - 0.4463461226929807, - 0.46106698722152106, - 0.5177982110271153, - 0.535256235606594, - 0.536350688595701, - 0.46809196920991686, - 0.5032043400996469, - 0.4276792740037433, - 0.49920946760897394, - 0.4608768073953631, - 0.44424496442264394, - 0.5504287567482792, - 0.47796942562117833, - 0.5376494011849174, - 0.5019674716996712, - 0.4676118369098697, - 0.4772439858789415, - 0.4333540800606849, - 0.5234071955246892, - 0.4958726850427261, - 0.47189533596378674, - 0.5002299394447363, - 0.4919430565661693, - 0.4830465928482867, - 0.5214003259890607, - 0.4400266957470094, - 0.46177618957706695, - 0.5077149879987751, - 0.5298025837421618, - 0.461494226890884, - 0.5130870748258489, - 0.5588283106487462, - 0.5283703690808557, - 0.4536821945176296, - 0.42315021557559473, - 0.4267041153778884, - 0.42941911676780037, - 0.43753245013600567, - 0.43773575964586076, - 0.4666301357878745, - 0.4238310561875971, - 0.4641099062078938, - 0.4814752431861758, - 0.5319964872988311, - 0.4283931945545535, - 0.5578248335591258, - 0.47736256698968993, - 0.4936416038747841, - 0.4561656524257176, - 0.532321643608201, - 0.5005300885474115, - 0.5259713079942137, - 0.4667581158087286, - 0.5165925344207315, - 0.4540160847040554, - 0.5499753540527009, - 0.5349494623189285, - 0.45502856433569094, - 0.4659050479660257, - 0.48200318718544655, - 0.5079258189016995, - 0.46753606649412, - 0.548372954199307, - 0.45203087562281286, - 0.5143354445396339, - 0.4298780149685375, - 0.4713006871245582, - 0.5326088885048545, - 0.5247896408121969, - 0.4205642786455023, - 0.5063579054588674, - 0.42517766164806614, - 0.4855292919833238, - 0.49658885210186976, - 0.4750542852507247, - 0.533527109736083, - 0.4999205184682987, - 0.42268389142263313, - 0.43000459700346416, - 0.5187921016388372, - 0.5385550138253897, - 0.5303492826446319, - 0.45663395365377674, - 0.4342176250041899, - 0.5448767670585315, - 0.5463985268354181, - 0.5245818880978801, - 0.5354781543853468, - 0.42641874806170116, - 0.5138731068335951, - 0.5216590241318608, - 0.46650498228856446, - 0.5167681532737276, - 0.4247354869990692, - 0.43408386636981666, - 0.5534403228839637, - 0.5083426027795693, - 0.42631163324486016, - 0.42124745648844464, - 0.4646693666881031, - 0.44488758158325614, - 0.5208691178396178, - 0.5480716641464831, - 0.5326835112574649, - 0.5377991744385804, - 0.5043472121732779, - 0.5030154557605829, - 0.514622888436876, - 0.5519884211257884, - 0.4385162410144874, - 0.42364929215172475, - 0.5225390784806002, - 0.5099697918953106, - 0.5296643170562929, - 0.5563638554225862, - 0.515972751015057, - 0.42608335231522837, - 0.5100133476566324, - 0.45059788671186607, - 0.42181470086961687, - 0.4607170126472727, - 0.5485222757550451, - 0.4932081340146549, - 0.48786749584618905, - 0.4741129752939235, - 0.4225929354020509, - 0.4994370306965763, - 0.4694518236303803, - 0.5050790023751958, - 0.5589616015436553, - 0.4279696789897156, - 0.508114958711041, - 0.5210546478397772, - 0.49396244529859223, - 0.4609046768849655, - 0.5493501422533443, - 0.5211654563261653, - 0.4424523749941371, - 0.4656794091589282, - 0.4817301331720862, - 0.523256245828136, - 0.4414037310886546, - 0.48633916940488087, - 0.47409024283489287, - 0.5196524982292928, - 0.5469925778582805, - 0.4550099339997873, - 0.4397899062006768, - 0.49199151678955066, - 0.45859947918934524, - 0.5573601354623221, - 0.4717100403782704, - 0.4445757028090285, - 0.49550533849515127, - 0.5123011833269584, - 0.5442484011870232, - 0.4462173760356874, - 0.44210615588540153, - 0.49530387412995425, - 0.5131811136203477, - 0.4532422632716309, - 0.4986586432895398, - 0.44600394139040694, - 0.45280553746416474, - 0.5370341918604162, - 0.5271598729375023, - 0.45433696442265203, - 0.46103748047793713, - 0.5371677062926871, - 0.5194974852795395, - 0.48967076582059105, - 0.4919546686380737, - 0.558795572005863, - 0.5587677086568894, - 0.44963959431370426, - 0.4368242413876246, - 0.5570665933851285, - 0.5548626069009404, - 0.5589605732942228, - 0.46243640629279753, - 0.47396071019465624, - 0.5157365854010402, - 0.4711379677455171, - 0.46298814615099754, - 0.5085739747782168, - 0.4454033355516573, - 0.5384993905770833, - 0.4665714898958382, - 0.43753266853806133, - 0.455003801393021, - 0.5340876391230893, - 0.5401735126020366, - 0.5406322077441975, - 0.5467840452233218, - 0.42023625672334053, - 0.4303893129935143, - 0.4751588315327141, - 0.5479634989054165, - 0.5436797269541135, - 0.48273853648189385, - 0.4870284789237199, - 0.49210523533468564, - 0.535752957637063, - 0.4639371130174475, - 0.5324041864688108, - 0.43167362586846747, - 0.46397240709054116, - 0.4266729700853558, - 0.5051609815307132, - 0.4962799730079546, - 0.48370266793573446, - 0.5144511335733633, - 0.5005850424776852, - 0.4648988646269511, - 0.5003034673962461, - 0.5034583525126808, - 0.5488388842644799, - 0.5599838456742683, - 0.5437982598571316, - 0.5006722779374964, - 0.5035973345971798, - 0.44046122452770176, - 0.46630304815140816, - 0.43967990589005723, - 0.47978167301206004, - 0.5284842343139424, - 0.4515760362924833, - 0.4449820572425699, - 0.5039140931932946, - 0.5456884678252764, - 0.4471696586818966, - 0.4583486923224653, - 0.45068274993091145, - 0.4396508886240779, - 0.5202526329124679, - 0.4540578638185848, - 0.4284160964651863, - 0.47157031080746237, - 0.5236561924578306, - 0.5023291809672111, - 0.5202463774866419, - 0.5598901778171093, - 0.5540561312541388, - 0.484481546755412, - 0.5418202922574613, - 0.5503211997604112, - 0.5355705559745283, - 0.513696835676123, - 0.5454737115002004, - 0.5122545196429243, - 0.5445814472752626, - 0.4980514473874753, - 0.49896559507715177, - 0.5575815936931424, - 0.42065404451959515, - 0.4528760200382605, - 0.4953092191353945, - 0.5406919536456657, - 0.49399243233450163, - 0.5277279635360734, - 0.49326321874927864, - 0.45571925640297384, - 0.46007494222779693, - 0.44367047759483896, - 0.5136613740341041, - 0.5572472518845537, - 0.48392399694469124, - 0.5067230739654188, - 0.544854728899556, - 0.4332604410856834, - 0.5213696023856746, - 0.5215267291108454, - 0.5077742238272112, - 0.48462374595784696, - 0.42010418984549686, - 0.430982286699331, - 0.4821080153371603, - 0.5054939467426104, - 0.5315594975981851, - 0.42308631040592637, - 0.5305533185144266, - 0.48423357433336617, - 0.4386865758568948, - 0.514809257568055, - 0.5191220021650773, - 0.4284418187855607, - 0.5315529003352681, - 0.5329451451490799, - 0.5130697597095762, - 0.42546749738184886, - 0.49137890220836855, - 0.43760877284433, - 0.5578850799221917, - 0.555981951138588, - 0.5510932095726737, - 0.4266789535699512, - 0.5528997758851775, - 0.4403133414252198, - 0.5067102932542191, - 0.46780143826410103, - 0.4581178091581757, - 0.5396264749367379, - 0.46463583677625914, - 0.4683170163834156, - 0.4821056342419195, - 0.4486438416972412, - 0.5191640840068574, - 0.43806887461039984, - 0.42229604191476183, - 0.5026261802883695, - 0.455674714230107, - 0.5060229397715745, - 0.5223628274825639, - 0.4573771772433342, - 0.5599387620293514, - 0.5571157324567086, - 0.5126761016493635, - 0.5389941336411641, - 0.47512474914666764, - 0.508119154881844, - 0.5316365957375738, - 0.43651174814590393, - 0.49955966432093984, - 0.4637270778863378, - 0.46588407008109534, - 0.4471244963853867, - 0.5596528822906413, - 0.4749617361240286, - 0.43407460110864876, - 0.549512929750555, - 0.531597223322439, - 0.44444542700546597, - 0.4792654556253019, - 0.5468215680083712, - 0.4447787086100258, - 0.45443980106492604, - 0.5561459559530993, - 0.474841896109786, - 0.44867723785574454, - 0.42696958205151186, - 0.42767441817888086, - 0.46331649228880684, - 0.4546343417746808, - 0.44644397985369444, - 0.5311153972281489, - 0.5577816771409948, - 0.48522671623458435, - 0.4830178638446174, - 0.4392443193084068, - 0.5416428208390714, - 0.5505765553962698, - 0.5475349408067338, - 0.4810760368445099, - 0.4756339328353852, - 0.5360739165827098, - 0.47004263356339016, - 0.5209593672169226, - 0.5436790089633725, - 0.5053573421811499, - 0.5477415504535041, - 0.4461057993739469, - 0.44252594044906346, - 0.46629843276675853, - 0.4558846939236738, - 0.422939413990959, - 0.5022697468062881, - 0.44705214695906137, - 0.4810334444340353, - 0.541588322269886, - 0.4736241379459288, - 0.5501967071891746, - 0.5560127779683482, - 0.5378512963731161, - 0.5436476139766966, - 0.553670724611869, - 0.5036113517065816, - 0.5065537558156094, - 0.49000583478269677, - 0.5256169229266838, - 0.5032118211424959, - 0.43224174370703505, - 0.4400152057586105, - 0.4866580281396071, - 0.4704382287903727, - 0.4227393390029014, - 0.4925093894763093, - 0.516548702744744, - 0.4773889941872379, - 0.4958258334449899, - 0.5365153177619078, - 0.47075998684560727, - 0.4443392092330809, - 0.4267203955272717, - 0.44187279608733, - 0.559748454301284, - 0.4970509570064208, - 0.4222480259206397, - 0.5167526302203168, - 0.5151590305907228, - 0.4671066801301891, - 0.5265124516184005, - 0.5120844233944395, - 0.5334814584116291, - 0.5548575565659476, - 0.4536725350275045, - 0.522126433652728, - 0.4360034521044277, - 0.5300640902552406, - 0.45134367566957817, - 0.5553646966220642, - 0.46106363318878374, - 0.5575013917402707, - 0.4240030687157332, - 0.44798928145291106, - 0.44410549263757515, - 0.5391268404450653, - 0.557607065045453, - 0.5455165180517338, - 0.5271806175038709, - 0.5421779480060089, - 0.545942229169182, - 0.5279075822684627, - 0.5171152566632201, - 0.43212815519471165, - 0.46070259990016293, - 0.44542478054889595, - 0.4202987550102304, - 0.5453165318871546, - 0.5091761975381326, - 0.5123260225357882, - 0.43200636252323, - 0.5552257509078923, - 0.4603167786544235, - 0.5260973555867372, - 0.460842250398404, - 0.43363206479666416, - 0.46637940611227957, - 0.4453229878063086, - 0.4485431443039898, - 0.4432746503881077, - 0.44371181775469853, - 0.48910835098728755, - 0.5429733401574245, - 0.48146106596892396, - 0.5312929729437973, - 0.548358130447499, - 0.5306418949549038, - 0.44563056469131773, - 0.5366194353280577, - 0.4705610288514195, - 0.5422017148395508, - 0.4661771387477044, - 0.5193584120028858, - 0.46028744135342364, - 0.5185108707618762, - 0.5262362371993399, - 0.5170837440571036, - 0.46634009487333483, - 0.49407651220731397, - 0.5480669136411975, - 0.4673178035270616, - 0.5205055930220265, - 0.45758494176370623, - 0.5072535544437511, - 0.45879403023596266, - 0.443440956602887, - 0.5129660376622768, - 0.5504991993141645, - 0.5478932413965926, - 0.4916399906817064, - 0.5178570745399825, - 0.5539194660911984, - 0.42252159138936446, - 0.45142129924896984, - 0.5336645025468681, - 0.5268718119280773, - 0.49956908686873436, - 0.514761199707233, - 0.5407376241967714, - 0.4930916404194676, - 0.4541758901811524, - 0.5598810253622983, - 0.45341921208791486, - 0.45605960499941667, - 0.4732173858232187, - 0.45478305444622824, - 0.4359007401092397, - 0.5167122651033879, - 0.46638271106500656, - 0.5597226908272183, - 0.529011136619826, - 0.47095382943117325, - 0.5495045601522025, - 0.4852387152266056, - 0.5413374229734148, - 0.460002510080524, - 0.5406127946238419, - 0.44214367250861847, - 0.4667384924185706, - 0.46953755613700354, - 0.42148646063678047, - 0.4484213933942726, - 0.5450788538910286, - 0.4454784916557663, - 0.5481268773496843, - 0.44029391858135447, - 0.42885071097711946, - 0.44275601887222216, - 0.5296513714331302, - 0.4690502242898728, - 0.503535806924637, - 0.4929247081467515, - 0.44821394601900383, - 0.5054902086149918, - 0.429638755118767, - 0.5235937510413452, - 0.5131161356437438, - 0.4676502724929987, - 0.541932811654141, - 0.5410085591528958, - 0.51049589641832, - 0.5353268954422326, - 0.4670542119260123, - 0.5395135129904413, - 0.4904193059483777, - 0.46689874829950706, - 0.47998250583598984, - 0.4492731514812546, - 0.4247774302807127, - 0.515146547056379, - 0.44483629131483055, - 0.5340173719572691, - 0.5196369028144066, - 0.43576995514690975, - 0.43202674230680904, - 0.4561852949601885, - 0.48023936352426305, - 0.4236346317452358, - 0.5370469049128229, - 0.4758435452948945, - 0.4801242119963212, - 0.4765426579975997, - 0.503286466898945, - 0.49572804550324023, - 0.4666234329517999, - 0.5109834692234847, - 0.47037683697471405, - 0.5025059773458191, - 0.46275824516878256, - 0.5085418068552648, - 0.4744055284286103, - 0.5385023661785685, - 0.5008106478339536, - 0.4259291163404673, - 0.47260083207517584, - 0.5463564089591569, - 0.42755958897827445, - 0.42550162258552704, - 0.5227159934235086, - 0.5096359111786853, - 0.4311444307036384, - 0.4247331027549425, - 0.4305426383680627, - 0.5304648980555866, - 0.4618457674869688, - 0.5161584237880488, - 0.4435216347291532, - 0.4437654420992488, - 0.5520240624259594, - 0.4862934937903507, - 0.4284197626581037, - 0.4469128577295855, - 0.46164132922439166, - 0.4948433636025917, - 0.46571837202046734, - 0.4910204958036243, - 0.5031043250503705, - 0.4949609238376096, - 0.43187111448645843, - 0.49810631952641116, - 0.553129094900231, - 0.48149330419078434, - 0.5313178767781501, - 0.47744091698424374, - 0.45587177148095925, - 0.4683781673965895, - 0.5015823068449886, - 0.5385781492437114, - 0.5558394041422533, - 0.4926902599022547, - 0.43903490513252785, - 0.42067010349148504, - 0.551749051136768, - 0.4265578357231545, - 0.4652098128135455, - 0.4929943057243738, - 0.4420671804902241, - 0.4598984453469901, - 0.45646968913241714, - 0.5096030512768509, - 0.4317320500133343, - 0.42659491784001174, - 0.5371833037820996, - 0.5175269059060921, - 0.4559964750172232, - 0.4228882039592853, - 0.5092528311054653, - 0.5394814693775909, - 0.4856600423518334, - 0.5020083725783258, - 0.5217988598985762, - 0.5555115964078094, - 0.446255715657348, - 0.5488683870958848, - 0.4688684206929537, - 0.47439915718307807, - 0.509849041302761, - 0.4442547182534308, - 0.46801500691886877, - 0.49894051833445097, - 0.5532024277278029, - 0.4621921197290583, - 0.5189382236074832, - 0.46746371681459786, - 0.45156753835494035, - 0.46154567414890646, - 0.55787385302351, - 0.42950342091552074, - 0.4481310980925645, - 0.4666572456880842, - 0.4970736839578902, - 0.5128790014164709, - 0.5122771781665333, - 0.5501505036395749, - 0.46053241934515554, - 0.4387736893022746, - 0.5439413842382868, - 0.5535843896417497, - 0.5594748480875243, - 0.5411007219514778, - 0.49200111818835685, - 0.5579665477573577, - 0.5258212788283906, - 0.48060456017775965, - 0.46706387004636324, - 0.544386588268817, - 0.5139789581560625, - 0.5035473262583539, - 0.4751911164912665, - 0.48631107761552844, - 0.5273821541876441, - 0.4342234326303349, - 0.49660012085955385, - 0.5232486040507252, - 0.4507856592648926, - 0.5215272200048691, - 0.5237059226092268, - 0.4211511874097379, - 0.48910043445676427, - 0.5223002648412697, - 0.4565680504068061, - 0.4886127253402253, - 0.46743675920886807, - 0.4392410515687342, - 0.49549844076499355, - 0.48319805649485914, - 0.4848601475570168, - 0.4352916581804716, - 0.4893275059713252, - 0.5512576337305362, - 0.5510999653556787, - 0.4665960711608636, - 0.5216873809841863, - 0.5038663758765061, - 0.47194660884833806, - 0.539510298673395, - 0.4724482336898549, - 0.43186118547323665, - 0.4974358007396271, - 0.5365544706002775, - 0.4970283376303055, - 0.47284436862858814, - 0.465182210262885, - 0.5347086735086608, - 0.42268476888655204, - 0.4631318253309618, - 0.4363797257677811, - 0.465941447516018, - 0.4367193410173248, - 0.5409360885751008, - 0.5287486644144405, - 0.4406147278465668, - 0.47748716172229866, - 0.42346134001290636, - 0.45969725317746285, - 0.5040428099979503, - 0.5251066343191994, - 0.5462452534368445, - 0.4429499846482246, - 0.4388512356270236, - 0.4647024494845904, - 0.43280145290809885, - 0.4966382999542671, - 0.5332612052864432, - 0.5061735593402289, - 0.47336287040099034, - 0.5544777668625019, - 0.5167294051917959, - 0.5429578441653818, - 0.5315681060024975, - 0.4546536495402296, - 0.4808363569533827, - 0.4200298053765452, - 0.44070061145776995, - 0.46358768863844074, - 0.5107249392660633, - 0.5453735006843935, - 0.4455629994378313, - 0.440104509628542, - 0.537454758721457, - 0.4396182480076277, - 0.4461793222308473, - 0.5474361322687532, - 0.45492498332959724, - 0.466445774375579, - 0.4450424750055613, - 0.49047409636084494, - 0.4815969942806557, - 0.5391009233305671, - 0.435223638898211, - 0.4495197895588027, - 0.46771681310283747, - 0.44346915485197985, - 0.47077253886330706, - 0.4815662589589093, - 0.5378326613964353, - 0.5475009873455128, - 0.45266958444688915, - 0.4993957709441753, - 0.4903964490802334, - 0.4839232823458408, - 0.4431419593102446, - 0.5250211461443633, - 0.5157680542090332, - 0.4501206058394932, - 0.5246811282478441, - 0.4768244848138311, - 0.48803196108877855, - 0.5542612171117799, - 0.5062166101524102, - 0.4939541109585167, - 0.46057842827647477, - 0.4849956533190807, - 0.4468531391652827, - 0.4470992609039954, - 0.4216268785085575, - 0.4565768972889219, - 0.5361858108976397, - 0.4756808129026121, - 0.5519226655086406, - 0.4219515350962207, - 0.47703450685165677, - 0.43294326191408605, - 0.45929740587532736, - 0.48471085779332257, - 0.5250546121609777, - 0.42933308579975, - 0.4533557255243672, - 0.48342657157623004, - 0.5559565031482876, - 0.5571368755242107, - 0.4285852535680217, - 0.5386434775317176, - 0.44153115788680836, - 0.5572533394079908, - 0.43700317890591056, - 0.4491646976448631, - 0.5131101118393775, - 0.5332523255996796, - 0.540102532719686, - 0.4868978656727081, - 0.4621983684012656, - 0.4381792583234371, - 0.4604901533830079, - 0.45389797674847815, - 0.47234343415728236, - 0.5013002238628532, - 0.5332682256172141, - 0.473908070876866, - 0.476397998199507, - 0.4521815388116853, - 0.4486063421306411, - 0.5423849418511396, - 0.43260098009556947, - 0.540130074184728, - 0.48959672883274596, - 0.4595052474928613, - 0.4297557641049296, - 0.4685024899647484, - 0.4234153845012784, - 0.45281065244201796, - 0.4607820332787096, - 0.5310672270222856, - 0.4807851228605046, - 0.49720590641085727, - 0.5473186402115402, - 0.545561937804224, - 0.48005192725391965, - 0.48791424058972316, - 0.5104489049266244, - 0.43355168074251715, - 0.5181442838054167, - 0.48277708244933404, - 0.5012864683176981, - 0.46655454934068313, - 0.497890960594006, - 0.5374716777437918, - 0.5127897201806157, - 0.4329725995665827, - 0.4776486568348324, - 0.44491891795687183, - 0.5538182367361051, - 0.42749725097720054, - 0.4639609784307241, - 0.46244504248713203, - 0.4430766926397516, - 0.4281217883771539, - 0.43615820036550823, - 0.4700836666448264, - 0.5008307337986525, - 0.5413129090670988, - 0.4515458074758248, - 0.542184960518777, - 0.5230642812775991, - 0.48385117647434683, - 0.4692896721499664, - 0.4317484512475401, - 0.49250817979051315, - 0.4580911133173475, - 0.5500388357765424, - 0.4440625878074374, - 0.4226884234110932, - 0.46467210665754866, - 0.44372380314695836, - 0.4412141352114542, - 0.552057878299024, - 0.5084528884104225, - 0.49358268153688284, - 0.4997193220952584, - 0.4905736633721533, - 0.4357512023559013, - 0.4279185767899768, - 0.4887577129226172, - 0.5495280283965389, - 0.46088976157332767, - 0.5480540468123467, - 0.4374839090565673, - 0.5141914790310019, - 0.4828738420725382, - 0.474052936801726, - 0.4665109458643335, - 0.5138229789773113, - 0.47112675870565657, - 0.4609612782752446, - 0.44534021665467055, - 0.5037972078058232, - 0.44606376998589575, - 0.5298275418872324, - 0.49500950818034667, - 0.49264167944952497, - 0.43892915771120117, - 0.5095923978916157, - 0.5086027762475082, - 0.5000024045244518, - 0.4901030650336101, - 0.5446043742453578, - 0.4536612364650127, - 0.517518209318667, - 0.4928306594381166, - 0.4938326631709732, - 0.4950415961516809, - 0.5051530711296066, - 0.5594449988342832, - 0.5429946510973354, - 0.5060744273279368, - 0.5458015457082697, - 0.5256042832450235, - 0.4539152306017574, - 0.42046670104253275, - 0.4869774847718094, - 0.558441471600647, - 0.53293910604304, - 0.4600411550855274, - 0.4796044324290207, - 0.4662156136691472, - 0.46138707984535765, - 0.46938511964190505, - 0.4427871449253075, - 0.5128558125485321, - 0.48896199468662677, - 0.4975550378502418, - 0.5151137641731177, - 0.5562404230935318, - 0.4709877074141944, - 0.5124029836445607, - 0.4608521360655619, - 0.5100375879073864, - 0.5130528742769633, - 0.5310704089279388, - 0.45701675210627013, - 0.5495178827343438, - 0.483967727683085, - 0.5168410669216102, - 0.5337863968158659, - 0.4531800266428175, - 0.5553213953513731, - 0.4810490053493783, - 0.43254058517006067, - 0.53607987377814, - 0.5058836758975652, - 0.42333085002664866, - 0.5177448434630586, - 0.4720652028380054, - 0.5274055945424411, - 0.45093053788473647, - 0.5258468623658983, - 0.4707206239405402, - 0.45904734153963295, - 0.5084958940768048, - 0.5583013381901297, - 0.5212169472828779, - 0.5177617022743579, - 0.5087288466067813, - 0.5549883727980229, - 0.5514581724349337, - 0.5055565618272712, - 0.5181518574189029, - 0.47540534669833356, - 0.42250443064537135, - 0.48466333940659845, - 0.4368292229528091, - 0.48595552504469275, - 0.5160012690559286, - 0.42649298482686526, - 0.46661264547039183, - 0.4665853961968336, - 0.42197185585723807, - 0.5446078667094412, - 0.5216631131083311, - 0.5135700155260168, - 0.4892415758363057, - 0.45029267903024706, - 0.570286988284926, - 0.5794862648671476, - 0.6333682562927927, - 0.6020097152022865, - 0.45123928872241637, - 0.5878462215656923, - 0.6464483672044865, - 0.4461478860047812, - 0.4408865517069536, - 0.5891479147609632, - 0.5314712473313276, - 0.511451061231593, - 0.47013259134173513, - 0.6593148524311402, - 0.46896335969990977, - 0.5025691031853627, - 0.5732254138941845, - 0.4586336021083235, - 0.634267322907903, - 0.4423948480682358, - 0.46979014709772854, - 0.4530433726465093, - 0.6562976535867787, - 0.5069799285304726, - 0.5250477401874099, - 0.633573428592878, - 0.446947110935833, - 0.5688197207153616, - 0.5967414901773355, - 0.529117859372725, - 0.4470146857894404, - 0.4471321067382465, - 0.5843665633692028, - 0.5435936027406657, - 0.580050188075589, - 0.5422990166824461, - 0.6225997437688816, - 0.6477545146394261, - 0.5017556053085894, - 0.5076336029531726, - 0.6313117256035133, - 0.6127122538992517, - 0.6344424344519289, - 0.5420760646397078, - 0.4642370600987805, - 0.6154362145444623, - 0.6529411402659915, - 0.5979684626609523, - 0.4934336997038841, - 0.4932974113762861, - 0.6059073826388699, - 0.6590288618180524, - 0.6400002089011607, - 0.6340737033599894, - 0.554263843245606, - 0.5781846794140888, - 0.5440672050696278, - 0.5365523373318049, - 0.47712720591380814, - 0.45234316746232517, - 0.5093835788556704, - 0.48533586747418156, - 0.5192981989630171, - 0.5201658514194644, - 0.5445330121996443, - 0.5682174013447352, - 0.6579545901309921, - 0.536363877007709, - 0.5085869277515381, - 0.5141503510952671, - 0.5296311451912077, - 0.5391270289231864, - 0.4735080141173954, - 0.5937674120286944, - 0.5169202224549958, - 0.5838564691978522, - 0.47863736602862, - 0.597382843526152, - 0.6557392551543055, - 0.6333299103753988, - 0.6534515302498736, - 0.6239426470118117, - 0.46794875282063886, - 0.544051415155195, - 0.5384169028301887, - 0.5294266805064154, - 0.6252650933193009, - 0.5304582332121351, - 0.6455864477232257, - 0.5519415917361687, - 0.5271847996656108, - 0.5838633610082963, - 0.5905464862774545, - 0.4458874587469817, - 0.623430147894676, - 0.6155092593761924, - 0.4506830662976475, - 0.495709214211565, - 0.563912737730167, - 0.5403556201653604, - 0.48807230006592794, - 0.46346509767176297, - 0.5995541247451346, - 0.5334058998747474, - 0.5945546409583142, - 0.4853572051879187, - 0.44233077315337693, - 0.48703435987310684, - 0.4618201295593254, - 0.44519405405588225, - 0.502159073239301, - 0.5478394252973057, - 0.6174641841424786, - 0.6103519077524294, - 0.45084032886798514, - 0.6518530851537893, - 0.6148754466566302, - 0.6064655979359257, - 0.5399205038112664, - 0.482299028692846, - 0.5094795955796142, - 0.48114760564874554, - 0.6551940899546821, - 0.5144665928737769, - 0.5024216680709631, - 0.5293537685097207, - 0.5336160078088312, - 0.49085641438894195, - 0.6570892910723276, - 0.643423524394263, - 0.5039595669665831, - 0.5724133319733196, - 0.6556097130297784, - 0.45931509683038585, - 0.5536095133732826, - 0.599148524891669, - 0.6392219689322751, - 0.5983884259352062, - 0.6010849479044851, - 0.4568714724201069, - 0.5030192021742828, - 0.5099295057134303, - 0.6322537966306738, - 0.5192696962726273, - 0.4503841311232381, - 0.6504931801713129, - 0.4799934453437237, - 0.6270890980003707, - 0.5032380823874738, - 0.5311550559819217, - 0.5376258955143035, - 0.6531298336108134, - 0.5298964074020034, - 0.5835458465580896, - 0.641419935427289, - 0.578673275400503, - 0.5170946155208408, - 0.5307266777258178, - 0.558296448927336, - 0.5432088467405898, - 0.6142727498035815, - 0.4960643025384184, - 0.4693936601405554, - 0.6101953996751316, - 0.485758005459361, - 0.48170197904264306, - 0.6087752260217804, - 0.5031800662596757, - 0.455446029179229, - 0.5277027654745251, - 0.5847018165995103, - 0.5438390212095581, - 0.47215586051194075, - 0.46711522464012245, - 0.5438093794446065, - 0.537261825381794, - 0.48248395776799835, - 0.6603917479272448, - 0.5270897909262955, - 0.6138009426258654, - 0.5183474500724548, - 0.5261542462836607, - 0.488512179116874, - 0.5037006653809543, - 0.6395214710218263, - 0.58880052421507, - 0.5256368096061783, - 0.6363229500068782, - 0.6149488894864399, - 0.6561882084482501, - 0.6030749109915563, - 0.5561818979630969, - 0.6191514089283676, - 0.638008064532487, - 0.4681260934216831, - 0.5323070383642473, - 0.4461914866822256, - 0.5212453560520244, - 0.6303453688863603, - 0.5300993207454672, - 0.6479940215711066, - 0.443247823611399, - 0.4895215225276733, - 0.5691844705536737, - 0.566309099222034, - 0.44046915910094064, - 0.6002490124015598, - 0.45679388593476977, - 0.6144598992009855, - 0.5727453136294723, - 0.4881909419265302, - 0.6159466787128092, - 0.6461747430316069, - 0.6439697364962624, - 0.5988903961520551, - 0.5703157322539334, - 0.46780215673528275, - 0.5647676682271082, - 0.5243692875762995, - 0.4832819099524418, - 0.6619816540782069, - 0.5955768776123288, - 0.5226444855086176, - 0.5293549948483988, - 0.5207869830342614, - 0.5363290291952582, - 0.5728419623916627, - 0.49443590109961866, - 0.582742610746812, - 0.47655915121741627, - 0.49751016663751246, - 0.5722920235257372, - 0.4443246803158507, - 0.6080610849972928, - 0.5710656069236841, - 0.6254621116024797, - 0.5334513219567788, - 0.60304857455972, - 0.6619867468278937, - 0.4807447237434256, - 0.5123591483603755, - 0.4934993002419229, - 0.5419029547361225, - 0.4775926675983641, - 0.5225094545251464, - 0.4415433451855878, - 0.6386251543097714, - 0.5415663431290286, - 0.4967462420257747, - 0.6031614548597182, - 0.48999760481989363, - 0.5125333579979512, - 0.48196231941227047, - 0.5389640060100112, - 0.45495918050583, - 0.602501093743488, - 0.5789530907660191, - 0.5977318151131172, - 0.526976347697868, - 0.6169928473745914, - 0.5772860107111354, - 0.6326927817443195, - 0.6460693232215375, - 0.5555964788421279, - 0.5108522721423667, - 0.6355244874359489, - 0.6480963790802657, - 0.5039263486408188, - 0.46119464855181524, - 0.6602032112876555, - 0.5308867579260079, - 0.49898960407065335, - 0.5026555547796746, - 0.4959009310662372, - 0.5373292480348895, - 0.48043112869286114, - 0.4980854252978672, - 0.5532572404052807, - 0.5012150426324772, - 0.6452691445518932, - 0.6227298279479876, - 0.6077843843595065, - 0.5485670230435764, - 0.4410711914731909, - 0.5342295545801204, - 0.484620299827096, - 0.6543436253366806, - 0.5488509076090876, - 0.5085221523081681, - 0.5486411960327727, - 0.5658627644705025, - 0.5673406749968384, - 0.5284811846211239, - 0.6108578983939333, - 0.45537991857327836, - 0.6572832816767984, - 0.48602335736810676, - 0.47429824635620776, - 0.5834079501693352, - 0.4403771495741037, - 0.6049008167399924, - 0.5175447574871777, - 0.6127204971958488, - 0.511893166526707, - 0.621115257905003, - 0.590549800013125, - 0.6102070929861345, - 0.45340243541780917, - 0.5579908360441868, - 0.659927258102413, - 0.5458523357197262, - 0.5605571322070984, - 0.6544204353344795, - 0.6561513170902781, - 0.656083213640741, - 0.4547200131710281, - 0.551853591218566, - 0.5824388649962925, - 0.44727842900188025, - 0.6559848713127586, - 0.650030274140297, - 0.5888321803046863, - 0.5038577253086953, - 0.62380682766385, - 0.5548510622198658, - 0.5590972015104739, - 0.604478764108121, - 0.506670332319051, - 0.5163745256386891, - 0.6437683652732163, - 0.5235118081110188, - 0.6232982828330574, - 0.49082918513791146, - 0.6562590461873462, - 0.6204820266098858, - 0.5133585521819839, - 0.45508312534413414, - 0.5108054776166103, - 0.6063103309705359, - 0.4744482674327513, - 0.5987302374801192, - 0.49383671219409625, - 0.5850626627801379, - 0.4549456661306571, - 0.5838334450560456, - 0.4612510005141441, - 0.45347395134252466, - 0.5010793803957101, - 0.48457285088808555, - 0.5449641581629685, - 0.5935705808133128, - 0.5344966005320435, - 0.5609901512010285, - 0.5227506523191925, - 0.5105022419967638, - 0.6156098482788064, - 0.4839943986252904, - 0.48753151365153125, - 0.5043173146061682, - 0.4566234752820283, - 0.6089341133684718, - 0.514302809423054, - 0.45136441879817263, - 0.5426699266944331, - 0.5738377037454088, - 0.4476194257622068, - 0.529013195070678, - 0.4793925483012868, - 0.5794360758486614, - 0.5846664056045607, - 0.630072137159644, - 0.5192003636968925, - 0.6358461027413439, - 0.6357232979836727, - 0.45422548458231987, - 0.5707260562618128, - 0.5651247898011604, - 0.48313448406153636, - 0.46130281727127176, - 0.4663596633214763, - 0.5509657230594117, - 0.6528291773942925, - 0.49806110069060006, - 0.6584401787519607, - 0.4954553780317167, - 0.531266328827407, - 0.6294951640978386, - 0.4701663726484921, - 0.45451278933399103, - 0.4476734792426804, - 0.5132109787743163, - 0.6480354000166207, - 0.5849872968681107, - 0.5906102384840323, - 0.45462822477341697, - 0.5053569164776324, - 0.6163998105514483, - 0.5195149545473976, - 0.559158693208645, - 0.5678521900604183, - 0.6158299860417198, - 0.4824938199269902, - 0.4706135996756476, - 0.5173596128562277, - 0.6554337455631034, - 0.5020056217692329, - 0.6087771566940664, - 0.525624353117038, - 0.6078036904797095, - 0.6403795512763293, - 0.5531204716844453, - 0.4431076031683427, - 0.5184602227937609, - 0.4856964533487342, - 0.5052602774081829, - 0.5539267308422963, - 0.606958928627126, - 0.4502791669043164, - 0.6299329962931199, - 0.6482061512170076, - 0.45765144309139283, - 0.5633895469513795, - 0.4668303071583017, - 0.48943626872461016, - 0.4739591860878424, - 0.620874611162541, - 0.49905317381263736, - 0.5366829570956647, - 0.6259609339085448, - 0.649834962749509, - 0.4409094218264931, - 0.5200054998826095, - 0.657766377805072, - 0.580171153720205, - 0.5216844016560771, - 0.6448770406679027, - 0.6070440351217641, - 0.5992003675826187, - 0.6322198603960993, - 0.6445419654530551, - 0.4825389652430815, - 0.6026666329330553, - 0.5467268489211372, - 0.48145128520196695, - 0.5783606813524147, - 0.45880072314326636, - 0.440849430615728, - 0.6125259152252689, - 0.5506091151035524, - 0.46534672241902847, - 0.44647461241061326, - 0.5610393543964243, - 0.6436283885683345, - 0.653980660995752, - 0.560384647170865, - 0.48519853000109486, - 0.5409734568657686, - 0.6371973975220144, - 0.6420982180205911, - 0.5272275438821117, - 0.5135076230294281, - 0.5412813344076757, - 0.5028646596500485, - 0.6602103627173849, - 0.49408782958363906, - 0.5467901809872764, - 0.44400962264557625, - 0.4642336441342303, - 0.5614469436532149, - 0.6148691608566188, - 0.6178994743970335, - 0.6001701115817168, - 0.6512745977126109, - 0.5565423829114078, - 0.6230244824851101, - 0.4763780981842214, - 0.4547796460509259, - 0.6357456857830494, - 0.6088350590139342, - 0.59384381240401, - 0.5657781702434156, - 0.5666151446905275, - 0.45623316347236026, - 0.4602109809906714, - 0.4793091298647895, - 0.5304410152254307, - 0.48271633301986194, - 0.5670682320922336, - 0.5983470417569804, - 0.455402095210643, - 0.6240667000018583, - 0.6469968694830509, - 0.6407863072919027, - 0.6516112197115117, - 0.6533833535440211, - 0.6319400936367996, - 0.45888916390399437, - 0.5838181611385844, - 0.5139043466691003, - 0.545032991213096, - 0.5930023471378436, - 0.5980716433046545, - 0.5882785967504065, - 0.5246489689896944, - 0.4606762217738319, - 0.538312282174235, - 0.45085298351285086, - 0.5648784563162933, - 0.6288457079983127, - 0.6518874507156335, - 0.6128619314170431, - 0.6386819677933825, - 0.5994544260798289, - 0.4787022993449153, - 0.6510992932940077, - 0.48581210933400715, - 0.5895172818367502, - 0.637127190925552, - 0.6328991145271539, - 0.5670544091733767, - 0.5761096989070076, - 0.4418298286322434, - 0.4786523833689567, - 0.5164519356051187, - 0.4424567280319428, - 0.5427811497521842, - 0.6082616464798525, - 0.6425706080204155, - 0.6015998624109904, - 0.44186466406558533, - 0.46500728443718875, - 0.4787486574246481, - 0.4927193090284299, - 0.5195772129879508, - 0.6624195935970703, - 0.44165450565630576, - 0.5744204265758505, - 0.6375426841359454, - 0.5769650046556105, - 0.5193811330931977, - 0.5214302787653768, - 0.507266811294021, - 0.466630256555366, - 0.5171351526713941, - 0.6215683597528683, - 0.647981708809198, - 0.542923731052805, - 0.6147243031061349, - 0.655509655334112, - 0.6004544709951205, - 0.6096785908000424, - 0.5617082574157262, - 0.6425910523456395, - 0.4682078127349712, - 0.5944975532782257, - 0.641795308482924, - 0.647024454273252, - 0.6570342603267779, - 0.4530689449250315, - 0.5174991350984213, - 0.5619314074134159, - 0.5392377162652808, - 0.5743608343393791, - 0.661899698208048, - 0.6347464478755767, - 0.5403073939728757, - 0.5509039256083538, - 0.4695086462535613, - 0.5928987082068862, - 0.5354405267699661, - 0.5871436958916201, - 0.5638770787729424, - 0.5713430984677835, - 0.48054972851161465, - 0.6290679392682278, - 0.4782478078728675, - 0.5220423684887253, - 0.5660015275327361, - 0.5319148405247384, - 0.5263916314205485, - 0.4554432926656597, - 0.6613984614494952, - 0.5673794863696144, - 0.5177937605056242, - 0.6272222062826138, - 0.48096447981231705, - 0.5967951732351329, - 0.5939026762188784, - 0.5472139416628178, - 0.5851929633165285, - 0.5760341905490214, - 0.5632292195739835, - 0.600269199105226, - 0.5069321898688987, - 0.5147156610519621, - 0.5672403251391909, - 0.48304101366957886, - 0.636680981862075, - 0.6199444835419128, - 0.6325841579098597, - 0.5594094328695006, - 0.6357488613019424, - 0.46658374011037895, - 0.5684395223247247, - 0.5471685108196138, - 0.4620776777977894, - 0.6125653443740956, - 0.6396866173663095, - 0.5176775213750482, - 0.4541069324595469, - 0.4642380630667161, - 0.4756469617054887, - 0.6248992166093998, - 0.6137247875163022, - 0.5160261953842827, - 0.5439524020794332, - 0.5281839392194863, - 0.5181364130318814, - 0.5084679385635187, - 0.5451648752515763, - 0.5739612627255812, - 0.6066460654003762, - 0.5331499598306815, - 0.46319625675324166, - 0.48521740762825916, - 0.5940901536935365, - 0.5400998091488218, - 0.5235808271790197, - 0.654362979375953, - 0.5107073749030717, - 0.5559636742381051, - 0.469060803023433, - 0.5694341189942012, - 0.6155156857959978, - 0.5810929978196426, - 0.45846886329983877, - 0.5229683692961816, - 0.5226789660611564, - 0.5415769695079619, - 0.5510587242604245, - 0.6045159309229557, - 0.5151349852303287, - 0.5967852109237135, - 0.6195629109923751, - 0.49092088331176037, - 0.45354475855584997, - 0.5257117647577074, - 0.6481001800913444, - 0.45629735237430885, - 0.5362993892938946, - 0.5670152984309351, - 0.5643307345784775, - 0.47093879463749466, - 0.5852278446977282, - 0.5476940536202562, - 0.6214209007187346, - 0.6246554324473409, - 0.4799137103200544, - 0.4529935467729769, - 0.6300843466742793, - 0.47823930403981535, - 0.46107500580059585, - 0.6082296385879375, - 0.46217926329112585, - 0.5097421124947384, - 0.5818678006712544, - 0.4845544906294958, - 0.5804718706736385, - 0.6027783546501776, - 0.5651111468906074, - 0.6277844509766798, - 0.5805152439060823, - 0.45102097809751035, - 0.45046306008115194, - 0.5746632777170653, - 0.5770558854857711, - 0.6558845388406107, - 0.5320160238139364, - 0.6133353575352212, - 0.6213276373967607, - 0.6542546532812508, - 0.4845963956484827, - 0.6548860414491646, - 0.538592546856089, - 0.6630693889776484, - 0.6040140635222491, - 0.6135309422214247, - 0.580068225967308, - 0.5845263854244127, - 0.5096052693271259, - 0.6600841546870828, - 0.6211403263297962, - 0.5215810942194128, - 0.5249723359197244, - 0.5557292942821961, - 0.47399850696102475, - 0.6321615413547238, - 0.5156139701838984, - 0.6020853675045754, - 0.5346984440760153, - 0.5960295863147084, - 0.5906564165341648, - 0.45382071319401257, - 0.44902822882220456, - 0.5653637704427499, - 0.4634444141384257, - 0.46913000424699575, - 0.6556062132631639, - 0.4444357253088923, - 0.4878612959769503, - 0.4601326018905063, - 0.5561906665052043, - 0.5023765533219454, - 0.4797918177063639, - 0.6063264538399342, - 0.6048902893437624, - 0.4751881385774848, - 0.6323056407642552, - 0.6288529135845954, - 0.4850855231336758, - 0.6498359002561654, - 0.6330683931157077, - 0.5594676169550676, - 0.6558735422857936, - 0.6250348110244428, - 0.5061421303881768, - 0.48276750856342127, - 0.6394631781652951, - 0.5062610134238463, - 0.6494726125185997, - 0.5007238052431172, - 0.5867046711629913, - 0.6473988832241105, - 0.629062924903846, - 0.4591960900119295, - 0.4887667923335594, - 0.48905632786779907, - 0.46765320922647174, - 0.46129306009968457, - 0.5452077055518313, - 0.5808722150453007, - 0.4481022840906842, - 0.6325661563220918, - 0.5621399001885377, - 0.5833254147991627, - 0.4994475926083504, - 0.4558109440978301, - 0.5310453809177492, - 0.5954140712954206, - 0.5364725949964514, - 0.5252162182641927, - 0.49605174105575184, - 0.48680244128557004, - 0.633858382848257, - 0.5880685756832397, - 0.6325247823627455, - 0.5903552261956084, - 0.4412552971164392, - 0.6377033028076852, - 0.44051100284481404, - 0.5189778771485404, - 0.5830228031514648, - 0.603971703124002, - 0.6520020661775217, - 0.4751615916382285, - 0.5764365374951732, - 0.5070789076649321, - 0.6157187261461375, - 0.562818079217114, - 0.46135122948884477, - 0.6311835615195656, - 0.5202277915724293, - 0.6604148400343296, - 0.598153188991214, - 0.5783621204104556, - 0.5148320054387332, - 0.6400011985682708, - 0.6611248071851619, - 0.5855309152160098, - 0.5784955993471156, - 0.5908801691137882, - 0.5855600786972665, - 0.5804404635342439, - 0.6202308038449794, - 0.6436322831169088, - 0.5677365020133058, - 0.5723952179073282, - 0.6387725135555039, - 0.5688610570616689, - 0.4655269002969925, - 0.47026094952715103, - 0.48793529357721743, - 0.6385631814142494, - 0.6090118062566627, - 0.47672283994564646, - 0.44429654656194145, - 0.5072172987863357, - 0.49830262904004996, - 0.5427558043939685, - 0.5653515341237689, - 0.5317093327754757, - 0.4901318689194839, - 0.5742018871087593, - 0.5043354827196777, - 0.4410198841830598, - 0.48251017642521593, - 0.6561142122909649, - 0.4838551830690673, - 0.5735801119369076, - 0.5414651590493275, - 0.5748682394471226, - 0.4865949981033042, - 0.5070629112595159, - 0.5137002555834275, - 0.5512232675512174, - 0.46400204998721706, - 0.5259518578354021, - 0.6572306606691584, - 0.4633204039641789, - 0.5039061460665446, - 0.6629523749514681, - 0.661315851905704, - 0.49305121476790337, - 0.5738894595364112, - 0.5749050754883673, - 0.499208380006098, - 0.5319164661811308, - 0.44250246849320624, - 0.5684753280016858, - 0.48792689596953465, - 0.6625688814150315, - 0.5114519936542131, - 0.661019556899547, - 0.5107905615336208, - 0.49835833095149806, - 0.6030861439506308, - 0.6374607267537789, - 0.5229416557917741, - 0.6187658125020379, - 0.6430529999712825, - 0.5640367809702789, - 0.5975513439054756, - 0.4627987142309011, - 0.5917351472739534, - 0.6614548297424638, - 0.5922753425734026, - 0.6275049365859854, - 0.5097605699533989, - 0.5459534343431944, - 0.602933634705015, - 0.66125105611303, - 0.6447247783677491, - 0.5691891084843566, - 0.5580210454267189, - 0.5243078335948529, - 0.5030898668135418, - 0.4709038211243367, - 0.5410351652406133, - 0.511941377187228, - 0.6149228793649737, - 0.45422952626328483, - 0.5366425631278653, - 0.5385320625676169, - 0.5363514245667227, - 0.52608028922982, - 0.582312942561269, - 0.622512774960372, - 0.5176087946401635, - 0.647237943015212, - 0.480084343377193, - 0.4793927731126365, - 0.5451333649268473, - 0.5797831663753645, - 0.6434759722591414, - 0.6372486673260018, - 0.6618891907327141, - 0.5267283683328766, - 0.5651128243126554, - 0.5921951775470526, - 0.6153386044694602, - 0.5878278981110814, - 0.47655422917690626, - 0.6342567054422774, - 0.4736468213136832, - 0.54050436675501, - 0.5067152768128856, - 0.47149456690790814, - 0.5778844102487215, - 0.46255517684474856, - 0.6141791334760152, - 0.46389503628950524, - 0.5628800330155299, - 0.44486452604514587, - 0.591515679317123, - 0.5408924414371395, - 0.5443533869744454, - 0.5454609228532747, - 0.6613667261946548, - 0.5963793993754197, - 0.6292091798603765, - 0.656402665503931, - 0.44789122322082153, - 0.5567719031357828, - 0.5697304945076305, - 0.4936408751683292, - 0.6524379281056092, - 0.5276203717595562, - 0.5830102964756902, - 0.48258802910602744, - 0.6049688337954138, - 0.6242148789583893, - 0.5344825306433154, - 0.46147457024776484, - 0.549279861572526, - 0.626115215799149, - 0.5765714396077777, - 0.603775689170384, - 0.5316136366071892, - 0.5744250393837361, - 0.5365978145419047, - 0.5898600641597395, - 0.6537953578535443, - 0.6125737307645818, - 0.606781512343515, - 0.5379481740669403, - 0.5166758910047837, - 0.48724756048469897, - 0.5952878133178541, - 0.5051169105537862, - 0.612286563888966, - 0.5124224661684611, - 0.533874404448397, - 0.4657065872938351, - 0.596519221115591, - 0.516451756415182, - 0.49142548472243897, - 0.5710670473622114, - 0.650373429927166, - 0.4609151747901368, - 0.5932869125996934, - 0.6578585809987704, - 0.5710324484801889, - 0.4977916340571564, - 0.5494036682714517, - 0.5335856058822706, - 0.5332363891898495, - 0.6419471451310421, - 0.5905225172360283, - 0.6189834624372395, - 0.6429282151366019, - 0.4648705931817338, - 0.4502387823728122, - 0.5214573165678819, - 0.6315379748247014, - 0.45264483129833566, - 0.4928953950519291, - 0.5224823675949615, - 0.5404922085273672, - 0.4944266886074341, - 0.5207051482013256, - 0.560772290698775, - 0.5436508766539484, - 0.4881722901603142, - 0.5527112966258244, - 0.5177671758320254, - 0.5946428876314663, - 0.5938811885150271, - 0.48637450281803263, - 0.5536062009312114, - 0.48585645204871447, - 0.5814070639799787, - 0.5386558216654445, - 0.6371140031375921, - 0.5485171851304155, - 0.6193364723264174, - 0.5060645838808097, - 0.6544143171255272, - 0.5790360756435216, - 0.6443265571557864, - 0.53578054300436, - 0.568643614508813, - 0.5416236903494775, - 0.4685956367080625, - 0.5119818723027355, - 0.6224868768354261, - 0.46073792697852706, - 0.46848864141114177, - 0.5338850250341416, - 0.4883879063615012, - 0.4645684899136797, - 0.5853332053296874, - 0.6521802181224414, - 0.5308117574572698, - 0.49488592143883675, - 0.45409501934835916, - 0.6528681079675999, - 0.6030493015935778, - 0.6107375775969428, - 0.5197949992789009, - 0.617793962472035, - 0.44652925671896454, - 0.47551483626191327, - 0.5615461557877105, - 0.5690840909566475, - 0.5723733152503158, - 0.6621522983476402, - 0.6352790756218946, - 0.5739389777361676, - 0.6342754992944779, - 0.5671663843659809, - 0.5775070292578922, - 0.5228244418338164, - 0.5546849321409015, - 0.6361805102596221, - 0.6405905104536298, - 0.6462493897454781, - 0.5288032465247304, - 0.6458590785840647, - 0.5715693385406039, - 0.5839561276988029, - 0.49133334393357225, - 0.46988945312511543, - 0.4914593809375865, - 0.6102928299007527, - 0.5668166085785759, - 0.562168290579512, - 0.5891589661922534, - 0.5129965699397484, - 0.5598081098072141, - 0.6627154445451214, - 0.5608084377087084, - 0.6152771896539693, - 0.48164617849555, - 0.5336264187066465, - 0.5818928478135942, - 0.6007462482107707, - 0.4783700487045091, - 0.47373771876548454, - 0.5626566817833839, - 0.5162153308178679, - 0.5797657297808009, - 0.4605993023104847, - 0.5086414337399571, - 0.51298243428798, - 0.621254259910546, - 0.6611145733120302, - 0.5215276316542885, - 0.5389733577686314, - 0.5911896787401294, - 0.4618765681873196, - 0.46752059246987937, - 0.5643080489820481, - 0.6220497624160777, - 0.5137667520536466, - 0.5071787073747709, - 0.4564189388262528, - 0.45996374152531005, - 0.4527963910294846, - 0.5411298482817113, - 0.4663850707811351, - 0.588737145288359, - 0.4568199051852399, - 0.6077992502158993, - 0.5733261212404059, - 0.5736842992606543, - 0.4624960284999269, - 0.642172893588695, - 0.44946699598368106, - 0.46599441046652545, - 0.5450496766240644, - 0.6225475173408443, - 0.6557915641481267, - 0.44560956846420513, - 0.5230914354272375, - 0.6328379464094734, - 0.5985049675682865, - 0.49090857897056955, - 0.5676333397500618, - 0.6071794099442095, - 0.5062690501587317, - 0.4687593402693735, - 0.5845366681914945, - 0.45158340384418877, - 0.5918388766495675, - 0.5129446751333335, - 0.5757994483368793, - 0.49790149679412565, - 0.4597786882450119, - 0.64541938820969, - 0.4952151201976618, - 0.5866405216565903, - 0.5101568047646915, - 0.589438810492763, - 0.47892983949371304, - 0.4530856928650305, - 0.46380203066437836, - 0.5265161565217664, - 0.5423658284656355, - 0.5882331315002318, - 0.5468243214993546, - 0.6318662337996335, - 0.5518845495468349, - 0.5180386517144263, - 0.6604635297834276, - 0.5450497336323765, - 0.5833098416850572, - 0.5293667390510404, - 0.6297314881094571, - 0.5405750119958725, - 0.4924530721843322, - 0.47743282745927684, - 0.635728064873122, - 0.4518836369596041, - 0.5618297020679751, - 0.447633595606244, - 0.5795072330210478, - 0.6173227215789759, - 0.5279200607841191, - 0.48320899989854915, - 0.6374518640272036, - 0.5543471869820374, - 0.5257047270101608, - 0.5170014761140584, - 0.5162372640015471, - 0.4802059204717278, - 0.5799769954089931, - 0.47208638041901035, - 0.6152940082014116, - 0.6477030557909423, - 0.48600714479751683, - 0.5847955006814404, - 0.5705455705783334, - 0.4774182578570689, - 0.5280905429622818, - 0.5847038575800094, - 0.4654946532122812, - 0.5965548186333411, - 0.44727891115364377, - 0.5066285133633229, - 0.5094812072722323, - 0.4907875239461229, - 0.6630004013564228, - 0.6107931837537192, - 0.4470303151119168, - 0.6553289384147221, - 0.48154330948953705, - 0.5109063839895849, - 0.6191629597549515, - 0.6344072560112016, - 0.5490494484904718, - 0.6437246977823571, - 0.4640117482256221, - 0.46713594022399646, - 0.4711077864352812, - 0.6034901821685688, - 0.46659164439827394, - 0.6212814440752833, - 0.48313970248470384, - 0.5392598134320163, - 0.6196572371542486, - 0.6052696403162995, - 0.6490814844912799, - 0.6324345576280335, - 0.5451030707818959, - 0.6398688382657369, - 0.5905999252647394, - 0.5420881208935937, - 0.49521161289595494, - 0.4423300033995132, - 0.45872680841821417, - 0.491366233907669, - 0.4611180663838801, - 0.5441636716382939, - 0.5795265796485288, - 0.609248192763629, - 0.5093649571692975, - 0.4584403753208447, - 0.6139625431971638, - 0.5529524960135062, - 0.5783248090807025, - 0.6446807241616371, - 0.4887397880672523, - 0.6264396717965408, - 0.45377087062106564, - 0.6171576240251606, - 0.5232190810460352, - 0.583393763694933, - 0.47272593361211507, - 0.6470323036981246, - 0.5633853119820394, - 0.622881640205239, - 0.5950547418122702, - 0.5423709558514926, - 0.5239135377919436, - 0.5492275486353166, - 0.6575526355073653, - 0.510472441452732, - 0.4445682461510064, - 0.5350510229343044, - 0.6444885257593718, - 0.595573142979184, - 0.5735995246448302, - 0.6219572066392471, - 0.6496848028680846, - 0.6593419018388134, - 0.5315643796083035, - 0.5927984144786713, - 0.5463298270929748, - 0.6089914778400026, - 0.6124493933559263, - 0.4590786871435691, - 0.5974749151724774, - 0.5767609580778283, - 0.5279124388432257, - 0.592884405271666, - 0.4471496292271653, - 0.5965236730798473, - 0.44975166253017074, - 0.6112755466821064, - 0.5522601635584856, - 0.5919760307196884, - 0.6405264411088, - 0.5694469976982259, - 0.5419252415616576, - 0.5708846128180357, - 0.5146939403738285, - 0.6220218318525398, - 0.6371780576465078, - 0.5937887551728463, - 0.560245088077235, - 0.593034490154041, - 0.5206360288586488, - 0.6468918462277442, - 0.5689976105000591, - 0.5641680751047967, - 0.6482179775708792, - 0.5855824955765643, - 0.5560693640402147, - 0.5296251871393013, - 0.5761576135589073, - 0.6307657709045413, - 0.6441441159884069, - 0.5921190784294292, - 0.49240251091558446, - 0.5981045271853277, - 0.5265146150737515, - 0.6194283333033443, - 0.5356333288363961, - 0.5025679793757448, - 0.4726632281740474, - 0.4422887404725629, - 0.4673911585777075, - 0.6131439016647235, - 0.5226309585066504, - 0.6400727591242701, - 0.5656420829009082, - 0.6063379442264413, - 0.5823855152650018, - 0.5736331539073558, - 0.5841439665293211, - 0.5158213801529613, - 0.44410255818965316, - 0.5552858886864318, - 0.6096111535950959, - 0.6305484334911977, - 0.6166365754806213, - 0.5367972043939236, - 0.5280390915794005, - 0.4917002402124853, - 0.6554308918026238, - 0.5270829600896932, - 0.5915740607772215, - 0.5101985858450836, - 0.47636545938372515, - 0.45578157671571223, - 0.6339013710002354, - 0.5694046510756335, - 0.5353541857896266, - 0.6252438268502594, - 0.5760974212348409, - 0.529640434377717, - 0.597007207154925, - 0.6595150492357988, - 0.6197231801892785, - 0.5415796543353106, - 0.5688731903674952, - 0.5004459598983578, - 0.6274863400708898, - 0.48468017400916147, - 0.4796398056850334, - 0.5590969843067648, - 0.5263898920183112, - 0.5026499476171926, - 0.49187096930705587, - 0.5953325530177285, - 0.5010294787378323, - 0.4802479839226425, - 0.5512106742972323, - 0.5204647916973749, - 0.549509681661157, - 0.5804658226033317, - 0.5259514413612058, - 0.5380127702660731, - 0.5823509771216702, - 0.6485356519869048, - 0.5636437097800002, - 0.6498369101288373, - 0.5763847577111025, - 0.5204148785752255, - 0.44369659088835234, - 0.6544385900167123, - 0.5899516946901628, - 0.4778545600047648, - 0.47525710372523217, - 0.6063591314277964, - 0.5422010700124389, - 0.491454289403681, - 0.634404138423917, - 0.532275440541597, - 0.6315614270861067, - 0.46038409563319327, - 0.5594911485274211, - 0.5263967917294945, - 0.4746575216226371, - 0.47532639041949265, - 0.5469245970110151, - 0.549459488078008, - 0.47325830516558093, - 0.5892196436737562, - 0.6369768631956112, - 0.5352329268554391, - 0.6573306435115699, - 0.6283824229400751, - 0.5223379354126755, - 0.4993976521999684, - 0.49415337801190734, - 0.47218644639386675, - 0.6257249242964915, - 0.4485524183948477, - 0.5479712414393609, - 0.5987246351951313, - 0.5399357515135761, - 0.484431095172232, - 0.5560158833212305, - 0.4854922231896715, - 0.5555115137813609, - 0.4618995054798819, - 0.4752606387539206, - 0.5908901295807387, - 0.5932524488612914, - 0.5759919974289607, - 0.5557290857418079, - 0.4924200735891474, - 0.44157625528115524, - 0.6152409107509031, - 0.45992693792451406, - 0.6402702636295917, - 0.6033393433026081, - 0.6172155891431319, - 0.49911366205352087, - 0.5895204414390645, - 0.629698441103386, - 0.5951074853371419, - 0.5311156555865789, - 0.61206411856271, - 0.579954543602695, - 0.5103917850345905, - 0.6198164430495239, - 0.5489638527402142, - 0.4436362867768971, - 0.6524406363354298, - 0.5374507486228752, - 0.4546184573143441, - 0.5777639295659301, - 0.6030173451643548, - 0.5673312608913869, - 0.5917137080560041, - 0.504850718422277, - 0.5045487993434375, - 0.5695153800308608, - 0.6131964779641121, - 0.5955099125734425, - 0.5382873867947946, - 0.44893140793408, - 0.6627416656740861, - 0.6282656646670481, - 0.46821031463113816, - 0.6057380703226926, - 0.6482134885971091, - 0.4663717159705027, - 0.45779924347950973, - 0.5444999452928938, - 0.5417995113317696, - 0.5932670243424576, - 0.5514542609784188, - 0.498979372976281, - 0.5658525753267639, - 0.5139123928024829, - 0.6420711741613182, - 0.45827770316306515, - 0.5283765912964754, - 0.5829326004443689, - 0.562158490909068, - 0.5603911532503824, - 0.6131178443700257, - 0.6464623647942829, - 0.47427759605845954, - 0.5700978002693623, - 0.4742591811792927, - 0.5280971824512306, - 0.5715306438971319, - 0.6607805942233611, - 0.5951228312099706, - 0.45523537131852065, - 0.5271059874866768, - 0.47852952513576963, - 0.49684007550870063, - 0.44075940052000456, - 0.4931827309043814, - 0.4609262116178457, - 0.5295721529587214, - 0.4910306220897516, - 0.5495846983170736, - 0.6017488001875654, - 0.5660786543942764, - 0.48286848950510375, - 0.6106039343795643, - 0.5871417750741138, - 0.5905552601784935, - 0.4759677767335193, - 0.5502879531952424, - 0.44124800391566105, - 0.5181161344891103, - 0.4769790369021981, - 0.5034351850639527, - 0.47398433097387804, - 0.5047751430729752, - 0.6033911248732726, - 0.5838404222410155, - 0.49069097748221135, - 0.49643228731691047, - 0.4983960790512128, - 0.6039367806558154, - 0.5263973469103135, - 0.6170675257603335, - 0.4465549281412054, - 0.6488353282499527, - 0.6402171729636037, - 0.5925041943796093, - 0.5396052150815809, - 0.6340898188718463, - 0.6522930560591196, - 0.6432547990487465, - 0.6310625624404811, - 0.5705512807914708, - 0.5782577678375276, - 0.6287030310150256, - 0.47800431528091764, - 0.4671679128662468, - 0.598035534743157, - 0.6108645742935928, - 0.45604877066553, - 0.6157728564772569, - 0.5554833218423358, - 0.5687715171706538, - 0.6261196127845134, - 0.4863213288987924, - 0.48555658593853007, - 0.5998751001205475, - 0.5960838517717643, - 0.4914301258833425, - 0.4841269014498236, - 0.6224141640460443, - 0.650935306113029, - 0.5392214960694902, - 0.6116030351762977, - 0.5992808186068687, - 0.6268220627256134, - 0.4900886039022405, - 0.5512882177212071, - 0.4965751886147183, - 0.5051332663090943, - 0.6196515769776535, - 0.5675735113569549, - 0.5602269929730872, - 0.5684329401048633, - 0.6241154252625922, - 0.59060401748968, - 0.5958513220600758, - 0.5252688190940605, - 0.4815715629495454, - 0.5450184528013915, - 0.5839396495483783, - 0.5144580207285758, - 0.4795102549389405, - 0.5500961022922686, - 0.4777102126448724, - 0.6106425012839043, - 0.50385867051939, - 0.6178047380041978, - 0.5204250780870274, - 0.6438817863748303, - 0.5798740540898724, - 0.6410861781677828, - 0.4925718304064529, - 0.6043592449688995, - 0.6224196647266205, - 0.5899407271366337, - 0.4871012636644787, - 0.6115637457308909, - 0.5355333663333504, - 0.5459955642320808, - 0.4548210281254913, - 0.4668174649392271, - 0.5755687488430193, - 0.45957538650544005, - 0.6272955122539615, - 0.6182445163210737, - 0.5155358365434146, - 0.5469407170429106, - 0.45083072689478837, - 0.5213981672929938, - 0.5441147558626797, - 0.44230448172902126, - 0.44198480303079385, - 0.5913217972468479, - 0.5541281189696381, - 0.483267782978438, - 0.5615881149493298, - 0.6272425830053541, - 0.6237397769772729, - 0.6065377505139147, - 0.5968679122297349, - 0.5486371938099007, - 0.6460841749849702, - 0.5892187377357053, - 0.6562242614873901, - 0.5335836027228262, - 0.5202691548757744, - 0.566739089915941, - 0.6080759794580755, - 0.6572615969721993, - 0.6217576702629706, - 0.6513874192748924, - 0.5025489428189885, - 0.4962516455633073, - 0.5647415734313436, - 0.5672596362873215, - 0.45585805894868275, - 0.5923657759423293, - 0.5967276189183864, - 0.4736283637269939, - 0.6619550466557595, - 0.5045146243860151, - 0.5218002545013155, - 0.644946269367848, - 0.5742958493153111, - 0.4959338227438429, - 0.6444375522898889, - 0.48168876187893805, - 0.5975822796900339, - 0.5040392358085382, - 0.580521721261853, - 0.6568954565614262, - 0.4996946339686394, - 0.5486349375784707, - 0.5040831238159268, - 0.5081296184020507, - 0.5846141918122287, - 0.4883775397853155, - 0.4654172645190959, - 0.4566086662894613, - 0.4439228268014822, - 0.6151855653268015, - 0.6029194533757709, - 0.5912969871002439, - 0.4992546756347684, - 0.6532455462725439, - 0.5309685285257727, - 0.6057209451725882, - 0.6337869167261997, - 0.6296690388296212, - 0.5659281671723434, - 0.526212578301812, - 0.6358361681031579, - 0.5242244408865967, - 0.5159134811461762, - 0.5424646544257996, - 0.49939822876154094, - 0.5728881472573404, - 0.5269638720408611, - 0.45635618477351786, - 0.5206554765360614, - 0.6246080445335515, - 0.6555762666500689, - 0.6303272566999542, - 0.6122645802286093, - 0.5770156679324062, - 0.543850720176267, - 0.4830569219472776, - 0.5956959714845421, - 0.5813148593320332, - 0.5008505145752997, - 0.5878814099122175, - 0.6269890066616665, - 0.5141769647198211, - 0.6021714373324348, - 0.45261561632405894, - 0.6512389566190696, - 0.5940645491906182, - 0.5682165152356994, - 0.658853118945776, - 0.47513410017297025, - 0.5640706325258198, - 0.6444329864791787, - 0.4441101279266843, - 0.5301669396115938, - 0.6292551018930491, - 0.5790230009628275, - 0.5468233791775257, - 0.46408824785027797, - 0.45166692432733707, - 0.4432649432401232, - 0.5358003267379892, - 0.6004317584470789, - 0.44283726632437953, - 0.6220759660782722, - 0.46037960580946613, - 0.6415417998116074, - 0.5122638881228853, - 0.647088199391292, - 0.47258544724208706, - 0.6114480983589075, - 0.5042211840344232, - 0.46387684531898543, - 0.4683790023707964, - 0.6537408151001834, - 0.4718130109490031, - 0.4991568779591651, - 0.4942913599582826, - 0.6583758390833363, - 0.658979553064881, - 0.6018763655783078, - 0.588881159001478, - 0.603522666789551, - 0.5817272008425913, - 0.44454147519384946, - 0.6144323791897065, - 0.605883068756049, - 0.518452031236688, - 0.6528305972314489, - 0.44999005324910013, - 0.44311933494997097, - 0.4770140795341103, - 0.5788431424019036, - 0.5151074538159648, - 0.632042157400355, - 0.6080453896075653, - 0.4665401230052134, - 0.5315616287100452, - 0.5339621508532416, - 0.5602499202327745, - 0.49271791048663044, - 0.5254132138481367, - 0.5971412296566359, - 0.6214831363226837, - 0.5337434374221849, - 0.6402533762408551, - 0.5712892818494857, - 0.49022057184571605, - 0.46940380990458175, - 0.5570674883985869, - 0.5337682639522661, - 0.5453327067337047, - 0.5524417758705297, - 0.6480183112209046, - 0.4802558521274828, - 0.49519838027580854, - 0.4405453356340962, - 0.5444165025759315, - 0.4811088719956291, - 0.5348845653757933, - 0.46345020382256225, - 0.45493415971784085, - 0.62893126867925, - 0.6449102725359779, - 0.5687886015601502, - 0.4412226960282998, - 0.539455806404417, - 0.5552709341992711, - 0.4583666871848123, - 0.5540846409656824, - 0.6272416338105251, - 0.5023617000498979, - 0.5533111472369594, - 0.47507681451809575, - 0.4682252435571955, - 0.6556105416082475, - 0.5444999336090008, - 0.5065894767831122, - 0.5239194663990885, - 0.6420171788678706, - 0.6263341439967567, - 0.47628097480476694, - 0.47918727354314805, - 0.46841000936108407, - 0.5084785713761769, - 0.6404906288522201, - 0.6285546983591839, - 0.5314779245075554, - 0.49348865058215435, - 0.6034754917484064, - 0.6024349697559951, - 0.5609057745387657, - 0.52971588102951, - 0.576305424856531, - 0.5864004740174408, - 0.6594995296796766, - 0.612035179205245, - 0.6233465584588511, - 0.5704456361324032, - 0.5330760088124564, - 0.516274016305236, - 0.6006801305611391, - 0.46637767321315343, - 0.5665214666931209, - 0.4894139372590041, - 0.4797273840349814, - 0.649044626868058, - 0.590203616039256, - 0.5257425165079348, - 0.5688170691776, - 0.5151476180647182, - 0.6197160634803975, - 0.6323953042112546, - 0.5459218685288358, - 0.4485688405533153, - 0.4969762821034176, - 0.60045456831404, - 0.5919379026842253, - 0.6165783562687849, - 0.6318935796951656, - 0.4664911650870921, - 0.5947921298435035, - 0.5226671153051496, - 0.6146185811206382, - 0.6487562351074109, - 0.6262595197017742, - 0.456973526994908, - 0.597694451102209, - 0.5138625014337165, - 0.6018169162206719, - 0.582829788929152, - 0.6294668716240636, - 0.5518472866221459, - 0.5841749096795126, - 0.650542708701191, - 0.5131571263836645, - 0.5063167710256521, - 0.5768061407512677, - 0.6406806299304084, - 0.5865626826119303, - 0.6436253604480281, - 0.44042750277195586, - 0.5378251404171261, - 0.45676946644006283, - 0.6007943886988956, - 0.6097418180188833, - 0.5067746938406766, - 0.5969585471986976, - 0.5841008609832814, - 0.5338830097048338, - 0.5124296266207745, - 0.6554959049797292, - 0.5996396081422544, - 0.5051878190259123, - 0.6289299076384158, - 0.44388175891215975, - 0.5221919734147621, - 0.5789782972048172, - 0.6222895899657475, - 0.5681464945845147, - 0.5079171818453359, - 0.6020252575250682, - 0.5437207211236403, - 0.46382532008763044, - 0.6334174972764904, - 0.5205129612499428, - 0.6412998597076712, - 0.4801123759184433, - 0.5345158562200776, - 0.5626284560944269, - 0.5777141599082698, - 0.5467803056768954, - 0.5350418646949517, - 0.6626905166024751, - 0.46107004644293414, - 0.5204048791055695, - 0.4990115876058973, - 0.46676759759140735, - 0.5125305204143282, - 0.5343163856600126, - 0.4628429290992125, - 0.6606017062451137, - 0.49569985041647185, - 0.603770105778569, - 0.44784024121802374, - 0.5831230841504125, - 0.4441579959308629, - 0.5415557185316072, - 0.49846008678487475, - 0.486112544656727, - 0.5177383617681899, - 0.505484287003496, - 0.5086826630344325, - 0.5851441798671196, - 0.6244722997378519, - 0.6211620333628405, - 0.6089495699670673, - 0.5525334662234563, - 0.5427615258411588, - 0.5342321970706494, - 0.47621653302948563, - 0.655138145564674, - 0.4821136515844728, - 0.5708734405679023, - 0.6122894084564448, - 0.6580462841587617, - 0.483817395049366, - 0.5622627945471949, - 0.6422942204870988, - 0.5802033005396019, - 0.5007484342940474, - 0.48148344100782503, - 0.5348023789904648, - 0.5386071406721472, - 0.6429804862885135, - 0.5219711854924349, - 0.5385257618205667, - 0.4766161233721402, - 0.6474852712430456, - 0.5643789822107229, - 0.4713506609827226, - 0.5382668763763581, - 0.6529339386031496, - 0.6028143324066415, - 0.6446716701415232, - 0.6244983199185179, - 0.5752181095817759, - 0.5593088634233236, - 0.4456333415245058, - 0.4821505807859139, - 0.5369074716730385, - 0.47459699924816734, - 0.5343559738679361, - 0.5677445605522174, - 0.6603994213843654, - 0.5289525230819249, - 0.5064724469849655, - 0.6471005287091863, - 0.5634139187862995, - 0.6046441241189668, - 0.5695862009376401, - 0.5644778001711926, - 0.5037407435873807, - 0.5397915099267734, - 0.6286486663008016, - 0.537870794478115, - 0.4717454054538763, - 0.5036253660459813, - 0.6253715351784906, - 0.497905470987521, - 0.5699710102495075, - 0.5335659137767805, - 0.5233495103777505, - 0.5784089253845907, - 0.5141583785850722, - 0.561193992362913, - 0.6591227436319621, - 0.5457559499819828, - 0.6462580310711963, - 0.6091701094571749, - 0.5062781444019873, - 0.47676310376523445, - 0.5545309001823433, - 0.6210062869023867, - 0.5446037214980778, - 0.5309898693288063, - 0.6606758819323166, - 0.6469078743726004, - 0.4728739581570522, - 0.5700501448718095, - 0.6466262061483994, - 0.46964333270570435, - 0.5065987188193997, - 0.5228321279265609, - 0.5843477551683605, - 0.5040370056047073, - 0.6398391568534983, - 0.6305385723178303, - 0.5943092567930266, - 0.6438830540154532, - 0.6215625541570944, - 0.5392629159135656, - 0.5474983444690628, - 0.6537695482365408, - 0.5845585615681514, - 0.45409812377346936, - 0.6042094341260486, - 0.6414609638454367, - 0.5108425066584653, - 0.6480904352188939, - 0.5921596825774829, - 0.5175963537192374, - 0.6116991884715421, - 0.4779515151660467, - 0.44938761585110987, - 0.462911110192633, - 0.4563080106243879, - 0.48107252277083473, - 0.5362619828862096, - 0.5229044831222576, - 0.5239611251766856, - 0.47885636501767576, - 0.533763458666634, - 0.46215761352924145, - 0.546760071854423, - 0.5211531578603885, - 0.450746464492405, - 0.45067767673575027, - 0.44705425673154786, - 0.48603282259070396, - 0.44002841461609266, - 0.526598414033105, - 0.5502207369446479, - 0.5135731123233551, - 0.5296051364904825, - 0.45745140209722496, - 0.5368671153929743, - 0.4625893585981875, - 0.5121653815522942, - 0.497761468988845, - 0.4459132115143539, - 0.4998924636236082, - 0.5175405332059352, - 0.44965503334915047, - 0.46650458969208153, - 0.4790284368427222, - 0.45994162081196005, - 0.447783579747223, - 0.49992704188433507, - 0.4590385848580455, - 0.5210296431070495, - 0.5463085263756771, - 0.5108878122376033, - 0.48748512062063165, - 0.5253554628242325, - 0.5192354268503, - 0.5147806619318216, - 0.521451339765208, - 0.44166244692086193, - 0.5083067493631628, - 0.534945907008597, - 0.4646270370329289, - 0.46192639615663694, - 0.5015122314725056, - 0.48374928124569205, - 0.5377155259587866, - 0.4974930783234369, - 0.5475234350258965, - 0.4566305227893087, - 0.48078503003838075, - 0.5453099344011437, - 0.5218338110335202, - 0.4806423964177092, - 0.4889315667330145, - 0.4405370028020923, - 0.5480480025571413, - 0.5472566047292625, - 0.4788238363330264, - 0.4714556534545457, - 0.5003897993665635, - 0.44481630332575095, - 0.48426282405171883, - 0.5000478764235377, - 0.46759782133763383, - 0.4910699837696759, - 0.5443905676531134, - 0.5022186307827335, - 0.48684406880916087, - 0.5313672263696252, - 0.48984055428177875, - 0.4788386975058849, - 0.5025616431445954, - 0.517504191548617, - 0.4997002797852144, - 0.4682657557772974, - 0.5031624741380548, - 0.4460935714067617, - 0.5443728372032599, - 0.4924426801193217, - 0.45818347882487204, - 0.5473740539600478, - 0.4572557404910296, - 0.46226059067816216, - 0.5098914244967012, - 0.4899412212271815, - 0.5403879262632095, - 0.5257640624652672, - 0.4923361336458026, - 0.4707073620192267, - 0.45492848445895084, - 0.5020841210964045, - 0.449124392881784, - 0.5299673027289001, - 0.485901484530853, - 0.5191658634088191, - 0.5481914444254975, - 0.5402121602626762, - 0.4909649323074542, - 0.4431710040228994, - 0.518409182311388, - 0.5246677491818067, - 0.5508824248364158, - 0.5259076306113466, - 0.4421046208219581, - 0.5390650255115803, - 0.5345603519848843, - 0.4982715856794865, - 0.4946764590250501, - 0.5079329120778403, - 0.48652752190969484, - 0.5007504112032415, - 0.5220843135700487, - 0.47346414313809426, - 0.5279936278525559, - 0.5464299633887214, - 0.5007980579763358, - 0.5217469873686531, - 0.48645631818746016, - 0.5093200395018589, - 0.5095694325275899, - 0.4565512949422361, - 0.4941260295151863, - 0.5435101222924519, - 0.49930779542220843, - 0.5297491017566093, - 0.5320265676845953, - 0.5263503087661392, - 0.5002926083339357, - 0.5175322163633126, - 0.49533391234937474, - 0.46178708799484847, - 0.48242291650151964, - 0.5363325252811623, - 0.5467678445025547, - 0.5073155983594969, - 0.5303521353436152, - 0.4840950640279553, - 0.46658382780549873, - 0.4629987292665493, - 0.4862672938388731, - 0.5355278554088189, - 0.5323737491686743, - 0.4993197635327316, - 0.5146321071141229, - 0.4563442394196472, - 0.517517612960158, - 0.4536132988918578, - 0.5026677128630891, - 0.45122285261963363, - 0.5339645888631674, - 0.44350036916156144, - 0.4535705778811892, - 0.5004441386574914, - 0.5021481839107926, - 0.5032747209723456, - 0.4471294108126076, - 0.504936298390065, - 0.5495164647342335, - 0.4925325947809809, - 0.5408292886745945, - 0.4572410730997889, - 0.4809202661070691, - 0.45726053513083503, - 0.5391645535593442, - 0.5219773305015949, - 0.4721770496214336, - 0.47323964763579845, - 0.46511035322515254, - 0.4583667518697029, - 0.47711113840334185, - 0.4670405706560235, - 0.5107063710838278, - 0.5444969818433723, - 0.5433954920026887, - 0.5437530373087541, - 0.5029742686909884, - 0.4908900535782552, - 0.5505550677267828, - 0.49058741411092555, - 0.5403517628392998, - 0.49792039503951685, - 0.46797813479441863, - 0.4424283173514819, - 0.5299969370250625, - 0.47977680048802906, - 0.46174868101946814, - 0.45807211226989686, - 0.48522751411735077, - 0.47465793970031994, - 0.548997797022595, - 0.45168037674426764, - 0.5231327580225373, - 0.552578199872215, - 0.5506113044810136, - 0.4605386313208377, - 0.5328140039878324, - 0.5369471100026542, - 0.5122201654792792, - 0.4428008844367746, - 0.48169414586530374, - 0.48196597853446943, - 0.5511886685469572, - 0.46599573196954985, - 0.4912121853392228, - 0.46929916424859774, - 0.5442116340800611, - 0.4435064662033388, - 0.4778789923213032, - 0.4823025879948802, - 0.512387955100536, - 0.5036108023584304, - 0.5422217812818584, - 0.550316721058889, - 0.4531273282675673, - 0.4820368921438827, - 0.5446916432698791, - 0.4401583829498117, - 0.5202797983337846, - 0.46721826911559466, - 0.4818513525198108, - 0.502295880247652, - 0.5261856037653357, - 0.5099702893609099, - 0.5417046562360849, - 0.46025247347428955, - 0.5322746805695373, - 0.5271248695125625, - 0.5300790746415558, - 0.46595248313638815, - 0.4978458605683531, - 0.455039972858799, - 0.49538910626266547, - 0.5490159373692401, - 0.5123631962573527, - 0.4558917504977572, - 0.5035802817995109, - 0.4520026037519931, - 0.5509629997596902, - 0.546340800228662, - 0.48553634701300663, - 0.4403797581724139, - 0.45408328440454626, - 0.5527290750513354, - 0.4664234663862078, - 0.47828958662202464, - 0.5388653404409051, - 0.5272276680998217, - 0.525204169396334, - 0.46332163889139305, - 0.44835569555221944, - 0.47241775118786694, - 0.5042288258559819, - 0.4619781469531728, - 0.49526908720160834, - 0.507677128624789, - 0.4986285514285781, - 0.5379345404802417, - 0.5025613734036029, - 0.5067057044579115, - 0.45393540636926705, - 0.5219736471694149, - 0.4889623126061655, - 0.4542574842854277, - 0.48092409095456207, - 0.5363391457934567, - 0.44943474537600603, - 0.44740464140633057, - 0.47189563372753923, - 0.47953038126468944, - 0.5461312436913969, - 0.4698664990845312, - 0.4709006521051946, - 0.5185331397990933, - 0.44131257446710753, - 0.55324372802346, - 0.5166050519150517, - 0.4951112657248874, - 0.5145927680224582, - 0.5331498489426274, - 0.5349951268444707, - 0.5200794986358326, - 0.5414697069925833, - 0.5353456737504952, - 0.5510913030346523, - 0.44654638925719403, - 0.5029706319942161, - 0.4753285025592933, - 0.4403563209137715, - 0.4602890594657261, - 0.4935202676503201, - 0.47084637640303495, - 0.481758419388865, - 0.5477451170677488, - 0.5192010137273964, - 0.48270861949888144, - 0.44538264190523824, - 0.4840813606998736, - 0.453808328771069, - 0.5073067331863319, - 0.48743097733343693, - 0.46723248912006704, - 0.5068642240681684, - 0.4933743823924902, - 0.44168776766835655, - 0.5355165793476518, - 0.4651107542696686, - 0.4535172007902023, - 0.5048392187352013, - 0.5300512719364976, - 0.4590951499137685, - 0.5235430422894845, - 0.5016322629829356, - 0.47850976821845076, - 0.4825889161797091, - 0.5417545228889756, - 0.5020463159359633, - 0.4733512165347729, - 0.4788751427992347, - 0.5079570619372276, - 0.45557344420623086, - 0.49860482441927484, - 0.47853333136469695, - 0.4630444627274992, - 0.46789544451492715, - 0.4728896915125145, - 0.4968147713813522, - 0.4989623214999106, - 0.5459362648040386, - 0.514194916049787, - 0.4794434026629243, - 0.5168859615181041, - 0.5302714944190517, - 0.4815273178862476, - 0.5509836671832962, - 0.47776278028442143, - 0.4457307928862806, - 0.5335787285642646, - 0.5525586912960719, - 0.4951647960223211, - 0.4489057645942433, - 0.5020612662328023, - 0.5422018989471856, - 0.4673091075809664, - 0.526502069960038, - 0.5364601489781403, - 0.47671054812538793, - 0.541234087972872, - 0.4896628937640873, - 0.449105102168695, - 0.4469436080644785, - 0.4475025926073451, - 0.4730425554780745, - 0.5077794179386329, - 0.5427742310489462, - 0.5457772546519686, - 0.4621533127948775, - 0.4788745542573978, - 0.49769017840479346, - 0.5015376517318516, - 0.5217942168692028, - 0.4967834453543757, - 0.45185068499539294, - 0.4591440159041572, - 0.5235841169392541, - 0.5063764015731761, - 0.522670153635166, - 0.5374619266511503, - 0.45174962577158106, - 0.4455650207175721, - 0.4721540662099931, - 0.5105521446167013, - 0.47628163480603825, - 0.5383533577407129, - 0.4671001818941347, - 0.4813956201389645, - 0.5067589546492673, - 0.45868840168445907, - 0.4510120246783962, - 0.4605364438614253, - 0.5027388997662727, - 0.463021253765109, - 0.4701676836929815, - 0.4687795718084852, - 0.4785297760647492, - 0.5300120103644423, - 0.5202452497785532, - 0.4662442063187078, - 0.4801641418911408, - 0.5453911937883829, - 0.5512614564629349, - 0.45893276160006136, - 0.5521702459416883, - 0.44759129595714486, - 0.4757001153983449, - 0.5150013829740698, - 0.530772695701723, - 0.4865015666965814, - 0.5108006484481005, - 0.5351453221808341, - 0.440948190750314, - 0.474841134468187, - 0.48704669619841684, - 0.4837230303274437, - 0.49753012312770284, - 0.5271734961876385, - 0.48101216511312483, - 0.48564567810959663, - 0.46513188791059124, - 0.44239815336317106, - 0.47486357629989223, - 0.5103133959741393, - 0.5076078322677531, - 0.45771458094002193, - 0.522106709954659, - 0.44985717929884167, - 0.4654783565358801, - 0.5345194895171855, - 0.5384566561533041, - 0.45639749856618517, - 0.5159885110354646, - 0.47122806917955345, - 0.49139580288420065, - 0.4842264777224117, - 0.5323867062752629, - 0.4417368711548055, - 0.5418900133442175, - 0.4630548285351318, - 0.47652584496764444, - 0.46911177626053063, - 0.500006205405925, - 0.5522723134543562, - 0.502089506444127, - 0.44607224267130274, - 0.46532762400767474, - 0.5175775786456223, - 0.5289836034520852, - 0.44143918364700657, - 0.4668457259153231, - 0.45759233091497936, - 0.46357417408692425, - 0.4750953709117337, - 0.49873656682137857, - 0.47562832536384037, - 0.4509183182410935, - 0.4502499161091297, - 0.4613633562086863, - 0.46825653619667934, - 0.5218723054540533, - 0.446541577841261, - 0.44276344886866886, - 0.4627541287342283, - 0.48836527957797304, - 0.500015815179826, - 0.4815388079373886, - 0.5159208361064009, - 0.4617205734645964, - 0.4912100843931819, - 0.48396192269853144, - 0.4959691624147033, - 0.5121459866128932, - 0.5518113889508504, - 0.49556974461569553, - 0.4539704845785117, - 0.4626329329184366, - 0.4921435325272624, - 0.45404330014773353, - 0.4998963265646167, - 0.5132881654078496, - 0.47615809001277887, - 0.4910797091724631, - 0.4584832321274609, - 0.5515752141328351, - 0.5109893955668225, - 0.45737855034390523, - 0.541993821434818, - 0.4519511593033392, - 0.4823277996929634, - 0.5000030855654043, - 0.5296412599182709, - 0.46639135609133536, - 0.4530225708271324, - 0.5156086099752867, - 0.5046157824746257, - 0.5114570082559318, - 0.5478914722501212, - 0.5463789093433056, - 0.4984939207278336, - 0.46021823278141083, - 0.48743798209137024, - 0.4785735660514743, - 0.5513267204850484, - 0.5084921871537009, - 0.4421530896541187, - 0.5259788999369474, - 0.5368589256066334, - 0.44086662164879276, - 0.47033531898009623, - 0.4457181080854798, - 0.5153847063088709, - 0.4506838385727391, - 0.47031726129069934, - 0.506384427457336, - 0.5456818430579751, - 0.45529155793340015, - 0.507416673741163, - 0.53274890440812, - 0.46034368892799216, - 0.5092695837488931, - 0.4467615439227067, - 0.4466210409220705, - 0.47093903242101365, - 0.4828689866560092, - 0.4998280861664851, - 0.5010008360589852, - 0.45239782359771713, - 0.5467718493310956, - 0.45462564300157393, - 0.48181580126723234, - 0.5057982032800061, - 0.5052964651645784, - 0.5126345155559717, - 0.4541662946826917, - 0.4538935398865571, - 0.5011442946458606, - 0.4910839933881806, - 0.49539319578806384, - 0.5423756941808072, - 0.5228512857534042, - 0.5467328810630565, - 0.45617355751081373, - 0.46093992644963605, - 0.44166295027847685, - 0.48740990180719573, - 0.4451842383673549, - 0.5164563788944292, - 0.5106594995356926, - 0.5445585782030533, - 0.5070593528514863, - 0.48236494190431034, - 0.47826297960554337, - 0.5406366984809535, - 0.5131618731178538, - 0.546491039550791, - 0.5457440903614441, - 0.5076896615138708, - 0.4913668151553753, - 0.4544864315018098, - 0.4917195130288148, - 0.5210773850663668, - 0.4533765985564488, - 0.5387598910844058, - 0.46375097022584144, - 0.4939139857155669, - 0.4738614667603051, - 0.48223066895365213, - 0.5481624546378039, - 0.45121406901466493, - 0.5046509105533664, - 0.5428593650346907, - 0.5377734076574995, - 0.532686341065169, - 0.4989088496178363, - 0.44992023555512234, - 0.4725921752797091, - 0.4744161046903463, - 0.4650205830312435, - 0.5008563755670546, - 0.5249060450851248, - 0.4675598434880448, - 0.4414574265072676, - 0.5221004252865693, - 0.5368830957620438, - 0.5250274341986604, - 0.5132930993670766, - 0.44793299331686226, - 0.45720525628330877, - 0.5485614256996251, - 0.4710418990158193, - 0.5290332577960132, - 0.44901353172439773, - 0.5417414035620551, - 0.47608177119393924, - 0.44445065024844793, - 0.5078737405905928, - 0.5270850892028363, - 0.5110057320748058, - 0.548786627276374, - 0.5049939868490348, - 0.48742033596091766, - 0.5167074171103884, - 0.5127561370900736, - 0.5332572496444233, - 0.4411179568225041, - 0.49204856381066847, - 0.49762434811008316, - 0.4987959347200178, - 0.4585905797681445, - 0.535529150910604, - 0.462107382014067, - 0.4592087358946877, - 0.5349876227735795, - 0.5243555840996619, - 0.5197337179154131, - 0.44575171144998005, - 0.5033728607810628, - 0.5053794636105378, - 0.5010892574601941, - 0.4429187197832827, - 0.4493194073839649, - 0.5476339752037618, - 0.4990044570460863, - 0.4590409102354493, - 0.4546875345277549, - 0.4538187883858361, - 0.5412637571567273, - 0.48591756451181667, - 0.4907711765086819, - 0.5533189694831956, - 0.4603706668658596, - 0.5153463794852624, - 0.47596767441015764, - 0.4672744113427578, - 0.5370785265386098, - 0.47149302121469205, - 0.44239464655377436, - 0.5501899767084522, - 0.4436830073864848, - 0.551066852963243, - 0.5349905912180943, - 0.5528656207744774, - 0.4552980201906272, - 0.4846277831487615, - 0.5309661139032322, - 0.5305115838658034, - 0.5169500586097333, - 0.48657457434750084, - 0.5310391810455939, - 0.47993559278975034, - 0.5225582988791954, - 0.45582408210239894, - 0.503784398656077, - 0.4559625880993094, - 0.475237429819579, - 0.45968761364214444, - 0.514687381475134, - 0.46807940666615666, - 0.4552782027549243, - 0.52377173986203, - 0.5190937717200438, - 0.5232417775397883, - 0.5376195859974419, - 0.5101975228769575, - 0.46189112286913275, - 0.5409418925781326, - 0.47832564092094354, - 0.4675260332657397, - 0.4467475139041063, - 0.5466712570948692, - 0.5255720074323038, - 0.5373131222954796, - 0.49473489155970785, - 0.5277232172064109, - 0.5348705469053461, - 0.5234609518923833, - 0.4925409918182786, - 0.4463980076851703, - 0.4452021253933797, - 0.457094713411212, - 0.5390482821869671, - 0.442091852287482, - 0.5015069927647505, - 0.5055795276662466, - 0.4871579207642571, - 0.4787272333014726, - 0.4697212665554169, - 0.549317972793842, - 0.5258560956317291, - 0.5407733071835003, - 0.5125685574572524, - 0.48029488371205814, - 0.5402611162283056, - 0.4811192611360284, - 0.5104993983831588, - 0.5103139267524675, - 0.5215850640099329, - 0.5135851612298221, - 0.4528419423427511, - 0.46041718594522707, - 0.45560815386108744, - 0.5411062991168208, - 0.4892819663717165, - 0.4863505361359645, - 0.4658015411505831, - 0.5265327355272612, - 0.447399260033877, - 0.4421679468748482, - 0.45308250566597175, - 0.44912077995493754, - 0.4701422720166558, - 0.5034356688898316, - 0.5143872981788751, - 0.5355402688633852, - 0.500482275128798, - 0.5281562110469555, - 0.5136693179224251, - 0.5317688160409614, - 0.45374328929378327, - 0.4808293842246736, - 0.4413493675565063, - 0.5091341265226429, - 0.5505863957372679, - 0.5512069221962359, - 0.46182323972702666, - 0.5379791189475073, - 0.4969703640451069, - 0.4520325321586253, - 0.516540765821514, - 0.45452352687806186, - 0.4771408773186752, - 0.44429756758251077, - 0.539371668830732, - 0.5156936985213147, - 0.4929343938787932, - 0.44434612766721204, - 0.5106507154355794, - 0.5307152085597312, - 0.4804816070923549, - 0.5208600376777535, - 0.47520798069201503, - 0.5297308556286909, - 0.4796610943266165, - 0.547781902148371, - 0.47950078885514524, - 0.4776719720124711, - 0.5216018675386163, - 0.48889436846165035, - 0.4841616237883435, - 0.47447245040130814, - 0.4624381704635183, - 0.5480825684133458, - 0.44342220281740047, - 0.47943550925699246, - 0.5310105424934201, - 0.5055035005640872, - 0.49146479512106156, - 0.4803968055559209, - 0.5534189756052006, - 0.4461767454410557, - 0.4808803516257766, - 0.49133937884409906, - 0.511039186990897, - 0.5457031007572569, - 0.44699034690417994, - 0.5050491994089897, - 0.5025165447445437, - 0.4943942054099541, - 0.5321930609918629, - 0.5105405463789405, - 0.5414158563732695, - 0.5265997187961963, - 0.526487584742934, - 0.4491918431876195, - 0.4432276025074855, - 0.5160557438399503, - 0.5169006446622898, - 0.4631706819907446, - 0.5143538414568325, - 0.45573205267024297, - 0.46924520021629196, - 0.5022477344657738, - 0.45181851387383004, - 0.4403930625707694, - 0.5446300814175196, - 0.4508400900096651, - 0.49765311691473446, - 0.47540030688369556, - 0.47090447051009515, - 0.5260366250130509, - 0.45538361175653586, - 0.4560938164543154, - 0.5058479543163334, - 0.4470360447776797, - 0.5509673166489288, - 0.5229401815851451, - 0.5367670244737311, - 0.5529195564499607, - 0.5036326593375595, - 0.4608729613125435, - 0.46076780450888255, - 0.4552574971587883, - 0.5110103808529872, - 0.549630236224851, - 0.49725323479750116, - 0.469544138513334, - 0.45710593820842177, - 0.5418536328446193, - 0.45500125033388883, - 0.5502996612429033, - 0.5283716523882835, - 0.4453074947587272, - 0.5227289666832792, - 0.5304582496977208, - 0.44666489384510166, - 0.4912792525036186, - 0.4946502321774491, - 0.5001260734588265, - 0.5042046019932855, - 0.47499917256243906, - 0.5250760350830503, - 0.4934522511217839, - 0.47924208642792976, - 0.4487549202636265, - 0.526923410518135, - 0.44358609664152954, - 0.5004549462216699, - 0.47469086191859533, - 0.5454956961206777, - 0.4905046878388103, - 0.5143547884442125, - 0.5510485191585832, - 0.4629743145381516, - 0.4970177103290863, - 0.4663127746021906, - 0.48012531794864827, - 0.44149661711764476, - 0.5297608856128495, - 0.4521572331107762, - 0.5361842282265815, - 0.51376006869797, - 0.4464887287953578, - 0.5002034477010708, - 0.44710908170391894, - 0.502820414514233, - 0.5332518360848747, - 0.5132058233511357, - 0.5154857977362195, - 0.4445929264504716, - 0.4479031789390023, - 0.458236750239433, - 0.4899320835634953, - 0.5434904219547608, - 0.5295625371903081, - 0.4678756188691911, - 0.4415219357677384, - 0.5152982972880799, - 0.5443984478417179, - 0.4616438482180163, - 0.4467289805898012, - 0.4549911985667051, - 0.48170678382142884, - 0.49798110156103736, - 0.44087485893840495, - 0.4916983037190902, - 0.44172227792007773, - 0.5113323309326967, - 0.5256467670232251, - 0.539846167400816, - 0.4910884829065345, - 0.4930500439172758, - 0.532894423669495, - 0.5432342247033063, - 0.5067554760719893, - 0.5122767883610125, - 0.5373453932460163, - 0.5337247806409201, - 0.5242428616848301, - 0.446631605668007, - 0.5265933313710164, - 0.4499953884348078, - 0.5403719394823583, - 0.47243157515010414, - 0.48486403031277603, - 0.486324899596646, - 0.5528366945252511, - 0.4492765140434767, - 0.4982874119738987, - 0.5377993054234241, - 0.5383525823587335, - 0.5300386464425273, - 0.5166099826909274, - 0.4572268336073937, - 0.5189473721806308, - 0.47949643629933075, - 0.5026354131682594, - 0.5352061235861053, - 0.5107336691332633, - 0.4846590486781145, - 0.49378753654287144, - 0.4789019831948677, - 0.49447059447778374, - 0.5291326976839306, - 0.5333949291827702, - 0.44921958665675316, - 0.44334953866882615, - 0.5339301131793522, - 0.44810305041567555, - 0.4519962984696866, - 0.5012990685970427, - 0.5203957336512022, - 0.5471943573081114, - 0.48121909639217636, - 0.5307547945606108, - 0.5154275535232132, - 0.5530688881869443, - 0.44067684689577447, - 0.5073809083116458, - 0.4713698311414736, - 0.5482854250330547, - 0.45115945239840805, - 0.4517148714678872, - 0.4915908717718096, - 0.4668638767789661, - 0.5276106849053377, - 0.4849986100950562, - 0.46097343405053154, - 0.46781735337951225, - 0.5499903646480734, - 0.48457472995966616, - 0.5029710720443011, - 0.46332896399562656, - 0.513569128773052, - 0.4623127039816655, - 0.5424388736269014, - 0.46956005926913125, - 0.44922938569774995, - 0.5003248382854477, - 0.5190452672173378, - 0.49507927842500116, - 0.4489611941876066, - 0.4678946192858283, - 0.5036951511647517, - 0.539307172819995, - 0.5432864861065136, - 0.5470784547677895, - 0.5401992629154225, - 0.4965038198402175, - 0.5003642998500335, - 0.5069803695662246, - 0.5364028196229667, - 0.5330268648749421, - 0.4406944178699931, - 0.4546006201759097, - 0.4886364315107116, - 0.46798953166787, - 0.4880293206478107, - 0.49219409043822726, - 0.5483093694644429, - 0.49829705505326, - 0.4906532697712913, - 0.5293594380876822, - 0.47896830440181404, - 0.5159878533820229, - 0.4632048402222659, - 0.4671730730510926, - 0.5271148785681365, - 0.5191236887917348, - 0.4688365375414827, - 0.5048934601125359, - 0.4702627730799759, - 0.4679122978565587, - 0.4579859708968586, - 0.45468409448799213, - 0.4547375423442659, - 0.5014583974679948, - 0.4755342350517367, - 0.5501998652257157, - 0.4471019855841126, - 0.48107289738846293, - 0.4661318688246098, - 0.5064585446012317, - 0.4433801572402066, - 0.5346749702400588, - 0.5036174803257399, - 0.5482323016059815, - 0.4992264502952363, - 0.4875437143651878, - 0.4416498834813909, - 0.4950647724027781, - 0.546240993298694, - 0.45790400470845855, - 0.5530704929002845, - 0.5191818560602143, - 0.48667903348055547, - 0.5516487527657697, - 0.4919994885042355, - 0.46376459472402676, - 0.5303138008550918, - 0.5304612473452238, - 0.5175627627513973, - 0.488040376761444, - 0.5075954759047477, - 0.44414941739393976, - 0.49144214882599396, - 0.5469263406207248, - 0.5521609411340809, - 0.5437400083781558, - 0.4961812208304578, - 0.4917366205990187, - 0.506894242312347, - 0.5443261828471464, - 0.47613855100075947, - 0.548306620387643, - 0.4459190521451631, - 0.45338281304001393, - 0.4793482914296241, - 0.550244523758478, - 0.50161367141672, - 0.4643431407550042, - 0.5081089093695307, - 0.46616870402181165, - 0.5263904226716384, - 0.5123802017538529, - 0.5051554201237162, - 0.4534534341260816, - 0.4751965052618189, - 0.5008320943323015, - 0.5149747980535236, - 0.49860519869292697, - 0.5398018898924527, - 0.48053503811721576, - 0.44290301459373105, - 0.5012968063142275, - 0.4847467168551127, - 0.4418813836464243, - 0.502108008317298, - 0.4707178616149799, - 0.4515208221447101, - 0.5480171332648236, - 0.5074661980819748, - 0.523045894525048, - 0.5314587229393163, - 0.48893974683486824, - 0.4771350252103715, - 0.5020235312932626, - 0.5460380955025493, - 0.4494975066497413, - 0.4616079314135315, - 0.4861072224200993, - 0.5446748648200749, - 0.5192815099787836, - 0.4789710290165945, - 0.5270319960332845, - 0.44635226564275676, - 0.46956187019185314, - 0.49663724123747144, - 0.47316964801412065, - 0.5186355267689801, - 0.4849205750082371, - 0.47477428130521726, - 0.5241255546264043, - 0.44203763264012974, - 0.5289825815265561, - 0.49346311618955213, - 0.45669775904382276, - 0.4432966235555716, - 0.5119893705247172, - 0.4662041920664602, - 0.5118600883986756, - 0.46185207954421414, - 0.532784665421828, - 0.45613775015095787, - 0.5335331238923945, - 0.4774842275620574, - 0.45675513894077563, - 0.5017534038768106, - 0.45103110405277413, - 0.44094419247064204, - 0.5295325147329069, - 0.5029943232932422, - 0.47277929520198436, - 0.47590261196920086, - 0.494349177989466, - 0.5309214241673685, - 0.4468108738729687, - 0.4465820114184036, - 0.47297949485148155, - 0.5301528460916047, - 0.46599191152695457, - 0.44028291683418425, - 0.5305989884825816, - 0.5211075017418028, - 0.4552858281686318, - 0.5332691647917254, - 0.5520215652961308, - 0.46126034482229683, - 0.4549289035060767, - 0.5173255612405041, - 0.4608469954701173, - 0.5267575546698593, - 0.4832928533632398, - 0.4830493261216277, - 0.5061901332905884, - 0.48964632090721866, - 0.4459940528555494, - 0.5009427977615182, - 0.4951581974675898, - 0.4484530406418354, - 0.5342103213376296, - 0.5185523969272089, - 0.5320298260552798, - 0.5071025120796921, - 0.5027771723839407, - 0.4583833698636522, - 0.4823122997533228, - 0.44116272451394134, - 0.46535665757743166, - 0.5283811652584431, - 0.5140974944387031, - 0.5320357645408036, - 0.524268753193475, - 0.546969599056871, - 0.5050412213554192, - 0.5388781762861101, - 0.5027794718521297, - 0.45074271372603847, - 0.5450469422689722, - 0.4677914550790257, - 0.4464944230401873, - 0.4933052736980481, - 0.5218958606611134, - 0.5312506195643989, - 0.5467237173732243, - 0.4430017878793317, - 0.5462491366984001, - 0.4885018776765826, - 0.5094129776272089, - 0.4482008052564541, - 0.46714455995613335, - 0.518097666367832, - 0.4544714124860733, - 0.5158212100742421, - 0.5381229351010351, - 0.4847653100853379, - 0.5406962236736547, - 0.5516867694655906, - 0.5081701822156369, - 0.44917375555247635, - 0.552206630197514, - 0.5379236128381756, - 0.4472932295673548, - 0.46702293831442854, - 0.5306122085402483, - 0.5498943066198502, - 0.4446806075592518, - 0.4599785119129316, - 0.5076275699248226, - 0.47800100039092513, - 0.460388930224422, - 0.5154465825312976, - 0.49859219761269447, - 0.5192946587039377, - 0.5066821995117871, - 0.46617431038595664, - 0.4583425967742644, - 0.4832248754876481, - 0.5156176308925695, - 0.45672762322433924, - 0.46692400008505386, - 0.5094700202742256, - 0.44746802562223875, - 0.5324329308488497, - 0.4552030745742683, - 0.5069040132805985, - 0.5036629388682207, - 0.5443416626770786, - 0.4447265204408574, - 0.5234280859411982, - 0.5432986235290292, - 0.5264400258646774, - 0.4487463530975136, - 0.4750528889329342, - 0.5153639700201968, - 0.5452356869817088, - 0.5105547986303212, - 0.5280969671148599, - 0.512918728227619, - 0.48060751218491554, - 0.45246132122145016, - 0.5147355958473846, - 0.5453638272997836, - 0.44417638191877906, - 0.4781526791971333, - 0.47486016776322393, - 0.4563742154378906, - 0.5274638811268246, - 0.45960459076039456, - 0.5328974683781041, - 0.5157375281254828, - 0.49996299558878066, - 0.496541620120387, - 0.5100184500831642, - 0.4903004489860588, - 0.4615033024840659, - 0.4430297804152742, - 0.5203935428400672, - 0.44461209383441863, - 0.4509940357251125, - 0.4617160753503343, - 0.5430656249366109, - 0.5334532086768957, - 0.5372325421038235, - 0.4901893859643443, - 0.4494908491734759, - 0.46814148403680733, - 0.4654125119676598, - 0.48058485603226486, - 0.49229431144701497, - 0.4588458150802379, - 0.4860017962343945, - 0.5237635889451376, - 0.44726819954254976, - 0.4788263333516783, - 0.5397114075061935, - 0.5242432370792873, - 0.5067556447030681, - 0.5014521114188255, - 0.49582281424107916, - 0.529744761954119, - 0.47506686409669546, - 0.5130254981547309, - 0.5475972764652667, - 0.49309114663607523, - 0.44842839358535613, - 0.5409352338509593, - 0.46729805687175435, - 0.4738599386564965, - 0.46753704123267525, - 0.46411722964623625, - 0.4538739600100913, - 0.535151593110296, - 0.5241716312413662, - 0.5296286564235096, - 0.49011397440742865, - 0.4653762495174707, - 0.5271564296682635, - 0.5387264775961049, - 0.4684239405512661, - 0.5443625367444644, - 0.5108203886253626, - 0.5300439537113296, - 0.4519266408959544, - 0.5437854489497662, - 0.4625993465685969, - 0.5405214014492219, - 0.5325499966531769, - 0.5446674653565458, - 0.5198419215422815, - 0.4845758763231344, - 0.47301269753193365, - 0.4508565650341526, - 0.4502210776044697, - 0.45069243604758114, - 0.5512935916972337, - 0.5005800008580662, - 0.5243086534852252, - 0.5165474354666498, - 0.5084725882933403, - 0.46190038386536947, - 0.5478441756333154, - 0.44066774582535795, - 0.5354638813110831, - 0.46325220405032974, - 0.497938364040164, - 0.4606319178766538, - 0.4478367632328056, - 0.44322144373021527, - 0.4517226004352327, - 0.49733635046222513, - 0.5333343757744493, - 0.4531360481444345, - 0.49101085207374096, - 0.5365672072458925, - 0.4789953727212264, - 0.4590468663867284, - 0.5249656728097299, - 0.5159390331779541, - 0.4870829564777227, - 0.5383197719435922, - 0.5069254427342442, - 0.4729705731838629, - 0.48108558688058983, - 0.5364745589340477, - 0.49674684269361824, - 0.5460184097185247, - 0.5423945585959032, - 0.5456715383028027, - 0.4805316800195723, - 0.46199223107934495, - 0.5011487836553764, - 0.45244312774426954, - 0.5157534041733747, - 0.48504603706831767, - 0.5261429917763164, - 0.49693331511852906, - 0.480204784317094, - 0.48085568618467633, - 0.47906301325196676, - 0.48862160001475374, - 0.5079591893820599, - 0.4755837481100354, - 0.5495526479781047, - 0.4972803324649533, - 0.4722698107393224, - 0.4817867144648583, - 0.5368352399414733, - 0.5116040053940484, - 0.5019971795448482, - 0.5514696331288484, - 0.5187472258258977, - 0.4702672920214145, - 0.484433213453397, - 0.5056035006763899, - 0.46193919968737235, - 0.4794313831800915, - 0.5194297245617107, - 0.4873218854445327, - 0.5253021081767355, - 0.4970054564035638, - 0.5017746252521208, - 0.4699354984988603, - 0.5015869097578934, - 0.4730067750924821, - 0.5333464025243904, - 0.5437208209103795, - 0.5528109099883967, - 0.4757408569893929, - 0.49374958522707346, - 0.48691141873913985, - 0.49980616975654923, - 0.5314694969251379, - 0.5521967236204901, - 0.4807849011962033, - 0.45811661614719684, - 0.4831239516156174, - 0.5418280063598604, - 0.5259214770981423, - 0.5381861489480628, - 0.5161856535968452, - 0.44015633778887847, - 0.5280128480081128, - 0.485092049325427, - 0.5151765178749639, - 0.501325122914442, - 0.5328490639402064, - 0.44006713268217934, - 0.5243412980642084, - 0.5105738103399142, - 0.506221383011969, - 0.46694789849202, - 0.4623909245768868, - 0.4980203415106383, - 0.47666687097016447, - 0.5447298787879546, - 0.45343338968810704, - 0.5060311061763887, - 0.5095883202892385, - 0.5165059001088457, - 0.5022793888509088, - 0.5370299297776853, - 0.5453770397693822, - 0.44340455075509483, - 0.5124847049637019, - 0.5098531850280912, - 0.5086751271155578, - 0.5102549239937544, - 0.45270105671710514, - 0.480568962528218, - 0.45964150889794625, - 0.5464360377474282, - 0.4900691771131225, - 0.507320082681845, - 0.5301969006913286, - 0.5193770442865873, - 0.505403959693892, - 0.4604584515764735, - 0.5432334450138312, - 0.5092065416599147, - 0.48960089645425897, - 0.442803969010633, - 0.5309952067513715, - 0.47034399769443813, - 0.5306627703978996, - 0.5133886394964058, - 0.5125771160430307, - 0.5022138101549647, - 0.4968194800380454, - 0.5429446021087878, - 0.4674405546806191, - 0.5312834951843005, - 0.5493108589880927, - 0.5466088261406132, - 0.49843137716550173, - 0.5232370481689891, - 0.5101884109298276, - 0.4435297859284207, - 0.49164605714726306, - 0.50107282401424, - 0.45437650540762786, - 0.48432565442119413, - 0.4990130382917627, - 0.457435321055733, - 0.47344838772276443, - 0.5461096822176705, - 0.4839149332419697, - 0.48946780123760136, - 0.46458254928090403, - 0.44635896973621264, - 0.4724286678486628, - 0.5039499170585952, - 0.5395037354148615, - 0.5233609658502799, - 0.48399501049991084, - 0.45951809612559, - 0.5048139924658714, - 0.5263076511351072, - 0.5419074677849566, - 0.4889574286201239, - 0.5502337769056302, - 0.4953515832064734, - 0.518623764973478, - 0.5371953119910509, - 0.5387731774281754, - 0.5324763431460008, - 0.4952412432298074, - 0.5287966435816176, - 0.5267486086659434, - 0.4972704027544774, - 0.49778490906264466, - 0.550999831072219, - 0.544153136677973, - 0.49027119295493515, - 0.5163848821428202, - 0.49182684084825096, - 0.5450288361821898, - 0.45858030514945186, - 0.537580607280582, - 0.5514214729193034, - 0.5426994770367901, - 0.486731104538965, - 0.5325853875993151, - 0.44602345640111807, - 0.5075374157380916, - 0.4852049537518027, - 0.47758812957544083, - 0.4804949352345807, - 0.5083880388918152, - 0.4855283116766912, - 0.5410735131659439, - 0.4437043915401175, - 0.4575284212892631, - 0.5128333183177478, - 0.4520950298178065, - 0.45830692446308136, - 0.5032555249724819, - 0.5157840873836536, - 0.5361033202220022, - 0.5413597739454974, - 0.5050473272894825, - 0.5048364125666189, - 0.510815224685285, - 0.4618009055900819, - 0.527394973182295, - 0.46489682636469865, - 0.5267262958400412, - 0.48844810817178375, - 0.5076401602601615, - 0.4851796814325862, - 0.5488914035140267, - 0.488789520609771, - 0.5058882662934556, - 0.5167213354490097, - 0.5342584702696291, - 0.44183654813889717, - 0.5515689084066324, - 0.444317595175212, - 0.4616581853363521, - 0.49304144517624804, - 0.5033940578885173, - 0.5346656292938698, - 0.44679700183579546, - 0.44608379753808064, - 0.4539412629955789, - 0.5469383281740241, - 0.44059891962320225, - 0.5456041784778148, - 0.5319943228128267, - 0.49667300153938765, - 0.4863348318446412, - 0.4621270495146784, - 0.46963825429565254, - 0.49336370254434453, - 0.548793526068379, - 0.5196135244985227, - 0.525053993890254, - 0.5105320304543862, - 0.546941610930436, - 0.44509327054482856, - 0.4721416001353115, - 0.444470719103569, - 0.47030356118199945, - 0.49562890377735874, - 0.513684384046535, - 0.45598605402313674, - 0.5534343285081059, - 0.49004289613681556, - 0.46459712076469095, - 0.5427563935011184, - 0.49508392176680605, - 0.4441521664201505, - 0.5183330696867833, - 0.5010052532769761, - 0.4833178567181273, - 0.45578772457318567, - 0.44109198065178135, - 0.545020014783491, - 0.5504999549896962, - 0.4907164311601893, - 0.5436282196803198, - 0.5157090843812179, - 0.5048197244506879, - 0.4859640005870544, - 0.4620338008481399, - 0.4958471266084517, - 0.4806088647664765, - 0.4602409043088068, - 0.44753786213380053, - 0.4471882709968754, - 0.5451884503549318, - 0.46611994587544625, - 0.48348721034624914, - 0.5096513456114391, - 0.45683080965051165, - 0.543396436617825, - 0.46117420845556456, - 0.5318470671935385, - 0.5096356592195326, - 0.4517088349418612, - 0.4716584454319964, - 0.549459865874414, - 0.46866892696995904, - 0.4872190106712515, - 0.5335589969300423, - 0.44830460748424755, - 0.529499694730307, - 0.447340223850716, - 0.5423308613546949, - 0.5044542551488971, - 0.5233552881835286, - 0.5503268389409359, - 0.5384543607509125, - 0.44990735856011366, - 0.5195904414695889, - 0.5000149633339458, - 0.45635427598395, - 0.5489332366951806, - 0.535525184512137, - 0.4423798977825255, - 0.4910821746698986, - 0.44558763818550623, - 0.4652676916751222, - 0.4545888460800088, - 0.47113716520004356, - 0.47729010894835355, - 0.5351714444914265, - 0.5422795564756224, - 0.4497796983959006, - 0.5140827093481741, - 0.5483904807021865, - 0.4994383462670028, - 0.4900830340924063, - 0.5341986461948024, - 0.5429310401960679, - 0.533681247840101, - 0.532431172621701, - 0.5455706787950352, - 0.4634439313128956, - 0.4971061799193746, - 0.5350062644610544, - 0.5183120325233794, - 0.4814438776946617, - 0.5270406230363252, - 0.4975482138092503, - 0.5319450109405951, - 0.4862168219745583, - 0.5172511715180287, - 0.47801843384402454, - 0.5308705817091913, - 0.5482303219700663, - 0.49030505815374514, - 0.5438292766031639, - 0.4599721018497812, - 0.47837578181517454, - 0.5042187727777778, - 0.45192749559766265, - 0.4704129836010993, - 0.49268132079471283, - 0.4882578258056005, - 0.47941833502236053, - 0.5505100818659281, - 0.4910518426532234, - 0.501752572414556, - 0.5012865842176092, - 0.4731466744397388, - 0.463425270300923, - 0.5157244481066056, - 0.5034916475389876, - 0.5315986402947277, - 0.5060684112219911, - 0.4524566180664896, - 0.4957228971539362, - 0.491233222182925, - 0.5094343316069827, - 0.5079483904061188, - 0.539991912799589, - 0.4497470494360594, - 0.4969113647991615, - 0.47842255326647115, - 0.47823637105625105, - 0.5310019998635432, - 0.4509705276294815, - 0.450116864761496, - 0.5041088934386859, - 0.4940843568317277, - 0.5487621206356995, - 0.45710476379947973, - 0.5104894255110819, - 0.4680010238941056, - 0.4633163868647723, - 0.5395553820391381, - 0.48144703061573835, - 0.5030207919408705, - 0.5074262943146478, - 0.44837067901387695, - 0.5287697754073852, - 0.5119835293818694, - 0.4589302008555962, - 0.457483919253918, - 0.5530521514629825, - 0.4851490714684783, - 0.4806168874032344, - 0.4429764565795546, - 0.5195215379515985, - 0.47596739143508143, - 0.5160439271149626, - 0.4766190893572023, - 0.5493051875569751, - 0.443081051167442, - 0.5498935888504649, - 0.4799739036143562, - 0.46505292398732717, - 0.45227114442876976, - 0.4619902427644081, - 0.47878740432186473, - 0.47951330391240105, - 0.4508374972173599, - 0.5322604046097068, - 0.48692015140144657, - 0.44589118878769196, - 0.4957172652125736, - 0.4822924768279617, - 0.46059190042755127, - 0.45223588794877273, - 0.47067957650179576, - 0.49122588341749057, - 0.5350493918093794, - 0.5418236942737616, - 0.509665684394355, - 0.44735138062929913, - 0.5335430553499962, - 0.45635309198584684, - 0.47973270836727955, - 0.5360730963499952, - 0.5371815991265003, - 0.5086203475284568, - 0.5434279727959479, - 0.48604487112395744, - 0.5053174789370474, - 0.5329891168812134, - 0.5481309069784515, - 0.4405171262669118, - 0.48180534036990996, - 0.5268622922849143, - 0.5230682678553852, - 0.5168221501182532, - 0.45771342582152375, - 0.503094810015974, - 0.5321545831249596, - 0.531812128464478, - 0.5093581154282532, - 0.5079649530465087, - 0.4518864921912359, - 0.5230351801137897, - 0.5411023196106397, - 0.5372860996488291, - 0.523739741820909, - 0.5498119578355719, - 0.5482362123588953, - 0.4819829635242672, - 0.4432036095283536, - 0.5504192790401939, - 0.44664036717682204, - 0.5238698357057009, - 0.4414795772675521, - 0.4903010289558375, - 0.5079346277895141, - 0.5391235032155154, - 0.5363248666485857, - 0.45516818348960436, - 0.5442449530485653, - 0.5385050270766008, - 0.48864678486877594, - 0.44002388166093653, - 0.45866729170920967, - 0.44219862552005934, - 0.5188511083870305, - 0.5482142591825072, - 0.44199457644306916, - 0.47718134536551016, - 0.5189474810016099, - 0.4925123897117636, - 0.44111623729143173, - 0.45387400835883457, - 0.5335217143729948, - 0.45465193061477815, - 0.4571193898870802, - 0.4807406715561094, - 0.5491063097639924, - 0.4613347709442926, - 0.5445077958684232, - 0.457641970683243, - 0.48216354127298405, - 0.4966239373542392, - 0.4411183396115584, - 0.5483837291909318, - 0.49354012275150055, - 0.4666373139532217, - 0.5117926380876113, - 0.5140545766953135, - 0.49104351871885615, - 0.5448340060632225, - 0.4573438836223842, - 0.5418021804117191, - 0.4435888368051842, - 0.5055608126384828, - 0.5119896772814707, - 0.5519528371173769, - 0.46712524621240126, - 0.5095143040338311, - 0.5244032247040804, - 0.508021804636702, - 0.5519986256793902, - 0.44277729762639795, - 0.5081239805006906, - 0.4778022248902097, - 0.4741459206672787, - 0.5261687369321055, - 0.5501950007240795, - 0.5355294324889266, - 0.5160874420022421, - 0.5147935952405853, - 0.4681470163927913, - 0.4870186939900394, - 0.45043501005716186, - 0.5155648257782606, - 0.49446026836554374, - 0.47996444266348626, - 0.5351610800255984, - 0.46831259593917174, - 0.48540396398357927, - 0.5403830008032882, - 0.5193057642968153, - 0.4692869055955966, - 0.5372747168506324, - 0.5093389687132814, - 0.5373252100523167, - 0.5273320204564803, - 0.5346433682114686, - 0.4591093767632141, - 0.5165328982034377, - 0.4921751581787868, - 0.4984386068736154, - 0.4753233521397704, - 0.4522540711959321, - 0.49157005990759944, - 0.5251212566506703, - 0.46262654166491485, - 0.5006550915914544, - 0.5436465651391724, - 0.47410224361645015, - 0.46664834178537967, - 0.5179816857318394, - 0.45511477318428356, - 0.5223862287316959, - 0.456763181919643, - 0.5134006073199406, - 0.49915005065187523, - 0.517695866813784, - 0.4779348706263414, - 0.509314044482189, - 0.45099319347536554, - 0.4884041137122358, - 0.5305351161445514, - 0.5350845245413441, - 0.457918033093942, - 0.467640879806544, - 0.4737397345151282, - 0.5403966140760506, - 0.48386855691966063, - 0.5322328886314546, - 0.5174371637430711, - 0.5011641494857392, - 0.5475550146587499, - 0.4846573256526714, - 0.47477992817038317, - 0.4963075207425974, - 0.5322111044558804, - 0.5354360401009193, - 0.45574409646963276, - 0.45160311090586114, - 0.4528830294908986, - 0.5346052364231253, - 0.4454303123596849, - 0.4851554788230875, - 0.5049649208581555, - 0.45437395542985615, - 0.5084505349625794, - 0.4968482850768335, - 0.455416449507977, - 0.5355914637119905, - 0.4591679012582008, - 0.5387933730808036, - 0.46225702930141344, - 0.5304376297434239, - 0.47753136816160446, - 0.5031142592494904, - 0.5427158059485686, - 0.4567821897103461, - 0.5354618325759841, - 0.5450172523207727, - 0.4839007224750504, - 0.4831352101005972, - 0.5052018768916776, - 0.48113492506678635, - 0.5167149927842631, - 0.4422135675235022, - 0.4551689181366713, - 0.5295131820919736, - 0.4876419038302507, - 0.45292812453739406, - 0.4717544468075724, - 0.49358029176227314, - 0.44962902677309835, - 0.5058294619176974, - 0.4928293677597785, - 0.5106708830758048, - 0.47466373604290724, - 0.519341837844961, - 0.5042633991446686, - 0.45872651758338406, - 0.5333377207871395, - 0.5122993243242949, - 0.46575871203105423, - 0.52459054927003, - 0.5433668951234547, - 0.5016708445549627, - 0.5103544076107847, - 0.49653618690387796, - 0.47030075953035105, - 0.5229786043891167, - 0.4490229182516422, - 0.4915047990674398, - 0.543870055389204, - 0.5178023592315658, - 0.5036210056808561, - 0.5195805279297785, - 0.5471169311790629, - 0.55295943824205, - 0.4675832046120239, - 0.5021630184130779, - 0.4573279502809836, - 0.4803844980313016, - 0.5365880436125715, - 0.49354694022295287, - 0.5175082718561442, - 0.4940081277161223, - 0.44412185141766153, - 0.46824850676086777, - 0.5413791362530747, - 0.5277410967130627, - 0.46695716997663494, - 0.46009714930498147, - 0.4523297918418629, - 0.5200461536722337, - 0.550207292234168, - 0.5377127637540643, - 0.502211924007159, - 0.4729903036323002, - 0.5470115233699702, - 0.5461964653869991, - 0.5348110479520313, - 0.5357399494106869, - 0.5111960102278816, - 0.4950918968680071, - 0.4476260398320017, - 0.45290749356588533, - 0.5081411991234438, - 0.5124618176403843, - 0.4613412746525475, - 0.5438340644381673, - 0.5523932107236297, - 0.517689498151181, - 0.5478294747579303, - 0.4806494244935603, - 0.5423551348651094, - 0.4766250588208707, - 0.4404988760101469, - 0.5233032082363418, - 0.4818167599392931, - 0.5070993459091313, - 0.5013772390954181, - 0.4816277195955149, - 0.47030470030073573, - 0.45104348519130416, - 0.5265526645505121, - 0.515677991668896, - 0.48928738388636733, - 0.5148592474396262, - 0.4556423131478119, - 0.5044783473003479, - 0.5031406143935703, - 0.5333203481359144, - 0.4674874424137923, - 0.44739178839215404, - 0.5310438159772812, - 0.4788732660633662, - 0.5412668229558761, - 0.5236717354617694, - 0.5457904938549094, - 0.5516276864184184, - 0.4743564802559072, - 0.45029908289446596, - 0.4628226586985427, - 0.49659614408467806, - 0.5289966612041788, - 0.4854246845698435, - 0.464260022098271, - 0.5216160132386239, - 0.46210239877195225, - 0.46426234569133157, - 0.4891292056828672, - 0.5082290965957491, - 0.5393936392866054, - 0.5120276389406444, - 0.4731854192582958, - 0.46922933558560853, - 0.5244615905883708, - 0.5073131270174155, - 0.5465974371307761, - 0.4492553938911763, - 0.45150727170539867, - 0.49176955743208184, - 0.5445762232767685, - 0.4439879686047917, - 0.4770823570993184, - 0.5389752243503222, - 0.4779734367202759, - 0.4745552001696044, - 0.44365894646826826, - 0.4600099244259736, - 0.5522454295280248, - 0.528446781323649, - 0.46799455184312616, - 0.4805535866028231, - 0.5407146643259719, - 0.5249101837504178, - 0.49826211342903415, - 0.5523576394188892, - 0.5445792790478049, - 0.5261231551636398, - 0.4575196233678574, - 0.47506596083999736, - 0.5220293393795983, - 0.49498392474534175, - 0.5014363197317365, - 0.5039121329427522, - 0.5506202953859224, - 0.45272783464807315, - 0.4940086708165929, - 0.5417740052853435, - 0.4956878595465703, - 0.5174935338369353, - 0.5410481691348099, - 0.47423970182193476, - 0.5239310169947955, - 0.5178355269779793, - 0.5078500163469254, - 0.5382156690283552, - 0.4651136987381, - 0.44318001660295897, - 0.517967518764415, - 0.4489898920182634, - 0.4823451401564358, - 0.5340688103300767, - 0.46209364210058235, - 0.5195840494009112, - 0.5095773387389141, - 0.44379738137869584, - 0.5164791415458176, - 0.45986446158247674, - 0.4914960495792694, - 0.47534542946106123, - 0.44163114790080754, - 0.5197933258211177, - 0.5455289443917992, - 0.49536707370044464, - 0.4674075738468274, - 0.5136007526227369, - 0.4642637652780939, - 0.44407437312661957, - 0.4828423790331744, - 0.4949664983398338, - 0.5010555667067211, - 0.5105325548058796, - 0.5252369063061624, - 0.45358537212640215, - 0.4417621103283898, - 0.4552530492508831, - 0.4875023417253113, - 0.504429450432551, - 0.4607366961223264, - 0.5120288381464381, - 0.5446000879543458, - 0.5438652841365869, - 0.4943514135242846, - 0.5047482119776977, - 0.4752666534486843, - 0.5277048098183363, - 0.5102420030370676, - 0.5505467324224924, - 0.46103252836166253, - 0.5399536182725838, - 0.44905396277395204, - 0.4827685582187117, - 0.5074370957929605, - 0.5248119584514711, - 0.4941988872242729, - 0.5486180166915255, - 0.5397156983806143, - 0.5305275172028412, - 0.5274746256434522, - 0.4506816228154093, - 0.4631379343835678, - 0.47731314191174806, - 0.4979833869632962, - 0.5175829490727902, - 0.4784879317076122, - 0.46765975159972645, - 0.46594537717062456, - 0.4831602543263648, - 0.4552416826351042, - 0.4816748943503433, - 0.498339294967086, - 0.5383770443063525, - 0.4911842661739461, - 0.5212848369084148, - 0.48841276127384875 + -0.5054885099117004, + 0.5544019130358191, + 0.6465415925726117, + 0.5653704267974764, + 0.22882361554909503, + 0.022373648538888125, + 0.6574049213255879, + -0.2201693096148264, + 0.4670589259215312, + -0.5944170432036455, + -0.28578948101801577, + 0.5088841610270673, + -0.2479555474158764, + -0.5202670033024328, + -0.019980114460358744, + -0.0018206038353352216, + 0.39306701060721627, + -0.42189460282822017, + 0.14667933027800062, + 0.07913616951058433, + 0.3389043190063912, + 0.6533072162326867, + 0.5541027182533327, + -0.2764181719671143, + 0.6577510443753245, + -0.3482070806886038, + 0.13764097102799933, + -0.11451344438018018, + 0.6523498839263238, + 0.6010946777054926, + 0.3555671677338055, + 0.7047426774308712, + -0.641820715366076, + -0.6398567553194306, + -0.4116458128082596, + -0.13059162449168216, + -0.6424720993460674, + 0.49833735745009644, + 0.3621987792532524, + 0.11330285483728042, + 0.5596681281399141, + -0.5479736209909093, + 0.45720718455141296, + -0.5400220225939456, + -0.28471434490860176, + -0.1666800643049049, + 0.42830246604149846, + -0.5282303695609815, + -0.49107463868491336, + 0.3140671302909428, + 0.45418463757432725, + -0.6190926615873668, + -0.5051302805187237, + -0.22584528519605196, + -0.6930253509819768, + -0.2870234350699684, + -0.10599911744197543, + -0.5373919688882629, + -0.0886802928478071, + 0.12077274288493278, + -0.6196249953515058, + 0.07669264217322092, + 0.11893538425220662, + 0.011985452647678585, + 0.6536875443137165, + 0.4435084026334679, + -0.2261213306186307, + -0.07952281960933916, + -0.04381434363784864, + 0.4214420808509176, + 0.05775210508565387, + 0.2967828720738255, + -0.6712907582765341, + -0.6566737182824577, + 0.4560906060535572, + 0.02630306534796012, + -0.1698687572215456, + 0.6214608902327832, + 0.09748937449061412, + 0.3553657026781203, + -0.17709403693302472, + -0.34643859865605375, + -0.016718761736664423, + -0.6316376442003354, + -0.3984685793499152, + 0.17717079078140008, + 0.5177061091775241, + 0.6931463862261202, + 0.6175488118741763, + -0.31015238311987325, + -0.636607644325355, + -0.1932477761732423, + 0.3275318559682743, + 0.18198313020964652, + 0.6241378217459996, + 0.12907011393846124, + -0.27324627396634565, + 0.33027439532396663, + 0.13893331045021584, + -0.4132701275566833, + 0.13223388796264135, + 0.1424705338486334, + 0.01947381178967944, + 0.05175899034062559, + 0.6271169745423508, + 0.5647047295434879, + -0.6321433335394628, + 0.409956451003193, + 0.16805462007577232, + -0.2941048177406229, + 0.18359168229533895, + -0.6673492632607388, + 0.497061401556369, + -0.561095897679825, + 0.5326900165361397, + 0.6793218507925927, + 0.726945027696863, + 0.36526653909385587, + 0.20494038223244415, + 0.621903260364322, + 0.5987432928582916, + 0.08059937250455418, + -0.4343117267436658, + 0.33362850368030306, + 0.6289492701793926, + 0.12794265199539878, + -0.19188516293979163, + 0.18393814411863318, + 0.3927273020851152, + 0.5246815736335382, + 0.6334544879386164, + 0.48282311579566617, + 0.6838634131746242, + 0.30554909871349634, + 0.3899227950013675, + -0.5060352267124264, + -0.6280015180143976, + 0.5266495488845657, + -0.18023872798588325, + 0.2747809293422294, + 0.444659957021748, + 0.4895232854541731, + -0.5708495562491983, + 0.27160028641924305, + 0.031873863381078005, + -0.1566975197559024, + -0.007721099730944592, + -0.39089799916229845, + 0.27211891701015367, + -0.36824622406062135, + -0.12451591851043642, + 0.5667039384791861, + 0.015398483746554725, + -0.6810612583466602, + -0.4335250120619058, + -0.14947020221800378, + -0.5398367230155151, + -0.49484516818149393, + 0.2040602443261308, + 0.5099510227512087, + -0.010354663393207675, + -0.052420247687519295, + 0.6928993959417153, + 0.09076765064140091, + 0.5651770792230864, + 0.2859497386420431, + -0.034085629383341476, + 0.5750746453193112, + -0.08072318826339353, + 0.4784996826209138, + 0.48118468488876975, + 0.20921780183934657, + 0.28503428705995715, + -0.28416616222636054, + -0.1224423801031953, + 0.4964082441848887, + 0.6236794716190073, + 0.6849441870059112, + 0.5112418780180794, + 0.26825087999248964, + -0.5131235485427412, + -0.08712728233135703, + -0.4164136942818055, + 0.01136141998315321, + 0.4348954890563972, + 0.28655278508971804, + 0.002718027142452062, + -0.2641079554322445, + 0.08670765976319073, + -0.5840914262676046, + -0.18711670169062178, + 0.10696424058811527, + -0.6314676033423328, + 0.2885683534333996, + 0.3184687425664221, + -0.12923088220199896, + 0.050218330232481456, + 0.2895441012768327, + 0.0175776829293669, + -0.3895678765459565, + -0.5870421476354659, + 0.6962627612159527, + -0.06633009741688434, + 0.4297633657321738, + 0.38586480277991586, + -0.11915152081460156, + -0.3804141106494903, + -0.2631435009371642, + -0.02920389188545991, + 0.7113329324751265, + -0.43343020419954664, + 0.25451133870087195, + 0.5884452959277182, + -0.2674198352028108, + 0.42825664523494367, + -0.16822367924921322, + 0.07801559404321778, + -0.5224615300790034, + -0.25107677993329286, + -0.32325437268032486, + -0.1712321764120669, + 0.3922949629981278, + 0.29741704543801406, + -0.028135970147384004, + -0.056261944232383954, + 0.33938726670875674, + -0.25879481967044843, + 0.025853367514801828, + -0.5291337035142096, + -0.6932111293025227, + 0.2180612575767219, + 0.050772125820713554, + -0.11282355944063038, + -0.33395138991773926, + -0.722978520089695, + -0.5763609247478333, + -0.2757845193254082, + 0.24650874396324252, + -0.1242153690773169, + -0.49112482458274004, + -0.02349506248351585, + -0.07836921757877036, + -0.6788481261802811, + -0.4819638490462905, + 0.3893822047618316, + -0.12450171724405112, + -0.06374536437411893, + 0.11431926053694852, + -0.49163843385564676, + -0.3579373168024579, + -0.1488048030449315, + -0.5658624992579452, + -0.3013768854657577, + -0.09583562592988437, + 0.4360685332480567, + -0.28899467845653437, + 0.11005275043204132, + 0.5207360662033025, + -0.4962549978136589, + -0.1985034940936552, + -0.6858456356972067, + -0.45232799860023454, + -0.1174989105143992, + -0.2914070070734469, + -0.5902118868024246, + -0.08571716708121568, + -0.19727844922164017, + 0.37152869262746324, + 0.709705031698908, + 0.5579184088263747, + -0.540811352548963, + 0.4291164206817242, + 0.09500993058242024, + 0.413707393253808, + -0.3276233196574725, + -0.6911525798154635, + 0.6967836665098681, + 0.5921367476994273, + 0.45094065365821967, + -0.3759867076619442, + -0.6932986226718897, + -0.553628499529381, + -0.2973742920722042, + -0.42487803951462905, + 0.4476142694228318, + -0.4422434027179486, + -0.5485907200126918, + -0.4404336624029022, + 0.2168038244412449, + -0.7007264356979266, + 0.4077142594971166, + 0.3605866874718333, + -0.7071558260465095, + -0.3259687079179267, + -0.5819771806359626, + 0.5431930280238613, + -0.4832438229021716, + 0.1079892240475766, + -0.5341695698041927, + 0.07752664832567036, + -0.6176584560716178, + -0.49462212156232255, + 0.2560866347977666, + 0.3061360902073931, + 0.6481719844527409, + -0.222030093715462, + 0.015044188882887721, + -0.4351672935221238, + -0.07940005481600143, + -0.4153543830000355, + -0.6008627761524308, + -0.04256063493430051, + -0.16141649888894616, + 0.5449958176410734, + 0.4233559627441812, + -0.18307482662435692, + -0.654945844965531, + -0.6395968336664294, + -0.37135051603310093, + 0.6017605530647834, + 0.42128236060579316, + -0.5275048915864413, + 0.5236221172168245, + 0.2917571746460361, + -0.5670942327704313, + 0.4079043297549223, + 0.5762740709322478, + -0.3152217417773077, + -0.09510014227007146, + -0.6315124343925201, + -0.5762307804892264, + 0.5179759115609404, + -0.4927615446020748, + -0.38486959876927807, + 0.5597362254632718, + -0.1913881081592974, + -0.2446369505466212, + 0.7137658116560284, + -0.10126921571281666, + -0.09325291337595676, + -0.38609071148073, + 0.1283544262618136, + -0.6518684151792324, + -0.3853970417761446, + -0.6056785290606012, + 0.5514818685346816, + -0.30656908885559353, + -0.34544666944441443, + 0.6170281695093367, + -0.06556991393142819, + 0.31885645716900224, + 0.6861691782604438, + -0.3456709962842611, + 0.534061460553217, + -0.3830608853867089, + 0.2957868474837855, + 0.3200159108589513, + -0.5278741889994711, + -0.032786790430364476, + 0.5993200221467541, + 0.6409463133759519, + 0.5853320597020271, + -0.6959406015029048, + 0.05062311959402599, + -0.6719155684140347, + -0.3814172035831502, + -0.03659490056247783, + -0.06609155547823098, + -0.2771201517883568, + -0.11102525363197013, + -0.3906690180306251, + -0.3235094330159517, + -0.5041181858563141, + 0.7262834409849293, + -0.18177204299211214, + 0.05513839836671708, + 0.46119745587973004, + -0.31017228116159673, + -0.5048090203009753, + -0.2795464688476727, + -0.37617327573403203, + -0.19784110150660927, + 0.42412924528834073, + -0.23688992375240658, + 0.6524764766535962, + -0.11652862040487799, + -0.6793690633896902, + 0.5038224135864775, + -0.678981195621205, + -0.09721254234712795, + 0.10652200166784265, + -0.6940256265426842, + 0.3976929460429963, + 0.28138801074547604, + -0.20881494528723543, + 0.45365992551183165, + -0.514240336245483, + -0.1625742878114127, + -0.5726535755961268, + 0.43707499583550424, + -0.22077857387888444, + -0.026869345238716202, + 0.23099847480057223, + -0.4925333174261896, + -0.552656942282399, + 0.21603395579373275, + -0.3002986960793039, + -0.17247726876245084, + -0.33296802954002014, + 0.32178694046680745, + 0.49758436619905577, + 0.726351056463904, + -0.4217789762959508, + 0.45531482937865286, + -0.30165511338817236, + 0.3517485614193847, + -0.24995427141215865, + 0.6249535894784752, + 0.03357381917737057, + 0.623961615724502, + -0.39031490218749276, + 0.694016078566956, + 0.6292800298377916, + -0.49908143946930206, + 0.007125389967973184, + -0.3372393545469999, + -0.15219843194282479, + 0.5174551587536966, + 0.0010491129408971567, + 0.2778763489298357, + 0.37385185498276474, + -0.3221502392855777, + -0.7083690252159082, + 0.685210972695125, + 0.19921183622270533, + 0.49700567220344016, + -0.511757703331241, + -0.15278582380905759, + -0.16116741258761857, + -0.153365764596326, + -0.34621670528308224, + 0.47356278468174295, + 0.16199449584415138, + -0.6999195548606288, + -0.5226422968550618, + 0.43662464143812896, + 0.3879110748461716, + 0.4488089511613056, + -0.20092819867755563, + 0.27955979951911236, + 0.6392716571405836, + 0.48681066192812916, + 0.30430281866680975, + 0.3149140929819947, + -0.4279152470457843, + -0.6092535630625211, + 0.6818240092434409, + -0.5202220528580478, + -0.5992069510162555, + 0.12868561713050775, + 0.39266414802995064, + -0.643255815857565, + -0.3052699560813608, + -0.6272030781787268, + -0.04304272187778457, + 0.04045094505416147, + -0.1903272362344407, + -0.5368118392168194, + -0.1357215077879903, + -0.6716821577401261, + 0.32758154638008374, + -0.4126776029500265, + -0.15066658282694778, + 0.4122999606446818, + -0.13868045455120281, + -0.665941268304644, + -0.4220181021761827, + -0.09159737779839006, + 0.39706590529039354, + 0.3041772621087351, + -0.03943458389999566, + 0.18622831458313227, + 0.12149604892956778, + 0.6556062533831848, + 0.08169026154932535, + 0.2542243595976741, + 0.6947856271862973, + -0.6918995818053947, + 0.6918550982843759, + -0.2872322172385215, + -0.6230921533068694, + 0.25139079997150715, + 0.11948386816605572, + -0.1081377778442486, + -0.4603053492419115, + -0.29872745329201894, + -0.658468243618296, + -0.19930948240413782, + -0.6298971669454048, + 0.49473978431299814, + 0.388290520229162, + -0.1475796302680613, + -0.1481216310850656, + 0.6418395863685284, + -0.1132810208524142, + -0.5539665386715467, + -0.35782678487104497, + -0.647484240384889, + -0.46081260560820503, + -0.4092221521354031, + -0.09165776249076163, + -0.049447551358565156, + 0.1930863950629761, + 0.02186556727952682, + 0.664799986409891, + -0.16930388236300697, + -0.4199615432762584, + 0.6180317811007312, + 0.2212469933129354, + 0.20190389473254322, + 0.7173826671957484, + -0.5765959795462148, + -0.5129364151493974, + 0.5191776230881455, + 0.3383320836534145, + -0.558473130401715, + -0.1557713143706122, + 0.7138838605187714, + 0.08370627527939423, + 0.2515179345865868, + 0.10844945483247681, + 0.552141968224056, + -0.040698142921791636, + -0.45328568531441, + -0.33929667416667136, + -0.10728071994425903, + 0.24838880968155164, + 0.4325109785293695, + 0.3861264612670574, + 0.23534746904424908, + 0.015186413495884787, + -0.280893919869197, + 0.33785122290077263, + -0.6999842383871219, + -0.4457675002633011, + -0.4149602946305086, + -0.6304428867574764, + -0.31942731632333365, + 0.7098818699071012, + -0.032791812055385505, + -0.6609089403767593, + 0.13654935531852674, + 0.6194130403291993, + -0.33801658050357447, + 0.6622362327354236, + 0.09878231035567941, + -0.17663960452669503, + -0.0051240944338402095, + 0.41272188845207247, + 0.5126156621557443, + -0.3349751616526061, + 0.4198229247240326, + -0.1518111968062935, + 0.382533946183671, + -0.20923988466421928, + 0.2682010808580152, + -0.48980672438102535, + -0.6746326691620592, + 0.2588853970393895, + -0.23197921363179225, + -0.44635735389841374, + -0.0280550051198184, + -0.43762056658177867, + -0.7229519934680833, + 0.07652196303090475, + -0.25944225384487934, + 0.4859045009248544, + -0.08385824424298971, + 0.0143698345825779, + 0.06131477927227891, + 0.3629955907513289, + 0.6705691875406137, + -0.46013001845388857, + 0.6150413112191284, + -0.005272611943640038, + -0.607368793127193, + 0.44946662694433015, + 0.14394089288600687, + 0.42025572739320793, + -0.4323918971369253, + -0.15398245650831288, + 0.6698994474549627, + 0.43111914862899914, + -0.13469548339572113, + 0.03211984090953057, + 0.1490552473721024, + -0.17294536618276857, + -0.5765874820897829, + 0.5321452641674989, + 0.36450788239687126, + -0.4836870882518476, + -0.4055453275907872, + 0.49433431823013896, + 0.32886759825709455, + 0.602089610631805, + -0.41916594533508666, + 0.6994782929801076, + 0.4730772380202952, + -0.0968406314496354, + -0.29706117107567204, + 0.6993665668840567, + 0.07306450838220757, + -0.47787137812075187, + -0.19947744592810135, + 0.6255050387418977, + 0.6250825537471543, + -0.46896581784831937, + 0.1589820500550988, + -0.5924290472628186, + 0.10507896848298115, + -0.3839012333378843, + -0.37178937171987814, + -0.5286382983877309, + 0.06867280778456053, + 0.7086601344593628, + -0.48002831996431705, + 0.38361620502247584, + -0.6589735901138092, + 0.15293975864345155, + -0.15985872195806516, + 0.3526401451330132, + -0.008017882873872062, + -0.3295929328287862, + 0.5287415426209865, + -0.06698203968088223, + -0.49846696421732806, + 0.4222923941800589, + 0.6416139951942725, + -0.11434242030874309, + 0.4368947231956879, + -0.2454816846796618, + 0.06305675576267922, + -0.21989051844047525, + -0.5126879583278892, + -0.39652943038469746, + -0.11712254339249184, + 0.5990715073804214, + -0.6438590899792883, + 0.21441627028239185, + 0.08183722479099564, + -0.6630642937678559, + -0.19177907866765231, + 0.6804308621582067, + 0.6417072786222582, + -0.49568819141799225, + 0.6185354729711077, + -0.06931235169949002, + 0.15624658624028853, + 0.6307689357592248, + -0.5494559704059688, + -0.2106176301934587, + -0.4771870142256701, + -0.5032912121023108, + -0.26208160489137655, + 0.09313477866408659, + -0.29428116762226214, + -0.23990685999787337, + -0.06524709740793622, + -0.4601292465746178, + 0.27236773605307496, + 0.13391053715196788, + -0.0707245727470821, + 0.10533290138830975, + -0.41430500192671466, + -0.6146253633208668, + -0.07565853785077736, + 0.2873112183581268, + 0.19763908291483556, + 0.025289217606068948, + 0.5650198413315228, + -0.03177596319321907, + 0.47178475839752454, + -0.3376404735968601, + 0.1565700525179663, + 0.619363565614764, + -0.41176648767640234, + -0.5639973230652564, + 0.4077622725296488, + -0.44987823947881306, + 0.35603210909646155, + -0.47695021621245176, + -0.08920764799930925, + 0.49514145336165605, + -0.46132838158446726, + 0.6273527528799114, + 0.33933930574018123, + 0.1856935895974754, + 0.6484540891711945, + 0.5020567360206254, + -0.008600602344175812, + -0.17606033666768361, + 0.08076115847174725, + -0.6754668432677882, + -0.1965169216324818, + -0.6340389099287128, + 0.47298691033472195, + 4.8110903955778106E-4, + -0.4835605663017023, + -0.05272358313612613, + 0.5469515324214662, + -0.0634318311336246, + -0.6305802151614247, + -0.38993413396794974, + -0.5073390361072424, + 0.25868718476744856, + -0.20026069495369225, + 0.5971589844068668, + -0.016705898925582274, + 0.2176353021806381, + -0.05381937159668204, + -0.36715499033246274, + -0.13939243212930663, + 0.34592785196132514, + -0.2520749968394535, + 0.2943041179881072, + -0.29318815257459946, + 0.008299433131125467, + 0.28497619492162873, + 0.709945065924416, + -0.7050955575594801, + 0.14936036271406694, + 0.673579024411783, + -0.40253791490333796, + -0.055414774499555786, + 0.4228371397375479, + 0.09630637869562808, + -0.27354175466794306, + 0.010061522888500929, + -0.47243019110300594, + -0.5846321990649188, + -0.13811586044616386, + 0.09980596526301777, + 0.5438743390787117, + 0.682202106524642, + -0.6004405614599525, + 0.5868988130472317, + -0.5515815784809761, + 0.22794792392092444, + -0.1438663864279215, + -0.5413434964970147, + -0.056841417001691874, + 0.6189697191189145, + -0.4845515175274502, + 0.3730876239229053, + 0.21873218168740272, + -0.3037180886646952, + 0.6933304970518663, + -0.30133334507236315, + 0.43072055738942816, + 0.5351167047092076, + -0.5766436153252112, + -0.4260440834364748, + -0.5226516917708023, + -0.03258467766807749, + -0.4741318003089149, + 0.25196530851445187, + -0.3813360057932335, + -0.5100039674132659, + -0.18864397725868876, + -0.6008606974874313, + -0.18256382393724468, + -0.5115111058270595, + -0.2339901264639403, + 0.4743149819370698, + 0.46294339540876894, + 0.47338236673004586, + 0.7119655180777025, + -0.19967960773544424, + -0.07686490368459642, + -0.21445457858404127, + -0.38219894309872815, + 0.3405369394472, + 0.37205809215702, + 0.4778299137023274, + 0.119137472659953, + -0.43894807286317944, + -0.45936539963097306, + -0.714249434909103, + 0.5906075352426958, + 0.3903950379659613, + -0.5457064184296082, + -0.00846002137954227, + 0.28261010770126505, + -0.6797943866970944, + -0.37990407590713193, + 0.11665369432462747, + -0.6175787451347167, + 0.4854939389276378, + -0.5791951903167006, + -0.07732513634919702, + 0.39639874366974137, + 0.2786359612779272, + -0.13719267426602155, + -0.44481665952782135, + 0.17997061895198319, + 0.11568309051888359, + -0.16821875906122252, + -0.5641037655139813, + -0.40595724489995155, + -0.05428407467728891, + 0.14951267335785923, + 0.4091206742280682, + -0.4098364896037443, + -0.10718910774913659, + 0.6950282502627756, + 0.5966767891129932, + 0.28569033024798385, + 0.355168977167476, + 0.18892458971655413, + 0.14012381344710356, + 0.7238274775220359, + -0.392832281009215, + 0.557124710347598, + 0.15278965611960105, + 0.2563578187535741, + -0.23498396809042937, + 0.1156990252120047, + 0.39342335052882116, + 0.021032272423083254, + 0.19665976096295756, + 0.15198983339626604, + -0.18081910746324614, + -0.4924861638470828, + -0.389558392811154, + 0.5213289667013505, + -0.48707723143254694, + -0.3661970042110816, + 0.47576759516589906, + -0.4807347854413801, + 0.6871321130433006, + 0.15282344550397708, + -0.5761949473529971, + 0.5734226679664656, + 0.4347011427495744, + 0.09470882456429441, + -0.22355444237507882, + -0.42084247239184597, + 0.06094923653660933, + -0.14920746328095302, + -0.674056445728278, + 0.002808472031340714, + -0.4086373584360739, + 0.12135094064162577, + -0.6262519707156099, + 0.22830091477387626, + -0.2924775625502956, + -0.6800044902367288, + -0.20173558685455317, + 0.37338727229700663, + 0.6746279988653487, + 0.1994952369038896, + 0.05313535496654298, + -0.07974248864378697, + -0.6423362615344326, + 0.2001015936062852, + -0.00628578443717287, + 0.1778728398749504, + 0.5656657461259051, + 0.5334443171324055, + -0.22312987658895644, + -0.07320808612111107, + -0.2563802765767556, + -0.25399284760400914, + 0.26378065068225953, + 0.31142941842929983, + -0.7169810482672261, + -0.2629702243980847, + -0.7195746223334649, + -0.3289538301981074, + 0.5200810026096414, + 0.7197435501426399, + 0.21913257063653058, + 0.10295495517577613, + -0.27856238453753934, + -0.6188272457942313, + -0.31978386415469695, + -0.29163505979176235, + 0.05015560438986055, + 0.6867359253477214, + 0.143422104011668, + 0.4123112473582524, + -0.4998152645988235, + -0.3941865651385245, + -0.7168319627294719, + -0.4896465361196556, + -0.5617221626910779, + 0.03837822591457074, + -0.716151635768681, + 0.41169945398327434, + 0.06400394142522636, + 0.26357067151152214, + -0.7285771293270537, + 0.3884224063269568, + 0.21706126520072822, + 0.5575191737114897, + -0.0728225667043434, + 0.6866933818670493, + -0.4736837092463271, + 0.18037335056171877, + -0.19074847195968725, + 0.41229238680875335, + -0.1369124228331301, + 0.34951940867406295, + -0.1678185496345468, + 0.48934587769353444, + 0.24774403400955802, + -0.6284794330543311, + 0.7210100619284117, + -0.2483034613044633, + 0.4066078562121396, + -0.5539666816643912, + 0.016512822115595904, + -0.6863835942959364, + 0.3981962227647615, + -0.30991227020156253, + -0.17769210577826744, + 0.5534195886670839, + -0.013156863314255918, + -0.1369895125067142, + -0.00339857859563919, + 0.6554052730555195, + 0.1771117114917482, + 0.696775228607668, + -0.2752160026631653, + 0.15276529805679373, + 0.5973817333867473, + 0.5137145615586078, + -0.28217520888896763, + -0.6813955571074511, + 0.07018149727740974, + 0.4776951710802275, + -0.48487261682509053, + -0.3903679290790426, + 0.30572290037641836, + -0.30133373022227966, + 0.04891609548907683, + -0.5637224782659683, + 0.03200189635305606, + 0.36712416827782257, + -0.13295298206509787, + -0.3595436055542189, + 0.2661220818741943, + -0.5647109238676316, + -0.6618122767115504, + 0.10227024223688141, + -0.19188547982265514, + 0.5194851749749585, + -0.2867444128731743, + 0.5746771267839756, + -0.4332947673861449, + -0.1124124754664213, + -0.3818761103237956, + 0.48845095978519004, + -0.4735971003830455, + 0.4814002877274557, + 6.256932411291549E-4, + -0.6929190708302724, + -0.0614682408694861, + 0.4031777061210149, + 0.7089560424862054, + 0.3833471381798854, + -0.023189715986299153, + -0.28190917997253256, + -0.022354136266075075, + -0.47364018931993473, + 0.5185811150559818, + 0.5005992086365336, + -0.04183158834117706, + -0.5405842584974478, + -0.29875345179412716, + 0.4936377905382372, + 0.4170696172622965, + 0.004226178718428342, + -0.230873655122875, + 0.15342668637800005, + -0.4787458663044657, + 0.2642862886060132, + -0.4331717555779272, + 0.0069747555673678185, + -0.4935747657478328, + -0.16501322170929378, + 0.10938978046225156, + 0.554240332824562, + -0.27444292357612005, + -0.4432473204521233, + -0.33249518333858147, + -0.7284573070844362, + -0.4170029969771956, + 0.2653742917129809, + 0.24079364612951182, + -0.13248979223490254, + -0.41561171070841624, + -0.5272983136103785, + -0.6165843969967332, + 0.6739193606418368, + 0.35579375220720433, + -0.34627030282550364, + -0.09666562360672148, + -0.2998260270735095, + 0.30168776344546533, + 0.38550804308231545, + 0.6991082103509565, + 0.45592526436945, + 0.45168047520192367, + 0.6801015100854544, + 0.02539163635968833, + -0.5243649101570356, + -0.25908309660205364, + -0.06566516891750762, + -0.32496167128488423, + 0.587521606550758, + -0.3736153649611483, + 0.29461667657847146, + -0.6769910589658078, + -0.05683833975453345, + -0.18757874673823283, + 0.721061131087209, + -0.09139573077927587, + -0.6998780322807956, + -0.5604232108048091, + -0.5303825802590102, + -0.08975535742454954, + -0.2658503919195324, + 0.5376311128672671, + -0.03462899710927503, + -0.374348542571425, + 0.22295540816226367, + 0.46603307129474003, + 0.5642303315328954, + 0.5364363642348811, + -0.3618491821342585, + 0.23595867803517878, + 0.5655410499183837, + -0.47323741643983214, + 0.7219445336024319, + 0.5181683696163468, + -0.22638823474278846, + -0.6337551708206376, + 0.6261466146797645, + 0.27507646180930423, + -0.2369237815814652, + 0.4040389973696734, + -0.6051684815063922, + -0.462305929913643, + 0.4969438541603435, + 0.2978147186900073, + -0.16487539309073795, + -0.6159457051877145, + -0.061478691115474104, + -0.5078378676697227, + -0.6009527267366499, + -0.6171044898013096, + 0.6220494019419567, + 0.21859243261263517, + 0.6363907106311728, + -0.6639177846216807, + -0.20110776680732778, + 0.3530899665292082, + -0.16481589386581952, + 0.448862235660787, + 0.12687085179727953, + -0.47030123222915093, + -0.606811494440418, + 0.4880663841229691, + 0.3444826898774811, + 0.25612609159119504, + 0.12376118117461554, + -0.7283531701810323, + -0.6656135215813632, + -0.4683393105238971, + -0.0240840885818433, + -0.2174994653224006, + -0.24597802939659957, + -0.3475568840082577, + -0.09061769871082004, + 0.17408247710726166, + 0.5306912051208896, + -0.47232171206752005, + 0.23016547463861203, + 0.4540943045744159, + 0.1721745899224808, + -0.4752528124849629, + -0.26265250182909644, + -0.4959618200007502, + 0.07946228515489218, + -0.41245708059130776, + -0.570815747215539, + 0.13931214732505626, + 0.2694494522704284, + 0.6714601915584635, + 0.38337165494374537, + 0.6485765851229932, + 0.5201297980298489, + 0.5277962037261796, + 0.6575878235525945, + -0.6699091830330873, + -0.05005107803579223, + 0.1943964754000418, + -0.2956949145157592, + 0.14758003535568565, + -0.09133313794879527, + 0.5202486810521065, + 0.49846882787001867, + -0.7091066103604404, + -0.20904515197568196, + -0.048190594430077005, + -0.07634998552036043, + 0.3706975550462379, + -0.0050505608557444015, + -0.6652811166414923, + 0.6663009685130779, + -0.41886825826114443, + 0.5937784630343095, + -0.3884629107119005, + -0.19050305294236858, + 0.5060172178606746, + -0.10478466732247449, + -0.5796325228374151, + -0.5574579132906611, + 0.3920395900852429, + 0.49154909795676827, + -0.623876670330565, + 0.6785736441187022, + -0.44255426538515785, + 0.6713007277927796, + -0.37405162401123954, + -0.4202422896277571, + -0.25548887708769624, + 0.19735611997218228, + 0.17156062521133797, + 0.01536652218187673, + -0.5385011489414402, + 0.5908445559818742, + -0.3594711444190709, + 0.4329379554722921, + -0.176234103498916, + 0.267522094599827, + 0.20784303393598258, + 0.02849620211789805, + -0.26578873813288634, + -0.6297517976877867, + -0.03262025967705695, + -0.07212853103654737, + 0.6306076049124854, + -0.5087843942613304, + 0.20182614593110282, + 0.5673911971719054, + -0.028515894393830066, + 0.05946423987502614, + -0.4654554805386191, + 0.6439595172228039, + -0.3037758385798615, + 0.7272691634878516, + -0.40768075667985965, + 0.699744094129624, + -0.02916242615178688, + -0.5613040323738434, + -0.7275345642070121, + 0.5989993372583151, + -0.3704493676478128, + -0.21660861538352627, + -0.21775588389748823, + -0.05428118190020448, + 0.6411472528381625, + 0.10016908581383743, + -0.3824209773785032, + 0.24681683756316308, + -0.21496668965100563, + 0.4688647770504113, + 0.5478268823479766, + 0.35386860949726073, + -0.3887596097456987, + 0.4938432857128221, + -0.044552494601106774, + -0.534603101492747, + -0.4227106547976334, + -0.3282713082208058, + -0.2706660050050272, + -0.47173463384014097, + 0.40156013075853747, + -0.46437524820623244, + -0.6703061323691042, + -0.12131513393647353, + -0.7131441812540773, + 0.3373496574573638, + 0.2230642877392055, + -0.14165315985810345, + -0.5040359134741286, + -0.34678853399620213, + 0.2308194936454353, + 0.29258640262964253, + -0.6782696811808008, + 0.6839502183731134, + 0.2536237560187976, + -0.6292286181225134, + -0.09899648266899352, + 0.6608023193194146, + -0.3286630597945646, + 0.4386019092081128, + 0.1717804311654798, + 0.3149344524377653, + 0.24653704820175537, + 0.6884529546583411, + -0.14544242222612724, + 0.6304016321374957, + -0.6585496128623437, + -0.2049791171010622, + -0.584866102168527, + -0.4066480749935582, + -0.6121855379266247, + 0.4130361531112843, + -0.5291663181908559, + -0.4128211818226024, + 0.19435312374089175, + 0.22948347651951118, + 0.1430470226003122, + 0.5493397021966635, + 0.014585704978946401, + -0.20280285532676223, + -0.18718763406338101, + -0.27483763297862857, + -0.19515431267493533, + 0.581835219542306, + -0.4491433208922495, + -0.07228414370228853, + -0.004943671468050748, + 0.13977698685895723, + 0.3842693509721058, + -0.6656905783167394, + -0.29926906589694746, + 0.006680681203364958, + -0.324524110611646, + 0.3959372510743415, + -0.6206508972446293, + -0.14069280436729403, + -0.7188882616642369, + -0.40221515243546935, + -0.2849637964644157, + 0.0176203474541774, + 0.3360281685421307, + 0.4088303021929609, + -0.6557839594547094, + 0.522336762920941, + 0.3867642068643591, + -0.2333092728762683, + 0.14652100244203126, + 0.055482781541315584, + 0.6051844964946715, + -0.3095075754987584, + 0.19001609625850735, + 0.6642694336082837, + -0.3140435337211299, + -0.11051650923292666, + 0.1126853323286372, + -0.6761401496315065, + 0.4084269768660391, + 0.3927955120235329, + 0.6983268113606669, + -0.18706692469010422, + 0.6898325674832841, + 0.07705727790607297, + 0.26644641389737633, + 0.2075831393652129, + 0.29358324575489725, + 0.24823126128512096, + 0.5277898928041163, + -0.4452820831314486, + 0.0802196626258429, + 0.6135658616327064, + -0.19136588017822243, + -0.09075742744695214, + 0.6002154299176323, + -0.39586756269144535, + -0.3560686917276069, + 0.7093178031104717, + 0.7171801187237228, + 0.20015906071425948, + -0.058804063782038174, + -0.007388858553300293, + 0.21427384866501376, + 0.23000220703019114, + 0.0789918734262205, + -0.2709774204247314, + -0.46373099072793555, + 0.5763226009077826, + -0.17412236115241664, + -0.21564606507635198, + 0.6920914827464779, + 0.5541914031802457, + -0.01380429703089836, + -0.6320005412868661, + -0.672974379404826, + -0.6595568002746898, + 0.341311347890928, + 0.05478901270956571, + 0.036548704553281075, + 0.5089723830864776, + -0.6243241605054604, + 0.0451583387589104, + 0.32199672901026943, + 0.2500701167847258, + -0.28622594489113745, + -0.11646056925180148, + -0.2022284882091252, + 0.308401884682761, + 0.5058970486466896, + -0.5362674131947172, + 0.5737808629882704, + -0.45790995125981493, + -0.29681562998406774, + -0.055594181098540196, + 0.6275962589083413, + 0.5234133461524231, + -0.2747175493871208, + 0.49329095910121334, + 0.10421940401400365, + -0.3361547928586422, + 0.33330553872037094, + -0.3799125979851467, + 0.4665024669802369, + 0.5751519133298124, + 0.2406215802535715, + -0.18864528255103308, + 0.22532371266550633, + 0.45626700981420965, + -0.27095361902850956, + -0.4797576585333737, + -0.5784137839661432, + 0.32046889012606705, + 0.1269624363098648, + -0.2882403663817569, + 0.5668347202946433, + -0.18326588481153383, + 0.41908249739304515, + -0.5299923647410996, + 0.29307421391246624, + 0.32198482844404874, + 0.3433671857935654, + 0.023463716223066644, + -0.48836498098219494, + -0.30365831436731716, + -0.42814198684298876, + -0.09551354034111659, + -0.3018986019350952, + -0.14799653619758713, + -0.14298881414257325, + 0.12283125579395282, + -0.3872670670536338, + 0.17999512007759522, + -0.11109203740177931, + 0.4400528018863281, + -0.33445853403470377, + 0.22025457521853864, + 0.30702398665993647, + -0.22109953507222058, + -0.12512101001063936, + -0.3978000964779072, + 0.46771067234390573, + 0.0938777418913217, + 0.013114429632272606, + -0.29818557188053024, + -0.696720775783383, + 0.20016041117316397, + -0.6044746311652417, + -0.1496726402129347, + 0.6159878813553523, + -0.6355713283815715, + 0.6346556722636787, + 0.17787006483327272, + 0.7086700044987755, + 0.3324078943334363, + -0.6907334883761825, + -0.1696729405458106, + 0.17046691303858852, + 0.44757219811828475, + -0.6560999319774371, + -0.41994053584639884, + 0.6796751379920947, + 0.12618153865402337, + -0.40538465650411826, + 0.5040546478063963, + -0.49643833397859793, + 0.1134616494448587, + 0.5048429521987492, + 0.5254833844388043, + -0.6573143127618946, + 0.22450435411515923, + -0.10398387379297747, + -0.18515325292789453, + -0.5170355289015118, + -0.30292324863660736, + -0.6885935064717469, + 0.3752080101878015, + 0.7142914738250492, + 0.6258868812960292, + -0.40527257299874464, + 0.17783771364263712, + 0.6754338700122917, + -0.3397642086189893, + 0.19287350476873255, + 0.5576287792478747, + 0.44385745209438077, + 0.47984756366086523, + -0.06381882009334883, + -0.6208275912919219, + -0.6055105540841724, + 0.30198337674655407, + -0.3233799757625262, + -0.6781871339940968, + 0.3081099975232642, + -0.6664185056996441, + -0.691647972879972, + 0.29386147798470263, + -0.22826244554846253, + -0.7162578979356852, + -0.30987943188125494, + -0.4712605306967174, + -0.4255506731917876, + 0.3527956850806484, + -0.6553302643137049, + 0.6198451852494051, + 0.11916149871834025, + -0.017621515135773702, + 0.1382886932386055, + -0.04245652273570377, + 0.056410996679062686, + -0.5336412871803964, + 0.5255042787295865, + 0.6308790866608487, + -0.29458047777853535, + 0.16698565434269474, + -0.1444816718286117, + -0.2456244372120377, + -0.12809451993280163, + 0.287080981966523, + -0.07395530974561615, + -0.36641116130621604, + 0.3078431026224455, + -0.24842130870254353, + -0.24901628411291643, + 0.16169292737689844, + 0.4234938313287957, + -0.5512746488334785, + -0.10527095967319822, + 0.17232302817697787, + 0.42257691586605706, + -0.14470165454393036, + 0.3295423605974972, + 0.3291155605112652, + -0.39400008988624297, + 0.1727178210984207, + -0.12396659215886507, + 0.3240940839465172, + 0.20043795863482305, + -0.05489768135512496, + 0.36870788095799534, + 0.3018773218199142, + 0.0908038766616327, + 0.6704067274420891, + -0.06979260651000219, + -0.46462371359618565, + 0.13807403479051394, + -0.5176955218782829, + -0.20305448308396135, + -0.46811411197101366, + 0.6982616925037861, + 0.6747624235203682, + -0.42458270912314183, + -0.5273990026962999, + -0.11492325381790969, + -0.03086245828770262, + -0.4845190833538233, + -0.13243069878607672, + -0.6860563386574505, + 0.5974248210125632, + -0.37264257703845355, + -0.23671848053654143, + -0.48346729509498876, + 0.6489032772960124, + -0.2804096230392192, + 0.024262871029339328, + -0.5829104565195018, + -0.6303903967172787, + 0.2364621458977635, + -0.507973043863362, + -0.5667827073474279, + -0.30686031185740037, + 0.6072675528335834, + -0.5453147613272009, + -0.3663694623517208, + 0.7227203837407616, + -0.5185868021716269, + 0.508611864343931, + 0.42567377600894596, + 0.19583920091293294, + 0.4344447729623786, + 0.1005118754476736, + -0.41016175346580797, + -0.20466126472293822, + -0.5193087000168011, + 0.6607763302317682, + -0.04038163124340788, + -0.5262848689802506, + 0.05338262380348058, + 0.7141601020758106, + 0.45678225336795375, + 0.5461107850750435, + 0.31679512072739735, + -0.43266772032789536, + 0.6401259456932444, + 0.040158316159432994, + 0.542732780340786, + 0.7229051411025571, + -0.2349164191591771, + -0.21051524111330233, + -0.3602073783467451, + 0.49305289152391607, + 0.4125232805918415, + 0.5398515547361857, + 0.044710758617058755, + -0.1270270486331816, + -0.45476027515368506, + 0.2942590859085048, + 0.14899763830039114, + -0.33039258591843984, + -0.6244642122637316, + -0.13579003545020618, + 0.4791555188217438, + -0.665328443152638, + -0.2074687522481412, + 0.3674430364171839, + 0.6356602403003901, + 0.3479888204788135, + -0.5674828539433193, + -0.2277811408468604, + -0.13073782302913872, + 0.341016727709484, + -0.5885881443712238, + -0.6331698396746788, + -0.6257283569902625, + 0.5592061147463783, + -0.28751516452250814, + -0.15692447918457075, + 0.5390884428451439, + -0.7033125499376849, + -0.2520007913474737, + -0.35338693754685674, + 0.5373572404944644, + 0.25665966974950716, + -0.06834149165651027, + -0.5431135605815187, + 0.5514698421773405, + -0.3255061548684845, + -0.014776279935761694, + 0.12691981998657642, + 0.4415032812547841, + -0.390684356449274, + -0.17286478517751058, + -0.18796207056325265, + 0.09347197335693735, + -0.4392700492040172, + -0.23070391500259502, + 0.4754769858324428, + 0.5430000289995174, + -0.5032849125766448, + -0.3863846696945054, + -0.3042261336057074, + -0.4750560482391389, + -0.09489552844771554, + -0.6326648767247589, + -0.16781499395044908, + 0.20298690414581222, + 0.47812006638405413, + -0.4787723078792359, + 0.6608502848541478, + 0.5079244664633553, + -0.708410414758126, + 0.45007553252414634, + 0.2553858543169769, + -0.4018317053883751, + 0.02480283113327042, + 0.326611607918734, + -0.47739622813229565, + 0.4469006979563086, + 0.5407455311568783, + 0.25721011985952325, + 0.193405337714754, + 0.6766888052350692, + 0.46067188176458274, + -0.2963088522532355, + 0.09220659947260246, + -0.5912648067995938, + 0.31055285296193924, + 0.6742183525761105, + 0.5921670142582489, + 0.5204423062706338, + -0.037414180527190255, + -0.03216817450774356, + -0.5635026002400385, + -0.09572303170769614, + -0.5942147403418052, + 0.7230055002771831, + 0.2321286360827789, + -0.3879957129043579, + 0.5768489449540188, + -0.6969283076454749, + -0.2634329612701424, + 0.2995451211924578, + -0.18771511465033008, + -0.4643444136413256, + 0.6654985734302132, + 0.34173461600214416, + -0.19135518257383777, + 0.14187930619114664, + 0.3700740147234538, + -0.6479008820396088, + 0.08140390180248602, + 0.6599671561311218, + -0.16149621570423167, + -0.07481718750442212, + -0.009264892331415586, + -0.7197803519925514, + 0.570442203162105, + 0.6199566122808644, + -0.006253487801033186, + -0.17419188698944132, + 0.6578189025154755, + -0.5101901236354225, + 0.11974307688695518, + 0.3754951994498763, + 0.31233303309083316, + 0.1050298891283723, + 0.443237347398463, + 0.43478919064342847, + 0.6870670223730022, + 0.15331348581404325, + 0.6252792094586928, + 0.5968230992334278, + -0.3188822457040218, + -0.16722379641045837, + -0.21425239323579504, + -0.12152542145034373, + -0.0993637540580381, + -0.281851933948659, + -0.08466492934090886, + -0.6865319849314891, + 0.4893756763301327, + 0.6892048150701995, + -0.33836910004365056, + 0.701674914808819, + -0.005298655460294732, + 0.3726776593668826, + 0.26455220492250475, + 0.14090321638184755, + -0.12315403745436682, + 0.6797292715549603, + 0.12573436999805077, + -0.32228520830849106, + -0.7085426068550221, + -0.41420994206479794, + 0.3800074830746605, + 0.4528009394136616, + -4.163733166161476E-4, + -0.659487193092766, + 0.18017037947786796, + 0.4845987296418852, + -0.020272134319514468, + 0.1117765304037841, + 0.6144786659978292, + -0.5457924882988697, + -0.20623650306507002, + -0.7183441514300682, + -0.38764927269873234, + 0.07389894396316699, + 0.3396967155838577, + 0.20620735056874362, + -0.6073429569727071, + 0.008739300740248979, + 0.16951983776529223, + -0.36107578692810943, + -0.6951030869224541, + 0.517938113090104, + 0.17872006639912752, + 0.39433784346270406, + -0.68288016905383, + -0.45939956940137755, + 0.6592852301729906, + -0.024937785540627866, + -0.5973571688672941, + 0.31595053639712645, + 0.33601614629170595, + -0.19584924573063456, + -0.18733398589262273, + 0.35069954988250607, + -0.38851793539188817, + -0.2038263930713593, + -0.12916508917911917, + -0.23635201767878683, + 0.07295391735188095, + -0.6980933034311805, + -0.5658191605889741, + 0.3682680027956342, + 0.5233138683573271, + 0.0901056227421817, + -0.6348063743688643, + 0.20747227456280037, + 0.3571553943602368, + 0.25909901142846414, + -0.550616479863211, + -0.26987996715678286, + 0.15885431315252263, + -0.3074159599541724, + -0.44166635063244764, + -0.016717011166058837, + -0.638839877334879, + 0.05803067667234674, + -0.11747191741695584, + -0.4332492229385963, + 0.35331708989106936, + -0.07300714644363615, + -0.07003130153209047, + -0.08973641860772885, + -0.7283329508715325, + -0.6158947780583485, + -0.6427041210224657, + -0.2561977351859823, + 0.6569190979886277, + 0.5330130494386216, + 0.5189306899566111, + -0.38545739682338104, + -0.13499295682657864, + 0.5259158438360916, + 0.02523005334422901, + 0.14933603513673088, + 0.6297546413904938, + 0.16888442963877548, + -0.24049485592842396, + -0.344388541280789, + 0.06611314772766008, + 0.5440343059107653, + -0.45454227004903786, + 0.45384910325692207, + -0.5187465961534733, + -0.4918208746752021, + -0.22518712136624064, + 0.06456894298108018, + 0.2640781578947293, + 0.4755498029488405, + -0.31403542825530734, + 0.29599257295116854, + 0.23851528102857733, + -0.2653315227874921, + -0.07276951288873612, + -0.03396630333352069, + 0.1800709781179981, + 0.35156352745432917, + -0.4089055913562124, + 0.7075472722005358, + -0.4132429271353329, + -0.4577495190326355, + 0.6429098228230192, + 0.7080609582517297, + -0.49274862372564804, + -0.7210268396839304, + 0.301640545713699, + 0.33544348337334373, + -0.29360574399418127, + 0.4348030538872898, + 0.152193814731032, + 0.05628727389903776, + 0.23211357188559434, + -0.5224906263148574, + 0.320548574475656, + 0.6123062071305403, + -0.4690303453931071, + 0.04604268776122966, + 0.1365834627988315, + -0.2233628687010214, + -0.465248067606381, + 0.6909221865126012, + -0.577293584418457, + -0.42450929291498707, + 0.32678513606244897, + 0.6154026492971085, + -0.3462565122978351, + 0.481699874103672, + 0.4990907456374869, + 0.02269060870428774, + -0.6932813459122183, + 0.42840199359542375, + -0.34046321139607105, + -0.3066401200480669, + 0.6767762810220599, + 0.6155716979619319, + -0.011715741727117979, + -0.25175888329889373, + -0.7192879673077227, + -0.6591119860300365, + 0.44492300168789534, + -0.24711301281408654, + 0.2979731242276926, + 0.07431766376419868, + 0.22698418184550695, + -0.3434349899529182, + -0.43754405781206324, + -0.25659676432034517, + -0.4176831074390508, + -0.35381976178529134, + 0.5860477683165934, + -0.4949060260036433, + -0.6915413348075695, + 0.6354272862616017, + 0.32844916697431814, + 0.4280448532416756, + -0.5810083759590312, + -0.5595942671699904, + -0.16759831330764674, + 0.26167962763639663, + -0.6197842051312596, + -0.021758370227999757, + -0.2795708836618334, + -0.022156334097253816, + -0.5759126476467725, + 0.13810832578535004, + 0.20886397550387503, + 0.03611423504877043, + -0.16174495161614033, + 0.38040216790085557, + 0.2844053559732247, + -0.023117573004785674, + -0.5593677048953767, + 0.49520648811605117, + 0.3518093873870609, + -0.30365753010044955, + 0.101504011104667, + 0.37210086122136343, + 0.11242775516434955, + -0.24414063063291153, + -0.5535074331010603, + 0.5619658523346165, + 0.38618221451690893, + 0.6752745972769172, + 0.6616350751357438, + -0.10568619740402208, + -0.5725785452742094, + -0.5974408357531379, + 0.39531988907185545, + -0.05046592878778089, + -0.2016692037798009, + -0.2085099829106396, + -0.05086120094147939, + -0.38519997092787783, + 0.5824785069896461, + 0.7092631664385458, + -0.030458553422198165, + -0.32947037393517425, + -0.2318303373236294, + -0.5540034777845041, + 0.4379743673723955, + 0.4363810393065777, + -0.166947396641833, + 0.17139356799121086, + 0.317866199151265, + 0.3976370562549545, + -0.1976541303737136, + -0.16759478132616878, + -0.6549204707150411, + -0.553627538415201, + 0.20651819243711522, + 0.30772473845248105, + -0.42111329712352397, + -0.08809651648637229, + 0.7036307090499987, + 0.4561975015297097, + 0.6058969935960976, + 0.005420001795305995, + -0.698281947811213, + 0.08706789123211067, + -0.6396882487121266, + -0.5420941472638808, + -0.1478630710907336, + 0.6935696348858222, + 0.17512951282725164, + -0.40520424074030076, + 0.7113660851525421, + 0.11590663369086518, + -0.3010105653477196, + 0.1955839504015623, + -0.05619567332928643, + -0.33541957422901064, + -0.5634274694010432, + 0.16350668048632266, + -0.22762697933391274, + -0.5659010294346007, + -0.09382720721599236, + 0.7157887007505694, + -0.6506234540963822, + -0.46531685096366465, + 0.014258244453500213, + 0.09721307700299964, + -0.20355321191417697, + 0.43084787190568763, + 0.1133832856964827, + 0.038123298272715433, + 0.11033478939155261, + 0.330239640170644, + 0.2008415647176438, + -0.541729458351025, + -0.5443647693577525, + -0.33608575885432385, + 0.43789907126004035, + 0.7138413171593396, + 0.21126138211425294, + 0.42774285919558874, + 0.09426730854140075, + 0.19634154876155763, + 0.4485828861410992, + 0.6392628399909146, + 0.42980677365744624, + 0.5844784209050848, + -0.004366105109385843, + -0.08724143003120532, + 0.5584957504304597, + 0.31331762039848043, + -0.2568349310671943, + -0.5700931387606836, + -0.17615516183235247, + -0.29605196099932385, + -0.21781590410407825, + 0.44208122703577635, + 0.4194920858400242, + 0.6350795689111075, + -0.4608539146821501, + -0.7231126418682953, + -0.3559824595409686, + -0.421063487760399, + 0.2703318137559424, + -0.6644315662440757, + -0.06975935126173216, + -0.14127613402220052, + -0.4192702708136351, + -0.260692701330817, + 0.012725118919802547, + 0.6523071747126215, + -0.6765732915535889, + 0.1464757979190613, + -0.09601189652980946, + -0.06440692771079248, + -0.5234790797099403, + -0.33968329535806313, + -0.6960810841535411, + 0.08449195435987678, + -0.11384807733566549, + 0.6122904634641921, + -0.23909114393435, + -0.20719230679933343, + -0.5830403613762875, + -0.17705290878684843, + -0.1314796751754026, + -0.7193837411995238, + -0.5742180564855137, + 0.6049609866100176, + -0.3923012312733116, + 0.20171884995123235, + 0.5787648014963087, + -0.2777248691922575, + 0.4999964274499462, + -0.6968110796341327, + 0.6386154419653993, + 0.2495145933355566, + 0.19552383258056327, + 0.515659990448734, + 0.507226378219622, + 0.6485651379422623, + 0.03938765537748423, + -0.570068817288539, + -0.4281913275382835, + -0.5403249008469071, + 0.3401166165195808, + 0.2685275486572626, + 0.08680818430547443, + 0.3329386489120105, + 0.5654921947026561, + -0.5426782859333993, + 0.4268307765763266, + -0.007899758726876649, + 0.34347984129627096, + -0.709276482262019, + 0.5020764864051763, + -0.5518432674058151, + -0.7206753277629444, + 0.33446383491753684, + 0.5242362390238826, + -0.5424679962883125, + -0.18595383712411628, + 0.26054849727801166, + -0.24569356561300043, + -0.31320393488659326, + -0.3656825991736216, + 0.5719831484364777, + 0.49087394190083744, + -0.5231916190094621, + -0.6998346047540807, + 0.016182437887274026, + 0.6153785114457782, + -0.48741259263621717, + -0.233961453572667, + -0.6591606509719015, + 0.5775240116312463, + 0.5680234976764331, + -0.15035708860673658, + 0.2711663212810722, + -0.014604698019482942, + 0.4092138422066762, + 0.23438295684619115, + 0.07097590813895538, + -0.703709425296641, + -0.47552323366673754, + 0.29265638669825855, + 0.689064325951003, + 0.3823003554229829, + 0.19775023706145278, + -0.07987259190656082, + 0.4348252630039109, + 0.47671613749603003, + -0.15286924710905048, + -0.14932762712672043, + 0.04418044746009897, + 0.5674069063128528, + -0.19144679546387755, + -0.2723665750658232, + 0.6307026101574185, + -0.12009200418412713, + -0.38259502092078157, + -0.15377695624394683, + 0.40979759886620926, + -0.4544975899579134, + 0.620873620061893, + -0.6587610418569798, + 0.3940008954803138, + -0.20438689509651864, + 0.6784150946009968, + 0.615767467606291, + 0.0986839395506075, + -0.4388933469153374, + -0.6735723578307138, + -0.6833462470099336, + 0.05179838860243613, + -0.519864981237725, + -0.4115521576129838, + -0.1817509105693591, + -0.09763320918778984, + 0.5626726300824824, + 0.2246199294714616, + -0.47903423855661054, + -0.05421039704979791, + -0.758802422011968, + 0.2934767966752979, + -0.4357597011091418, + 0.5853222200881986, + 0.589439061949021, + -0.042228967485763436, + 0.09346394038109895, + 0.20121631466144663, + 0.5530021725445088, + -0.7820022614195979, + 0.3655565965018329, + -0.14496085244818757, + -0.7622606546982912, + -0.7103200315174754, + 0.3540193137664386, + -0.7029720191342886, + -0.4112024914289654, + -0.5767348799765781, + 0.45873213459429374, + -0.20382995356659428, + 0.0272120028180588, + 0.5112174833195492, + 0.47353136427253884, + 0.5945984950911599, + 0.1780240532173607, + 0.2631261642525452, + -0.07488013157195361, + 0.24932450935781436, + -0.25123070923166113, + 0.08248535527572431, + -0.27789452435253537, + 0.6361695279108436, + -0.6606189995897418, + 0.5699959390888721, + -0.2677888278169086, + -0.1668268649061876, + -0.5178164219428929, + -0.6062857174111406, + 0.12176296906692763, + 0.04390020343226919, + -0.5427330503380488, + -0.7353684962651468, + 0.09747829538369235, + 0.3553206600105069, + 0.39806661018537925, + 0.5122276286631048, + 0.40005944854806563, + -0.28142461901360516, + 0.18291115938655056, + -0.6959078895484415, + -0.269199418941537, + 0.29506476242508384, + -0.07207157600976444, + -0.3267711054201179, + -0.4000167835095919, + -0.10623602361191387, + -0.4887248583878462, + -0.21611056924166894, + 0.23050078230024018, + 0.3256318986497292, + -0.3556342698373696, + -0.24200224645623925, + -0.006250788221316972, + 0.038038505452386295, + 0.23155747989772635, + 0.3886059530585372, + 0.646549137588304, + 0.6560223239737227, + 0.10276512336765731, + -0.7136274202125182, + -0.3234443210889592, + 0.03202756986024047, + -0.284028669404902, + -0.6517398293919975, + 0.3497278889551888, + 0.38382517019774387, + -0.4090925929400717, + -0.21982061995993818, + 0.4759862231923685, + 0.06864127360052552, + -0.5620574706544962, + 0.027558000153159457, + -0.46876599764541504, + -0.5233725985131557, + 0.5426859741889621, + 0.20631796184527518, + 0.6491324106942739, + 0.2839208633885354, + 0.00563292392179815, + 0.5119882191244202, + -0.6396022966601674, + -0.27903237173162476, + -0.40782673527208474, + 0.46140314920196757, + 0.06740996554956358, + -0.2952841577979024, + 0.5680219599179802, + -0.5027692114587725, + -0.09684080123655248, + -0.4109840219091477, + -0.13958319503330385, + -0.38358259435054415, + -0.8028154831648873, + -0.4043117223946343, + -0.47230916625058783, + 0.058969456010117494, + 0.16445086630346906, + -0.1372738890583144, + -0.25031572521906786, + 0.41157313083718117, + -0.543175640257124, + 0.32608115526284276, + -0.5243177229890496, + -0.15130164387658485, + -0.04337360450323813, + 0.4642215553685306, + 0.6214143393574326, + 0.22788156717626362, + -0.5237312599076441, + -0.03718312722781936, + 0.2910991142106819, + 0.5213545867278341, + 0.1390186541309275, + 0.30007264960726465, + 0.05990354111425911, + 0.6326763543071606, + -0.6309794373264324, + -0.21371636002547034, + 0.35540718380566194, + -0.6554809054430891, + 0.2793178634046011, + 0.6194851513961802, + 0.10764424687252827, + -0.732127195520468, + 0.0524926572765787, + -0.04485637394260156, + -0.3656203586204217, + -0.3089515810547171, + 0.30011880118923184, + 0.008056857938439244, + -0.6894995501368425, + 0.4924576821081138, + -0.41002764168001105, + 0.27279352424053294, + 0.18345828217113536, + -0.3519064884916687, + -0.2988418120612286, + -0.7785573722597254, + -0.7515416748628421, + 0.37928407668944863, + -0.404477973344274, + -0.3867358741642036, + -0.49653643128464364, + -0.15159046876044946, + -0.15836988109594563, + 0.4298545943851765, + 0.520149649208497, + 0.3968952348190725, + -0.3260117534178106, + 0.06910586503739591, + 0.23106630287215413, + 0.43147805279818174, + -0.3879237573843486, + -0.6133348110607749, + -0.5892142175814905, + 0.010712257710879136, + -0.17819939445215394, + 0.15648691805157178, + 0.03714299644415964, + 0.5363434295231705, + 0.16280228955980103, + -0.7194710451722938, + -0.4781290931206146, + 0.484242805249642, + 0.4712097901304423, + -0.24364765437627367, + 0.11166472459671506, + -0.06719353234813363, + -0.29760463644929613, + -0.2414565095616007, + -0.04737138783972106, + 0.011096723474450898, + 0.5257392959630703, + 0.25327999186747674, + 0.6552489472900979, + 0.48850043278264266, + 0.3983407059644216, + 0.5642907402334728, + -0.5644446550705225, + 0.2322330254825239, + -0.010000643423106359, + -0.05908466289179892, + 0.4946286848441984, + 0.498972967515226, + 0.45415637195863756, + -0.33440019420118766, + -0.7516185198309601, + 0.10480845244189751, + 0.27129038573755293, + -0.11843259020809549, + 0.26878404118711197, + 0.3031715711387285, + -0.677195653076197, + -0.4862757565405449, + -0.07362036349745837, + -0.2335224014324696, + 0.25134360712823167, + 0.5494715300798351, + -0.0672602697192376, + -0.6865872699788121, + 0.5996684788665688, + -0.7880393429437355, + -0.2756730721838818, + -0.35782216999680444, + 0.61837777979247, + 0.26557949926037494, + -0.4048307658947597, + 0.48470052873398684, + -0.4920354323986954, + -0.36983327860720094, + 0.13519149893687898, + -0.14224077271508606, + -0.23243248296628782, + -0.6339686721014173, + -0.5659150423589333, + -0.35717358271151484, + -0.3369711888164919, + 0.17521367257906229, + 0.5915273203877139, + -0.4415773513713179, + 0.1917618158269162, + 0.5267896465592498, + -0.3657419976189678, + 0.2873853340999045, + 0.3885793274063961, + 0.16422351018398462, + -0.7367292701251379, + -0.04768250689982656, + -0.5793103687114085, + 0.27613925530707106, + -0.5225027807029476, + 0.2828016656796032, + 0.1857593770914192, + -0.588066268815504, + -0.052903518151069084, + 0.18809614794697338, + 0.33647609795774003, + 0.36067952442048534, + 0.5478869129337295, + -0.5911304298969753, + -0.3131456906182175, + -0.8070164766650566, + -0.27932665038379756, + -0.16888633653452667, + -0.43134668148904864, + -0.6149815013236324, + 0.629392748555106, + -0.5585854881420251, + -0.6711850072310593, + 0.27806411432667766, + -0.5865723003040398, + -0.4659318457251553, + -0.28240378783151054, + 0.6228486116684154, + -0.39298677888461664, + 0.4878524602843751, + 0.41260443528078816, + -0.6438576778842996, + -0.3608135400527468, + -0.04015502478367672, + 0.3194408650017396, + 0.16953829232329298, + 0.5859602140514893, + 0.4198378450582839, + -0.5818826419304749, + -0.6363070513059172, + -0.15928907367799505, + 0.6290908903482003, + -0.3601749420360275, + -0.47662759238892194, + 0.04812209966798586, + 0.42293138759298066, + 0.4305886935701101, + 0.5312020302052679, + 0.3195983399815633, + -0.13670822971714391, + 0.06935627043122927, + -0.37484652784216216, + -0.44460803294390483, + 0.587381784276995, + -0.28688290144187834, + -0.011787941136510827, + -0.43797293532152765, + 0.6568962931925718, + -0.3611661204940649, + 0.09131894423029674, + 0.6420853527638876, + -0.28559562890343615, + -0.42036915797558755, + -0.7657133144938758, + -0.1820956600859579, + 0.6225863922516092, + -0.35586036606856075, + 0.27139563676419554, + 0.44316807432020544, + -0.364949865206406, + -0.48123443350547906, + 0.21010921902357393, + -0.048805329137146636, + 0.02732465386938432, + 0.13713777682933637, + 0.34227877816569474, + 0.08734930654941053, + 0.5732506701628558, + 0.3176005746659921, + -0.7664634416468888, + -0.6406830082938871, + 0.07722663025521292, + 0.12881603049238421, + 0.27969227648118367, + 0.5906718814144364, + 0.6221844491996172, + 0.4833832466179465, + -0.53148328485787, + -0.5606533108700986, + -0.07427279588709645, + 0.41338180090317656, + 0.31715324733234496, + -0.5229576145214949, + 0.5645037112055479, + -0.12803608836705882, + -0.10544375087244162, + 0.46580744088201864, + 0.30151937096904435, + 0.26189342445298747, + -0.2223578404035491, + 0.4690896916608839, + 0.17490924316671774, + -0.4132445339303366, + -0.43885727860684964, + -0.32988536051865003, + -0.7994488565526151, + -0.6956427671709634, + 0.42028234534358544, + -0.410328727123899, + -0.7165174367258744, + -0.6226629041864504, + -0.7767193872493733, + -0.13017535350307252, + 0.21704777429458233, + -0.7162708305793032, + -0.30846571698586156, + 0.6167910187620617, + 0.3399442527032889, + -0.10064835338800326, + 0.2662247480154666, + 0.21967314698755935, + 0.3023713747286062, + -0.5172634059125967, + -0.5542683875506549, + -0.5978703480034648, + -0.0779348762953983, + -0.6081074751258904, + 0.4944752114969916, + 0.49420131690377345, + -0.2708791266316324, + -0.8058913184988435, + -0.18928587545921172, + -0.10794659895819247, + -0.2521819155265562, + -0.6125552364392275, + 0.34424745685400515, + 0.31502474101901246, + -0.6439629607809559, + -0.059540825782767204, + -0.3416636805729835, + -0.3717628429262871, + 0.2254835030080432, + 0.07503086873953435, + 0.22833493140845607, + -0.6571409161597783, + -0.37246181461678646, + 0.34674544463461354, + 0.1812226215975965, + -0.09138098946601603, + -0.2162406828948531, + -0.6030734133291096, + -0.5885402913054656, + 0.5743139397806415, + -0.5674142960838315, + 0.3615529950627959, + 0.0813539970981324, + -0.7987265324604416, + -0.0063867995209977435, + 0.173050080512539, + 0.17653953191100968, + 0.2341277359473236, + -0.5017982582915625, + -0.3445523783282629, + -0.7489389737003262, + -0.6975759354104263, + -0.4487727146102944, + 0.12930731157263886, + -0.7973920630300269, + -0.4070371622650498, + -0.7393858729413967, + -0.389348640946649, + 0.4395350671845172, + 0.3393144362701409, + -0.581430276531107, + 0.370568714458101, + -0.4716304394488731, + -0.1612480687311999, + -0.11135508052601939, + 0.15655797388103687, + -0.15551224447054646, + -0.1579613625199332, + 0.5170853573172237, + 0.37871664337277366, + 0.4298139155355566, + 0.5056272180984943, + 0.3849925999117262, + 0.6355992623440098, + 0.460305776804773, + -0.10090882754377739, + 0.15574563627341265, + -0.5687522228711869, + 0.44580341503693, + -0.07837681459058177, + 0.06416293545022067, + -0.39292333482247094, + -0.47664602215767315, + 0.027567337684918924, + -0.34148051194070383, + -0.4883296452524546, + -0.6514354746563722, + -0.19584195759548684, + -0.5176771358073835, + -0.5755706953135115, + -0.08679025989169553, + -0.5686109909977749, + 0.45257910051167916, + 0.42249183326707096, + -0.5089004791209494, + -0.5213612385396069, + -0.2142369922918479, + -0.04933672149907775, + 0.33059119931491654, + 0.06011960029922769, + 0.4282464206125923, + 0.31967097401179034, + -0.12007776210067889, + 0.3341135750547851, + -0.4337848682376992, + -0.2763585027800991, + -0.20660125153210962, + 0.5633095976207426, + -0.03330776769997168, + -0.007108468989926564, + -0.3494467646859112, + 0.6376025657825536, + -0.22843167197800762, + -0.6350297878508664, + -0.20434675383989243, + -0.4478721532803174, + 0.2503428255519379, + -0.782333810970986, + 0.6053076118074175, + 0.4521563051489058, + -0.44559171491948346, + 0.07604784884627658, + 0.35520961221468494, + -0.0763336996150743, + -0.4948899455063018, + -0.39043507626458346, + -0.3509054708743125, + -0.29440764721347634, + -0.6933730070020365, + -0.11858583834679237, + -0.3746311841835871, + -0.14728183073393186, + 0.3515619549724335, + 0.4785055741552192, + -0.1581899092658191, + -0.4467468127950527, + -0.2058573823563773, + 0.4674033374604806, + 0.022216487308391986, + 0.16818379864600086, + 0.4931267794425095, + 0.15236390837551095, + -0.5110246094660849, + -0.1321818299740617, + 0.5018613827584429, + -0.5625259234049966, + -0.08749889585374926, + -0.6348444768415737, + -0.7388275004069236, + -0.14855390437834415, + 0.5780765800689481, + 0.24727681093016762, + 0.4326509935888644, + 0.5297462854710208, + -0.13937091739497043, + 0.527926082782937, + 0.562490683472277, + -0.02587174240467216, + -0.1029817544166527, + 0.021599319583191723, + -0.5802077119531882, + -0.7816518902012686, + -0.06122049902983706, + -0.2382339298298195, + -0.18747102466420762, + 0.24852624695943037, + 0.3351337501978039, + 0.39596800823932743, + 0.1528840754240448, + 0.46543205922576025, + 0.05372573462059338, + 0.539452928016681, + -0.7418108344248174, + -0.44278685805515694, + -0.7825231048175048, + -0.4195534188838794, + 0.21762150425743332, + -0.517150118107554, + -0.01441454547987242, + 0.0016204987549606198, + 0.555595728873889, + -0.49406913913172146, + 0.053089109061856044, + -0.26671421776074744, + 0.24029777669533614, + 0.6576335394736975, + 0.090774008938034, + -0.04576157122764157, + 0.06500680897751654, + 0.24176364771808723, + -0.06172866045765657, + 0.2342052457012752, + -0.037732871379776545, + 0.5743988326150277, + 0.49504102382800974, + 0.5095553579117821, + 0.3416404522082682, + -0.03615173369000513, + -0.676158833069763, + -0.72746930427273, + -0.058741280355799064, + 0.45052951341568204, + -0.4833863126112252, + 0.15517546121805426, + -0.27895944614921064, + 0.6509781215834652, + -0.42990230289172887, + -0.716238676781893, + 0.5049205499397581, + 0.20324429872032435, + -0.31197975949455165, + -0.40896788232656034, + 0.0029110091792746706, + -0.07319698232653049, + -0.015128993011679914, + -0.11616417704253135, + -0.4055410040117586, + -0.21875928739194384, + 0.48695822684003487, + -0.40640449054873284, + -0.6982410234652283, + -0.6469996442084007, + 0.5985589344220371, + 0.30639199124156147, + -0.22284248025071707, + -0.7912692146343965, + 0.21717019622969425, + 0.22050675751422177, + -0.791939885371092, + -0.0700419350267314, + 0.1923360669171953, + -0.7287725066902785, + 0.11769445247816701, + 0.10513800407978902, + -0.0558648956177501, + -0.634345003279447, + 0.11450508951028693, + -0.3445021637975401, + 0.21017561285559883, + -0.4627038012599868, + 0.23201001506028673, + 0.4914448731306983, + -0.27607499511086175, + -0.3540197068902837, + 0.49300255213264255, + -0.3803870527052089, + -0.18064874410003384, + -0.48171236246960003, + 0.1269202536419225, + -0.501060506601808, + 0.14332101570212907, + -0.721596556904119, + 0.42399075590907176, + 0.2286415814218251, + 0.3036472094169981, + 0.2541125904403646, + 0.3783274840305112, + -0.40372546755490174, + -0.4085845655798936, + 0.45403205923336654, + 0.4890006989664676, + 0.2300658286131455, + 0.5466442573457438, + 0.029395806125493973, + 0.27825748105108417, + 0.002180137695481532, + -0.2857288314861439, + -0.7812574233236377, + 0.5652675585960393, + -0.13436080932283323, + -0.3199360595905154, + -0.15828467251676503, + -0.030468447555640044, + 0.07415374919217765, + -0.5159540027018603, + -0.09803877727822885, + -0.18221625738588387, + -0.03551316932192472, + 0.1748390903039928, + 0.15655111521567378, + -0.2852319698038963, + 0.27219424601306386, + 0.03180088501471179, + 0.4613393135371425, + 0.6184737130429624, + -0.24056408403522977, + -0.1600050446513871, + 0.6034402117632279, + -0.0098046785635717, + -0.35632136440599205, + -0.5634058149312995, + -0.2123800913029399, + -0.7036077804523945, + 0.07095525100926225, + -0.8003782414689555, + -0.6220584604702554, + 0.5329434971873664, + 0.04980250242733075, + -0.7342145476898054, + 0.5771763978281109, + 0.01968845490917881, + 0.120800469663357, + -0.5163224421823933, + -0.1757449261742554, + 0.059790793979866086, + 0.22167166424876072, + 0.6022391144771589, + 0.08173614155550246, + -0.4860202674595504, + 0.1212592389250261, + -0.6719819992110725, + -0.603187862035374, + 0.09777099944216394, + 0.355603384158829, + -0.40371672151880034, + 0.328289280896232, + -0.43258855000573776, + -0.44624543021841107, + -0.07658608882186635, + -0.16788030926380149, + -0.7182122965850626, + -0.2685284042882108, + 0.00939081251084839, + -0.28838550334639734, + -0.7701060977573823, + 0.25855176100419863, + 0.2001455970972178, + -0.4112605245672707, + -0.3398000397917175, + 0.5359004581816659, + 0.2539273845995217, + -0.07920086612667987, + 0.2323169692184185, + -0.7097980060908408, + -0.0012423625306735575, + -0.7345676172642325, + 0.046665091553287574, + -0.373937661040994, + 0.3954676514898964, + 0.5460953549735911, + -0.37839873329554746, + -0.0394127846947695, + -0.4419494870331962, + -0.43781463327500847, + -0.5192272401344031, + 0.24964120487541097, + -0.2963741710140736, + -0.8013313891692556, + 0.28049256159353575, + -0.47790877948633653, + -0.025476837387226614, + -0.23044957874177996, + -0.10958249029645739, + -0.7448205875620502, + -0.6131240299064048, + -0.09130874127123034, + 0.2857287319044769, + -0.1391835177486619, + -0.4859328398588169, + -0.7834986880952152, + -0.560736223629569, + 0.36395776918455447, + -0.26747810415199225, + 0.2051947399659212, + 0.09769075190950516, + 0.33163205373144533, + -0.19135124658286562, + -0.5900359669522354, + 0.0015952439673727614, + -0.22535367148849106, + -0.12180616239741116, + -0.45047298577226336, + 0.25405246190405106, + -0.10172057376767707, + -0.737285527102213, + -0.7575763584074334, + -0.6079388038843105, + -0.3507713123941528, + -0.7607583000960008, + 0.08803195961326815, + 0.5862713741250837, + 0.015970346762074872, + -0.38149311111752854, + -0.2813560005980683, + -0.25072610183800303, + 0.1433345066163909, + -0.8058781208698949, + -0.6034095953615473, + -0.7166945373345305, + 0.3075741855275095, + -0.40904509816647056, + 0.07522134271220549, + -0.03375926336822632, + 0.5049722275646865, + -0.2049707095742851, + -0.510728278769397, + -0.5676532708831079, + -0.5341016161514989, + 0.1158554463128949, + -0.29809049695818945, + 0.12618182060719885, + -0.3522180886826241, + 0.18528444243611075, + 0.24351955042477658, + 0.16538195755436136, + -0.5844680428741763, + -0.4452296682579553, + -0.4209751811665656, + -0.6085736545062788, + -0.46738805045967735, + -0.5143303642420678, + -0.2838902084453474, + -0.40849831051851254, + 0.317686889061389, + 0.19017943697676787, + -0.08639222392964108, + 0.48674795506605906, + 0.20298525860041916, + -0.7991980329659426, + 0.04672156762014279, + -0.09576938174280014, + 0.6150725013720061, + 0.5891961624719081, + 0.0453631357475196, + 0.3809894691000325, + -0.7728955888374, + 0.5320528093620184, + -0.5112519521038985, + -0.6572326783905027, + 0.504368979275171, + -0.4987918376822062, + 0.1836064387779872, + 0.5200909123729295, + -0.7390282454519588, + -0.30509611276327975, + -0.6696089457872997, + -0.13816434306649283, + 0.2428119042732254, + -0.47070775121599534, + -0.09165474287344655, + -0.19478722477483867, + -0.17015733570189717, + -0.2175139683265903, + 0.375825249780556, + -0.7194659254936239, + -0.4905753340738999, + 0.37400073340837714, + 0.4205876986261864, + 0.5335831161016352, + -0.4570076802383014, + 0.2557648520427033, + -0.4075336514732723, + 0.6522977018365194, + -0.7920863172494634, + -0.06612269974798413, + -0.002069184294965387, + -0.11639755192907997, + -0.4735329889801274, + -0.6881028400030471, + 0.27543881566863726, + -0.7125038774522338, + -0.7390719312548593, + 0.02235801309749652, + 0.40773816277588126, + -0.5249542418323223, + -0.7920407929078993, + 0.4341952877067433, + -0.3526146537574461, + 0.46894278400689615, + -0.7813802804629377, + 0.19103975583305421, + 0.09587042349223995, + -0.5044191679118063, + 0.39968100768895887, + -0.7551250426121333, + 0.5925348848744457, + 0.15805131636455183, + -0.4093934646365584, + -0.380800332901504, + -0.4579206831571593, + -0.31453751859608564, + 0.6387663455259024, + 0.16404898794932088, + -3.1498463430756907E-4, + -0.34105474556951954, + 0.43982419588678623, + 0.6245530569590841, + 0.1708481670855473, + -0.3129738239795349, + 0.4376709300300038, + -0.2927440167028119, + 0.09512875102206364, + -0.7444453219395235, + -0.44348734137714685, + 0.015374170191923109, + -0.4793978827369162, + -0.1745724670223734, + -0.6345708586151612, + -0.31263627000962596, + 0.3984394611472243, + 0.2589855708240346, + 0.650151347469282, + 0.3085958108704697, + 0.1412561784187364, + -0.10438030995973868, + 0.17490030322382166, + -0.0871862140368227, + 0.41527055488520837, + -0.22160374805196703, + 0.3852113561717855, + -0.008692758412074286, + 0.41620217585463626, + -0.17849284056064652, + 0.5304128011130395, + -0.7750203700338053, + -0.5665385878948526, + 0.5903872070266013, + -0.6255277294241397, + 0.5376390896734958, + -0.08824091255671163, + 0.05254327003096437, + -0.12784114324212514, + 0.633354913798485, + -0.04737782304611815, + 0.15436379750716067, + -0.6294845587681172, + -0.30276797995932503, + -0.6153684369091029, + -0.21844856335417673, + 0.3658382679685944, + 0.6331878902573284, + -0.32813172621394904, + 0.36677299361555515, + -0.7291477107083437, + -0.25362601029237564, + -0.4634425612006736, + 0.5841312106487048, + -0.10460139016181225, + 0.2362992483039873, + -0.6330709618426014, + 0.34465130934417, + -0.6626792288224572, + -0.766178967896262, + -0.46954605349659145, + -0.3069729161323582, + 0.07535262037757307, + 0.6172177636772241, + -0.21025308557986233, + -0.3823558230767732, + -0.1045656238988264, + -0.5189450809602756, + 0.30977247764431726, + -0.18905465143175548, + -0.08117140386687549, + -0.6631233897363045, + -0.5276897999334855, + 0.5163953416193775, + -0.018716148613351247, + 0.6299158950952154, + 0.5396184090052895, + -0.6038054838067926, + 0.2625196503937547, + 0.6288720568323883, + -0.38137236543398656, + -0.45050373338741245, + 0.3993724599262628, + -0.6118855581183533, + -0.27533771433623266, + -0.16415577733236608, + -0.6670139503243935, + -0.6100915659427907, + 0.313598814391325, + 0.3156219916713844, + 0.3649641795067352, + -0.022691728840721015, + -0.3862173563144694, + -0.252569548903529, + 0.13353335601430438, + 0.20877003255631543, + 0.33411835655300204, + -0.692539071735581, + -0.27497804699773654, + 0.13237733426689857, + -0.7080461584806346, + 0.17670584204808115, + -0.18813061889325222, + -0.21213982878116056, + 0.5589498010352408, + -0.1448144200157372, + 0.5801629183925247, + -0.6966166638199227, + -0.010355151981914612, + -0.6781525648743887, + 0.05227649631420905, + -0.4603203281129968, + 0.1512480780384552, + -0.3849408858786166, + -0.5313157967700564, + 0.37264299163308146, + -0.24844946238344756, + 0.5768767555685538, + -0.4629816983119276, + -0.05905495250332238, + -0.6277991852642829, + 0.041726711079052126, + -0.29190419237676735, + 0.03528038333860428, + -0.4684824715425836, + 0.42627734752978264, + 0.10519554866057801, + -0.35657623033840136, + -0.2195363418324866, + -0.06674588172245688, + 0.5734482171778347, + 0.02028561277877028, + -0.6746506301587126, + -0.5283612032830325, + 0.39543668283145916, + -0.5840278438190372, + 0.125829079921704, + -0.5069277706902977, + 0.5605621407287776, + -0.25922047425376293, + -0.058284470329559634, + -0.05588558754288753, + -0.7866501488451908, + 0.08179668073099533, + -0.15580542981434098, + 0.23432030338204657, + 0.3792962802825296, + 0.12503761806709912, + -0.007958331459044898, + 0.185337544540512, + 0.07012467326110317, + 0.04085682098538301, + -0.19587104432320823, + -0.5836238803612958, + -0.6099895458927994, + 0.2503568862079203, + 0.3568238724514513, + -0.5311011683872338, + -0.7549054784928809, + 0.3863800787015249, + 0.021398898888737472, + 0.5481787528152636, + -0.19845869310352626, + -0.32140810487045346, + 0.43090769444370347, + -0.7974580748215503, + 0.09458623495908358, + 0.6271736698954876, + 0.6074137106525127, + -0.59881837893545, + 0.11392054812709118, + 0.10145946862714794, + 0.4545056949927223, + -0.3458276845969578, + -0.6218282385511203, + 0.4986155302305698, + 0.5423404956373615, + -0.7108354764053149, + -0.6055974336986474, + -0.5912179333203156, + -0.4690573720084226, + 0.6141754710899828, + -0.28100242316468405, + 0.3682251383102556, + 0.0824281460129268, + -0.7838339970610338, + -0.2877106515198834, + 0.11536827495565505, + 0.436873157595827, + 0.018461822579350584, + -0.31949233680971606, + 0.3856047479128776, + 0.4372818385015588, + -0.41181664800236534, + 0.35162567130805467, + -0.3713243712662971, + -0.5864488114015708, + -0.7453959150091778, + 0.6528247940719903, + 0.3601041161468105, + -0.04205848491659436, + 0.5436618433354353, + 0.6206673105083603, + 0.09159986801631026, + -0.6299047924954095, + 0.43874289007830847, + 0.3159469443654005, + -0.13057999151087907, + 0.5739540112758773, + 0.22669912860184505, + 0.5879419028029992, + 0.051405701139080495, + -0.5320042539545411, + -0.18998737141870758, + -0.01661382830024971, + 0.5928683514780065, + 0.4208462167863166, + 0.3155740016764318, + 0.17241201123636818, + -0.6422863232248389, + -0.7450054611733831, + 0.2167177575501188, + -0.45708132576333227, + -0.34223101890053825, + -0.17525134827021294, + 0.5389128490225384, + -0.5653007886038537, + 0.6135254919560259, + 0.4214846721929416, + 0.4812088059259375, + -0.7245535635947117, + -0.7486558984845816, + 0.6547662743351131, + 0.21579383027222254, + 0.27287149701541813, + 0.3454146509444692, + -0.5009733303903208, + 0.1001309637709239, + -0.5446302067043254, + -0.754450798736934, + -0.434714469976221, + 0.04189984921099865, + 0.5851530287255257, + 0.3422709460730532, + -0.7280476114849611, + -0.6245577360216115, + 0.5636623113899905, + -0.20184122215995404, + 0.015314214279704919, + -0.1071442138770815, + -0.7459312151277527, + -0.46366450429481665, + 0.43801364937048637, + 0.6311067128666658, + -0.6927124974289931, + 0.48144950766301775, + 0.1750130708002008, + 0.4366094107646562, + 0.5384813509858325, + 0.06314835059000068, + -0.23158502574483297, + 0.0411014949006665, + -0.023001806409465586, + 0.3756723527940383, + -0.0929633900892739, + -0.3661618291625113, + 0.11247438321812342, + -0.010335155321305023, + -0.2346626564055846, + -0.6074247210751097, + -0.3550011093818805, + -0.3199025974387961, + 0.3094492661204383, + -0.6537355249163981, + 0.6213234737905856, + -0.7305137794802261, + -0.4163414487247493, + 0.19845182359167068, + 0.3301616256239167, + -0.7680439622313756, + 0.4125066071880842, + 0.1700546856792836, + -0.7305582285697326, + -0.29852522546649884, + -0.09819288467360965, + 0.41185202181565195, + -0.6147368415754991, + 0.29025465855743315, + -0.49839699243429886, + 0.19826895876614603, + -0.7402186623088383, + -0.5985655488637746, + -0.6187597106365201, + -0.11937850814831497, + -0.3551530527936301, + -0.6343957322278153, + -0.7430574862363035, + 0.08657982533732334, + -0.1574607933348039, + -0.2923634832275118, + 0.30384008073672975, + -0.3768613971960984, + 0.5708092031277284, + -0.6022174075588116, + 0.32540662147937527, + 0.5328087675361034, + 0.453178519288031, + 0.5246530367538754, + 0.09695872942924533, + -0.6390825948886486, + 0.5381610407199552, + 0.007642140331203806, + 0.40023225657981143, + -0.09562163808742707, + 0.3753409710201169, + 0.5039804758317664, + 0.447569561015252, + -0.32043898418726435, + -0.6990408416246189, + -0.04631471503771356, + 0.33901354120987015, + 0.4708290698128167, + -0.3401164795299312, + 0.468283096365382, + -0.28880248635966077, + -0.2377666886932822, + -0.1958187110340922, + 0.5688291802752331, + 0.04261277849537792, + -0.37029683856249085, + 0.3173786398120485, + -0.5886154695991402, + -0.522264920716582, + -0.5282741100770139, + -0.48384717835550306, + -0.28713947057916633, + -0.4454707653598717, + -0.7502310654510012, + 0.3244354790059022, + 0.26557313213813616, + -0.31962240247748497, + -0.2993100055443527, + 0.34731224250057136, + -0.5038014362492731, + 0.1998898653855522, + 0.027328322625116086, + 0.3885564872606607, + -0.37778760974931413, + 0.11249366898514912, + -0.15942154349695736, + -0.21812627101854087, + 0.08503155913139904, + -0.14645583813858942, + -0.32424341819004215, + -0.5370435676186769, + -0.1463320300714932, + -0.23297088358979678, + 0.2777345385123259, + -0.3899109394766677, + -0.6313114370554606, + -0.04430718603666162, + -0.390956767223345, + 0.35478837605582225, + -0.48706010444500414, + -0.1253587473616914, + 0.10580644356199076, + -0.5689643510691392, + 0.43283212620498335, + 0.2561389863448479, + -0.15277806350979117, + -0.3553778643775371, + 0.13219563683626168, + 0.3440774136826429, + -0.03317940204129388, + 0.1704546271344365, + 0.5079687606223048, + 0.36763510932389243, + 0.4345054251128836, + -0.2680847244105171, + -0.264272810350928, + -0.12835143008224048, + -0.7815180800655174, + 0.5667438509707169, + 0.508417431307122, + -0.7702148686511748, + -0.7427885217726937, + 0.2472097911886092, + -0.3369226839338411, + 0.2150753351963789, + -0.7944785115210358, + -0.3998210859700662, + 0.5365978551156122, + -0.2361399035237033, + 0.12302452017903631, + -0.5297435156487529, + -0.3149255872797417, + 0.5047101518229588, + -0.5968149782915888, + 0.0519844563529287, + 0.5381886901563472, + -0.08843127049539612, + 0.2779145516954816, + 0.29369372441648467, + -0.11145305664760286, + 0.20551629945039307, + -0.27928922942399137, + 0.6201857059634835, + -0.43740834562336783, + 0.07445801825223586, + -0.005286461193175551, + 0.41497872045553696, + -0.6616833664679135, + 0.14078340177458604, + -0.4249910651817229, + 0.17102794935959997, + 0.4023605742008781, + 0.10578475260500331, + -0.6125409151061613, + 0.35109029601770014, + 0.3919053664966624, + -0.30527905026139435, + -0.26821213028948576, + -0.11654426964697173, + 0.12144455853508851, + 0.31668776825952893, + 0.5283792882458446, + -0.012700349959462565, + 0.07387086983626523, + -0.6634806050704234, + -0.22941773764229478, + 0.44518953654437954, + -0.250287747380155, + -0.7531331963832071, + -0.3395425956393742, + -0.5079503256935665, + 0.06009823046984175, + -0.6378009646909801, + -0.7105491171283114, + -0.6896780189360239, + 0.26466138192136357, + 0.5776442774190521, + 0.29932360859023166, + -0.6179741265637362, + -0.34816052676303677, + -0.18264236527528732, + 0.4266224766011494, + 0.026667378538263176, + -0.05476686170676537, + 0.41458527754451036, + -0.7913971990954426, + -0.69947362983857, + 0.4524379241545943, + 0.29791787726145247, + -0.08257737861101788, + -0.23670693966474943, + -0.6347282309861921, + 0.521489050255057, + 0.13718584033920422, + 0.542483372235207, + -0.5926069094348736, + -0.6503576984521892, + -0.6987832328222177, + 0.5047902537318733, + 0.004984454547737438, + -0.4142950522873363, + -0.7607564210389817, + -0.3139617215658897, + -0.29187010699420735, + -0.1757050398773844, + 0.2087321013251805, + -0.38135586722483156, + 0.44896293366965223, + 0.12679116528340773, + 0.34953820877764097, + -0.014754513857092477, + -0.31803931508313127, + -0.751781156331612, + -0.22730262032602744, + 0.1029128415229601, + -0.4257132014456985, + 0.45226438028237836, + -0.6861300253624423, + -0.3873570840125936, + 0.44209921977328326, + -0.22730968951567865, + -0.7758229610042993, + -0.08447261017343066, + -0.415477302026921, + 0.5667826782943836, + -0.4732917462022489, + 0.506880250424799, + -0.3612023350188101, + -0.030015283309399066, + 0.5018379240721117, + -0.11696660359780187, + 0.3163743751592202, + -0.7925448888377893, + -0.02844841763446815, + -0.22929119760021166, + 0.40256357127622555, + 0.1398883462634436, + -0.2934643606026408, + -0.6221332514592222, + -0.4387870070912106, + -0.35745270909657195, + 0.27463001713572, + -0.3881369591827885, + 0.24516998997606898, + 0.5748984915411764, + 0.017524012606514705, + -0.26006482002601594, + 0.008761493180547753, + -0.35611181222028593, + 0.006266825075592397, + 0.3192393232427705, + -0.009394895870203257, + 0.22921417121045085, + 0.59583937978226, + -0.3554352068518551, + 0.580827447897165, + -0.7412341303003356, + -0.3410650621964998, + -0.271086940424612, + -0.7728638289934571, + -0.7949652667383206, + -0.2769084448371706, + -0.7298581318634962, + -0.2513416871147356, + 0.24081793373871185, + 0.10922624573112949, + -0.0541014680128884, + 0.6120877118536502, + -0.3832525219558189, + 0.2008919236515, + -0.48341067405614835, + -0.7471381265569967, + 0.3655200067475418, + 0.6187093261062563, + 0.38881150372716633, + 0.031271401843625646, + 0.295532724827931, + 0.10030913042000067, + -0.05787366880190703, + 0.5583650840968152, + 0.6139848070735011, + -0.40867510822012965, + 0.26463696046438356, + -0.7416661560681922, + -0.61573475710375, + 0.131707842161904, + 0.12753640043854642, + 0.42569074343917535, + -0.3656170934115125, + -0.29355234493750737, + 0.11173975765527033, + -0.5064443371526827, + -0.23433631711645786, + 0.09233029891183775, + -0.18776709841844874, + -0.12045885861396477, + 0.40810715411977305, + -0.5643484246887911, + 0.10469278480533706, + -0.6814441678625499, + -0.5711690513849196, + -0.5241944635987554, + -0.49088171486524174, + -0.757053241990778, + -0.6376521485102413, + 0.4948382914424251, + 0.6220426699959679, + -0.6698550169402442, + 0.18140562838347574, + 0.34378806080324564, + -0.35552753049126995, + 0.6146857484496909, + 0.4176165492800915, + -0.1830392727108512, + 0.6412114513750543, + 0.01620832456996668, + -0.035110141841141806, + -0.6369749135304877, + 0.007179542222735202, + 0.5706664907244606, + 0.005017989889955055, + -0.3891524916437782, + -0.7845154701430548, + 0.402724862901242, + -7.283920178804415E-4, + -0.11688282274256978, + 0.436263351612587, + -0.19942056701265354, + -0.4790632445365585, + 0.5573460215570015, + -0.22297603828519497, + 0.6435983065826715, + -0.2026175398875124, + -0.7366700341762881, + 0.10107755035309884, + -0.17488158946200394, + 0.24428938548914003, + -0.6620020297759469, + 0.40136827943785713, + 0.39537670456159135, + -0.3383067515348361, + 0.22936503695554544, + -0.6323956880335808, + -0.019680837275675045, + -0.41114340461276516, + -0.006079153603618659, + -0.46056925994615405, + -0.4852952584877976, + -0.06527374729458901, + -0.20377539628489172, + -0.040414410293211134, + -0.23227224366487542, + -0.42032557279863303, + 0.2412804747237255, + 0.02653928233948577, + -0.7497152721044097, + 0.4508265416195735, + -0.24141260433017753, + 0.5135487238403901, + 0.16992666428884617, + -0.6011131368532934, + -0.6289439763084249, + -0.3154987165515437, + -0.41736149653615784, + 0.4447500210146905, + -0.5042703193871504, + 0.06412719768042119, + 0.2573346816152403, + 0.0816130999350414, + 0.3173811058882693, + 0.29595060189892874, + -0.1910516600238128, + 0.20058294465688575, + -0.08875759841395958, + 0.21906864639643897, + 0.3341222761450694, + -0.10457063038753855, + 0.6088958670334513, + -0.3814243676201579, + -0.4459696542220709, + 0.22749825300538096, + -0.6041375498021132, + -0.5582657175219928, + -0.38017323106697853, + 0.22499579676831993, + 0.19014096094551136, + -0.1138260053394734, + -0.6180053406520379, + 0.5267459111385583, + 0.449816725231616, + 0.3328739356326661, + -0.12694868840695672, + -0.22972184981468757, + 0.16509000843691768, + 0.5308807079788641, + -0.7848958767782852, + -0.5200189520633778, + -0.18899472902424475, + -0.4419538354224838, + -0.20734758434328915, + 0.43167244970394913, + -0.03158284805617284, + 0.15641620518842037, + 0.6196552796422895, + 0.4865950154212809, + -0.43746850743698323, + 0.33703191804762456, + 0.024069191089879927, + 0.3220498372993984, + -0.5414703149501001, + 0.6218957564063855, + -0.6086988446610262, + -0.09476513102560002, + -0.20013479883119156, + -0.32525140909819233, + 0.5445371142718382, + 0.5196347106335336, + 0.31243055448163737, + -0.7156042549546292, + 0.35075583672885846, + -0.5907332284091602, + 0.22324977106503596, + 0.6002736576931554, + -0.008950797615311479, + -0.29170496224651, + -0.04213372176238195, + -0.20596651010797629, + -0.30007247611206533, + -0.12182614242094325, + -0.3784135732914046, + 0.6335056139990313, + 0.5205028417048007, + -0.09270015298453538, + -0.05443950613778026, + -0.7641970323606398, + -0.6735398289966051, + 0.18947756180560693, + -0.4579159362080438, + 0.48813223123288985, + -0.16265246177463555, + 0.1126229894898707, + -0.6360297248751426, + -0.2927025232442536, + -0.6840937736822628, + -0.6548247497091875, + -0.11501395039293116, + -0.4797994712157948, + -0.30573538003672884, + -0.7744636749637998, + 0.11909930656445433, + -0.42900391484143907, + 0.20477336658223855, + 0.1436518759231712, + 0.22533826866932138, + -0.18823160254279736, + 0.6311810118460576, + 0.05021909707046657, + -0.30906363530361547, + -0.4052689484693318, + 0.474919690272391, + 0.6518937621927136, + 0.499390714967208, + 0.47335063010639844, + -0.5236705038175987, + 0.50793914423191, + 0.6168312281312202, + -0.13504539768513957, + -0.7292783008742661, + 0.25461901234585127, + -0.6974536399702043, + -0.33829141480057406, + 0.026237742476862724, + 0.13034831743690956, + 0.2739140282246896, + -0.5627130716319532, + 0.023401507514204445, + 0.6441174471863319, + 0.04915254241253386, + 0.5250772177029576, + -0.581834339530509, + 0.548217217911601, + 0.5160297762441491, + -0.5094962729053174, + 0.560350282942229, + 0.015171073164488735, + -0.3615948755852992, + 0.384287327948437, + 0.21378475178238843, + -0.25591119674034835, + -0.3131489081832676, + 0.45009611302793673, + -0.39738519615533113, + -0.6034657730346928, + 0.020294324935732355, + -0.18223152398442366, + -0.17106100717195982, + -0.4967571302314775, + -0.028567925871977207, + 0.6068359881134128, + 0.16494710972655457, + -0.07616002106967545, + 0.4509537251912471, + -0.008979560624645222, + -0.7011438994726192, + 0.4030590451277264, + -0.30228397291847375, + -0.5574784249536384, + -0.6054375790120512, + -0.16933398829714508, + -0.23697173813014144, + -0.16254945688715017, + -0.3182135275910153, + 0.1286636100654961, + -0.07454361400722276, + -0.3585345163815771, + -0.12433736589135302, + -0.1032939965892441, + -0.315499568870803, + 0.023349709738075153, + 0.2812170771303433, + 0.12801110342474542, + -0.11648051226809819, + -0.39586674583531, + -0.3190725552444395, + -0.2810132834514293, + 0.3510154234107393, + -0.2002369507803894, + -0.0931895490849044, + -0.35279961062477094, + -0.049113610502525495, + -0.4344521670247625, + 0.08151386547298334, + 0.1556587699682328, + 0.00888049100517141, + 0.3462515952374837, + 0.3040401566178498, + -0.6909355718730885, + -0.6517889545747524, + -0.3454017159968334, + -0.3726017780538137, + 0.4106854124037246, + 0.35924662659337503, + -0.24531933456501337, + -0.401676444444175, + 0.2795725065206116, + -0.49549399723047605, + 0.16947129766167668, + -0.2824928300664756, + -0.21354695880056845, + -0.01556845788611605, + -0.018147818310230823, + -0.5241610601876245, + 0.18520739604038605, + -0.1180177329751384, + -0.45357627491598224, + 0.31817582207580297, + 0.340165724506568, + -0.2937967621884198, + -0.07810217316275303, + -0.1777676116651451, + 0.2531679439003466, + -0.26422783141088263, + -0.38005764297125394, + 0.04598413032024529, + 0.20018496036596867, + -0.6936902756687742, + -0.35220487898931224, + 0.34525652660440576, + -0.011299037561393499, + 0.36670812274778275, + -0.7019766174591385, + 0.2250075608430634, + 0.2782455844574979, + 0.3928480999763321, + -0.26913026317720273, + -0.5307192112023421, + -0.6505191466804601, + -0.505888717252615, + -0.3420328282559603, + -0.6312564911558629, + 0.18547888357554687, + -5.258905392778734E-4, + -0.016950593044684048, + 0.2986555801188119, + 0.07278602247513388, + -0.049774356246870655, + 0.17045517291380086, + -0.5278655685557092, + -0.4971329572410501, + -0.17216227389652794, + -0.009619597645491362, + -0.5164088368020392, + 0.24122034774637546, + -0.664015070143575, + -0.42114409835750205, + -0.15233394640567954, + 0.16025857111694097, + 0.24601920718710768, + 0.11146156864507117, + -0.4879590540014078, + -0.4134345640945945, + 0.17268674838563458, + -0.6224162553704259, + -0.2770153297314797, + -0.09052667464881137, + -0.03753618138625858, + -0.5959053002478626, + -0.45549732961337985, + -0.37855212645515113, + -0.19509923099425042, + -0.3291675365759759, + -0.2797856394004112, + -0.34910519453429456, + 0.05421448440538368, + -0.0706599207935884, + -0.5823402957446061, + -0.44276758499583196, + -0.677300103938786, + 0.20848625835767376, + -0.3775952549564716, + 0.0051347105455459285, + 0.36815281446356274, + 0.24111527912127095, + -0.26355825862648136, + 0.3206769505067736, + -0.039186782809589205, + -0.23337601483849624, + -0.4884240686270128, + -0.6185039572862462, + -0.1453378465337236, + 0.28856621384327097, + 0.23770063432018607, + -0.29641665552053625, + 0.014171051515559197, + 0.38770623695892226, + -0.6113057049869739, + -0.027426150011723105, + 0.16334022796047654, + 0.23970621613423182, + 0.019230571333441637, + -0.12029926540668179, + -0.6979159739289182, + -0.6642423952341723, + 0.1503531115472121, + 0.021102254338979387, + 0.2501621770807966, + -0.6827033638867493, + -0.06971574658475133, + -0.06127865877016159, + 0.33245745245345504, + 0.13312640807442988, + -0.6132161608831116, + 0.3754156693826908, + 0.214986941166746, + 0.004063006924723944, + 0.21678331026694986, + -0.2738783538122359, + -0.058631450935392904, + -0.029283421513292884, + 0.050699798459361234, + -0.07303926794688098, + 0.23985252759084796, + -0.21113496629317652, + 0.14430205381056282, + 0.12398985629326154, + -0.5697677242431091, + -0.23267961083524757, + -0.07698937281322982, + 0.18630926103013157, + -0.6964253672358951, + -0.2732917393096783, + 0.1860636821444397, + 0.12170813059744323, + -0.03887910648393644, + -0.28626526417109416, + -0.6133065095116782, + -0.07592521789453421, + -0.4661393178145659, + -0.2692731311851273, + -0.44349206333407637, + 0.1873922209211185, + -0.6012165096704886, + 0.39882011010636165, + -0.6276589447995504, + -0.16684604194724684, + -0.5043155287758172, + -0.3011362706047791, + 6.182928950426714E-5, + -0.5324339519975194, + -0.09409086626748164, + 0.20545629344026917, + -0.41964720227582253, + -0.6615299115743883, + -0.26170017007148233, + 0.3801621142412289, + 0.23346613936605276, + 0.324927081404475, + 0.2379952546805031, + -0.4711025326505498, + 0.20541643332762194, + 0.011327434639790912, + 0.4059608393760782, + -0.2628395373539663, + -0.4883973635314905, + -0.6203518067530661, + -0.013667919997689681, + -0.3682829908797452, + -0.2886877622577152, + 0.2776882168175073, + 0.17850623379693809, + -0.635070234251631, + 0.26991310630727106, + -0.5770877689563234, + -0.6819089364380764, + 0.08418263751119703, + -0.5558331518089962, + -0.1631744248658954, + 0.3941188510482351, + -0.19228088031234536, + -0.6888032825129659, + -0.44932734044350336, + -0.14322670950419747, + -0.20817795919492182, + -0.011522239764491515, + 0.18600796892611704, + 0.20686037807269486, + -0.05359651189105308, + -0.3363625945728731, + -0.4482164118256628, + 0.10300568964721402, + 0.3178368185323631, + 0.23316229972063418, + -0.14932216184810687, + 0.27995748060157966, + -0.4260757047581906, + 0.2833586463908955, + -0.360728239021434, + -0.4591780702417582, + 0.40087371171865904, + -0.3183914897422838, + 0.022459524590291546, + -0.5552599650205766, + 0.3575118207468583, + -0.2060029162588889, + 0.12488003734725672, + -0.17281831173916617, + -0.7018145442230223, + -0.2846378031794134, + 0.20875880701459604, + 0.11576534441314223, + 0.07719457455532874, + -0.013441282576179159, + -0.651324945620109, + 0.08490234043961353, + 0.2843899635778827, + -0.4366168852383602, + 0.3798077845306703, + -0.507308535038659, + -0.516308249066177, + 0.38628036531177423, + -0.6854102219301548, + -0.29756681940121077, + -0.4609079287279727, + -0.16625601107535704, + -0.25106185821366556, + 0.027986200921835236, + -0.19816640403641927, + -0.2024539693075449, + -0.4734556750419104, + 0.17276122924864146, + -0.42632390188125835, + 0.1773775068328457, + -0.10592753401768507, + 0.0075265291410774315, + -0.27995018945204764, + -5.29169671247165E-4, + -0.1841938090103723, + -0.3401442825159749, + 0.20863414230850874, + -0.16208770691626884, + -0.3694137347354832, + 0.37574542103005404, + -0.407066423439746, + -0.08074249199783134, + -0.09652536018453428, + 0.2976053151139263, + -0.09205392591881656, + 0.37946919858593053, + 0.010773217318186146, + -0.024584309690660833, + 0.351014749873498, + -0.4772408029166706, + 0.08151749069246184, + -0.4277893035764807, + 0.15830844851958104, + -0.3257749524856795, + 0.018384786319506463, + -0.3867583984967916, + 0.06348995580796268, + -0.21381576711838057, + -0.16054274377950273, + 0.07283246171623858, + 0.054881689835378444, + 0.40591931245814317, + 0.2910496362759515, + -0.3958903398619779, + 0.1412096155427761, + -0.3338760120658403, + -0.12033029251651306, + -0.5657436691534332, + 0.15219751545429894, + 0.17950961223752204, + -0.3100129316869786, + -0.49562047208326754, + -0.005938198036125053, + 0.3284098611382654, + -0.5103027325813387, + 0.06838597185376094, + -0.5804013285019918, + -0.1604434256631021, + -0.34541978925078376, + 0.04537969892256566, + -0.2661508430653749, + -0.3532179701185064, + 0.060909137593090246, + -0.46645801815028665, + 0.09893536289728311, + 0.1393068568207475, + -0.621521780985702, + 0.3603889861159547, + -0.2736956955176723, + 0.39538398194260094, + 0.18945147993394917, + -0.39048094193193517, + -0.6482192822519615, + -0.5201034430799477, + -0.25398494624814716, + -0.5476968784876475, + -0.23465179963580296, + -0.3068047403118221, + -0.0385823005689816, + -0.4030487379320165, + -0.08791594220722909, + 0.26723350195392637, + 0.27923475505971906, + -0.12477488733404285, + 0.09172831285089822, + 0.037723453533699325, + 0.1644926970788646, + -0.21716306084017561, + -0.33325435451041163, + -0.10417622503125479, + -0.22992558940521007, + 0.335458506437187, + -0.23304397227263152, + 0.15998261465114505, + 0.23128894232858466, + -0.6995773333429893, + -0.04577521311342114, + -0.39775384910704764, + 0.02714624387413822, + -0.33661244118635464, + 0.32985864277413557, + -0.6420595224481771, + -0.30786338988647016, + -0.025521620079939744, + 0.1644137551564, + 0.3253535260891015, + -0.670134864469691, + -0.4187468218737342, + -0.15510291517999042, + -0.6721927591100297, + -0.3292210962492864, + 0.24405106456159276, + -0.6024378939310748, + 0.1686354826006582, + -0.07666227753728261, + -0.1763042429928865, + -0.11924112660503938, + -0.49549751198398106, + -0.4404234722562272, + -0.31449428439134985, + 0.2429524981889597, + -0.014186909672743053, + -0.2500575012154166, + -0.42755492322431554, + 0.13655939815461493, + -0.367638449567925, + -0.2714923037108875, + 0.3016785165816699, + -0.40785460164575094, + 0.09161159838489252, + -0.3956064569777634, + -0.2322771495381732, + -0.34126929266661526, + 0.2117843541476231, + -0.4349189955277412, + 0.002319530620454202, + -0.008620859956774196, + -0.3884780414723412, + -0.1006905844820678, + 0.06547345457440024, + 0.29836506933699714, + -0.5303347692847384, + -0.36370537807891884, + 0.1541933203644439, + -0.506242854912629, + -0.17512028264947388, + 0.26831060006373386, + -0.6889754613970502, + 0.3003772622594022, + -0.31633800947352636, + 0.2469186828429849, + -0.24045230302986392, + -0.2800814316382597, + -0.18377609205162604, + 0.03376214183208115, + 0.3370123834607416, + 0.3439756654497187, + -0.45197810479456224, + -0.5559268726274396, + -0.34352049549127667, + 0.2982701161126188, + -0.1351938635389064, + -0.25921904394492484, + -0.2458503885486667, + -0.4195221502424128, + 0.2854855185429618, + -0.2825135240129763, + -0.07713549127859354, + 0.34611439220192, + 0.07531552063813007, + -0.41839223810022186, + -0.653523012200806, + -0.0826490812562588, + -0.14577313943840942, + 0.00896113646294805, + -0.6402329365355955, + -0.5717522907602499, + -0.274656807999528, + -0.5408699450139051, + 0.27028631732487207, + -0.2511764300736036, + -0.06132724156794789, + 0.2295308360436228, + -0.025353941035965444, + -0.20074344917373066, + -0.09112611233944501, + 0.013793932907944506, + 0.3053806697999045, + -0.06910183947525228, + -0.3097283619937729, + -0.4491236383365157, + -0.6522480677914633, + -0.12521615892278826, + 0.23984072802822176, + -0.2619771129885305, + 0.17174207190180957, + 0.3532019061909969, + 0.3160696840582421, + 0.14155943031147444, + 0.16258100445274482, + -0.506148798542532, + -0.39203164710602184, + 0.2083204269784713, + 0.37537271369656955, + 0.26940851866268, + -0.5295604434606785, + -0.6186533998984457, + -0.6164503461538894, + 0.41327445726631307, + -0.5390994765009973, + -0.040071192836395375, + 0.24467943484664434, + -0.5549301997678682, + 0.33513396161374975, + 0.08945009693412287, + -0.05101105988064203, + 0.1791985016889035, + -0.05490006542385184, + -0.09469259672599994, + -0.5569647489398709, + 0.2125323604438888, + 0.10719733507526763, + 0.17257332004151082, + -0.4319173551705631, + -0.6877300349252378, + -0.6288444471319501, + 0.16487238034913065, + -0.4753995102143641, + -0.5514703417821993, + -0.3971391083901975, + 0.07235484582470875, + -0.4130491103108409, + -0.6046160654286163, + -0.6658911115068862, + 0.33706828741847417, + -0.49567073212598467, + 0.3999881229125498, + -0.1990486101895076, + 0.13177782566521057, + 0.029145611335843258, + 0.2746550298652195, + 0.010579252228644975, + 0.3144754073193917, + 0.2663855763715156, + -0.13685396963697294, + -0.31075888062209567, + 0.3870377892733884, + -0.44671915233122245, + 0.2878299207874885, + 0.23982032873888304, + -0.6121262024992572, + -0.08791505052634652, + -0.011950058254645124, + -0.364209094451192, + 0.3632723554369982, + -0.49918743203035265, + 0.25158643613161413, + -0.3782554925040454, + -0.008819755147309372, + -0.5928018529483794, + -0.4766711367526506, + 0.059198443097987274, + -0.35145542283288805, + -0.2424287403376822, + 0.05183606567636323, + 0.0044124607362658885, + -0.16869646559394658, + 0.09801721636771887, + -0.4073286191370399, + -0.08063596535616546, + -0.6934958082477112, + 0.14299718518658433, + 0.1210016450936936, + 0.037330825843778115, + 0.22063694891918328, + -0.23219948451386224, + -0.1264723338208441, + -0.6373583952577221, + -0.18843146213532092, + 0.11028026383634926, + 0.35031282262068364, + 0.2852577049779893, + 0.39736231466709937, + 0.15713311618099324, + 0.2331076574776888, + -0.5296910252001858, + 0.3634075434343135, + -0.37791326905139316, + -0.464855500155118, + -0.3124604956132304, + 0.41728465966003003, + -0.3924223655815363, + -0.01706296906829141, + -0.4487461278790364, + -0.38629948205012804, + -0.1771449851127227, + 0.3834675883777189, + 0.16441433043107856, + -0.21630764643283595, + 0.2574358184357324, + 0.3653560195690039, + -0.5623930529058729, + -0.4529309214835349, + 0.14077441376288835, + -0.3616407799042873, + -0.38901305565115823, + -0.3786773219135412, + -0.16865391376972916, + 0.16343626956556434, + -0.2095136646917815, + 0.0194516985722617, + -0.07303029525403992, + -0.06785750630605036, + 0.21644644072585872, + -0.2849700047635852, + 0.14826801912280718, + 0.3813607411217136, + -0.12916785574199574, + 0.36865923362735675, + 0.3028252551179006, + -0.456624124830668, + 0.11211740333289766, + -0.19276967409352785, + -0.43949405317998197, + -0.4033609769686504, + -0.6172324982935643, + -0.25369599058131004, + -0.12785310544445494, + -0.4616096580287403, + -0.4826631039246423, + -0.4429858083382267, + -0.1255040944320599, + -0.5882226096762384, + -0.6437321311407904, + -0.2886812190651505, + 0.11416379886238337, + 0.298311881257301, + -0.5435685968666275, + 0.25894722019294847, + 0.2770243171229475, + 0.3306840387255817, + -0.09085453869757365, + 0.14688385530469084, + 0.14690870318038962, + 0.15884136885629863, + -0.5937772172392476, + -0.5100561524922727, + 0.3092074153362946, + -0.5432919636286178, + -0.1600185099650513, + -0.3684144433751327, + -0.0026241109391855755, + 0.20700155071148185, + -0.3424884308911739, + -0.2090960669140549, + 0.07428407120091596, + 0.1466886270871911, + -0.613274948900755, + 0.3064902015371075, + 0.4004306082714325, + -0.44331044654538604, + 0.12369306012504688, + 0.15034781301910294, + 0.10115580992909723, + -0.14773501527120025, + -0.3926261213443726, + -0.0701394479940397, + -0.3596930042000318, + 0.13717126863471563, + -0.6889664953881282, + 0.3872574160285721, + -0.228923920245447, + 0.29875162293274526, + 0.15438305401784747, + 0.28088009610028086, + 0.059646632783112774, + 0.17909509740678586, + 0.3992294036037899, + 0.32495729899706494, + 0.3572213967285188, + -0.49470875470210973, + 0.27717700350524055, + -0.37303159735871094, + 0.29998595929513383, + 0.0677165589233304, + -0.5579080862328576, + -0.3615843523686778, + -0.6423347663379569, + -0.6133507815507868, + -0.6841971278533461, + -0.534614863425937, + -0.5571080221844908, + -0.5537719649347068, + -0.6103235641433737, + 0.06070994092468063, + -0.6657455803005383, + -0.2912218242636571, + -0.6072647705616993, + 0.25026905944957467, + 0.07579816294350028, + -0.6238901679240318, + -0.3744040455086936, + -0.07529377950625704, + -0.019203073239693724, + -0.6623316689825955, + -0.11920139573952881, + 0.37918226956278145, + -0.38060774490190163, + -0.6219819430721941, + 0.37433072260063927, + -0.5692939600048944, + 0.05782929623167621, + -0.4189518207780573, + 0.18704880200332008, + 0.18103708288623632, + -0.3859167229662019, + -0.5308344369072249, + 0.31499724805704254, + 0.03690713742113605, + -0.6735470840717839, + -0.660942848204592, + 0.0973881785813211, + -0.4461549544060369, + 0.2695311847857279, + 0.361144219242847, + -0.6214763884238584, + -0.339776139045989, + -0.587709529804905, + -0.6956694241364589, + 0.15460762242939163, + 0.3739581260633772, + 0.09016315371398964, + -0.45989584313290177, + 0.18984318683536994, + -0.15455729998756695, + -0.2235548512319424, + 0.4177071876824948, + -0.5459171498556221, + -0.69661736467596, + -0.2537358741731797, + -0.30194106762252587, + 0.0965392245609713, + -0.2653102173943053, + -0.4096748236096164, + -0.3658012070439785, + 0.2723884590010711, + -0.2847203424682436, + -0.6399842287757097, + -0.1261062381924436, + -0.348266196759814, + 0.07042003569246202, + -0.30049577446994385, + 0.020603031471744693, + -0.6502835217521399, + 0.031242828907953157, + 0.28510128057271067, + 0.01349451507920918, + 0.13065110215885334, + -0.19473517417846453, + 0.19379820755662436, + -0.1843312360602657, + -0.6620193669340066, + -0.063046878258597, + -0.4490454789002669, + 0.4029815076858766, + 0.37223887351608986, + -0.19268592330090506, + -0.5461318341089568, + -0.34547007188091994, + -0.22471364695953405, + -0.36291080711262186, + 0.018694023715536523, + -0.5498396059069668, + -0.32099613558874673, + -0.5536222803239758, + 0.17689833069236582, + 0.32011565918286056, + -0.5879457608148078, + -0.2119050555085356, + 0.28500201522306057, + -0.5076593899770717, + -0.4232626478551743, + -0.6624138259424022, + -0.3126425884969723, + -0.6855505418896418, + -0.23800989786204918, + -0.170400441935057, + 0.021120678696635586, + -0.21474899980247547, + -0.11196484309446131, + -0.4255327325525052, + -0.4526498901604806, + -0.49537263336844206, + -0.3038172317986636, + 0.28939516712598834, + 0.31345322851229895, + 0.07246626550804769, + -0.16225950635348974, + -0.5090813864147972, + 0.14826504903791837, + -0.3184623107826686, + -0.15509134503096156, + 0.1162962964253822, + 0.12823519958227492, + 0.084800230579539, + 0.1698337748436659, + 0.05782551492579813, + 0.3646968922459589, + 0.1137449518647966, + -0.1917496881848033, + -0.4193073846559642, + -0.27562024180458866, + -0.4048903439852049, + -0.5844283507016059, + -0.11544875250451503, + 0.006201952463404825, + 0.034100123263759996, + -0.4213484921187778, + -0.41270351765952845, + 0.1876381293574546, + -0.6896186599324616, + 0.14640702208207912, + 0.052226691870783104, + 0.4008714255400717, + -0.29853187133317854, + -0.18179683396831026, + -0.3764341245333425, + -0.3049764047697996, + 0.2529162946181085, + -0.29834627219138166, + -0.5851436686906049, + -0.15452453913036746, + -0.39124687027561456, + -0.6796041833413478, + 0.08721913278284787, + 0.11671560689975669, + -0.457281032867889, + 0.22814223691090219, + 0.1151361923177574, + 0.09072310768919911, + 0.008264903328811801, + -0.28667611052916153, + -0.5221247425068524, + -0.18599920696036498, + 0.31513409446340523, + -0.2859846429555432, + 0.04775305987487466, + -0.18717156121934198, + -0.4823299628640667, + 0.09103541814450922, + 0.08249635254576404, + -0.28801172044433343, + -0.47993698958565756, + 0.11242583600521994, + -0.26454811966176106, + -0.28600467513493005, + -0.13834516839239674, + -0.5182435386777353, + -0.17665675623627908, + 0.09491662659997013, + 0.18440398104319822, + -0.2215914083447345, + -0.5398489385200477, + -0.4698383460602136, + -0.6123081844888072, + -0.36013777909046885, + -0.7006848561528152, + -0.23029812796060606, + -0.08358847647171008, + -0.333222127429511, + -0.292976882976256, + 0.3021253696513987, + -0.5502882424650664, + -0.6816264295469997, + -0.30222093650851944, + 0.0025862941857617283, + 0.28485426082404874, + -0.1364944540703742, + 0.2940390431853156, + -0.37515057812384356, + -0.3722825550114266, + -0.49840048223492783, + 0.22076712577755053, + -0.2561894099520757, + -0.16462795197375502, + -0.05627457745876718, + -0.3558508962720519, + -0.6010393877562694, + -0.44647935708699704, + -0.2162512962462914, + -0.17204616824465768, + -0.575537344141318, + 0.12272539242564229, + 0.13903311642943272, + -0.27049963489255363, + -0.6620677825043678, + -0.31035251048275975, + 0.3441489493037181, + -0.3550802398079024, + 0.17019921052520892, + -0.5009994630845045, + 0.1613482111917316, + -0.5818535310200825, + -0.18859826098826493, + -0.29411461351574225, + 0.34967686859732583, + 0.18817352994402337, + -0.26720441450104504, + -0.455170427023156, + 0.16381215874863853, + 0.057128083279991526, + 0.5779425653132095, + 0.6439705537967042, + 0.5652571475877366, + 0.6133337248158657, + 0.47447782724622894, + 0.5921644994807571, + 0.5496031465570355, + 0.5422027161842274, + 0.5134108923608844, + 0.6718052882467412, + 0.5255133568214381, + 0.4294863673123209, + 0.5721092824359152, + 0.5185972764154879, + 0.6246539409545555, + 0.5844848664617269, + 0.49951373839820923, + 0.4375939588210674, + 0.6725197131668648, + 0.6424281543874679, + 0.4719908310594352, + 0.5249882048773278, + 0.4514132708830425, + 0.5725886406375031, + 0.4948104298169378, + 0.5959399948047035, + 0.42445999859002503, + 0.6699252938806572, + 0.43155081939585277, + 0.6419727286934089, + 0.6402660941239895, + 0.6044199529354389, + 0.4349903463198891, + 0.48704977242227687, + 0.5748685305025525, + 0.6440750973931403, + 0.5747789146990099, + 0.4295332635382282, + 0.5186474349114933, + 0.5219013462767729, + 0.5699487637831819, + 0.5464137260627577, + 0.44745712498577417, + 0.5473644069365604, + 0.48950244001033133, + 0.4519726714783, + 0.6561008570583636, + 0.6087939260020652, + 0.5910886531573347, + 0.6483426624212391, + 0.4499995188003953, + 0.42428604199756176, + 0.6391756262094748, + 0.5085816694325153, + 0.42842395102687736, + 0.6298675828298803, + 0.5633311434017048, + 0.6213358156203891, + 0.5633776360494829, + 0.5692437811854734, + 0.5972282058538262, + 0.42997963886770485, + 0.6641943928878217, + 0.44227129345994576, + 0.5799627998837689, + 0.553579220176923, + 0.5469233039119461, + 0.5115001597302199, + 0.594200974906151, + 0.4911386140193395, + 0.5327685367632135, + 0.43762556681044773, + 0.5280415485346921, + 0.546938689406345, + 0.4430324055046413, + 0.5741556832523527, + 0.6248597312628457, + 0.5318475996630727, + 0.6524810150257707, + 0.5866744982510367, + 0.5002990459348203, + 0.5231666116154559, + 0.6204837286277582, + 0.5389128270385158, + 0.641750228315416, + 0.51204735949476, + 0.48234449423392256, + 0.5398022256865876, + 0.5499558346621722, + 0.6551053591681905, + 0.5289337037872017, + 0.5555687955324681, + 0.5196324485509445, + 0.46865350855760324, + 0.4437482592929627, + 0.5753946124541774, + 0.4735043677169636, + 0.4240591086365346, + 0.46052855778067164, + 0.576544154388041, + 0.6517755215794987, + 0.46386519165446644, + 0.6724169258006052, + 0.4350995883792854, + 0.5254561156916678, + 0.6018316709819317, + 0.6023759071883996, + 0.6428868399612621, + 0.4954640579979236, + 0.5379385859275558, + 0.4679242318471965, + 0.6144798432067886, + 0.4657266302773468, + 0.602628290005263, + 0.6193168848570574, + 0.5331613240495422, + 0.4286166760187622, + 0.6490944338570694, + 0.4860393681864434, + 0.6037704343358766, + 0.5470707897004365, + 0.4348475918677409, + 0.6330245444595658, + 0.6580951702441901, + 0.525761999765382, + 0.5415550494651035, + 0.5662443612123158, + 0.5627668893055788, + 0.6606828517547385, + 0.4234960046211018, + 0.5855306371630796, + 0.4919432776101699, + 0.5677733423200912, + 0.6320097342685249, + 0.6244590051743719, + 0.6694859109317959, + 0.5080189658856744, + 0.44379046830004243, + 0.5531705137684269, + 0.5403977869240999, + 0.6401591420151709, + 0.640653469443078, + 0.4791421577030953, + 0.5792820375176726, + 0.5384756235410184, + 0.5039950982112772, + 0.43693143755155694, + 0.6213199591325702, + 0.5611983261123538, + 0.426843019337323, + 0.6742385771643613, + 0.6054885660266494, + 0.4936304932205403, + 0.6745748277809476, + 0.6521901787097825, + 0.6321176718935841, + 0.43107886115050803, + 0.42006829423691655, + 0.4796110403522711, + 0.5307703966469114, + 0.4377094104639722, + 0.6253994523895243, + 0.5568117367553209, + 0.5192105090174995, + 0.49482804796408675, + 0.47774706736931466, + 0.5600569613271126, + 0.43055566958552544, + 0.43603323550944934, + 0.5988533558872381, + 0.44864897684344723, + 0.4689239801562637, + 0.634839265605339, + 0.4326038196430433, + 0.6743253091031791, + 0.43415282870185, + 0.4249980077165624, + 0.4386626792544888, + 0.42896473360543763, + 0.6581408473288961, + 0.5040411840876557, + 0.6400417576964512, + 0.46295882720478937, + 0.448696488321082, + 0.5223260347106409, + 0.4426889741575391, + 0.6313615494032425, + 0.45237019549616514, + 0.5721314194720034, + 0.667351716381194, + 0.5588826505919386, + 0.6011739176634275, + 0.44762156709301504, + 0.6221933317752357, + 0.4422481312671818, + 0.565928529647885, + 0.46095714402597937, + 0.5777736428438409, + 0.509303689243547, + 0.6748536745417312, + 0.41948882008504146, + 0.5158233419431135, + 0.6482223909632493, + 0.44255628520410223, + 0.6317062194409189, + 0.45616233156034586, + 0.4771284623381092, + 0.5875666535236956, + 0.51465319171075, + 0.6435350815154633, + 0.42016374316225047, + 0.594554164007632, + 0.4229816477345631, + 0.5640559868402435, + 0.420159612450993, + 0.5910097108754021, + 0.583584260123412, + 0.4848034281943342, + 0.61801915303778, + 0.5156982037201063, + 0.5140615790919251, + 0.5636684877363076, + 0.6744503886275859, + 0.6622330502541035, + 0.4916574580521237, + 0.5196556743161692, + 0.5761891610346607, + 0.558392043832338, + 0.4431549074249609, + 0.5363091178732162, + 0.5688096250670465, + 0.5735751509517875, + 0.6684985649722165, + 0.6278687316925267, + 0.4872847864593808, + 0.5397530822751104, + 0.6237577906950712, + 0.49519824860732653, + 0.5302921601097917, + 0.5663995944537632, + 0.5873038041452715, + 0.608268566897915, + 0.5554355810588748, + 0.4368285747952263, + 0.44090683133464675, + 0.6268705837733707, + 0.451450550852859, + 0.45442188622854485, + 0.5611315339932366, + 0.423859599124376, + 0.49894412608146443, + 0.5679755375186117, + 0.5185860323830859, + 0.5914379195430136, + 0.6538395034097455, + 0.5419234757148846, + 0.49588915988542553, + 0.6019075369521769, + 0.5502478434039698, + 0.6391015991910791, + 0.5304924001575865, + 0.593813529798428, + 0.6706321052896864, + 0.6512687654774597, + 0.44343036812820114, + 0.49631402471012775, + 0.46744606993041166, + 0.5609020756006207, + 0.4731675256495215, + 0.4211734296295701, + 0.4682949387576446, + 0.5808007444000103, + 0.5996343542796293, + 0.4396429463412783, + 0.5686351713193514, + 0.43295742718027314, + 0.42147568396603613, + 0.6633437019617325, + 0.45806164086780077, + 0.575770723679832, + 0.5872432619059903, + 0.605640248435941, + 0.530017516345671, + 0.5082676761701408, + 0.43669586115968395, + 0.618748967568082, + 0.6567444654542223, + 0.6477110129159571, + 0.6350356838814479, + 0.5869802247573116, + 0.5656846006055686, + 0.546457287224236, + 0.6304346203135788, + 0.5829180058712988, + 0.4418391451146105, + 0.5928204580266738, + 0.5828894509545818, + 0.511788409316098, + 0.652614149660203, + 0.43651827017522177, + 0.492987739799886, + 0.43233728593903653, + 0.4710867840083012, + 0.5931528660985692, + 0.6662117688886626, + 0.6306303121729, + 0.6655057720437917, + 0.5562095834663906, + 0.4724263793246081, + 0.4370109791627369, + 0.603613523893892, + 0.49935847469511446, + 0.5586734759035676, + 0.44984093429294153, + 0.6057017070468672, + 0.5912633926005133, + 0.65977812604903, + 0.5340952106550568, + 0.5666179446537236, + 0.423549871083612, + 0.4715347456588524, + 0.502937700401244, + 0.5429083943684312, + 0.6640205686678792, + 0.5005231112683645, + 0.5215260991551054, + 0.6533759755336583, + 0.4664693567663054, + 0.6043346622383458, + 0.5014030943059662, + 0.5676264277006591, + 0.6111646576726006, + 0.5234881779025315, + 0.44732589127820177, + 0.525622337214773, + 0.6592872900005924, + 0.5668168513429955, + 0.5107070427193491, + 0.6146639613823004, + 0.5455085859847784, + 0.46962125626736423, + 0.5948096602000557, + 0.4461260142305585, + 0.4896995738793779, + 0.5569841271611292, + 0.5447845830463482, + 0.6642425487516881, + 0.5600363314758106, + 0.5401776183376693, + 0.6625219940749861, + 0.5862584765728798, + 0.44616187341623315, + 0.6448793691833665, + 0.5713730868921391, + 0.6079594483779706, + 0.6639220656427156, + 0.4855565925445031, + 0.6733049868430641, + 0.6138248000536257, + 0.448392190619243, + 0.6588954200574442, + 0.43977386669409546, + 0.6443197367358461, + 0.6132859403077117, + 0.5320373444675652, + 0.43287675415525145, + 0.5252038470224653, + 0.6033450440936889, + 0.6166595092033813, + 0.527726840393649, + 0.5401175149705322, + 0.5049807667330133, + 0.5414671555833679, + 0.4779231672943125, + 0.5962367902006497, + 0.6354856646771282, + 0.6047582145918826, + 0.6325616996403229, + 0.623643906297046, + 0.5399126438770627, + 0.5803661973841674, + 0.4443227082624155, + 0.6607714419119123, + 0.46637438003909076, + 0.6373336912809238, + 0.6683672820985256, + 0.6236991603702745, + 0.5322542936174705, + 0.4759165696913342, + 0.5971998531887247, + 0.4887027634402013, + 0.5403343085228159, + 0.60822134781191, + 0.5994992373244357, + 0.5882387737432092, + 0.43561821319591026, + 0.6001826373625665, + 0.5537325663404746, + 0.47133398128107, + 0.5793673083013624, + 0.5806446161547452, + 0.4804276258064229, + 0.5303998341273229, + 0.524406632001299, + 0.6091742298994234, + 0.48252208812167513, + 0.4887094263994116, + 0.6524797172565195, + 0.47166465832250026, + 0.5217208857586941, + 0.5616368319236871, + 0.42453219583994584, + 0.6222917924943577, + 0.5915123513266984, + 0.6316566764791216, + 0.46847068945545745, + 0.6734825530022559, + 0.5076155869997369, + 0.6565654086694616, + 0.5336339967717157, + 0.5584779074423735, + 0.5651010065252706, + 0.4591291187341617, + 0.6203557935785269, + 0.6160707726221597, + 0.4803700105499507, + 0.5661940446282346, + 0.46523714564185265, + 0.5048314286458779, + 0.6707079658368352, + 0.6165153278273929, + 0.6265064443788075, + 0.45185466946840896, + 0.4431405864009634, + 0.6435203058292901, + 0.6375248852640913, + 0.5773705991589192, + 0.5649983869134625, + 0.5463433332523473, + 0.6657122812749052, + 0.6176562370645335, + 0.6205723749793204, + 0.41792874301155786, + 0.5006424078147248, + 0.6312239351015735, + 0.45951885756101246, + 0.5870767715229919, + 0.4521134283721228, + 0.4653871081297259, + 0.42139137609052596, + 0.5677604266562928, + 0.4358234088712175, + 0.6215626947715761, + 0.48155608401041833, + 0.5011670032874367, + 0.4557408747862781, + 0.5199415495954155, + 0.6053221637023009, + 0.4954802273204102, + 0.43982158698494433, + 0.5735818458836688, + 0.5554705365299905, + 0.49467083341683127, + 0.6185038587461522, + 0.5523805861647428 ], "y": [ - 0.8327792199010597, - 0.842165513546451, - 0.8436336956688811, - 0.8375806986990764, - 0.8440556119926065, - 0.8316424345593194, - 0.8301736779976755, - 0.8390281513961286, - 0.8479125952111829, - 0.836974286272967, - 0.8231808736518638, - 0.8444651041225978, - 0.8563348657693687, - 0.8325071025583624, - 0.8347290462839712, - 0.8246561378691087, - 0.8515170917905176, - 0.8233723838652922, - 0.8501024368451667, - 0.8530103608075055, - 0.8410744660268898, - 0.8387762845502543, - 0.8436833143541571, - 0.837878398958661, - 0.8212752740819541, - 0.8345471132860642, - 0.8267657000272743, - 0.8478322269740088, - 0.837850787204643, - 0.820034393391647, - 0.8486164521012235, - 0.8492158952809298, - 0.8278311021250901, - 0.8393594785971319, - 0.8446434729372418, - 0.832070158532396, - 0.8480791315931384, - 0.8514673318243295, - 0.8504893651082784, - 0.8435621020400943, - 0.8225015796207323, - 0.8513620216276446, - 0.8517576058421537, - 0.840487829110072, - 0.8449043062902718, - 0.8233306505174446, - 0.8233540129789705, - 0.8569705709356759, - 0.8415728484593088, - 0.8250174407220172, - 0.8208449658562015, - 0.8414877402161995, - 0.8293556939538771, - 0.8408927523538102, - 0.8250552100711683, - 0.8418001767233182, - 0.8541731301881036, - 0.8335539435559275, - 0.8462282279199426, - 0.8277984632494545, - 0.8320094601793414, - 0.8495628428750641, - 0.8322106564323799, - 0.8226082140368741, - 0.8551709333197791, - 0.8424153445827497, - 0.8562391242122903, - 0.8493563665331109, - 0.8437902329269884, - 0.8308313231460094, - 0.8294705628038663, - 0.8547741979222903, - 0.831498845691094, - 0.8231036381325553, - 0.8352821502905443, - 0.8526164371820409, - 0.842023901363802, - 0.851278788380954, - 0.8200922087173594, - 0.8245544791841062, - 0.8472771962587229, - 0.8355238881751981, - 0.8412737119332165, - 0.8374918628601691, - 0.8423056969264816, - 0.8521412173549062, - 0.8451564194474431, - 0.8271345969651037, - 0.8239077363382353, - 0.8540771441587254, - 0.8493097463370366, - 0.8505861175538263, - 0.8262386753053781, - 0.8510964833903409, - 0.8250356139853249, - 0.8476943752484948, - 0.8201871067157416, - 0.8509067450525435, - 0.855810543985663, - 0.8364690417822097, - 0.8573082158058601, - 0.8525686739692074, - 0.8235555688374464, - 0.8354328783363192, - 0.8412566132004926, - 0.8524528080575293, - 0.840253537118215, - 0.8513871744301099, - 0.8483938636174913, - 0.8405306185080881, - 0.8210908179423076, - 0.8238690775404326, - 0.8225182712005162, - 0.848422030232458, - 0.8320177424480698, - 0.8316325154232896, - 0.825682184401799, - 0.8512751046549235, - 0.8414435280921922, - 0.8544287845947169, - 0.8494292185896131, - 0.832529883363757, - 0.8518243407421124, - 0.8490640845579615, - 0.844762764778147, - 0.8530992876505815, - 0.8512944941086587, - 0.8456051704731866, - 0.8441033963986884, - 0.8221524010940301, - 0.8340941845655443, - 0.8244285572066351, - 0.8247024778966785, - 0.8456916929441908, - 0.8483109584371334, - 0.8276817475802386, - 0.837952590336012, - 0.8200443860812293, - 0.8576205347186361, - 0.8289066003406015, - 0.8496525712777753, - 0.8450040409246046, - 0.8496674398737446, - 0.8374340819449515, - 0.8445068507339881, - 0.8376107041113094, - 0.8444902975694013, - 0.8228972347677658, - 0.8234893571372253, - 0.8336435484625643, - 0.846295918259877, - 0.8382852520294265, - 0.8473660008766075, - 0.8259195624674821, - 0.8223714767320477, - 0.8202278958883689, - 0.8405999860478615, - 0.847266699259346, - 0.8211116243568297, - 0.8523925640536769, - 0.8543744794304159, - 0.8325428132080491, - 0.8383813573925697, - 0.8274553190698549, - 0.8408068170429434, - 0.8235490098318009, - 0.8355337449756938, - 0.8484200242865865, - 0.8575809992411432, - 0.8560226311883449, - 0.8563906665995805, - 0.8472562653569814, - 0.8242537416143707, - 0.8530804425576703, - 0.84601506835703, - 0.8227296612089574, - 0.8224311932690079, - 0.845195857759586, - 0.8461131538833053, - 0.8212048892689925, - 0.8510901969041355, - 0.836935546440685, - 0.8489273504005511, - 0.8444973066370244, - 0.8223393783068419, - 0.8374220433466085, - 0.8573765569470924, - 0.8471833229459362, - 0.8250599727316987, - 0.8562361707907257, - 0.826793793224879, - 0.8569773201611217, - 0.8488078420364431, - 0.8419547170731478, - 0.8464971122569582, - 0.8493568977587999, - 0.8296800905186162, - 0.8325740344191067, - 0.8306650837175107, - 0.8298613325025934, - 0.8504230983176487, - 0.8299786925141083, - 0.8367674969974175, - 0.8260741929612028, - 0.8559372684620017, - 0.8527195440739253, - 0.8301653328027946, - 0.8547760517603271, - 0.8412249314523135, - 0.8448032476681571, - 0.8485094674526993, - 0.8278761792058, - 0.8480654791368547, - 0.8355572892436053, - 0.845511056710237, - 0.8540713274674167, - 0.8231431467661573, - 0.8380183601588906, - 0.8438527139100261, - 0.8332106236315399, - 0.8325132915041001, - 0.837256296121305, - 0.8478173752385969, - 0.849984280854329, - 0.8313433499973488, - 0.8357865861165323, - 0.8207890396142096, - 0.855409261832983, - 0.8216663491001948, - 0.8417134610748357, - 0.8360265372870216, - 0.8463604184442005, - 0.8365403606304866, - 0.8436223333420795, - 0.8458010537006937, - 0.8302413761539043, - 0.8256325894783731, - 0.8297349815932031, - 0.8564419030323089, - 0.8371531231130604, - 0.8359693576746645, - 0.8406378123427183, - 0.834765589522533, - 0.8384135147021642, - 0.8346309684771434, - 0.8527147431959028, - 0.8291614074001308, - 0.823796200104185, - 0.8267957971982753, - 0.8506483805063293, - 0.8466195726762347, - 0.8340029819794866, - 0.8459091853904225, - 0.8353878361822358, - 0.8346222092587884, - 0.8514878408702279, - 0.830186273935078, - 0.8327842265355451, - 0.8440171364107238, - 0.8360384552442401, - 0.8387506563634664, - 0.8367046792154438, - 0.8265707880121927, - 0.8487376311359695, - 0.8333917712784698, - 0.8243569177774148, - 0.8349197232629598, - 0.8358478738631235, - 0.8286284063545728, - 0.8364173240037458, - 0.851431270435986, - 0.8404209029992831, - 0.8500201200948073, - 0.8283080756946137, - 0.8574575371163948, - 0.837314725908941, - 0.8392412314206764, - 0.8376091078344146, - 0.8286533077230515, - 0.8323146995473157, - 0.8326827520030973, - 0.8281131541660445, - 0.828913020139969, - 0.8280198089043879, - 0.8541712674257933, - 0.8360258777185574, - 0.8329777331625391, - 0.8246983896979496, - 0.8545192076413715, - 0.8532942528818377, - 0.8456520733223043, - 0.8243752740176801, - 0.836274310405278, - 0.8493159622834172, - 0.8381945710851636, - 0.8514614827363006, - 0.8370820538010211, - 0.8560781205707473, - 0.8372980477525578, - 0.8343141280348665, - 0.8530544111321884, - 0.829182095992117, - 0.8507546661835804, - 0.8427025862086772, - 0.8340124482496379, - 0.8311759212699006, - 0.8556517896580198, - 0.8429815756559071, - 0.8394775874150803, - 0.8382967137561828, - 0.8247819408443607, - 0.853320394016968, - 0.8326988400660391, - 0.8333935370470561, - 0.8328601285856772, - 0.8275328751803093, - 0.8337898897097242, - 0.8220707017506212, - 0.827788859350335, - 0.8420141714310637, - 0.8280906407298795, - 0.8425139321063823, - 0.8497755661891426, - 0.8501992270988545, - 0.8407347400160364, - 0.8404098314880682, - 0.8515783742385603, - 0.8206040032673009, - 0.8272662438274407, - 0.8415774894149713, - 0.833937339034836, - 0.8402171518095916, - 0.8518245971089855, - 0.8219735284050381, - 0.8364700990428275, - 0.8367838248436407, - 0.8259883750494282, - 0.8573789503502598, - 0.8403657568588738, - 0.840881056255322, - 0.8556437506610051, - 0.8353654167557081, - 0.8453307518343753, - 0.8534531653136812, - 0.8481280564673529, - 0.8299803506751042, - 0.8407686111686701, - 0.8419470206846535, - 0.8557346617667513, - 0.8349862269978245, - 0.8538515966399336, - 0.8455224674208248, - 0.8375365067820918, - 0.843148823769496, - 0.85634409666153, - 0.8563073280237261, - 0.8478589451248195, - 0.8305227054203539, - 0.847642890442281, - 0.8287455298817924, - 0.8352244337373693, - 0.8524019829142435, - 0.8305969606862357, - 0.856688386947487, - 0.8572211942335836, - 0.8438808381861409, - 0.8511669191645148, - 0.8524485824457423, - 0.8488246463403564, - 0.8507026389626556, - 0.8555004136920078, - 0.8331510404868687, - 0.8369888819223278, - 0.8403240207237838, - 0.8545324178701628, - 0.8350237079710456, - 0.8452673777749645, - 0.8331380926632437, - 0.8234329104608294, - 0.8377228782792061, - 0.8242393532057031, - 0.8278542549465968, - 0.8416032049645185, - 0.8382225881425928, - 0.8507378255585987, - 0.8542707835510063, - 0.8475087825807386, - 0.8576488275393757, - 0.8461582528115847, - 0.8299240347876391, - 0.8355084774159297, - 0.8206531799174017, - 0.8249012411241602, - 0.8469144246337297, - 0.8556898547976901, - 0.8551066392955863, - 0.8408253372240796, - 0.8211269346540238, - 0.8373887772603145, - 0.8331816660293632, - 0.8450959371083563, - 0.8352877027626864, - 0.8501911451785606, - 0.8268356562062746, - 0.8263714092392479, - 0.8353006905298618, - 0.8527676238608929, - 0.8340090278042395, - 0.8321633312203979, - 0.8463779224444841, - 0.8528629423620453, - 0.8271916592733703, - 0.8496795561882593, - 0.8507186978455973, - 0.8463742270789189, - 0.8417040682838087, - 0.8518766832531273, - 0.8271523785837234, - 0.8478865469690274, - 0.8256370552811243, - 0.8573480647368588, - 0.8468810179950597, - 0.8432829944224447, - 0.8457901903475185, - 0.8268362047121826, - 0.8344724254357133, - 0.8449004017387942, - 0.8542788632593161, - 0.8201921669251103, - 0.822326124392429, - 0.8510179798388245, - 0.8540956705371011, - 0.8447813614129562, - 0.8315154122036016, - 0.8295365657743721, - 0.8573187879889846, - 0.830837209033064, - 0.8514783863274668, - 0.8441033291118173, - 0.8379098569922048, - 0.8418854231627948, - 0.8485055615275912, - 0.8538665307065083, - 0.8414201763485724, - 0.8289784211192692, - 0.826361534105745, - 0.8254828419350343, - 0.8361543653788232, - 0.8377685501279716, - 0.8552837918546035, - 0.8530909243374034, - 0.8541534263488518, - 0.8371783783515303, - 0.8492434587603874, - 0.8342020277182821, - 0.8475542654527162, - 0.8414777834532248, - 0.8301313365603281, - 0.8203299861655624, - 0.8223176976057828, - 0.8435414731870217, - 0.8394061029338394, - 0.8478111816916145, - 0.8411344365139194, - 0.8504902587713412, - 0.8501000493171106, - 0.8228629027717467, - 0.8263725003753212, - 0.8544325659886033, - 0.8534777854650987, - 0.8363842272236723, - 0.8219464018810463, - 0.8231582139757092, - 0.8397602063069305, - 0.8226850201900179, - 0.8455995588256067, - 0.8440036233612924, - 0.849532345175299, - 0.8543418994025157, - 0.834662608336817, - 0.8396327549752536, - 0.8371745989199674, - 0.8477135851362451, - 0.8487662984356128, - 0.8456251699068852, - 0.8522810214133225, - 0.8338053209704176, - 0.8515386154432695, - 0.8506938177413894, - 0.8413671229039024, - 0.8348291652609059, - 0.8501143354462227, - 0.8447432588942643, - 0.8467752170401025, - 0.8308691684085912, - 0.8338736747576282, - 0.8529145927104944, - 0.8565049352191231, - 0.828623144091728, - 0.8262200046153966, - 0.8485875032796831, - 0.8530454762153853, - 0.8248877980785648, - 0.8262079480595821, - 0.8553145484133124, - 0.8219014843901631, - 0.8442047196526562, - 0.8564350303372319, - 0.8479440977271664, - 0.8551161361986355, - 0.8244907438299929, - 0.8489481681589415, - 0.852346139419085, - 0.8245201922210769, - 0.8294542031416957, - 0.8269681522829435, - 0.826893669656617, - 0.8388335952617951, - 0.8344785723157107, - 0.8226897235293169, - 0.8441846300811521, - 0.8568839528876675, - 0.8318610075950574, - 0.8293401563649958, - 0.8535512093344743, - 0.8356986440333407, - 0.8511005541646102, - 0.8373114456341729, - 0.8520855224705249, - 0.8353742680666588, - 0.8368962789738018, - 0.8459315812191177, - 0.8420982541345665, - 0.8422672542142747, - 0.8254563102688319, - 0.8440577934094093, - 0.8275820163377591, - 0.8559854783094765, - 0.8329739416388575, - 0.8425142419056451, - 0.8494322806404306, - 0.8408898636249027, - 0.8263064560440464, - 0.8442265904667396, - 0.8225943648647841, - 0.8496668439910784, - 0.844065001497163, - 0.8461501048782966, - 0.8254608572385487, - 0.847301478322485, - 0.8545954692805761, - 0.848940452053928, - 0.8530400477771846, - 0.8436972863683602, - 0.8281932141506183, - 0.8475784701901155, - 0.8310361712108648, - 0.835441653182416, - 0.8278400379303277, - 0.8311239902033704, - 0.8247705581628516, - 0.8477409884046685, - 0.8401082514780275, - 0.8392935343203092, - 0.8268252408374341, - 0.8389288540754637, - 0.8344130769511651, - 0.8394815618737828, - 0.8278150261438111, - 0.8315816946553873, - 0.8518797610175314, - 0.8243000054891796, - 0.8236442232608963, - 0.8358069678652574, - 0.8329925395092904, - 0.845546201399697, - 0.8386073337428397, - 0.8326591671801518, - 0.8541416494971209, - 0.8389197385518168, - 0.8206349416576809, - 0.8285396406550667, - 0.8222906710877075, - 0.8335660569932882, - 0.828163408922224, - 0.8345541204712754, - 0.8213169029283776, - 0.8434401963376581, - 0.8535953660650746, - 0.8416372330765867, - 0.8265623395103339, - 0.8486336013784641, - 0.8416602314653064, - 0.850426914472643, - 0.8518381923613169, - 0.8298104512883826, - 0.822535368641852, - 0.8248701238260381, - 0.8293535718365893, - 0.8369114510253264, - 0.8536890304072213, - 0.8249104719244704, - 0.8455077361736493, - 0.8340661453893226, - 0.8489165852854462, - 0.8233474030204142, - 0.8317601772815473, - 0.8303321811074995, - 0.8473577591609022, - 0.8231884419757883, - 0.85037869394875, - 0.850822168295755, - 0.8266711451099213, - 0.8388037096597897, - 0.8265639892277005, - 0.8544192231046773, - 0.8545091895232584, - 0.8440126908952026, - 0.8560416353284271, - 0.8241359058361105, - 0.8469534089881693, - 0.8429282823731385, - 0.8380350065377995, - 0.8392691389360817, - 0.8421128255674114, - 0.8254749148753976, - 0.8545499738670825, - 0.8232228957189398, - 0.8393338267767632, - 0.8468873522423845, - 0.8542269809607809, - 0.8332227981474107, - 0.8350831404176999, - 0.8376912387978102, - 0.8514811077979703, - 0.8379357344848892, - 0.8241178760193191, - 0.8254538703464217, - 0.8222422329016229, - 0.8376068470618123, - 0.8255244115233975, - 0.8242379875395547, - 0.8201788154602228, - 0.8451628560207388, - 0.8328942106513563, - 0.8532173334086768, - 0.8426117459490775, - 0.8351045832810488, - 0.8364583148332783, - 0.8299283095881224, - 0.8291930283922937, - 0.8223252060990303, - 0.8209506072897172, - 0.8433503721151837, - 0.8374974392874758, - 0.8269793054419988, - 0.82718445694594, - 0.831259042025343, - 0.8538421201002043, - 0.8447910275281477, - 0.8300192617754871, - 0.8486782046005873, - 0.8221033869256181, - 0.8205093641780216, - 0.8477729581761964, - 0.828564125383811, - 0.8331238142668844, - 0.8496273778075072, - 0.8575034163379485, - 0.8501632791130984, - 0.833443662927811, - 0.8266480525572595, - 0.850495495140187, - 0.8254664952466179, - 0.8454944094627443, - 0.849412058521563, - 0.8464043632358788, - 0.8360101674882451, - 0.8459368002951497, - 0.8203722189009666, - 0.8479069117576504, - 0.857031574951588, - 0.8482123221074668, - 0.8422184137093099, - 0.8305136518099642, - 0.8337983164088084, - 0.8357081174094458, - 0.8575583893655497, - 0.8204989645901692, - 0.8293936197103932, - 0.826335047674606, - 0.8455714385336033, - 0.8504385336748003, - 0.8271097941793039, - 0.8283629872569437, - 0.8464988795817782, - 0.825838686481245, - 0.8392367769545064, - 0.848609056445434, - 0.8352778052958135, - 0.8422597373049574, - 0.8453146328173198, - 0.8239288750968636, - 0.8461882746482341, - 0.853981742655983, - 0.8507482815520401, - 0.8486683689193341, - 0.8256167166211379, - 0.8571063259475891, - 0.8520036591632791, - 0.8447818989996827, - 0.8270167106520838, - 0.8513295729525726, - 0.8258308604065727, - 0.8465367615471642, - 0.8416562201871196, - 0.8298366454229371, - 0.8201957414093577, - 0.8564239552195679, - 0.8306759641690279, - 0.832688592176159, - 0.8514279465468626, - 0.8203870954956829, - 0.8416661464586523, - 0.8427819343915549, - 0.8413041389266143, - 0.8276366767493613, - 0.84538174541406, - 0.8454999522868257, - 0.8300591695312738, - 0.8216514934769513, - 0.8213577116622994, - 0.8528579480753175, - 0.8391061099105118, - 0.8433055992412916, - 0.834640312537545, - 0.8485198637163927, - 0.8202541669829904, - 0.8373070763750062, - 0.8217321207442609, - 0.8396668665988446, - 0.83345647929676, - 0.8256235766998898, - 0.8281655341663094, - 0.828144215923423, - 0.8423943663088496, - 0.8340174618074554, - 0.8278835114990782, - 0.8309695751398167, - 0.8252306593806458, - 0.8390177798516019, - 0.8234313381641675, - 0.8344730310599267, - 0.8411428380158416, - 0.8307365566257662, - 0.8374912517601126, - 0.8279541172730284, - 0.8209617959608793, - 0.8345337032373988, - 0.8251061716515639, - 0.8398490069456074, - 0.8333274461744509, - 0.8330150833017103, - 0.8418573504199955, - 0.820488869246317, - 0.8214255927122351, - 0.8397636037922744, - 0.8331429469843882, - 0.8385238764374346, - 0.8233028533004584, - 0.8203664715297204, - 0.8257543834619913, - 0.8207367973956945, - 0.8429645266197286, - 0.8359118395712779, - 0.8367125631678021, - 0.8399222223753195, - 0.8396609671344817, - 0.8388569173031686, - 0.8411920398538624, - 0.826335937818682, - 0.8408901802374393, - 0.827526196594845, - 0.834128842580507, - 0.8366758791261285, - 0.833417594220333, - 0.8295461513225217, - 0.8217190521539469, - 0.835015783845235, - 0.8280337130147924, - 0.8408311786862923, - 0.8376272337971202, - 0.8313909658925093, - 0.8277482093850574, - 0.8424109183610122, - 0.8250199101264317, - 0.8266525703962393, - 0.8218634173769775, - 0.8338153053179229, - 0.8364867838423445, - 0.8375526831980726, - 0.8406857824501057, - 0.8310688232203179, - 0.8218519478398939, - 0.8344759727619272, - 0.8363232328527964, - 0.8387601925403404, - 0.8404525432241888, - 0.8289229210204411, - 0.8279127849513137, - 0.8260870895305779, - 0.8316879337652326, - 0.8385301112915671, - 0.8303698164484973, - 0.8284706758493533, - 0.8243750941297372, - 0.84061846673062, - 0.8369763338339121, - 0.8338042114643794, - 0.8408484498210772, - 0.8345634425736469, - 0.8336056135837595, - 0.823497060862309, - 0.8316951449657002, - 0.8249135237762101, - 0.8390947229876918, - 0.8384337971958206, - 0.837958984805766, - 0.8406690238974809, - 0.8225198694823469, - 0.8259065540061471, - 0.8295678251136468, - 0.8345728092787262, - 0.8283746789215236, - 0.8413395477882557, - 0.8240474042073929, - 0.8424507402122674, - 0.8299971819634043, - 0.8398222643286954, - 0.8314236650138851, - 0.8264866310940773, - 0.8409068251960432, - 0.8204733552486908, - 0.8299645343753971, - 0.8267881338916837, - 0.8234701704595954, - 0.8426745049751128, - 0.8257484462965073, - 0.8215312407094463, - 0.839690227203571, - 0.8230934267996654, - 0.8404125693683662, - 0.8313110592932041, - 0.8326949744506025, - 0.841691526504661, - 0.8388400741323953, - 0.838945831000366, - 0.835441272563023, - 0.8350014149074889, - 0.8324816650120073, - 0.820260715488867, - 0.8365913042350249, - 0.8360516171459611, - 0.8256851806826327, - 0.8337329218150181, - 0.8362884647236994, - 0.8234620108852162, - 0.8300074112794722, - 0.8242547953854634, - 0.8346752142842829, - 0.8402955051131922, - 0.8417871874030352, - 0.8307211550319995, - 0.8331270503181285, - 0.8290162483940273, - 0.833268715185625, - 0.8254641737040838, - 0.8258524697070906, - 0.8406243551939547, - 0.8410225854734398, - 0.8203234751345101, - 0.8397065681072124, - 0.8214324478072628, - 0.8260094994348787, - 0.8439474022332479, - 0.8412262382284419, - 0.8201635528672605, - 0.8405041939145063, - 0.8412190319711038, - 0.8286993130580677, - 0.8236608298457736, - 0.8269940845973918, - 0.8210552929131261, - 0.8234099864618273, - 0.8403993140543524, - 0.8235184331989595, - 0.8358147558395421, - 0.8327610240705039, - 0.8437205098607792, - 0.8334482108837709, - 0.8306511575615089, - 0.8218458610015935, - 0.8207943003631795, - 0.8311075327393236, - 0.8320145535606343, - 0.8258901423516022, - 0.8282167585536525, - 0.8420392844014327, - 0.8311675974540675, - 0.830039433125957, - 0.8283894752236285, - 0.8386124413619115, - 0.8291775627173377, - 0.825072425797893, - 0.8298862693754818, - 0.8412757443925303, - 0.842836516335511, - 0.8421672819789703, - 0.8419668129500006, - 0.8284434137750312, - 0.8350819329106152, - 0.8296015328403168, - 0.8381173595971488, - 0.8239284540287359, - 0.8426712736838663, - 0.838457709442622, - 0.8276563011859063, - 0.8371300792125157, - 0.831973723145571, - 0.8349880043006047, - 0.8349216081422545, - 0.8282986607240702, - 0.827686889011057, - 0.8256522793613469, - 0.8341154944650002, - 0.8414775608759443, - 0.8281603127127278, - 0.8354300957540152, - 0.820311295696552, - 0.8279085546952006, - 0.8213224921641612, - 0.8280029895729057, - 0.83406082573596, - 0.839224945957998, - 0.8298854532327744, - 0.8322469093428858, - 0.822496624693834, - 0.8300510597322929, - 0.8253238990763798, - 0.824241842900498, - 0.8255835597494054, - 0.8225448297884371, - 0.841460268065877, - 0.8373444612873422, - 0.8425132105644692, - 0.8339695673323875, - 0.8411167998077578, - 0.8364949861181995, - 0.8268820330317806, - 0.8335426657792481, - 0.8308852566349599, - 0.8385840538584498, - 0.8263722897988987, - 0.8255574040113182, - 0.8272324972531483, - 0.8325029035642711, - 0.8297813016612221, - 0.8338498729958582, - 0.8299087274488284, - 0.8437749867038556, - 0.8286284088186597, - 0.829043193004968, - 0.8360659817517385, - 0.8343760965040711, - 0.8413410306533008, - 0.8334869088684066, - 0.8384728483912189, - 0.840955691927196, - 0.8311020681044271, - 0.8205232369375192, - 0.8247978883023992, - 0.8304229140222193, - 0.829390242928918, - 0.8358607538312985, - 0.8203164501028822, - 0.8421009462020761, - 0.8203964590080646, - 0.8264045795682747, - 0.8290574299422677, - 0.8404442968910519, - 0.8222409804271585, - 0.8228321249444656, - 0.8268454173676001, - 0.8271458681000243, - 0.8339171847715888, - 0.8419351474086726, - 0.8300147059150268, - 0.8251195646013754, - 0.8242047797829075, - 0.8308213404135617, - 0.8352408640702416, - 0.8425650771088161, - 0.8208327648639644, - 0.83062023390406, - 0.8213794884908783, - 0.8202615018884869, - 0.8252181002172879, - 0.8420108313905698, - 0.8329121624466912, - 0.8348334977053828, - -0.6746141840785174, - -0.6886284765161518, - -0.6601040188768568, - -0.6655967348076679, - -0.6940409469739117, - -0.687455710582586, - -0.6745841574310276, - -0.6802424913903562, - -0.6788869778572966, - -0.6719371602015586, - -0.6699791544149387, - -0.6908070117658702, - -0.6930627788224111, - -0.6920528352604609, - -0.6613786416956481, - -0.6692206710409371, - -0.6942914952825258, - -0.6898026180708242, - -0.6791365734568852, - -0.6899642191497567, - -0.6715804410083333, - -0.6812903981860591, - -0.674591683548175, - -0.6972110935112932, - -0.683945085735822, - -0.6762502934078075, - -0.6973058956481382, - -0.6741865540931916, - -0.6860077587034613, - -0.6819701566948445, - -0.6667340495592315, - -0.6711914399502821, - -0.663710094676848, - -0.6955342294800742, - -0.6659717206277096, - -0.6876458889121088, - -0.6829550093007313, - -0.6960715771874232, - -0.6775303726150119, - -0.678368637165803, - -0.6932966334474095, - -0.6917399952013681, - -0.6864093778496579, - -0.6914893690122369, - -0.6977401662042911, - -0.6787370440849035, - -0.6888429902281146, - -0.6930263238837162, - -0.6672854406335794, - -0.6951963831888156, - -0.6694261112593567, - -0.6715003266575331, - -0.6873968971651537, - -0.6942096850416324, - -0.6937378424149452, - -0.6617493169902309, - -0.6754594657213264, - -0.6780017039243544, - -0.6747329556340319, - -0.6683002001522719, - -0.6651501711312592, - -0.6928774315932067, - -0.6703526712758717, - -0.6755407982273284, - -0.6708668912250719, - -0.6827522128150574, - -0.6667795747534927, - -0.6678491471767756, - -0.6962228836774962, - -0.6681336983404802, - -0.6670646368761041, - -0.6869537098598495, - -0.6735327896917102, - -0.6749161042536174, - -0.6607609925144794, - -0.6824391043422964, - -0.6814727636691921, - -0.6939686217301894, - -0.6934855029415801, - -0.6959686148640771, - -0.6732482009704546, - -0.6801764811788376, - -0.6663226957138189, - -0.6802820481779657, - -0.6653978592492075, - -0.6953870917152366, - -0.6759398443040056, - -0.6945392966875719, - -0.6949581526205741, - -0.6708794955173274, - -0.6730907250607087, - -0.6667113716499671, - -0.6713415550773809, - -0.6960388414938202, - -0.6640126052842721, - -0.6906810808505668, - -0.6798644003274743, - -0.6887513251705029, - -0.6952192099010965, - -0.6609861597647275, - -0.6864347920726361, - -0.6778850938651649, - -0.678253581972582, - -0.6892106710289049, - -0.6971311569796488, - -0.6656448031257765, - -0.694563259057485, - -0.6952098359062748, - -0.6948857728076272, - -0.6911667726852665, - -0.6622860682756938, - -0.6937249590455887, - -0.6700966937930312, - -0.665298358170495, - -0.6813846562562297, - -0.66144504711305, - -0.6632451455814717, - -0.6673705666927828, - -0.6947589631921681, - -0.6930855218100677, - -0.683585632695927, - -0.6772942311350535, - -0.6650686494049545, - -0.6739474884455319, - -0.6840132497431871, - -0.690031146752834, - -0.6669212180006778, - -0.6934592790849192, - -0.6652779914567487, - -0.6941656426276396, - -0.6688316606277314, - -0.6607716232467629, - -0.6894880164489943, - -0.6646797943780495, - -0.670760786003949, - -0.6858583181097863, - -0.6974211678267301, - -0.6760562367738313, - -0.6933939815112516, - -0.697581141837333, - -0.6887615133432778, - -0.6600069225816003, - -0.663923953099917, - -0.6704867607310226, - -0.6970625917876369, - -0.670772565767838, - -0.6607231354214145, - -0.6921814946230959, - -0.66793551537241, - -0.6654112221346467, - -0.6726985358797045, - -0.6687532036080519, - -0.6699503930002195, - -0.6634026389435991, - -0.6819784578105069, - -0.691326938462314, - -0.682732086699986, - -0.6700805533580487, - -0.6888021111618905, - -0.6748813927069008, - -0.6829504808560811, - -0.6951221306688757, - -0.6957729202986209, - -0.6712416695390037, - -0.6790242840366107, - -0.6736547929288142, - -0.6966711585093713, - -0.6933624338616954, - -0.6820460816255794, - -0.6652339559274938, - -0.677344350041237, - -0.6764599422983517, - -0.667608598461279, - -0.6668326318614972, - -0.6824601636498356, - -0.6783781235486522, - -0.6900296408450133, - -0.6930484758719688, - -0.6777421068380083, - -0.6668064338032343, - -0.6816281379919223, - -0.6965114695725022, - -0.6725418738033794, - -0.6616198503155789, - -0.6923671231549478, - -0.6762229005550496, - -0.6613827231074759, - -0.6660288937383735, - -0.683246446506367, - -0.6767804109831066, - -0.6977257421066394, - -0.6668256810138676, - -0.6689043736986101, - -0.6738656984864401, - -0.6641466587165921, - -0.6614201709461075, - -0.6807273301173363, - -0.6737070190222737, - -0.6814187871451918, - -0.6790739511156232, - -0.6777392982896252, - -0.6885633914579151, - -0.6946670881492347, - -0.6814411332622994, - -0.6952166563661799, - -0.6770274856921616, - -0.6885669516772127, - -0.6944584701738877, - -0.6659285140876098, - -0.6946296561877678, - -0.6694683472293828, - -0.6957724301121598, - -0.6933042340458916, - -0.6662246306548055, - -0.6933320635778694, - -0.6851745901220025, - -0.6851008516738358, - -0.6664773613105298, - -0.6889140745342193, - -0.6619753816748079, - -0.6844776420978537, - -0.6820975752364891, - -0.6853234386749736, - -0.6941313730669997, - -0.6666404813153626, - -0.6771601991413763, - -0.6907557133346961, - -0.6816598944248002, - -0.6725414181155871, - -0.6753715993655398, - -0.6753588067653471, - -0.686363042566137, - -0.6692428542343192, - -0.6673577696239847, - -0.6815819848529493, - -0.6843322284898764, - -0.6955484649810205, - -0.6611740114732744, - -0.6697971615331532, - -0.6686201988492472, - -0.6715785703430595, - -0.6619378300060514, - -0.6800727705492728, - -0.6610395491170569, - -0.683022201263447, - -0.6910534430997515, - -0.6947971116226088, - -0.6693475777179481, - -0.6825558239092868, - -0.6704474739784368, - -0.6807515204691592, - -0.6932702843455287, - -0.6862270644643407, - -0.6826705798708743, - -0.6911769569962792, - -0.6649239653096749, - -0.6675965457497756, - -0.6692675011724754, - -0.6795311260172137, - -0.6903068658536712, - -0.6782632556885907, - -0.6789022256242505, - -0.6919469409684276, - -0.6975792298339692, - -0.6787719366861165, - -0.6803267400976987, - -0.6895497052956906, - -0.6697803922099581, - -0.6802284970819463, - -0.6713286445393906, - -0.661542921979802, - -0.6721423809671493, - -0.6715952835941091, - -0.6606422824527411, - -0.681086503680562, - -0.6809674575087514, - -0.668132615011977, - -0.6725826088559591, - -0.6691576234048412, - -0.6964313122792681, - -0.671561501757517, - -0.6839006519665206, - -0.6672648702484053, - -0.6956961594746738, - -0.6914054559209156, - -0.675598256812254, - -0.6761303623245282, - -0.6649259307273713, - -0.6622675330094479, - -0.6825825922218365, - -0.6620365690877199, - -0.6754453006110023, - -0.6629611575447288, - -0.6906087288733064, - -0.6929299442865553, - -0.6795212377294962, - -0.6734584657805814, - -0.6957309166094032, - -0.6941780914640323, - -0.6810208380025617, - -0.6635121058639575, - -0.678575337056153, - -0.6849556292128414, - -0.6685061988289451, - -0.6708898447178794, - -0.6623101669062174, - -0.6603842641863717, - -0.6912105355625384, - -0.6642963125385545, - -0.6920701816067335, - -0.6638275786918244, - -0.6621570598730788, - -0.6965554701977301, - -0.6621366257161929, - -0.6773069803872079, - -0.6713947605745646, - -0.6638094923585318, - -0.6953156502459316, - -0.6946292293181813, - -0.6926457786525416, - -0.6837948677251265, - -0.6836342473171184, - -0.6664274577915912, - -0.6675997143653187, - -0.6854268497267045, - -0.6819101821298482, - -0.6654142347055736, - -0.6624069109656958, - -0.6971332742505527, - -0.6793531990989536, - -0.6930574787170009, - -0.6842272122392853, - -0.6866122088473987, - -0.6601214779469657, - -0.6788431266838921, - -0.6807493636356386, - -0.6772510599851753, - -0.6670054547463979, - -0.6647846718033822, - -0.6742356010200281, - -0.6761561525793798, - -0.6907887971386057, - -0.6879072400453848, - -0.6627368837672113, - -0.6862344087647868, - -0.6719191074186022, - -0.6733913574131228, - -0.6878054702640402, - -0.6610240860754436, - -0.6754944012153229, - -0.6813467800807157, - -0.685192613144929, - -0.6869348894818763, - -0.6708838335721231, - -0.696041650664229, - -0.6903872900345278, - -0.6795416480443517, - -0.6831301719275387, - -0.6822391249246678, - -0.6977063564904373, - -0.68696011316178, - -0.6602418778884843, - -0.6758956558490061, - -0.6621982462511796, - -0.6752588922290702, - -0.6691199693575786, - -0.6626592933842332, - -0.6933649102836178, - -0.6839984763903686, - -0.6754760538164711, - -0.6710543820853578, - -0.6741162409048135, - -0.6785339335453852, - -0.6634411906372406, - -0.6747870211877897, - -0.6845907304903196, - -0.6951478152868003, - -0.6807633520786521, - -0.683463227651484, - -0.6688857339812069, - -0.6676197635664105, - -0.6852240841214505, - -0.6945284822136585, - -0.6933375688804698, - -0.6604520834576711, - -0.6667821100751983, - -0.69479002224664, - -0.6664465025841261, - -0.6859813537064171, - -0.6956525297910844, - -0.669752994698008, - -0.6761195891152739, - -0.6905058407689199, - -0.6887493354798598, - -0.6768133761896861, - -0.6904502304704636, - -0.6878943439604596, - -0.6800099668244156, - -0.6972171482399235, - -0.6727137333072158, - -0.6601472122738065, - -0.660249325345894, - -0.6722134694452813, - -0.6653713441706426, - -0.6697240275195547, - -0.6659848524433125, - -0.6733428836419079, - -0.6743824484684026, - -0.6836778731244544, - -0.6617475439708467, - -0.6883397983860362, - -0.671940351636465, - -0.679769445052373, - -0.6764666963726652, - -0.6817960285379824, - -0.6963406627558634, - -0.6864595129484394, - -0.6661140540521318, - -0.6600362696923529, - -0.6908275271901851, - -0.6887856655886246, - -0.6603758816813177, - -0.6918215724431288, - -0.6844975326130331, - -0.6603461296233962, - -0.6766294718437241, - -0.6684390880771633, - -0.6743845995477578, - -0.6974341118120094, - -0.6954564616238984, - -0.6783526080899775, - -0.6762087583444282, - -0.6747526284975439, - -0.6947920292971516, - -0.6910100211457635, - -0.6888423277062988, - -0.6602724862543715, - -0.6609333740732911, - -0.6935898415780253, - -0.6829184421340371, - -0.6883963214704134, - -0.6888769194822435, - -0.6732894892885142, - -0.6828596698063102, - -0.6644884041859759, - -0.6852535616833239, - -0.6744848518137354, - -0.6873026588341064, - -0.6883579398896497, - -0.6802240188477496, - -0.6970741312231162, - -0.6880300780236311, - -0.688552569049997, - -0.661626536729126, - -0.6787633640995725, - -0.695510576520576, - -0.6651090243441025, - -0.6752980939362537, - -0.6647891146010826, - -0.6913832360519615, - -0.6655759068266525, - -0.6639875283844118, - -0.6813761431997847, - -0.6820909975409589, - -0.6847637871348109, - -0.6651087378988025, - -0.6862356409060374, - -0.6718306268634103, - -0.6905912890122553, - -0.6941922277033447, - -0.6888709416104346, - -0.6733367153466117, - -0.6825986756718786, - -0.6970634007583321, - -0.6816588218774726, - -0.6686995531136737, - -0.6853314852253869, - -0.6895677346532545, - -0.688350924823682, - -0.6806328752108978, - -0.6966626623408988, - -0.6775906902067996, - -0.6644980844404059, - -0.6684409343848937, - -0.6947698611696231, - -0.6908816080086646, - -0.6776951249001967, - -0.666364873444987, - -0.6816272729110479, - -0.6641777899346701, - -0.6868490926653473, - -0.6624768589609384, - -0.6736743765025385, - -0.6932647658735291, - -0.6719444060631047, - -0.6809871438903407, - -0.6763549666302989, - -0.6889813684215885, - -0.6845573831203583, - -0.6958444033531709, - -0.6692296940606933, - -0.6625232600331735, - -0.6623611206674921, - -0.6878204228735931, - -0.6869339586779344, - -0.6958788889250089, - -0.6897351845493644, - -0.678504924546521, - -0.6626662046885975, - -0.6844330108257274, - -0.6649357885016501, - -0.6645257980386753, - -0.6903893042670357, - -0.696191034505454, - -0.6976482411335778, - -0.6763717307867539, - -0.6891929704171622, - -0.6732414490513808, - -0.682936501277053, - -0.6652547068675356, - -0.689624855653104, - -0.6656552904604697, - -0.6699937343396408, - -0.6646656963012861, - -0.6838269807953417, - -0.6892510924545528, - -0.6942689656104019, - -0.665335397503783, - -0.6927003712264327, - -0.6605484999333536, - -0.6636130118941415, - -0.672383200104287, - -0.664294927401748, - -0.6760564644537552, - -0.6795078674625501, - -0.6809274571763406, - -0.661784496247274, - -0.6754102951815901, - -0.6908137737782103, - -0.6638941879513804, - -0.6622239371990131, - -0.6954314617042157, - -0.6633761339245652, - -0.6858118030451135, - -0.6948745809619966, - -0.6949805433491383, - -0.6857023852694862, - -0.6862450407016696, - -0.6942938737861815, - -0.66461334520863, - -0.6697463781645258, - -0.668068528227637, - -0.6795183422747151, - -0.6744814676780488, - -0.6829616235627527, - -0.687309237802271, - -0.6849899065456878, - -0.6836624271084395, - -0.6745587191361917, - -0.6658444017672613, - -0.6810493281926067, - -0.6799830577750451, - -0.6813081088870694, - -0.6840167630780499, - -0.6625601857884025, - -0.6814702977218634, - -0.6816239516152831, - -0.6786264186540882, - -0.6754693943678026, - -0.6895112702757065, - -0.6733713571492133, - -0.6689016865905588, - -0.6800297515290823, - -0.6710604278257589, - -0.6684504912085033, - -0.6701171185277435, - -0.6619591799905795, - -0.6825874927841656, - -0.6735858980255431, - -0.6644335346788923, - -0.6603918374273736, - -0.6964703399864449, - -0.6947222059891012, - -0.6781182709092023, - -0.6946082843105266, - -0.6855714109165199, - -0.6850442966636229, - -0.6748307566090712, - -0.6754149349158436, - -0.6757658449348143, - -0.6905031829496779, - -0.6913187561945626, - -0.6602547232747428, - -0.6872273250814173, - -0.6700107301301448, - -0.695400733546086, - -0.6867866623609156, - -0.664112197785645, - -0.6884921328659229, - -0.6949699478246412, - -0.683854498185014, - -0.691697501483643, - -0.6665531424108867, - -0.6802027097082193, - -0.6761793669764123, - -0.6870740099225621, - -0.6706541381164306, - -0.6839066421783172, - -0.6858873006585079, - -0.6725156554675198, - -0.6705503801087667, - -0.6698915716994726, - -0.6925354683007977, - -0.6741714840980962, - -0.6772726372412409, - -0.6852406522898356, - -0.6976847475060071, - -0.6738357288795459, - -0.6601373467435034, - -0.6746001057589305, - -0.6836878983229883, - -0.6682379828951184, - -0.678960724666767, - -0.6616558415992683, - -0.6846068006490835, - -0.6934396073421979, - -0.6827305560558085, - -0.6923322166640623, - -0.6688064525288602, - -0.6703313038690305, - -0.6675214810046828, - -0.6723702583799247, - -0.6697850856620029, - -0.6605195435661257, - -0.6951364117678613, - -0.6944020308132371, - -0.6877394615641371, - -0.6774306186565501, - -0.6933654907772052, - -0.6780060208332929, - -0.6637410819393393, - -0.6638759111373009, - -0.6607208672625781, - -0.6856352593658654, - -0.6901594942858211, - -0.6959958145787476, - -0.6819895896039675, - -0.6855910611737636, - -0.681248886252476, - -0.6777335539608192, - -0.6690264393927152, - -0.6696969682850866, - -0.682682136774839, - -0.6603114375893356, - -0.6881324685111765, - -0.6862188873119885, - -0.6643933467188025, - -0.6765936720306495, - -0.678679400991603, - -0.6856758656173493, - -0.6888645339935718, - -0.692241119391915, - -0.6798390361659148, - -0.6942458522663006, - -0.6646479166179272, - -0.6622496504873908, - -0.6694063579766252, - -0.6678516848510522, - -0.6973814891542861, - -0.6948155688138594, - -0.6838323199728185, - -0.6625997793805041, - -0.6696542036011097, - -0.6703737689475311, - -0.6850400660213888, - -0.6959769438815648, - -0.6828997168731955, - -0.6821704137678539, - -0.6778978803230582, - -0.6977254311519504, - -0.6623797867724716, - -0.6652219157091247, - -0.6725389554125811, - -0.6653641329602328, - -0.682044624529532, - -0.6838587996103385, - -0.6698697289384384, - -0.6970724915126271, - -0.6875605057611888, - -0.670478371857921, - -0.6724209148214719, - -0.6625832565154621, - -0.6745714968314281, - -0.6615885762622472, - -0.6859228020221907, - -0.681187669617963, - -0.6717719206252293, - -0.6694422455638718, - -0.6783815035367479, - -0.6859314084755539, - -0.686017135477061, - -0.6701822214645149, - -0.6609154926810725, - -0.6811874673653049, - -0.662285909696503, - -0.6904468411253498, - -0.6791717183606816, - -0.6830582546443873, - -0.6641657152218704, - -0.6610232381952378, - -0.6705472324260547, - -0.676661226343928, - -0.6859871198196634, - -0.6713136895728434, - -0.6730549815074504, - -0.6667408984642558, - -0.6745878347239797, - -0.6784331833201561, - -0.6900845649417741, - -0.6859831765278893, - -0.6954897987610792, - -0.6932867771445437, - -0.6668757097387835, - -0.6755249182678071, - -0.6668847044295517, - -0.6956985624758185, - -0.6670918049247632, - -0.6615935843782369, - -0.6902290211836317, - -0.6601001698882334, - -0.6659691978194161, - -0.6893559616002148, - -0.660739522085578, - -0.6874020691902292, - -0.6899601753282918, - -0.6839259121936698, - -0.6890878910457464, - -0.6904603345372745, - -0.6972870639294911, - -0.6782903391050586, - -0.6847334188544274, - -0.6763369356568024, - -0.6619466063398434, - -0.6767883978749699, - -0.6743381100746154, - -0.6950058698041798, - -0.6870753617998904, - -0.6791378130951656, - -0.6601967499766616, - -0.6910270233624053, - -0.675301116961508, - -0.6936568406862873, - -0.6803480285979479, - -0.6688627099299547, - -0.6737909932897717, - -0.678630921360456, - -0.6701342754219256, - -0.6724162381896679, - -0.6848711422896, - -0.6852964572105767, - -0.6896178519760607, - -0.6777663364481377, - -0.6683655002100122, - -0.6799240365920958, - -0.6713278405467107, - -0.6625519859468975, - -0.6872513588445184, - -0.6693464403031315, - -0.6718638412703386, - -0.6885284509673647, - -0.6816599452683172, - -0.6628323730682397, - -0.6912220970633121, - -0.6783280899083165, - -0.6635939361451534, - -0.6939254696089828, - -0.6942307909189023, - -0.6670308412075271, - -0.6825540752703775, - -0.6647294585651986, - -0.6628672667014036, - -0.6836366283354437, - -0.663770200783864, - -0.6738180544526224, - -0.6890813731897523, - -0.6772425773877552, - -0.6901249056972775, - -0.6773247076528338, - -0.6641586465622358, - -0.6850239764102113, - -0.6782886552849731, - -0.6967168054394723, - -0.6825011765142329, - -0.6887224847590199, - -0.664756462834594, - -0.6760562781558382, - -0.684979777649574, - -0.6823221244882101, - -0.691421284087173, - -0.6742092732627272, - -0.6687937084864094, - -0.6922075425609912, - -0.6652635704372011, - -0.6843393791149299, - -0.6700184700228072, - -0.6908146169898945, - -0.6679234446804524, - -0.6859957319993504, - -0.6653103727857191, - -0.6960148387884658, - -0.6724412773300604, - -0.6847063931892795, - -0.6608503308904085, - -0.6928329137383004, - -0.6790514509415956, - -0.696960934202054, - -0.6760461714800856, - -0.6886966089228946, - -0.6697228943301874, - -0.6930658817302809, - -0.6943070824374076, - -0.6759522949742962, - -0.6677075479388989, - -0.6895672069859192, - -0.6679689652850607, - -0.6660663931348076, - -0.6713434188627301, - -0.6660041352966444, - -0.6890792224034312, - -0.6644636353906871, - -0.6763208933712171, - -0.6934358673287988, - -0.6915794518062333, - -0.6860917184308937, - -0.6649233797620897, - -0.6763596478230952, - -0.6864826643167306, - -0.6893888172096097, - -0.6607223913405648, - -0.6955186883972332, - -0.6948345235560052, - -0.693296010962844, - -0.6604786353123839, - -0.6747395252753812, - -0.686524544631854, - -0.6857731223012055, - -0.6869429600859279, - -0.6839408645535698, - -0.6841563112510587, - -0.6757315820609576, - -0.6974650300186277, - -0.6745229906185262, - -0.6822790496801544, - -0.6661191091308092, - -0.6714674729403369, - -0.6618356255296656, - -0.6828993726228134, - -0.686170937428217, - -0.6738338758141356, - -0.6651708275987223, - -0.6882754488597818, - -0.6856079183593412, - -0.685247520773029, - -0.6699668771196525, - -0.6945221886170955, - -0.6693050136881674, - -0.6820243554036369, - -0.6647527923065154, - -0.677087476241349, - -0.6754025100209651, - -0.6745524363880929, - -0.6963303834686061, - -0.6655813061817024, - -0.6772369214564768, - -0.6648728942077734, - -0.6660652552306722, - -0.6705996458674133, - -0.6818544527090054, - -0.6920036728547695, - -0.6931148412766018, - -0.6738803291653084, - -0.6638268938681365, - -0.6767801722306475, - -0.669010558351832, - -0.6613693423314899, - -0.683468253225419, - -0.6645566031299482, - -0.6801452398044369, - -0.694515429349326, - -0.660052387011257, - -0.6784695147031921, - -0.6961456090668563, - -0.6839838484101725, - -0.6627275613664478, - -0.6813330863363941, - -0.6941136707094784, - -0.6679123240761775, - -0.6830450686040028, - -0.6656691513291723, - -0.6943126032027759, - -0.686602189600876, - -0.6817093043952506, - -0.6874595015094821, - -0.6839584959081116, - -0.6940422579309925, - -0.6906780756936478, - -0.6905851130205978, - -0.6789317562934533, - -0.6811070804691708, - -0.6616310870862109, - -0.6821171299060822, - -0.6908590818851487, - -0.6876256329538722, - -0.6654304333205089, - -0.6847400373998251, - -0.6977408401010384, - -0.6889336845023554, - -0.6932455137513162, - -0.683328284361242, - -0.6914277986408374, - -0.6859324178987822, - -0.6969696099100924, - -0.6810287809232763, - -0.6820801018128684, - -0.6798546010988465, - -0.6700523014980063, - -0.6868409298942117, - -0.6965499453231757, - -0.6800078504951066, - -0.6675521560220908, - -0.6770717327947787, - -0.6653675034423976, - -0.6795956601258437, - -0.6609207723999184, - -0.668166759043576, - -0.6730436169707711, - -0.6746666538757743, - -0.6719293011524974, - -0.6920111976211792, - -0.6746476440991915, - -0.6948191294878826, - -0.6878956144804721, - -0.6917594470756868, - -0.6869331431380431, - -0.6938764464194677, - -0.683124119215386, - -0.677498570119251, - -0.6696919353535923, - -0.679352397603181, - -0.6840239472957512, - -0.6729361677738068, - -0.6827367682272928, - -0.6671296075431027, - -0.6707791334949472, - -0.6963445845736387, - -0.6628765104000667, - -0.6622219387178705, - -0.6844303062745949, - -0.6824473976318826, - -0.6762335088318554, - -0.6623292802543552, - -0.6602087334948621, - -0.6888502792134712, - -0.6716606893895537, - -0.6617004381145136, - -0.6898489285865764, - -0.6647655599440013, - -0.6969169285852465, - -0.6753182221254993, - -0.6617465746401905, - -0.6937061072687631, - -0.6667400427461521, - -0.6808165580268543, - -0.6813432131519538, - -0.68961287892829, - -0.6673905048727781, - -0.6684850864718914, - -0.6738678556656402, - -0.6730868948792857, - -0.6725265184077892, - -0.6613792960124205, - -0.66638070050897, - -0.6653567776299272, - -0.6803697960461321, - -0.6764130753564633, - -0.6945193307182689, - -0.6659295401308543, - -0.6629695999313524, - -0.6908393760735516, - -0.697043300661734, - -0.6919270372507287, - -0.6941792334563361, - -0.6953521787398947, - -0.679958951811606, - -0.6921690110584846, - -0.6708181503413416, - -0.6791631818032826, - -0.6922058157445945, - -0.6746430876814385, - -0.6601182811795862, - -0.6927650952836475, - -0.6720416495417066, - -0.6942645656740892, - -0.6781186801122433, - -0.6707213665879485, - -0.6783231289258743, - -0.6633816188744308, - -0.695062011991768, - -0.6919167675236934, - -0.6692514329456851, - -0.6949644391451254, - -0.685513256495105, - -0.6801786012199507, - -0.6634104096283345, - -0.6617416221332484, - -0.6904413431151972, - -0.6600739306646641, - -0.6896911970962276, - -0.688087795782958, - -0.6782866687600719, - -0.6832232445787071, - -0.6712923662988849, - -0.6975407001000561, - -0.6906526017455021, - -0.6935892525448508, - -0.6799884554035347, - -0.6878429994557147, - -0.6631482650164132, - -0.6970258519030796, - -0.6898929281506682, - -0.6764921266888652, - -0.6681148363222812, - -0.6743894881485571, - -0.6927695669103751, - -0.668515338590879, - -0.6744742328122286, - -0.6655162971269207, - -0.6928080216142083, - -0.6655525274463691, - -0.6820900482583716, - -0.6898243805272337, - -0.6806382583029438, - -0.6756602471145645, - -0.687773921173952, - -0.677618785233191, - -0.694406735565021, - -0.6702648940631922, - -0.6853298472724901, - -0.6750579456023806, - -0.6653139220400532, - -0.6747777641226399, - -0.6842970140077071, - -0.6726420264589661, - -0.6640728507769519, - -0.6699243068287358, - -0.6963860415699744, - -0.6923238366192136, - -0.6620691054319603, - -0.6775643524906247, - -0.6782130389720502, - -0.6935803859265312, - -0.6629686285489127, - -0.6659309469220408, - -0.6972961362837272, - -0.671655079741274, - -0.6909914479309579, - -0.6667119728493196, - -0.6894763363841971, - -0.6912308655951994, - -0.6945131914049024, - -0.6663494805458908, - -0.6799682057937334, - -0.6662269192817467, - -0.6746583339952683, - -0.6705498461176341, - -0.6765613441600827, - -0.6799779687748003, - -0.6914021516796249, - -0.6776116384915641, - -0.6946430473042029, - -0.6818354534836437, - -0.6896773282293436, - -0.6849956290799664, - -0.6919974433459373, - -0.6646550560700297, - -0.664751748922092, - -0.6874382266588547, - -0.6720106050335631, - -0.689772460025647, - -0.6680734381517003, - -0.6795746716654804, - -0.6650709739025675, - -0.6712999637530539, - -0.662264312073934, - -0.6894489858111559, - -0.6793522991002983, - -0.6702098247686605, - -0.6802932243274833, - -0.6839436841277483, - -0.6937925896030703, - -0.6964764723156407, - -0.6609889837143061, - -0.6882944404916048, - -0.673838279192946, - -0.690967987099381, - -0.6690756636500553, - -0.6958117388539787, - -0.6634487679673438, - -0.6680639078481896, - -0.679157372877377, - -0.6605834861692909, - -0.6907221897627762, - -0.6757099902774428, - -0.6960363819200602, - -0.6878121127325028, - -0.6866403909075348, - -0.6675215966157483, - -0.6913228837808966, - -0.6945581703760393, - -0.6977172535815247, - -0.671416563457728, - -0.697174240214728, - -0.6771386933522396, - -0.6634301987111303, - -0.6721398381726339, - -0.6835678736446186, - -0.688207136926993, - -0.6689332264302391, - -0.6741242868998314, - -0.6710862973474113, - -0.6871103930477438, - -0.6902914424027318, - -0.6687267289537459, - -0.6829311134123511, - -0.6709791037119541, - -0.679478334746567, - -0.6970927685898821, - -0.671953478213447, - -0.6747479201523031, - -0.6674796638624269, - -0.6925129429617366, - -0.6888671718023027, - -0.6648152589334919, - -0.6601053001180852, - -0.6661859541133374, - -0.6623198126896133, - -0.6851023890509369, - -0.6799026882133444, - -0.667561571423204, - -0.661744717756065, - -0.6874414772277379, - -0.675198216881195, - -0.6883606421537922, - -0.6655783384591727, - -0.6629403216726506, - -0.6950294769432056, - -0.6891403552294741, - -0.6768460268466573, - -0.685567686196925, - -0.6859492956858243, - -0.6836719418721492, - -0.6755486349898543, - -0.6672087683811682, - -0.6826752218698353, - -0.6737840337157294, - -0.694360647789233, - -0.6745557062291581, - -0.6641959516707673, - -0.6864249024184453, - -0.6759586392225602, - -0.6870436553340612, - -0.682955709590194, - -0.6767811131179833, - -0.6897621736518913, - -0.6661438764256369, - -0.6819406019764187, - -0.6722185462755829, - -0.6971674394803365, - -0.670588294116879, - -0.6768306378040193, - -0.6630935889931323, - -0.668525272489879, - -0.6763364256437366, - -0.6836810481598791, - -0.6920393082594097, - -0.6964748996772245, - -0.6690731510492179, - -0.6632379599258845, - -0.6734891690241945, - -0.6754065751880853, - -0.6743272843942528, - -0.664687091091521, - -0.6898790084523083, - -0.6645075297658956, - -0.666217802910457, - -0.6905987762213343, - -0.6828866592730235, - -0.6876404656024421, - -0.6827600222129604, - -0.6908356863678654, - -0.6760103063266654, - -0.6942882941560792, - -0.6662668644135894, - -0.6722131681362502, - -0.6642350736189614, - -0.6619201321575426, - -0.6875881004650394, - -0.6609456471736175, - -0.685274249549011, - -0.6890659760631423, - -0.6633777668282899, - -0.6726991512860843, - -0.6838295555527969, - -0.6720744509950455, - -0.661689858179794, - -0.6659505016899365, - -0.6756604787804956, - -0.6950715152857632, - -0.6699637778056466, - -0.6728815612968716, - -0.670065003155151, - -0.6925979498294388, - -0.6808218859648221, - -0.691771365640305, - -0.6805276517366103, - -0.6695536456027104, - -0.6810431256485943, - -0.6722362119803829, - -0.6831805122059486, - -0.6916455653380844, - -0.6697253419730533, - -0.6678749577512987, - -0.6716206424348872, - -0.6927350017195629, - -0.6865887880944194, - -0.6811493519370384, - -0.6963664944121042, - -0.6772756465222945, - -0.679909868866722, - -0.6629532075396997, - -0.6694090196521282, - -0.6957054720095052, - -0.696622427785256, - -0.6634940610277374, - -0.6892388699676688, - -0.6684811644669957, - -0.6834692072095165, - -0.6677356997328431, - -0.67103725624618, - -0.6801350334484382, - -0.671324023266882, - -0.6846367254068946, - -0.6827405967606496, - -0.6773454291833074, - -0.6704254726270799, - -0.6957708221446083, - -0.6723828527134458, - -0.6770379875506429, - -0.6846318328548869, - -0.687027098270678, - -0.6851302156654274, - -0.6931768928065579, - -0.6967855744368786, - -0.6799148686912161, - -0.6681246982997961, - -0.697286411250418, - -0.6872818634933087, - -0.696661304813142, - -0.6925976332833031, - -0.6906497720160092, - -0.6762449151738805, - -0.6818480947834817, - -0.6872809185905433, - -0.6674437611695194, - -0.6726939334620584, - -0.6679654643318679, - -0.6622298254381274, - -0.6604153298929771, - -0.6634232047794218, - -0.6725586122292647, - -0.6937124855677474, - -0.6614064861108531, - -0.6655879818115533, - -0.6807025111389706, - -0.6720194314074666, - -0.6914837928648007, - -0.6783594944161238, - -0.678337591108074, - -0.6810117366020423, - -0.6860878366093911, - -0.6891640616322702, - -0.663289169035579, - -0.6729527542454519, - -0.6686342371691991, - -0.6826695134320471, - -0.6640017906942423, - -0.669872065326235, - -0.6959946779046207, - -0.674983164517916, - -0.6914855624312097, - -0.679221954089955, - -0.6938186589696134, - -0.6740234175753985, - -0.6739844350786226, - -0.6785845690516735, - -0.6831456007236262, - -0.6841388574214696, - -0.6975917917774193, - -0.666056398318824, - -0.6872544264439704, - -0.668189863996715, - -0.66817364387638, - -0.6647663009534135, - -0.6875050456376134, - -0.6652667059221818, - -0.6931420393223273, - -0.6853075078392803, - -0.6760429597070471, - -0.6720936106536758, - -0.6797862288894218, - -0.6684426803828294, - -0.6626771259869222, - -0.6653119147098012, - -0.6950729816504606, - -0.6907935350658361, - -0.6627911414696752, - -0.6899732283582299, - -0.6909849539971739, - -0.6945699928135668, - -0.6850509501194522, - -0.6970912764956406, - -0.6673791629225302, - -0.6929983604306441, - -0.6945695687853825, - -0.6763014401201268, - -0.6842908989792, - -0.6710614903914651, - -0.6602266523828683, - -0.6642028093414887, - -0.6772505759662178, - -0.6963523470139603, - -0.6852331307018932, - -0.6781563329169858, - -0.6838338153461031, - -0.6804833437710189, - -0.6754053571329968, - -0.6624291266449919, - -0.6842084674771782, - -0.6970437333197831, - -0.6961824134608616, - -0.6697989561601823, - -0.6621027358435413, - -0.6740386367700523, - -0.6798056368034838, - -0.6808045708552836, - -0.667825348485461, - -0.6775367106779304, - -0.6887281338805605, - -0.6794494430118139, - -0.6910132022874309, - -0.6914532193011151, - -0.6932101760059879, - -0.6975489237770228, - -0.6738470278319542, - -0.6791504521371138, - -0.6700696151636777, - -0.6609292628121038, - -0.6861577940123793, - -0.6627697680720739, - -0.6611180156837909, - -0.6960725528036611, - -0.6806951082987529, - -0.6863799807414959, - -0.6798283770474095, - -0.6886092970643627, - -0.6687806147207753, - -0.6939886002271214, - -0.6729365071172725, - -0.6920887822917211, - -0.6839292241776387, - -0.6875195602372259, - -0.677294059483719, - -0.6943036152672095, - -0.6677854403555811, - -0.6786799282377324, - -0.6862461237895201, - -0.6764735519681818, - -0.6776477382743485, - -0.6811685761077484, - -0.68658399165484, - -0.6752793364535454, - -0.6888216804068564, - -0.6696712056587935, - -0.6957595786070656, - -0.6757367868829003, - -0.682662263619943, - -0.6925980594710333, - -0.6612475860674104, - -0.6775071963156994, - -0.6602651766696861, - -0.6906164969927041, - -0.6953403367895009, - -0.6712165641768463, - -0.6602692437844891, - -0.6701832583554334, - -0.6948098950596887, - -0.6670570747519119, - -0.6862829939958408, - -0.6871860748868184, - -0.6818359658588492, - -0.6613593830636965, - -0.6768704667796747, - -0.6930935750021043, - -0.6974117471126111, - -0.681718536648049, - -0.6667314386422813, - -0.6945854226105568, - -0.6726031861625789, - -0.68466118862712, - -0.6619971491244699, - -0.6828602997994823, - -0.6976793784597808, - -0.6752348474572178, - -0.6887589995458859, - -0.6783134942502501, - -0.6779461413107882, - -0.6873544644987367, - -0.6758575615293594, - -0.6851955258123734, - -0.6627379496866868, - -0.6869159707906949, - -0.6826329231871908, - -0.6646511087785362, - -0.6690136109288157, - -0.6808618850913944, - -0.6614789225036978, - -0.6920513280966252, - -0.676599525981242, - -0.6952020209914223, - -0.6667309445512932, - -0.6846680323215785, - -0.678029652492314, - -0.6609507473855915, - -0.6944091238738621, - -0.6827604054873095, - -0.6750777979592932, - -0.6956817238177594, - -0.6708041529566309, - -0.6837169116790056, - -0.6758634133139066, - -0.6614266012515118, - -0.6758738157231715, - -0.6833364457973108, - -0.6735256934678312, - -0.6666894874162961, - -0.6770568533242027, - -0.6638495971907764, - -0.6845833959112412, - -0.6959388578618637, - -0.6860060942963059, - -0.6885874338709155, - -0.6631181799002115, - -0.6656198493025697, - -0.6942020733097257, - -0.6627700431527308, - -0.6861002451408925, - -0.6630898460678806, - -0.6708269561138879, - -0.6756396219342691, - -0.6649469291308054, - -0.6875954030168024, - -0.6953559178141927, - -0.6686344731758804, - -0.6836160494949891, - -0.6880623370906888, - -0.6737224493804856, - -0.6602550373383194, - -0.6631134407789977, - -0.6802855717992843, - -0.674654425174489, - -0.6861710555190127, - -0.6707414049904205, - -0.68407592348919, - -0.6728073406483758, - -0.688601585245522, - -0.6735831429133917, - -0.6955779873508309, - -0.683823970614698, - -0.691041802077868, - -0.6798131949630443, - -0.671581389018582, - -0.6887380792220447, - -0.6900380919130021, - -0.6773116151373348, - -0.6819414627315924, - -0.6698002483390159, - -0.693261361463937, - -0.6881782125146657, - -0.684061450381463, - -0.6862889704436388, - -0.6620709113347534, - -0.6777802039469352, - -0.6658986235436495, - -0.6767088279395986, - -0.6677133154561515, - -0.6839047827343512, - -0.6654358932102531, - -0.6807994724800226, - -0.6960031081622761, - -0.6952362964688373, - -0.6870391401379875, - -0.680959324612881, - -0.6864709221941706, - -0.6882155785217433, - -0.6744707433979625, - -0.6750459249836201, - -0.6774061431107924, - -0.6752827472064928, - -0.6617075479159128, - -0.6877772698110782, - -0.6668343143081599, - -0.666876155926276, - -0.6931595319836775, - -0.6655427802525903, - -0.6760825521860171, - -0.6651911081114592, - -0.6825256077405681, - -0.6793655626906279, - -0.6811210771760452, - -0.6928949267387551, - -0.6615197043962133, - -0.6897741811173308, - -0.6918743050934525, - -0.6753530460626138, - -0.6887315930820538, - -0.6730357032385131, - -0.6934645276374823, - -0.6701816624310536, - -0.6665888038786179, - -0.6967796183060665, - -0.6652817694087534, - -0.6942905645427806, - -0.6783268968974103, - -0.6856569615086835, - -0.6897882338603152, - -0.6655473744418994, - -0.6706348932670023, - -0.6685086161076256, - -0.6804675403656918, - -0.6659855222505514, - -0.6856834933909585, - -0.664313568969311, - -0.6608366551882838, - -0.6969616114667475, - -0.6914684216459602, - -0.6633574254905269, - -0.6966135440492925, - -0.6915137433648566, - -0.687713100303803, - -0.6770121865413958, - -0.6684402895423017, - -0.6900186771466346, - -0.6967736647063334, - -0.6607705659330411, - -0.6739468663360825, - -0.6622220213591462, - -0.6694171356987825, - -0.6602631750659941, - -0.6608247007318191, - -0.6609962877580743, - -0.6786883613356934, - -0.6878342177165813, - -0.671727805178135, - -0.6928767924062251, - -0.6757783661881112, - -0.6853872991064788, - -0.6602853014162304, - -0.6904440216470971, - -0.6931908257672079, - -0.691323397951282, - -0.6820011003712735, - -0.6609697793153273, - -0.6638361671423338, - -0.6939424067165783, - -0.6618369103992205, - -0.6689561474958134, - -0.6852019911360918, - -0.6843063839891654, - -0.6974360470643006, - -0.6930764919195065, - -0.6893903880278026, - -0.6742915384756283, - -0.6927634051133017, - -0.6878214114308622, - -0.6675385643952627, - -0.665473326423374, - -0.6722379815487818, - -0.6864586303238495, - -0.6940631233751487, - -0.6800841347654837, - -0.6781355860603744, - -0.6897355771124641, - -0.6782750461828223, - -0.6901219603482708, - -0.6681751461332505, - -0.6913591561754914, - -0.6700759117775952, - -0.6637496791537449, - -0.6736661439253805, - -0.6716299971617692, - -0.6629355385447498, - -0.6626477667199235, - -0.6718101199086317, - -0.6689763440399417, - -0.6855488448342107, - -0.6777880198386262, - -0.6859736021235279, - -0.6674123571423537, - -0.6680259472229403, - -0.6947263416052759, - -0.6668111779410876, - -0.6603948192752008, - -0.6899772334501494, - -0.6612981874087145, - -0.6915281928051303, - -0.6886361261250465, - -0.6693309151333993, - -0.6621867860432537, - -0.6751280098708455, - -0.6887761865023837, - -0.6647603715080921, - -0.6787578579744076, - -0.662170660407926, - -0.6797741549127545, - -0.6618981402861653, - -0.6657404313878066, - -0.6731570794001185, - -0.6789238684212862, - -0.6867863141462432, - -0.6623866476282485, - -0.6810245932989393, - -0.6923379956053464, - -0.6800257891565975, - -0.6897237695276617, - -0.6709644861374151, - -0.6640610388161057, - -0.6869395392388271, - -0.6940107871017819, - -0.681261634245777, - -0.6945613398762703, - -0.6910995335188319, - -0.6684475730628032, - -0.6800940638702028, - -0.6909690285937159, - -0.6902836981947678, - -0.6923242120916643, - -0.6864386562187127, - -0.680394601300569, - -0.6874876321262026, - -0.666982155525292, - -0.6934081536009647, - -0.6870741013238458, - -0.6610756035065875, - -0.6758260703202007, - -0.6954689183397278, - -0.6895550007297366, - -0.684050977780381, - -0.6691919432085031, - -0.6949525215646, - -0.6673338586256298, - -0.6631264512755615, - -0.6740735790072454, - -0.6686136034872043, - -0.6938570103556978, - -0.6698905172102271, - -0.6884851714138002, - -0.6645840730269992, - -0.695405172097749, - -0.6673397357547255, - -0.6969639557589473, - -0.6895750253899385, - -0.6865974771378084, - -0.6968614130667298, - -0.6795772040048131, - -0.6713359545323115, - -0.6888695374693296, - -0.6656528818361287, - -0.6602355266318771, - -0.6950315611902632, - -0.6619463460541736, - -0.6785368266359034, - -0.6933231959108186, - -0.6772100619646573, - -0.6604070588589573, - -0.668643387605257, - -0.6772543415619097, - -0.6940296147272571, - -0.6693026298459428, - -0.6934438402057589, - -0.6889060647839713, - -0.678236474876074, - -0.6963028135284706, - -0.676796774392656, - -0.682310491015884, - -0.6947406903873912, - -0.6902805950590825, - -0.6939818379288455, - -0.6783107488350006, - -0.6689324446815202, - -0.6689863380730167, - -0.6688251816029916, - -0.6720045490299665, - -0.664158661741929, - -0.6734967022168055, - -0.6887327976401898, - -0.6885435846358108, - -0.6919136997051241, - -0.6865448563146183, - -0.6654062000797991, - -0.6656070698185391, - -0.6618134827923989, - -0.6871729465011924, - -0.667088200190356, - -0.6888684651746658, - -0.6857722141150525, - -0.6765402234836546, - -0.6652231023423355, - -0.6741494675783527, - -0.6708406014324094, - -0.6930775702710844, - -0.6765774460203097, - -0.6910023348631881, - -0.684100459191232, - -0.6849764737486642, - -0.662620584683778, - -0.6835973951023421, - -0.6886229305788955, - -0.6928391904785537, - -0.6922643094569537, - -0.6892558070202082, - -0.6956371108127828, - -0.6718129904184356, - -0.6891973561919823, - -0.6866975306727819, - -0.6783188259235202, - -0.6969151517393047, - -0.6759766538750919, - -0.6697124977309957, - -0.684503440419006, - -0.6729044925083957, - -0.6729596250329484, - -0.6717915779906319, - -0.6607745357044513, - -0.6849961710949776, - -0.6864102252298755, - -0.6713387020921092, - -0.68414695927534, - -0.6904736332534671, - -0.685039914727294, - -0.6612107706480245, - -0.6736519130937015, - -0.6928007420636159, - -0.6612433500161976, - -0.6692068452468573, - -0.6692600978794168, - -0.6863449473746487, - -0.668887922586638, - -0.6744696304301374, - -0.6860778614134376, - -0.6847976996975548, - -0.6659076375761189, - -0.6693789786387505, - -0.6749871602288893, - -0.6706925063266258, - -0.6919992532563639, - -0.6932898360084259, - -0.6616486488026565, - -0.6919217240517208, - -0.6953439716014542, - -0.6677644023838503, - -0.6754518364592047, - -0.6937529812973326, - -0.6865327247825164, - -0.6664232785090369, - -0.6850078169011665, - -0.6947233968385566, - -0.6895085643256345, - -0.6665983970554035, - -0.6609041829102352, - -0.6887663454769573, - -0.667775240532318, - -0.6831504079109323, - -0.671001134284783, - -0.6698483176094285, - -0.6775620020122828, - -0.6647065051361573, - -0.6954024103312788, - -0.6800857898276765, - -0.6747559068969391, - -0.6871998876240792, - -0.6788670473463918, - -0.6911664669600909, - -0.663533085271234, - -0.6782490205521178, - -0.6615490744747978, - -0.6738657784032835, - -0.6951522534430712, - -0.6895969832545322, - -0.6827328140279411, - -0.6630709017354147, - -0.6851587715344126, - -0.6662967082687511, - -0.6750548073448224, - -0.6954214997588452, - -0.6971836508146557, - -0.6663007537364207, - -0.6673889085737384, - -0.6725440899571016, - -0.6642170271131129, - -0.6950949791366942, - -0.6880947935783122, - -0.6715436312171733, - -0.6735429675220264, - -0.6834984753720279, - -0.6721369051365197, - -0.6761583810443088, - -0.6803612581554632, - -0.6948980502045984, - -0.6781598897909548, - -0.662596620787512, - -0.6783142760944824, - -0.6862446480217225, - -0.6735534851459501, - -0.679908046424463, - -0.6647607648400234, - -0.6669471358665875, - -0.6958957279036927, - -0.696782580837614, - -0.6675157466051602, - -0.6635107119737745, - -0.663480701810269, - -0.6906537767089471, - -0.6872325662516383, - -0.6709115429666466, - -0.6732821227590878, - -0.6613653819020286, - -0.6977847951350087, - -0.6767792893468727, - -0.6809853803904504, - -0.6863470414068759, - -0.6943916692963243, - -0.6842129025688839, - -0.672223720719469, - -0.6878309192364624, - -0.6642191605949691, - -0.6826951985145107, - -0.6787069484564163, - -0.682023585727884, - -0.6781779702380255, - -0.6854175254115465, - -0.6968694198409265, - -0.6733669207373515, - -0.6949165331112863, - -0.6898735744038513, - -0.6673373934970633, - -0.665147634861431, - -0.6673745565457034, - -0.6855328871865872, - -0.6801602941421095, - -0.6820626509804671, - -0.6747699782709048, - -0.6683914204220394, - -0.6733761102531914, - -0.6829397269378238, - -0.6655914086675134, - -0.6750875382262094, - -0.6786976814929876, - -0.6824105086916041, - -0.6785164007807406, - -0.6794161792715614, - -0.6754351819119847, - -0.661118930579629, - -0.6652466576298275, - -0.6675395631518609, - -0.6618482056253472, - -0.6642968340817074, - -0.6851601579946209, - -0.6815846480314534, - -0.69386531921823, - -0.6776054767421945, - -0.6768473776562575, - -0.669115904755571, - -0.695605535339369, - -0.6845824109061895, - -0.676340151595163, - -0.6931482888691953, - -0.6636157421428805, - -0.6966346163527408, - -0.6661031915846848, - -0.694689689088112, - -0.6954037442928883, - -0.691958913684796, - -0.6683335683546654, - -0.6678395777914916, - -0.6795153634033079, - -0.6837998414602038, - -0.6615486131564381, - -0.6689155820436684, - -0.6799751335612643, - -0.6780021041413088, - -0.6973554960339466, - -0.6645003735006314, - -0.6807820314427774, - -0.6778635539297281, - -0.6813120565615203, - -0.6654537645687179, - -0.6790952775804372, - -0.6874429504744202, - -0.6824835988577211, - -0.8082537854559504, - -0.7809652936675557, - -0.7686186107417998, - -0.7367286006017599, - -0.7083101231982896, - -0.7011198642162784, - -0.7507427721426679, - -0.7733816193332199, - -0.8108085356899118, - -0.7850623663402492, - -0.7381511786753021, - -0.8051124254402168, - -0.7384043589584661, - -0.7244098866860297, - -0.6865579971798647, - -0.7183391099465046, - -0.7023000286111607, - -0.7501574834153549, - -0.7883245409586445, - -0.7648644004633011, - -0.7338123468093993, - -0.8078783844903993, - -0.8129545610217592, - -0.7481888050526007, - -0.6624418145187709, - -0.7483751982931963, - -0.7408063922007615, - -0.6997036695375833, - -0.8151620734055683, - -0.679147255599717, - -0.7055122667289377, - -0.7012072982717966, - -0.6784526969336174, - -0.7163946285279927, - -0.6802708326921996, - -0.7672001955487346, - -0.6929875064451335, - -0.7975780234648948, - -0.7530112910729103, - -0.6953432205199513, - -0.6779045701719233, - -0.6828333848613015, - -0.7077342065451093, - -0.7131962742442496, - -0.7840587986798778, - -0.7201040033078966, - -0.6932434858854518, - -0.7211026589229367, - -0.7518952763861728, - -0.8050339519818339, - -0.7559175531894027, - -0.7815923925415572, - -0.7813990478446698, - -0.7856699507229238, - -0.758673835677503, - -0.7835234973149285, - -0.8064932623547971, - -0.7749171761222516, - -0.7089430608044537, - -0.7014261834869834, - -0.7710455667317335, - -0.7252973810197845, - -0.72405419511947, - -0.7625855025390184, - -0.7789499845927068, - -0.7463836174468936, - -0.6781941171109842, - -0.7975158095614546, - -0.8146024349930661, - -0.6606496418498314, - -0.7159789845648135, - -0.7099923039390789, - -0.6740522123162795, - -0.726440474026224, - -0.6943128691331284, - -0.7342047228771882, - -0.7239539305061962, - -0.6701490073432164, - -0.8026257423559757, - -0.7054228180632809, - -0.7233476676195694, - -0.7109689001677423, - -0.67635589840931, - -0.675925021290397, - -0.6626927757158676, - -0.7492134448301406, - -0.7070476757236973, - -0.7564287391017832, - -0.8098849309496458, - -0.810805137563184, - -0.7641363078151392, - -0.7284504592380547, - -0.7505183193337199, - -0.6712103974338802, - -0.7650108584475936, - -0.7044712313754258, - -0.7113565388494385, - -0.7628493331939756, - -0.6681419802003163, - -0.6877969684813554, - -0.7573098925251769, - -0.8040837943171818, - -0.761462824618976, - -0.7801279201030749, - -0.7444933055696845, - -0.6783993643711261, - -0.8025477686154884, - -0.7320591448948601, - -0.7517031265921671, - -0.7406126396906796, - -0.7415103443238972, - -0.8100629135383143, - -0.7914870549113895, - -0.8112907475989314, - -0.6603091974864932, - -0.6787818938888602, - -0.7077408023337644, - -0.7604659167102941, - -0.7242017310713983, - -0.7269017721419014, - -0.805313947253889, - -0.702283245582013, - -0.6916238772620583, - -0.773890222058508, - -0.7095167889739532, - -0.7733932162477396, - -0.7478430978822835, - -0.6926955970685353, - -0.7684586367533139, - -0.7414082078110309, - -0.811198092002705, - -0.7931805575689981, - -0.6971998679002221, - -0.7427614527411136, - -0.7872591656271013, - -0.7246805377653839, - -0.7995518638108075, - -0.7202337315184324, - -0.7245409908827884, - -0.7096942630362476, - -0.728566397545838, - -0.7517862161539377, - -0.7385935739144583, - -0.6803830910283633, - -0.7766488293064546, - -0.8013666937148393, - -0.6663085400420963, - -0.8154341302053894, - -0.7756792737941908, - -0.6985995817693657, - -0.6799642400723069, - -0.7964497389248135, - -0.6929569978688812, - -0.7394984012088627, - -0.7433783484907506, - -0.7940584001399346, - -0.7777355360642009, - -0.6842300451926169, - -0.7798292919684131, - -0.739583003875077, - -0.7257922425274839, - -0.7151270707384795, - -0.7395313976696307, - -0.738043944084877, - -0.814439127392499, - -0.6983814212276914, - -0.6668536580852866, - -0.7062980809154539, - -0.7340579899501454, - -0.7636590861443354, - -0.7372898599510901, - -0.678732027219667, - -0.8087819695254485, - -0.679413988215789, - -0.754349375247956, - -0.7273276292301765, - -0.6817382897604457, - -0.7745685162108457, - -0.7916079367846374, - -0.7653714813210452, - -0.6826378879677509, - -0.7196650042481163, - -0.6957043119999815, - -0.8046691167799227, - -0.7287078204699089, - -0.7323029696707395, - -0.7020747480397972, - -0.8148313981441138, - -0.6827958638831663, - -0.7299770474948607, - -0.7063859900185623, - -0.7514163729880418, - -0.7377393010685498, - -0.6652619602049115, - -0.7896521360562931, - -0.7995753763497307, - -0.663172165886539, - -0.701417255321219, - -0.7350772672058106, - -0.7890769796082692, - -0.7207858423555501, - -0.7503068410097699, - -0.815425989247594, - -0.75259509903174, - -0.6832941389174174, - -0.7292765630957412, - -0.7232082143328096, - -0.8069069607552171, - -0.7880673373947314, - -0.7061800544539385, - -0.6740036851300922, - -0.6613354681669145, - -0.6843119270640606, - -0.6826107887842577, - -0.6997269779970222, - -0.7193208589463731, - -0.7691226382083544, - -0.6730085810464805, - -0.6807545069623241, - -0.6606828168810279, - -0.709625487766931, - -0.752626597740686, - -0.7620610013797376, - -0.6824404809522949, - -0.8102170785791366, - -0.6964470171237498, - -0.6998388655140427, - -0.7580707025171567, - -0.7613149790589431, - -0.6935584442069949, - -0.6626872995386094, - -0.7690930641292599, - -0.7009815449023018, - -0.6690058990908725, - -0.6882213161887741, - -0.7935694201994627, - -0.798271365948894, - -0.7415187645592832, - -0.7938805586970233, - -0.7724275771190755, - -0.8032376264257073, - -0.7818185430548307, - -0.7359452981969781, - -0.7102188666769571, - -0.6849795218422997, - -0.7925531682678814, - -0.7153367944548678, - -0.722841917764693, - -0.7129548650701383, - -0.7782483560336755, - -0.7701597511379804, - -0.7698006783108916, - -0.7215761683498232, - -0.7028876616155644, - -0.6667661705191923, - -0.7333467979840593, - -0.7793361176880785, - -0.7695489636600328, - -0.6796038250918358, - -0.7453377661474611, - -0.8110392091021217, - -0.7953854471366646, - -0.6651601805298681, - -0.7448873406690434, - -0.7642945362571354, - -0.7749084932957211, - -0.7257095979810816, - -0.6836072528074403, - -0.7444690303533339, - -0.7066186798588145, - -0.6678192960041613, - -0.7137655541549336, - -0.7822313660842676, - -0.780027933322762, - -0.7578853275973024, - -0.8024656274811484, - -0.6736261259642493, - -0.8032408156616507, - -0.759734595338244, - -0.7840832715373334, - -0.7784695023072972, - -0.7526615221309841, - -0.6775125549344729, - -0.7579719110635003, - -0.6732114582500793, - -0.6710471626556314, - -0.7870992688371143, - -0.7664547863417959, - -0.8042627194115393, - -0.6640288186835195, - -0.7708004830239259, - -0.7102531024671752, - -0.772553790033168, - -0.809653330847487, - -0.6940279810455523, - -0.6994463129739498, - -0.6717387716132002, - -0.701879509797213, - -0.7759496380341984, - -0.7001117440062223, - -0.7086474256117086, - -0.6743665336936229, - -0.8052625102500502, - -0.6894083029604956, - -0.8021614104429808, - -0.7068269310943087, - -0.7453172398786513, - -0.7352212326496468, - -0.6768310527448813, - -0.7461268464452655, - -0.7188228198351353, - -0.7310751574764904, - -0.7556393795621187, - -0.6872946320217798, - -0.7780964209039813, - -0.689170275992497, - -0.7079678845886694, - -0.7553187620795873, - -0.8154417018300902, - -0.7736467647078682, - -0.7690778298855347, - -0.7661629167030568, - -0.6927301051027107, - -0.7714542868818768, - -0.7565757102437599, - -0.8017430127881998, - -0.8009257212458369, - -0.8038241332538255, - -0.6603629017328185, - -0.805579700625961, - -0.6749913942932106, - -0.6726279046868531, - -0.6952418071551819, - -0.7627024241194795, - -0.6848091697345668, - -0.7621909192829806, - -0.7937719408755084, - -0.7602248228558792, - -0.6650006191433697, - -0.7064493653900563, - -0.6686199700956689, - -0.7712852894349207, - -0.7449466419994435, - -0.806808641835594, - -0.7375024613921416, - -0.792380266781774, - -0.8029290449633921, - -0.7666236877607284, - -0.7239031793427938, - -0.6906126432244638, - -0.7675839076274538, - -0.792271192562784, - -0.7209869934098567, - -0.6784852614524273, - -0.7210154704320523, - -0.7853006224063994, - -0.6713081461203879, - -0.7911555437103186, - -0.697387086296887, - -0.7926075191530563, - -0.6688151784168688, - -0.7583124929459502, - -0.7557043682892038, - -0.7805434788663742, - -0.7047799305846778, - -0.7220082388488656, - -0.7042754754964511, - -0.7482466352802566, - -0.7040879851261382, - -0.7355651859584685, - -0.6910282211174517, - -0.7158344021501759, - -0.6626693993518713, - -0.7442460206638029, - -0.8015965973092463, - -0.7476953421331541, - -0.765495230205194, - -0.7316009484641326, - -0.7878275219825316, - -0.7494043409005036, - -0.7046225612804555, - -0.8000706791105889, - -0.6655185889724629, - -0.7596683437148162, - -0.7291037257042312, - -0.7710635669716095, - -0.7468944660472785, - -0.7099212566800578, - -0.7464125743570005, - -0.777483385333429, - -0.662274377625539, - -0.7483129306354079, - -0.7521395528614001, - -0.7283466418416331, - -0.7581407553064078, - -0.8064587680099801, - -0.6961922135748526, - -0.7595852946610242, - -0.7610177553518879, - -0.7188879859364492, - -0.7956854565622351, - -0.7706197503465789, - -0.7300718029651299, - -0.6838191032403026, - -0.8040147054535768, - -0.7791456191935986, - -0.7004872048312789, - -0.7508833711504629, - -0.7453804025136574, - -0.6621903015486836, - -0.8056525343272534, - -0.6861773725673814, - -0.757963749191169, - -0.7630420044671244, - -0.7484033719421042, - -0.7829140833917044, - -0.7222278803114853, - -0.6784148867481953, - -0.742640389493095, - -0.7680604812448437, - -0.7843958982257437, - -0.6705311323705361, - -0.7796854312823596, - -0.8124087452206723, - -0.7424341466416957, - -0.7528301141947965, - -0.7436064341406099, - -0.7323884062138931, - -0.7815326256019546, - -0.7592696755702938, - -0.682276826931995, - -0.7277523657323578, - -0.7254880187214432, - -0.7944929808889551, - -0.6925720088923183, - -0.7934333286800869, - -0.6795930759529547, - -0.6619883866408023, - -0.7928080614801968, - -0.7549872903287831, - -0.7014257823915578, - -0.8078351377503764, - -0.7684392706884166, - -0.7428127491621273, - -0.8067543397135565, - -0.7491395595707501, - -0.6730842934837458, - -0.7584594157829575, - -0.7976194544477985, - -0.7072863506980254, - -0.759305126009165, - -0.7569211819906763, - -0.7507799700242404, - -0.7272060147534579, - -0.7765320471245952, - -0.7733744081934936, - -0.71654196382889, - -0.7648270359905373, - -0.8029776827119526, - -0.6978067842364062, - -0.6775138349135559, - -0.7682979722604715, - -0.701454404450971, - -0.7618381619093915, - -0.7035977828629639, - -0.7894779135365255, - -0.7954459757548651, - -0.7795533509385647, - -0.7155004289458575, - -0.8017791073655567, - -0.7236537329826255, - -0.8019940893544314, - -0.7780646349175464, - -0.7385156058536552, - -0.6973869628257656, - -0.7904879170304154, - -0.6987441065736678, - -0.6721944563927442, - -0.7842299891548173, - -0.7604497144451006, - -0.7284352145113691, - -0.7871571595340954, - -0.7076598720817048, - -0.761052758701599, - -0.6688812184208188, - -0.7281414766242302, - -0.7867426770913883, - -0.7828841241074233, - -0.7236732107028466, - -0.7104598646337651, - -0.7299679551040777, - -0.6922837281155474, - -0.8049317196548256, - -0.6750430570470529, - -0.6850018001613705, - -0.7033927762906098, - -0.7065097403567651, - -0.6886471257144453, - -0.7674584856573108, - -0.7714441857548647, - -0.6698171195404731, - -0.6914855714235834, - -0.6976005501625085, - -0.7349842522071324, - -0.6717563644284152, - -0.7249758568553377, - -0.6757409493867058, - -0.6968910010729593, - -0.7474567119746522, - -0.7670321648383452, - -0.8099294696701486, - -0.697776077083007, - -0.8024278050389043, - -0.7204289013853948, - -0.7769346129962941, - -0.6646583094908765, - -0.7465034264001303, - -0.7676632083298711, - -0.7446217306538653, - -0.7663841026777704, - -0.7079992351572881, - -0.7992322403919259, - -0.6680447697897225, - -0.7044657869050779, - -0.6761420289231191, - -0.7806824977857539, - -0.8129914001985269, - -0.6943292996149353, - -0.747765261056524, - -0.6889411950725823, - -0.6668341277070131, - -0.6687889238146889, - -0.7214354846315678, - -0.7805159990214072, - -0.7564685006731054, - -0.8158150220045834, - -0.8105331981822668, - -0.770307040969049, - -0.7461725308048495, - -0.7538086232221337, - -0.6678471846348895, - -0.7443286010371398, - -0.7460735593154385, - -0.6913894447447235, - -0.6947480607615888, - -0.698872558709676, - -0.8020565172914645, - -0.7749707015974194, - -0.8005683362249638, - -0.7473091113857526, - -0.748474264819076, - -0.795590983548681, - -0.7460536319192603, - -0.7429044008703238, - -0.7957863469291557, - -0.7543818362553986, - -0.7757257133946089, - -0.6836284723478581, - -0.7924257399668467, - -0.6772604917674151, - -0.7154195306857789, - -0.7840508109430195, - -0.7451618152250847, - -0.7167076345541363, - -0.7248367361062028, - -0.7511076218624673, - -0.6866638133729026, - -0.7318019759145181, - -0.6894211340666493, - -0.7166698215267282, - -0.7831396638272553, - -0.744306740418474, - -0.7525062179804173, - -0.7189420779662686, - -0.7404294327507748, - -0.7385987073015431, - -0.6950498583975995, - -0.7962393620708337, - -0.8052026066836679, - -0.6644285522045257, - -0.7993703566896092, - -0.7128505231632543, - -0.6922233863397395, - -0.7750092185702481, - -0.6946378207062059, - -0.7935413229571344, - -0.7301308889874755, - -0.7614488554275691, - -0.7508165653499657, - -0.8077206986827458, - -0.7641200887679399, - -0.7527313924350494, - -0.6718645635831095, - -0.7497825769575828, - -0.7289417380632915, - -0.7611827358211086, - -0.6733190254253136, - -0.6641148972963478, - -0.6894030896635515, - -0.773480118446543, - -0.7532423906394918, - -0.7168449885261742, - -0.7297805217111499, - -0.8047642468222276, - -0.6718408379273475, - -0.7550610492296552, - -0.7524145094212453, - -0.7974447552412944, - -0.7620758183715379, - -0.6682249598019396, - -0.7441221157698784, - -0.6995217575776682, - -0.7797159122283784, - -0.671620921005587, - -0.6731083107633816, - -0.7826900853894903, - -0.8027235172979295, - -0.6889355724584141, - -0.7200127449186442, - -0.7724653553358152, - -0.8039219223420013, - -0.7644829967647024, - -0.7100301061909446, - -0.7169764381820867, - -0.7655011942132113, - -0.7345491023597882, - -0.6813726787097941, - -0.755689866354876, - -0.7333876820468981, - -0.785870664418124, - -0.8040057052008431, - -0.8102331343690126, - -0.693550751942431, - -0.7342019857195979, - -0.7721037813772718, - -0.7373508669249541, - -0.7385376752087459, - -0.7335683412867096, - -0.7315121285936504, - -0.7801549009035966, - -0.7916231230195055, - -0.7982134610519361, - -0.7824524383968455, - -0.8123037109732814, - -0.7179061989806503, - -0.6923216261846515, - -0.689691800261539, - -0.7624418256949547, - -0.7433766303948928, - -0.7863147162702566, - -0.7387642466941002, - -0.725576714163906, - -0.7294721556939916, - -0.7326661834471119, - -0.7682649010531349, - -0.7829712916849253, - -0.7488038141146499, - -0.7198106431389065, - -0.7081008326244067, - -0.7559906576080972, - -0.7802394388821213, - -0.7869556970094248, - -0.7808381167845977, - -0.7891377787612494, - -0.8127289573992339, - -0.7345247131185234, - -0.6743365696973702, - -0.778785895749364, - -0.7211256018184269, - -0.7405108407122337, - -0.7279864662138086, - -0.8120772282098246, - -0.7249903380743852, - -0.754649029657757, - -0.7334170548790404, - -0.6877158498326699, - -0.7579026150026225, - -0.7968974412229282, - -0.7966318988546224, - -0.6823420116821588, - -0.765719687529785, - -0.7869670157585561, - -0.6899832144780219, - -0.7238259043560779, - -0.7113637596885162, - -0.7505249358724053, - -0.7122248168367424, - -0.6656705546579331, - -0.7237412015829119, - -0.7891018734030828, - -0.7507297988538327, - -0.782996727905639, - -0.7307539739768847, - -0.802260550780386, - -0.8028266514482325, - -0.7097300906273512, - -0.7453639999675478, - -0.7074160174740493, - -0.7320291935673744, - -0.7029560511028782, - -0.7647679946639261, - -0.6767808763278854, - -0.7138806057596462, - -0.8146692863991232, - -0.6819777720360913, - -0.6785331850372207, - -0.7070226891363003, - -0.7211898087161971, - -0.771662348891635, - -0.6687390258708819, - -0.6976380054315455, - -0.7132221610105157, - -0.6605199894357934, - -0.7056623320568997, - -0.7524324002161714, - -0.7015459131209439, - -0.7359125494017706, - -0.6921202714814172, - -0.666806865220135, - -0.7617011194176485, - -0.7536875847457383, - -0.7608389805101646, - -0.806598830766539, - -0.6733215491980302, - -0.763380180391726, - -0.700388039279875, - -0.6716090635486993, - -0.7890361991716089, - -0.6608574088898438, - -0.6784522273901789, - -0.7849937193264835, - -0.731433858308586, - -0.7178657511316396, - -0.6614971419759234, - -0.7107924162578008, - -0.7469152313451285, - -0.6783644313668784, - -0.7998239179662086, - -0.7384938322762139, - -0.7348611532731724, - -0.7869214794456628, - -0.7707688075295613, - -0.7921005496959647, - -0.6906908695415227, - -0.7843496787602396, - -0.7816413961993969, - -0.7207699719134759, - -0.8001800196798357, - -0.7838841566258118, - -0.7066775429508249, - -0.6604210988719842, - -0.6710247673292424, - -0.696723749583666, - -0.7740304502179406, - -0.7558775397088084, - -0.7036399439613457, - -0.7884837066970947, - -0.6939211314625013, - -0.7531138339322162, - -0.6758092878185594, - -0.7076237010669288, - -0.7275592127025399, - -0.8048883836753767, - -0.712788567014694, - -0.7349222213893829, - -0.7561998811927054, - -0.6606930523970591, - -0.7246217099499804, - -0.8015677485662851, - -0.7232339267988638, - -0.7933904092228733, - -0.7627195924205803, - -0.7986928013110854, - -0.6778755167851274, - -0.6681411605011304, - -0.7469489719966659, - -0.7323177322999942, - -0.6789697905904201, - -0.7146622133207896, - -0.7108037859805426, - -0.6920970729939742, - -0.7856449512314689, - -0.7495044206789842, - -0.7896254841802075, - -0.7345916259252537, - -0.768746716180541, - -0.789611634599668, - -0.7405083804050449, - -0.7913672917063534, - -0.7461761992917445, - -0.7945369024590448, - -0.7071082832606772, - -0.7112348639887496, - -0.7110603332509846, - -0.740790510829605, - -0.7683665066492832, - -0.8125263668700339, - -0.7250307539377775, - -0.6822248887567491, - -0.7822765468341532, - -0.8111152094934997, - -0.778968923071991, - -0.7004086581575973, - -0.7429310373698647, - -0.7774884157066356, - -0.7964091475543824, - -0.7179005113445704, - -0.7833586570972347, - -0.747043387157893, - -0.7415857681470452, - -0.7972799796359424, - -0.7305347171724625, - -0.7002774772123754, - -0.724192596800554, - -0.7297476887080353, - -0.7208429947591797, - -0.6697350509274907, - -0.7918579248904262, - -0.7759468652925904, - -0.7702924626083187, - -0.7755126907917859, - -0.672402999059041, - -0.7831451508237268, - -0.7591132542471709, - -0.7361893768386153, - -0.7411507269950964, - -0.6649230454095933, - -0.7672792930454481, - -0.7292113662921855, - -0.7386161196016824, - -0.8009252558405489, - -0.7177422736769368, - -0.764159548620302, - -0.7013257409351422, - -0.7113824059463504, - -0.6685029252230054, - -0.6986023180674075, - -0.697212794425147, - -0.7339726120514718, - -0.7842878867490071, - -0.7579700178341926, - -0.7781510503463753, - -0.7927146961679632, - -0.7311883390264883, - -0.8081865959233584, - -0.6846188450183727, - -0.7625744731951289, - -0.7221573305091141, - -0.7321771924796582, - -0.8039399713934013, - -0.6654485738443124, - -0.7569655603823341, - -0.6753730700477486, - -0.7569347971121814, - -0.6813504938716443, - -0.6892168814338687, - -0.7621853492000895, - -0.804246103058316, - -0.710417882482629, - -0.7380506788740471, - -0.6772180489616461, - -0.7087796805917684, - -0.6966892937032723, - -0.7049933880547565, - -0.7869222940230993, - -0.6688407894395155, - -0.7911656570753917, - -0.7435910569959452, - -0.6735456630575443, - -0.7110590666199195, - -0.6967676322084624, - -0.758936172300171, - -0.7210418733725021, - -0.7403871904064967, - -0.7359555121480165, - -0.8053870699834335, - -0.7082586083084541, - -0.7256485073514325, - -0.6717555132324282, - -0.7730768936520426, - -0.7123245922120955, - -0.7049236655820224, - -0.7821883945504453, - -0.8055288241030474, - -0.7208218281714355, - -0.6907594933896547, - -0.7615628564166433, - -0.8076290890718094, - -0.6600810349993413, - -0.6765532954169178, - -0.6812052435026779, - -0.7360322663145307, - -0.6774921528301369, - -0.7555402098526205, - -0.7562506985025329, - -0.7481230175679855, - -0.8109352920984156, - -0.809522828434831, - -0.789519636483262, - -0.8018925423115412, - -0.7878626373172004, - -0.6948223600387794, - -0.6629262415491219, - -0.786498492363722, - -0.694148899955676, - -0.6753305377171688, - -0.8101561674406709, - -0.6952168249841544, - -0.744739389196462, - -0.7753519013396009, - -0.6663732825483741, - -0.7109908827986059, - -0.7026720548345043, - -0.7344333618601154, - -0.7192872571629356, - -0.7839663316898323, - -0.7192427693571591, - -0.8084441218276454, - -0.6728631928129464, - -0.8141898044610582, - -0.7123219919169219, - -0.7172850701683341, - -0.7235542117685536, - -0.7453491748306825, - -0.7041066957294684, - -0.738637023734702, - -0.6751117281547816, - -0.7609434079655919, - -0.7733252928294513, - -0.7391946825150553, - -0.7978972554925584, - -0.8085953886387537, - -0.6742706701026637, - -0.6896881779245939, - -0.7567707685593605, - -0.781954730389963, - -0.763860229703268, - -0.6678646609392355, - -0.6751252910144083, - -0.7209659795521649, - -0.7260666938433473, - -0.7084646545427487, - -0.7722920076902159, - -0.7233573165587095, - -0.72114024693462, - -0.811994209769708, - -0.7313138232589913, - -0.685805746827782, - -0.7851581930707766, - -0.7607912431535444, - -0.8090362202677807, - -0.7097133627913706, - -0.7048478282416186, - -0.6921294699345355, - -0.725640208805393, - -0.6814859871425796, - -0.7893744433682931, - -0.7194977601107789, - -0.7202776488844339, - -0.6916927475800733, - -0.6891760429518293, - -0.7969044190549723, - -0.718794720542767, - -0.7957693354397309, - -0.6621416621865994, - -0.7461612928995878, - -0.7854920946605268, - -0.8077673324547844, - -0.6850734702994871, - -0.714412662013507, - -0.6740323507516699, - -0.7849480936198981, - -0.7265748830978288, - -0.7090444429524614, - -0.7225654037060523, - -0.7566535978129802, - -0.7672497251407902, - -0.7229277911442513, - -0.8107799963653843, - -0.7582386200699867, - -0.7891640550778517, - -0.7201379885030019, - -0.7618022000280426, - -0.8151993473682462, - -0.6920207331519646, - -0.702184967024168, - -0.6908188123832469, - -0.762136200446935, - -0.6936629396002046, - -0.6867371859242282, - -0.7123994273740932, - -0.7437898902747795, - -0.7992813264324438, - -0.794317113463664, - -0.7554084578891826, - -0.7479360247131999, - -0.7655476759020474, - -0.7165390224070756, - -0.7350789319616056, - -0.6713018772989634, - -0.7980913118386884, - -0.6742218362866654, - -0.7649398111304642, - -0.7520704144591094, - -0.7403674048044484, - -0.6783058456926958, - -0.8014943544891008, - -0.7437474909887928, - -0.7654698808242418, - -0.7041718401844974, - -0.6875085427028513, - -0.6678152353126059, - -0.7539654282397206, - -0.790921001069685, - -0.7585976010301232, - -0.6710775828226327, - -0.6788265195783298, - -0.7409927380364553, - -0.815534157242014, - -0.7331875395080014, - -0.7770167886650126, - -0.6693749300413788, - -0.7035896695588517, - -0.6860284002638348, - -0.7574713609055982, - -0.7920120509408818, - -0.7669995400701616, - -0.7042899853409208, - -0.6901011052995509, - -0.7375377135233583, - -0.8027171982118326, - -0.7788837355531758, - -0.6699696817765713, - -0.7690737911139892, - -0.6955231574888261, - -0.6759634763740403, - -0.735611721539926, - -0.6908364424816648, - -0.7832622331577449, - -0.6709967569267401, - -0.7162206128385583, - -0.7466991130448464, - -0.6633804996377675, - -0.7777963882716771, - -0.7369799398404155, - -0.7591836224313574, - -0.8006518379809809, - -0.7379865077174657, - -0.7711326427678056, - -0.7092598026120672, - -0.7666906703879091, - -0.6665168105497298, - -0.7711191132153907, - -0.6784813345689484, - -0.7975846945045995, - -0.7531449116939073, - -0.7611621705190522, - -0.7706277204390661, - -0.7382221419063071, - -0.7870496807132917, - -0.6737790761371374, - -0.7479653555316566, - -0.685215924161555, - -0.8006507959129547, - -0.8068174387644529, - -0.7194635196488061, - -0.694035560398018, - -0.7441585545463355, - -0.788825573729653, - -0.6776132462107983, - -0.6974860133229853, - -0.7255887261328248, - -0.7996825434371676, - -0.736528896882477, - -0.7323199222805412, - -0.7163350171160385, - -0.7104282847127971, - -0.8094996829119366, - -0.6718695097575313, - -0.7992548157233764, - -0.7616406208020541, - -0.7638977832560676, - -0.6698461550486514, - -0.7924255651638871, - -0.7853768024460672, - -0.7921298306559548, - -0.6966413577913394, - -0.7453753216540548, - -0.7244536196375524, - -0.8137020273762314, - -0.735039956513422, - -0.7524949266499379, - -0.6688424809166703, - -0.8036644834060788, - -0.7769780031984497, - -0.6985531931786431, - -0.7097846119915452, - -0.8097444116993268, - -0.7941425401452231, - -0.814572822449483, - -0.8074745169998926, - -0.7781138553381195, - -0.7337072292895511, - -0.7309969364605696, - -0.7479692680351608, - -0.7486341995919532, - -0.6616969340104808, - -0.699133795393928, - -0.7479689353375094, - -0.6848521870139657, - -0.798909629291144, - -0.7307129467597174, - -0.6640219850320446, - -0.7486705857810408, - -0.6675553587967697, - -0.7584370595260657, - -0.7358512619760491, - -0.7955014630915743, - -0.6916060045416389, - -0.6707967955405606, - -0.7902021674026173, - -0.7934816362381886, - -0.7375105466772836, - -0.7634567334562574, - -0.719795861153816, - -0.7043086841228582, - -0.7239494323706352, - -0.753318791532073, - -0.7868285248519464, - -0.6994864846674662, - -0.701171326051888, - -0.7074498877339405, - -0.6933984062757104, - -0.7167089910566458, - -0.7150850963197682, - -0.7876736692659748, - -0.6909812294886273, - -0.686292447001898, - -0.7755853978167426, - -0.6816411207039527, - -0.7416134412928547, - -0.7273235871970706, - -0.6856454239779612, - -0.8151957995716588, - -0.7365440974254582, - -0.7597401073917449, - -0.6848491823613744, - -0.7461571103407296, - -0.6803872079574149, - -0.8073105570143347, - -0.7228511038913246, - -0.675374291749858, - -0.7607248994781708, - -0.696104287805668, - -0.7863530211006788, - -0.7673275413709892, - -0.6985830992826282, - -0.6952864144130431, - -0.6609413975378597, - -0.7495513482334252, - -0.7280883899789921, - -0.8038242085216082, - -0.7439918169227219, - -0.6680825037555698, - -0.7535240885403038, - -0.7544054145603613, - -0.7980848693223017, - -0.6682291785116141, - -0.7920982057706376, - -0.7488682930350705, - -0.7662707955445659, - -0.7425320254805948, - -0.7759594179839332, - -0.779921816550078, - -0.7515933863897737, - -0.8101063602113888, - -0.6631203916340819, - -0.7043715852024258, - -0.6709383166384333, - -0.6742771530122732, - -0.6952915324332497, - -0.7517326897259435, - -0.6863629757507564, - -0.8054158817746618, - -0.6657711851319124, - -0.809478285063842, - -0.7945879859409238, - -0.7472267815630131, - -0.7398562906894905, - -0.680602723099934, - -0.69589910564426, - -0.7159386130109966, - -0.7648766309267039, - -0.7228354665440635, - -0.7124712019967713, - -0.674084142871464, - -0.6874740836228741, - -0.7273123575159471, - -0.7480530988558753, - -0.739401153337559, - -0.7917459446911628, - -0.6608669462430015, - -0.7269306436744725, - -0.8059579112793672, - -0.7430948283453122, - -0.6921331414936251, - -0.6680883695432709, - -0.8068276449699763, - -0.7790901742330085, - -0.6779941284059341, - -0.76374330053932, - -0.6749608894421216, - -0.7256674170253076, - -0.8143832303424023, - -0.7842606725529184, - -0.6961665050731126, - -0.7033193968536469, - -0.7665277635100296, - -0.7015714143231429, - -0.7311400945839854, - -0.8006945678488328, - -0.6907831707242142, - -0.7193911769166605, - -0.8084027965901199, - -0.7258540501737034, - -0.799169199255396, - -0.720846182677373, - -0.6940046493519433, - -0.739093677098169, - -0.7332387305063791, - -0.7563100735937504, - -0.789291492552848, - -0.7637660711871789, - -0.7538261803495147, - -0.7897202283086658, - -0.6895146886024994, - -0.6702249360757374, - -0.7397820156293914, - -0.7833294015692143, - -0.7202313957349916, - -0.7588035637801989, - -0.7925573573645549, - -0.7385279280999516, - -0.7616806708296937, - -0.6744819427381095, - -0.8156479834121129, - -0.7652841388220714, - -0.779550034913175, - -0.7759490401063482, - -0.7069167632400244, - -0.7006235855999146, - -0.7471577979537544, - -0.7609676774903695, - -0.7744659003716905, - -0.7512049155863658, - -0.8105902032891801, - -0.7719075378947243, - -0.7289284259271563, - -0.759201676947333, - -0.7979102570741325, - -0.6925943826267034, - -0.6639668410536362, - -0.6922496120135074, - -0.753211792856081, - -0.7003605149225384, - -0.8114725945566976, - -0.7141548686339305, - -0.7859011516838421, - -0.7142914375943187, - -0.7464329873741369, - -0.6966943305471964, - -0.7537626823444261, - -0.8023313622803704, - -0.7397344753990249, - -0.7333027275363782, - -0.7417511929536079, - -0.760245056271606, - -0.7645600082650756, - -0.6676411960405398, - -0.8102276453537338, - -0.815323913916526, - -0.7729895260463084, - -0.7475586591846453, - -0.7269168091336567, - -0.8118066065924378, - -0.7871905452523927, - -0.746322456895828, - -0.7045757878253148, - -0.6715442617646893, - -0.6722881523155182, - -0.6803105644107678, - -0.6641146410487323, - -0.7797820899969509, - -0.6845460604112699, - -0.6616761519297927, - -0.8073332043805855, - -0.7315637034760089, - -0.7718365230418186, - -0.7191397757902757, - -0.7044921911463197, - -0.7570189073235523, - -0.8076048287888096, - -0.6785143952105636, - -0.7227045424538657, - -0.812015316525915, - -0.757215786969652, - -0.6817386742323992, - -0.7416469172249968, - -0.6660711863232678, - -0.7470010324523257, - -0.7525580438148972, - -0.7923666203018562, - -0.7042688267621394, - -0.7898529180874823, - -0.7678223150282001, - -0.664935577830323, - -0.6936748083532766, - -0.7631017621908616, - -0.7473894345010683, - -0.7380275266004227, - -0.7886839720399822, - -0.7378093034782666, - -0.7472376448587381, - -0.8051321031584049, - -0.8110747210319684, - -0.6609821049256829, - -0.7721559031881661, - -0.7893711061469992, - -0.6999006642855621, - -0.7076222407325159, - -0.6685511033267892, - -0.809240161189783, - -0.6655208850866088, - -0.739026411416954, - -0.7963444367956436, - -0.8081164663834056, - -0.72032459768892, - -0.7355274263443945, - -0.6843452267515566, - -0.7990908702421574, - -0.7366853505144904, - -0.715066685888336, - -0.7981727449479343, - -0.6745028752484269, - -0.7082040248305961, - -0.7590333988462072, - -0.7521209445368177, - -0.7530286184999782, - -0.7298481148477911, - -0.669990955587965, - -0.7507983716651775, - -0.6927505596289146, - -0.7482208220478873, - -0.674897801455238, - -0.7873849008776853, - -0.7907391212826408, - -0.7845041825994967, - -0.7225689879537186, - -0.6684478629300616, - -0.7561669176494803, - -0.7028205810621556, - -0.6687744108083195, - -0.799799330236145, - -0.7275423127737011, - -0.7586237645137655, - -0.7609781913118755, - -0.771510299338216, - -0.6748468042892403, - -0.6825076498401257, - -0.6933669223679276, - -0.747146936075497, - -0.772887699227852, - -0.7088680211421045, - -0.6829141117630039, - -0.7085954603803464, - -0.7130120746959817, - -0.7198887547259835, - -0.7064964034347083, - -0.7440791411380815, - -0.6775169028584438, - -0.6613510511352116, - -0.7230236893214413, - -0.7442894293170874, - -0.7593054521278263, - -0.7855545842477533, - -0.7969412733925133, - -0.7673897656272093, - -0.7798318316113466, - -0.7666409966077694, - -0.8038823482078532, - -0.6773810823938471, - -0.6671922426693022, - -0.6967981914705655, - -0.6804669269366902, - -0.721322992449015, - -0.7659174699750609, - -0.7231993070927535, - -0.7294364356297915, - -0.738817039845884, - -0.6716821968060405, - -0.7238464075739066, - -0.7896098973553037, - -0.6873420657074807, - -0.7822499541273014, - -0.7915872070184544, - -0.7562580479588608, - -0.6623073521951508, - -0.6647318697118932, - -0.8020902993376984, - -0.7404520181585241, - -0.7584048388518329, - -0.8108459309306724, - -0.7009851037495519, - -0.702190035229582, - -0.792873387122339, - -0.7334653630639111, - -0.6610109536318165, - -0.7204067375741948, - -0.7527495585362146, - -0.7900942957982375, - -0.7696692096011256, - -0.734559945613857, - -0.7730488926562771, - -0.7696891463396547, - -0.7567200910704783, - -0.7834166172255321, - -0.7736618637799031, - -0.7587407800634497, - -0.7979207779416013, - -0.7245163572926223, - -0.7760765229218346, - -0.7151399876890636, - -0.7853666319058881, - -0.7673072235012707, - -0.7839665843967559, - -0.6868567280070883, - -0.7725946249518111, - -0.7032196371214802, - -0.757434018204111, - -0.7408957401680595, - -0.7160024917088977, - -0.678608593963779, - -0.7661714815078614, - -0.7412330598530315, - -0.7175714293290183, - -0.6962383401998063, - -0.6657412806399113, - -0.6749390733440968, - -0.7732674383544484, - -0.7848380650222793, - -0.7658004336421074, - -0.7385320622257779, - -0.7781441257310848, - -0.7166068932273608, - -0.6762640312119835, - -0.7482922942811147, - -0.694671274557151, - -0.6972165743731179, - -0.7610039666762874, - -0.8029605513163065, - -0.7760317977031234, - -0.6779469470711875, - -0.6837717434897973, - -0.7753611836093476, - -0.7332243448218394, - -0.7823638352954004, - -0.6867010465670567, - -0.6641221986430135, - -0.8035226060729984, - -0.7131209824429312, - -0.7763889777489072, - -0.7959199308472168, - -0.6657335857648137, - -0.7978395910136455, - -0.7569377051935592, - -0.7419108626608997, - -0.6975601743389677, - -0.7144944415360238, - -0.7213179163220133, - -0.7867735257783568, - -0.7738475086638249, - -0.6811973604759036, - -0.6932726313796788, - -0.6839455360698251, - -0.7805623453661955, - -0.8065288669973387, - -0.7374294458033301, - -0.7601267532405971, - -0.7133225712784229, - -0.6840677497190332, - -0.7738821516639494, - -0.69519080529227, - -0.7936905833213058, - -0.7865492155906325, - -0.6775908177302437, - -0.6888585310634245, - -0.7430508488287615, - -0.7176298891023197, - -0.7914495456360096, - -0.7345829949774273, - -0.7058280007457365, - -0.7637949273512119, - -0.6811644337664735, - -0.7862755730959412, - -0.789888837078046, - -0.7501445619009478, - -0.717023938115372, - -0.7564981013555313, - -0.7143889262456586, - -0.7544538555258276, - -0.6841240669820174, - -0.8079282872471086, - -0.7259344733886298, - -0.7871428018392196, - -0.7064052833168326, - -0.7834469134721398, - -0.703299522857611, - -0.77165705268337, - -0.804331176332066, - -0.6758622155910567, - -0.7253439737233871, - -0.7401380157726732, - -0.8090916618726461, - -0.7593050623602496, - -0.7903052189479113, - -0.6723134380994852, - -0.749933018599006, - -0.6740417273858782, - -0.7125048488041164, - -0.7764074326818238, - -0.7275232901501398, - -0.7280347095678024, - -0.7564317773356382, - -0.7876561730283542, - -0.7042709839127806, - -0.698752533500776, - -0.7580849206538925, - -0.6711520026779831, - -0.7316230214275222, - -0.7319371351162093, - -0.8092622986729481, - -0.6813482966302704, - -0.6884375659187809, - -0.7867770834822041, - -0.7967393578702425, - -0.7180084914913767, - -0.6897450624002903, - -0.7035576707850186, - -0.7154045869431749, - -0.8042640116613923, - -0.6709690649392271, - -0.755814751622787, - -0.7325324112173585, - -0.6677280268627298, - -0.7178684328147948, - -0.6960090841273272, - -0.7997727108044017, - -0.7226630170623306, - -0.7494518830991882, - -0.7996661459362268, - -0.811238387929563, - -0.7282261202609472, - -0.8010441580538108, - -0.671618209282425, - -0.6864804879764812, - -0.7170105202128937, - -0.7068376612404297, - -0.716845811303713, - -0.7157044206897659, - -0.7839004145589016, - -0.7704982661152396, - -0.8108533474576174, - -0.773452566326907, - -0.6775618652489764, - -0.8053366747647436, - -0.6705200825585502, - -0.684571675597338, - -0.7740528519616242, - -0.6828552681943351, - -0.8020560738952037, - -0.7719597002084252, - -0.7981800306217254, - -0.6871224475831841, - -0.7403830977652541, - -0.809031287240534, - -0.7787550760527734, - -0.8116432653995357, - -0.6938152714273699, - -0.6693539615313849, - -0.6711228895089083, - -0.8001598298638656, - -0.6800721473502925, - -0.702268545321733, - -0.72839740808505, - -0.7807120972910261, - -0.7906009041781643, - -0.7889812941102624, - -0.7823850949670232, - -0.675441666778349, - -0.745383831375856, - -0.6961982439067094, - -0.7482229753026669, - -0.7391455090713909, - -0.695281098609174, - -0.6761859495237563, - -0.702342690097608, - -0.7521543281012935, - -0.6787606544179371, - -0.6741198908303869, - -0.7771006361752744, - -0.7025269489381344, - -0.7295193554658008, - -0.6827177902237429, - -0.7627060557346143, - -0.6831310295266128, - -0.7642024266741264, - -0.7459952084243345, - -0.7413645972938903, - -0.8059190863032628, - -0.7767740927513767, - -0.7737740299112782, - -0.6747698410293389, - -0.7726760568262148, - -0.7440049767489255, - -0.7145836200462206, - -0.8037060755972474, - -0.8008540869060116, - -0.8103021758083492, - -0.7245239138212888, - -0.7756423269858395, - -0.7165402912537571, - -0.8130520148616087, - -0.7609724512370509, - -0.7671360788665742, - -0.7203957210024812, - -0.7389825221105745, - -0.7754924865822498, - -0.7116616464966546, - -0.7113317467240474, - -0.7441400933063106, - -0.7929971099172384, - -0.7049709766937762, - -0.7498007815719786, - -0.8011603928000367, - -0.72820607511402, - -0.6711779495395445, - -0.7833686904958705, - -0.7683669675481856, - -0.7237157143618207, - -0.6858889672005607, - -0.7779314008339426, - -0.7539070079629705, - -0.664749787594006, - -0.8010774850781952, - -0.6862611987729618, - -0.6986222620279169, - -0.7414651135448379, - -0.6960040394248774, - -0.6767214103331891, - -0.7873875041333842, - -0.7523184647161997, - -0.7326670067739, - -0.805860594989696, - -0.6961290229295439, - -0.7554130548278765, - -0.779637179429998, - -0.6698506755168634, - -0.7036138553968223, - -0.7531952794860022, - -0.7361185324016352, - -0.6842620279474738, - -0.7874692886435567, - -0.688506548016679, - -0.7267685852223045, - -0.6788548077470175, - -0.752070426083661, - -0.8076633350999096, - -0.7453281029638801, - -0.7539901981904893, - -0.690981322899291, - -0.8107074735491978, - -0.7216253490826241, - -0.7826894505478006, - -0.7109696766917752, - -0.7026192763057685, - -0.6751304026735714, - -0.7958810141812896, - -0.6845028449832584, - -0.7691422566675149, - -0.6832338633569981, - -0.6810636205676004, - -0.7677169475134674, - -0.6608167911050804, - -0.7598632578561842, - -0.7118618359915722, - -0.6681982889206732, - -0.7583992720528402, - -0.7510639918157515, - -0.6621945685774276, - -0.7180329380540053, - -0.8028193065951913, - -0.6858100923592535, - -0.7409985694428425, - -0.6914386293463477, - -0.674048889017738, - -0.7134579577455108, - -0.8140423410608525, - -0.755984836656482, - -0.8143172487124404, - -0.7079966111565369, - -0.784054084593132, - -0.675355925440501, - -0.7031664503907998, - -0.7564669070808995, - -0.8045173513382066, - -0.8101826537582486, - -0.6779381788727005, - -0.7206160086949251, - -0.8142293905909775, - -0.6666509209761522, - -0.7290592399426231, - -0.782725684071632, - -0.7364193181588419, - -0.6752434039498209, - -0.715605606576967, - -0.7815648962046593, - -0.7244500207686173, - -0.6854656183210095, - -0.81497956132002, - -0.7498672885960397, - -0.692740349892571, - -0.747437022371706, - -0.7098854733011941, - -0.8029561571617029, - -0.7434536112407483, - -0.7532551242735857, - -0.6920722363354338, - -0.7864599740753615, - -0.661115929108175, - -0.7766139770549453, - -0.8101091945477459, - -0.6891476356631573, - -0.7763250837495732, - -0.7953153483598608, - -0.7012227615337543, - -0.6804537196974064, - -0.8054602121621078, - -0.7062535434468625, - -0.7443174048340138, - -0.673511510845869, - -0.7555132907156367, - -0.6762995750703592, - -0.6679076963901314, - -0.6855513054900837, - -0.685821056653808, - -0.7205667202341297, - -0.6687442766029219, - -0.7419288711922405, - -0.765337126932476, - -0.7480448514849999, - -0.7499925537725918, - -0.7307831766199997, - -0.762187835124605, - -0.7455103959959638, - -0.8017247868890359, - -0.6987894299159023, - -0.660622986800712, - -0.7129013483721469, - -0.7030085834353939, - -0.8059414101422538, - -0.7801367607980806, - -0.6788055915429384, - -0.7219989260967355, - -0.7132406037232293, - -0.6851236252754729, - -0.8153083129657929, - -0.7221936398058819, - -0.8127507429087598, - -0.802007907445374, - -0.6734118162868469, - -0.7757462320007334, - -0.7679475158118978, - -0.739546768170424, - -0.7473674110391431, - -0.7926445179045324, - -0.7441136971752165, - -0.7642226410556974, - -0.8131041084512959, - -0.8093113350113457, - -0.7160144377001774, - -0.6876783292412365, - -0.6920045201653402, - -0.6842827352948712, - -0.6666392787951295, - -0.713488720202082, - -0.8024561366262903, - -0.687175941006638, - -0.7131388269099054, - -0.6804266143309616, - -0.6829575157976688, - -0.7423246449576596, - -0.7296825625367235, - -0.7927371931181114, - -0.8085887985228225, - -0.8034847574729669, - -0.7985423384711645, - -0.6823699689474295, - -0.7892755811317151, - -0.7562244986804998, - -0.8099485428036278, - -0.7186009825581647, - -0.7136113690539936, - -0.8073775819393868, - -0.7600002119066649, - -0.7366694521936535, - -0.769404638369748, - -0.746059260286872, - -0.6967389411336404, - -0.7678713902090439, - -0.7868009177694555, - -0.756207589341713, - -0.7367987324984208, - -0.6912330854053816, - -0.6728876397258114, - -0.7906249879053281, - -0.7644026910972239, - -0.6747643631005855, - -0.6769183443031411, - -0.7830655655868142, - -0.7137735480365666, - -0.8045989320955504, - -0.6762204512284646, - -0.7527225304484844, - -0.6959232064556172, - -0.7963634319717626, - -0.7204928920867572, - -0.7063702051909156, - -0.8104213483342828, - -0.6714200035592418, - -0.8006343315005244, - -0.808707419438853, - -0.7590459998119148, - -0.6665546199275185, - -0.7141860183893198, - -0.6676582573856752, - -0.8003892645013453, - -0.7759177146697375, - -0.754975988964665, - -0.7941869567729821, - -0.7673063505837635, - -0.7018730612466306, - -0.8015427913816999, - -0.662272527410531, - -0.7335811638141178, - -0.7304331378121316, - -0.6978670139538683, - -0.7623375949475877, - -0.6881653581368559, - -0.7106299094863013, - -0.7145345887761397, - -0.7935052508939953, - -0.8093496326564182, - -0.7633843842236946, - -0.6693179124680024, - -0.8039930642667963, - -0.7429160242517123, - -0.7920449985178777, - -0.7907591595110737, - -0.6782604049343581, - -0.7822601339074485, - -0.7856459158676546, - -0.6615406230849472, - -0.6701567779313664, - -0.7363718886269895, - -0.8013817808424463, - -0.7424964812580268, - -0.7996502830926292, - -0.7100161598251998, - -0.7848851874066466, - -0.6622447726078309, - -0.7971196112676326, - -0.6609526793018816, - -0.7359812190823524, - -0.7850344510449447, - -0.6635048318245536, - -0.6722700809946347, - -0.8097259922504443, - -0.7506643302069209, - -0.7729687105384623, - -0.7390314855238237, - -0.6859633146135523, - -0.6618127118689163, - -0.7772857691994737, - -0.7727658161085331, - -0.6740742388989777, - -0.7008853674319984, - -0.6966010409403499, - -0.763983089659523, - -0.7378223000987226, - -0.7054242673542576, - -0.7557792486763717, - -0.721853628259479, - -0.7958138071197088, - -0.7357987842195075, - -0.7266877361589086, - -0.7549400846771759, - -0.7080779995565673, - -0.7295138030353974, - -0.7757584284568817, - -0.6866992483865932, - -0.7290313103403723, - -0.6744983646377556, - -0.666172485417819, - -0.6612567083427433, - -0.7406440723111533, - -0.6758680448785717, - -0.6918495354980925, - -0.8076518919846918, - -0.784507147159672, - -0.7789566705116933, - -0.7773618516234327, - -0.7531562981376219, - -0.776158108952197, - -0.7309644692944952, - -0.796191709522725, - -0.7616099586722763, - -0.7980055886974053, - -0.7081575859953537, - -0.7484416429391999, - -0.7815527537261716, - -0.7655814921764652, - -0.7866134959206026, - -0.8107477958579912, - -0.7501626737680764, - -0.6883558364186203, - -0.6994897119696472, - -0.66680926210344, - -0.7514115049539742, - -0.7309307888212475, - -0.7729907382777383, - -0.6708650673155354, - -0.7260682588516252, - -0.7272801078294147, - -0.6631185868352933, - -0.7386489737797718, - -0.7979358084142633, - -0.8014336742211753, - -0.7716773817414699, - -0.8142323140845713, - -0.7231408703074783, - -0.6992796539674507, - -0.7699571879773831, - -0.69325386961385, - -0.7894601271801788, - -0.6946696233558793, - -0.6727967939360586, - -0.6875497177696569, - -0.7199656516662891, - -0.7063950755221037, - -0.748085020631708, - -0.7325977012472661, - -0.781023431156203, - -0.8050114451523405, - -0.6899891968222074, - -0.7406432095639056, - -0.7893626094789421, - -0.7934848637023069, - -0.7696451441957809, - -0.7927098527064251, - -0.702960794978946, - -0.7965294235483429, - -0.660118736071805, - -0.7153833349077348, - -0.6725938724685712, - -0.6944540354294951, - -0.7137370490293121, - -0.7207599353873562, - -0.7175642536968843, - -0.666228803028104, - -0.719286403293628, - -0.7025013984383981, - -0.6613760074732262, - -0.7150227635655038, - -0.7552480952207332, - -0.8085579829625927, - -0.7356572456803975, - -0.7445934402203505, - -0.7023527516230365, - -0.6685850170966552, - -0.6920209377690447, - -0.7380014917174742, - -0.7983431790106115, - -0.6620122691448233, - -0.8053791804359826, - -0.737012318538733, - -0.7849181056442979, - -0.725274496741997, - -0.7292988135941106, - -0.7743018452164439, - -0.7358113156607451, - -0.6699871993860849, - -0.679515569171744, - -0.7356845546935682, - -0.7172469395407431, - -0.8062696489615516, - -0.7525120143265247, - -0.7522565430677777, - -0.6719264039115227, - -0.7964764492854703, - -0.7642495664950247, - -0.8037767748800273, - -0.7371417433749333, - -0.750835466377189, - -0.7301750674208866, - -0.7576343266395776, - -0.7917476658408721, - -0.7470482662109825, - -0.7403291794762553, - -0.7422629139591508, - -0.7769799568263306, - -0.6843647951219842, - -0.7019607746121618, - -0.7246957745778003, - -0.7098207061931783, - -0.8085593882723588, - -0.7742835409446713, - -0.7281573592228834, - -0.7379156372740419, - -0.7955396508668157, - -0.7562549952716436, - -0.6653449669022728, - -0.7725992463388142, - -0.81146325108019, - -0.812460430477791, - -0.7038101948684662, - -0.6716640734570533, - -0.7511494031359737, - -0.7228655454311872, - -0.676071001595464, - -0.81345080240042, - -0.663801165194905, - -0.728884376197255, - -0.7448639995875606, - -0.8047400130681377, - -0.751277408507601, - -0.7853287619045813, - -0.6975898987920988, - -0.7597326984569063, - -0.6844266233033187, - -0.7762014801731147, - -0.6940209198273313, - -0.7949919942573866, - -0.7273384493099005, - -0.7008160184000447, - -0.7509066049791655, - -0.7660565896268249, - -0.7396186333658159, - -0.6881714376138341, - -0.8022502364082656, - -0.6695327623443953, - -0.8144778087486102, - -0.6896977096404038, - -0.7390048876158067, - -0.6708348042329467, - -0.6614345917495255, - -0.7873591817749991, - -0.7991454711513853, - -0.7692413833624735, - -0.6690214736166991, - -0.7294434142587649, - -0.6821440060867868 + 0.6666058106589906, + -0.6275223725150068, + 0.27749733836385937, + 0.2734034814790117, + -0.7175004596399989, + 0.5863355069113533, + -0.3750537393816175, + -0.05607200530899825, + 0.10278077023946186, + -0.08921989491936888, + -0.8469192679987135, + -0.018159479392680478, + -0.8656747721103595, + -0.8357749738293861, + 0.5542326595141317, + 0.17974022045381777, + 0.39213521084958114, + 0.2286227309811909, + -0.5660825750024856, + 0.10615234431851384, + -0.48627814545860903, + -0.04367915613828188, + -0.03071058518115255, + -0.8046517044761368, + 0.117469531448266, + -0.6852524206587929, + 0.577659839743946, + 0.6525862050663834, + -0.46802837798235497, + -0.6371528851349687, + -0.08401825767624005, + -0.11994849155408915, + 0.15498879923484166, + -0.4296885665851982, + -0.0918618162072723, + -0.702394963772518, + 0.07619979073869054, + -0.45631253796065774, + 0.24055256867101316, + -0.807856677779504, + -0.7331394547276625, + -0.33236852200552514, + -0.8335011288259746, + -0.18368987252999514, + -0.13285173760657532, + -0.7256162270452655, + -0.7011782634347644, + -0.5971794938744686, + 0.013801489692748525, + -0.0019442706192479564, + -0.7840748843213746, + -0.3774537319857801, + -0.8194474349622156, + -0.15373730833776345, + -0.6226667228388664, + 0.05960187420656615, + 0.49018611489886477, + -0.06931311646810867, + -0.6118337632411734, + 0.21466447228876662, + -0.7069918750156958, + -0.565707081541037, + 0.25219022364780785, + -0.12128218694923532, + 0.0435121835512301, + 0.43437868326591966, + 0.3498742014051138, + 0.2937202220482814, + -0.4879107624863442, + -0.8431696699512381, + 0.47128767952521244, + 0.39715782354731266, + 0.4093979680954368, + -0.2754716149313442, + 0.3927059325698844, + 0.16163387620810588, + 0.6134344739651144, + 0.4989525538784402, + 0.4641495485375816, + 0.4494335327277218, + -0.8704993237666484, + -0.1546108682577071, + 0.13768965589862725, + -0.6365510678500255, + -0.33899402761298425, + -0.6336695034500428, + -0.6944098898841129, + 0.6037127658087721, + -0.5023750984700437, + -0.8363416394021067, + 0.5901074892215842, + -0.15623165872274802, + -0.4639471107854012, + -0.2699639024879039, + 0.6089743154510739, + -0.13446666279265906, + 0.639422549696605, + 0.5895142224436197, + 0.29143975838335845, + -0.7886817474422991, + 0.23313864326939127, + -0.5649781281716582, + -0.30235861590802793, + -0.7461995588454036, + 0.25645667907364833, + -0.6835502017081007, + 0.07098992017896677, + -0.24926233994314106, + -0.5150046451356816, + 0.2171504202740696, + 0.15508116337982958, + -0.1726071214778424, + -0.16872631096284496, + -0.07987457867943693, + -0.3988233438810945, + 0.09018380331618814, + 0.5526543393562741, + 0.6215032225693417, + -9.380646665602121E-4, + 0.20567153846937092, + 0.1451170483120824, + 0.4960515678607681, + 0.38739151042467024, + -0.44134970509126914, + -0.2125465241281288, + -0.8662625620056745, + -0.2454093544286714, + -0.7565669367322918, + 0.38543216788551937, + 0.13514360187416552, + 0.1506835255607376, + 0.6253969234435707, + -0.7468261109835104, + 0.22779642843535342, + 0.5091740574790767, + -0.8457623266408381, + -0.14836628750855485, + 0.6089602503454258, + 0.5656370034831509, + -0.3336527055486763, + -0.508858698035447, + 0.11094372181936352, + 0.5440414613095111, + 0.33305591764360865, + -0.4245168135803993, + -0.8427330769509144, + 0.5941956535903828, + 0.18419106038827004, + -0.3841152424075892, + -0.3725505385034983, + 0.48264758367410143, + -0.3722079752830858, + -0.05813429667398473, + -0.8059505787514516, + 0.4682378542731206, + 0.12962818532980613, + -0.41061961162866123, + -0.4397732270288138, + -0.23422342414154707, + 0.3197876588992955, + 0.3762548500850845, + -0.49375206421843, + -0.36468238019017196, + -0.31595207880102716, + -0.058622601846185285, + -0.0819373874580771, + -0.026294703081305437, + -0.7333976350634521, + 0.5871689272172541, + -0.2669539534603903, + 0.18944201707163588, + 0.049313901772380264, + 0.622200683570883, + 0.4997890289885297, + -0.07335224296024823, + 0.3390351229857501, + 0.028089542063767348, + -0.37891646238684534, + -0.07570079387349826, + 0.0446426140012276, + -0.4160784644966179, + -0.15464039433561905, + -0.5277291987415961, + -0.7842281560931817, + -0.5943957257573894, + -0.18751189624176723, + -0.15161010062629943, + -0.6595028173028665, + -0.49168597911831013, + -0.20294035420903778, + 0.4820484207677652, + -0.21540740698298877, + -0.357283407270792, + -0.17775071687851118, + -0.18418657917500414, + -0.2725741720344095, + 0.5601126086725304, + -0.6821440644291283, + -0.6714120230040121, + 0.19342644448169144, + 0.533708306458235, + 0.4515743329679741, + -0.22845447395093688, + -0.4636288401626982, + 0.2261171690774345, + 0.6625489741929783, + 0.4419149616405543, + 0.3944399196014844, + -0.581661113592369, + -0.09399057395574806, + -0.5835152498225822, + 0.6712288094609408, + 0.3604183900051793, + -0.5691880661016439, + 0.10063463738304701, + 0.5224921768005432, + 0.023594173649594374, + -0.16632808566513158, + -0.06617712876236004, + -0.6058299524809305, + -0.35109231607599656, + -0.6358807043729054, + 0.4465838287202256, + -0.24905747868039974, + -0.3070149868368832, + -0.35649870653286664, + 0.3752078603453445, + -0.5030404049123106, + -0.3342405362841072, + 0.39463391311963536, + 0.34736690927703695, + -0.7440047841145556, + -0.08459578184816752, + 0.5436958637667196, + 0.6636216112375007, + 0.6787179171382675, + -0.11978361879997212, + 0.4248871223414682, + -0.6403257989649065, + -0.34676209274980263, + 0.6518174417400077, + 0.041047707742685846, + -0.19161578362922482, + -0.3473917047553917, + -0.8712490125687881, + -0.6474445000690167, + 0.30704209883158684, + 0.40650355635854807, + -0.11443176810412103, + -0.5902100206759611, + 0.15130704599200306, + 0.17817282405239931, + -0.4319867595428307, + 0.3761037148942029, + -0.5836163992288743, + -0.060841719494298174, + -0.4704848100986995, + -0.114387030520533, + -0.11861116674088701, + -0.5393455298584737, + 0.4504255225187296, + -0.5808023955276755, + 0.5382270931416498, + 0.11679290322936287, + -0.2503809338557711, + -0.801615896461292, + -0.45611709532077055, + -0.45867457314654514, + -0.8519137782655727, + -0.2565781535722065, + 0.274534684228782, + -0.6458491174905114, + 0.20159885534527955, + 0.39734630548494343, + -0.2838925864874252, + -0.3030274386188907, + 0.29310849318668664, + -0.3930756756419413, + -0.7128775548145456, + -0.02633510108647996, + -0.037201389877182356, + 0.6491364028892762, + 0.3469588703999603, + -0.5217122728699541, + -0.19917046329456167, + -0.3349666353477587, + -0.01162237908983721, + 0.314749354310805, + -0.17874098931066063, + 0.4115489047371538, + -0.26163559973755857, + -0.3919508242771738, + 0.24996503869006392, + -0.027192513641731697, + -0.3168900777190604, + -0.1586176417895574, + 0.3261781642801057, + 0.5796439395266363, + -0.5848152040109578, + -0.029844147240536634, + 0.6776237433109801, + -0.32377406311316625, + -0.7635571386974587, + -0.6902063158019462, + -0.6990581444492172, + -0.5677659933995398, + 0.5735700934287337, + -0.3213381131603822, + 0.18027084925260473, + -0.09478259380341014, + -0.7273983262954175, + -0.7001828885122763, + -0.6187034326214707, + 0.3826398925025466, + 0.43489271128727547, + -0.06374368187858659, + 0.16281770668399587, + -0.5128811376418514, + 0.5328912076677778, + -0.696797471603485, + -0.8139534828632933, + 0.5584134609133441, + 0.11558499547814316, + 0.27470742399416703, + -0.818352202075237, + -0.4979590879757463, + 0.07651840517657993, + -0.07154745161049558, + -0.0757372535283084, + 0.47710431723598956, + 0.09806765973650233, + 0.42608932847965575, + 0.40262010155470807, + 0.13463196832382673, + 0.30425343522295567, + -0.14954529374980108, + -0.4508294504653402, + -0.7734902010591478, + 0.4914209778693729, + -0.13667078460018012, + -0.33186796044526023, + -0.15867744689409924, + 0.4807755293326793, + -0.06507713560278428, + -0.3136508774787182, + -0.7877245060868477, + 0.14922237514415115, + -0.48726619262815457, + -0.7957635241474985, + -0.4846985195111213, + -0.247358950576134, + -0.1457849050977016, + 0.27985889841417977, + -0.24190118919456316, + -0.8123548411461565, + 0.24224014879767053, + -0.098351596742146, + -0.8689306883715002, + -0.7577803733237759, + -0.3897027044795488, + 0.5262295369360867, + 0.004308591761800429, + -0.5849742697107627, + -0.4654036698660823, + 0.2989707938109504, + -0.7205061328415363, + -0.7367932063143344, + -0.7953767701110582, + -0.3506846367498937, + 0.40480080242016003, + -0.7429911057498992, + 0.03900194071203644, + 0.35412929271023963, + 0.04375697707917081, + -0.3798233027203474, + 0.005488780197852594, + 0.36404801211625826, + -0.868883284614277, + -0.5679411027777095, + -0.010697514001007935, + 0.48337762617327706, + -0.6644152984755904, + -0.8282054802745701, + 0.07563535166537927, + 0.42162221820389345, + -0.12363106034786908, + -0.2020382877710002, + 0.2012209835531179, + -0.6792177548051743, + 0.6147574603768503, + -0.4388300723418587, + -0.0030679562555270268, + -0.3850246687569129, + -0.4801324230328769, + -0.3890459334612738, + -0.322541716949609, + -0.00677437998287056, + -0.810566459536732, + 0.5512162289981536, + -0.5045099788560967, + 0.13967412326021222, + 0.39945188937114773, + -0.817999380591487, + -0.47345731749560394, + -0.321251276682198, + -0.5355720985798125, + 0.4844188789298943, + 0.20528683746248444, + -0.09372494818896604, + -0.7290576893705198, + 0.5539819686712634, + -0.5361550469170071, + -0.7716572912907923, + -0.7016700531312638, + -0.26464212139612797, + -0.6840534272223701, + 0.5306113976708525, + -0.024135222679529278, + -0.7965092622993968, + -0.09696987243231658, + -0.014463855845343487, + 0.3673411543426418, + 0.2502461679422895, + -0.24873499355682116, + 0.11038092015634282, + 0.2835691264935839, + -0.3727487611510961, + 0.2840430454004125, + -0.06083075147139805, + -0.7365167569664356, + -0.4176133416178806, + 0.6646511504267058, + -0.8554072457574442, + -0.21263314287614332, + -0.20507177503856444, + 0.5866847648377295, + 0.3152649232398742, + -0.3183134746841453, + -0.7853290943023093, + 0.3785502227018508, + 0.26213660114265525, + 0.1466016722429403, + -0.2943939443468181, + 0.43127623920977254, + 0.13328438724309388, + -0.0038836911998447743, + -0.6641305884050027, + -0.4649083692352045, + -0.004954874674958476, + -0.6165763184735612, + -0.5685882268450291, + -0.6741767761933755, + -0.49905691562158333, + 0.338288985697781, + 0.37146622788511985, + 0.09886284394166289, + 0.5527950915372771, + -0.6936580427018579, + 0.2446335519305013, + 0.15278786449391146, + 0.10571301106945041, + -0.5939262959914926, + 0.35865009617105936, + 0.35312299954112636, + 0.672186734148578, + -0.4925799671512778, + -0.7030126676381847, + 0.30395002456192655, + -0.21242250356642478, + -0.2924927470609662, + 0.1444040718944276, + -0.0959525628547232, + -0.33450167685625054, + 0.05638765659767042, + 0.6532052472222568, + -0.838713347861875, + -0.5128516857807625, + -0.5488233311344153, + 0.14841571545325427, + 0.45035346363247275, + 0.5080893264781118, + 0.35668227762785454, + 0.007129127273367342, + 0.2587798403314828, + 0.48767830000439594, + -0.7235955173976463, + -0.308669869608562, + 0.3895906452439605, + 0.6202971613124598, + 0.4976652883980689, + 0.1582214273392878, + -0.7378059924516436, + -0.5952468208530441, + 0.057272230286255166, + -0.6866565103376003, + -0.6362766615842881, + 0.003613839228647775, + 0.4391909727693356, + 0.12443269621862252, + 0.08867613529965679, + -0.6321585633058063, + 0.07849347158435727, + -0.18501966657123103, + 0.31687302472126133, + -0.6492003383133447, + 0.3628850049649194, + 0.03950587751942103, + 0.02380992230996759, + -0.11395755793914286, + 0.05927865336057203, + 0.6563316345762503, + 0.6608565445151043, + -0.7296468047291439, + -0.1674520995970875, + -0.18643789513377607, + 0.07182467939546266, + 0.07659851841148158, + 0.47393235937104705, + 0.475169080135985, + -0.7931430903085271, + -0.47991494898497944, + 0.06368140195811522, + -0.14897249096754706, + -0.7327674186393174, + -0.39858467624335403, + -0.8649769100122217, + 0.2738822245522673, + 0.6393159599842367, + -0.39904852957470344, + -0.567854127710888, + -0.8378099938825434, + -0.5352516063091523, + 0.16421123234789736, + -0.8110961540113661, + -0.28021218675358506, + -0.03310543045462633, + -0.805326458259173, + -0.2005753757828821, + -0.05024190785089189, + -0.7455981247558594, + -0.3207624684857142, + 0.317830590467889, + 0.15031850522987955, + -0.8516203871262826, + -0.10411506622844258, + 0.5728075261386271, + -0.4332535765026046, + 0.3062453499965082, + -0.5630543349440429, + -0.42773223437334684, + 0.031668998339436705, + -0.731814737914162, + -0.24654130215279801, + -0.4104769052398364, + 0.6680020683766118, + 0.18935185317391234, + -0.6495441554071782, + -0.5788222571460122, + 0.5217714700215207, + 0.45113863135476084, + 0.470738933202992, + -0.018008273422736698, + 0.07477747252615852, + -0.8465481475795866, + 0.6806041779524569, + 0.2624086101210489, + 0.38090949665411744, + 0.5839811519001604, + 0.47322227341894674, + -0.459972922760751, + 0.21496766462807593, + -0.10890244132227489, + -0.8621595046499289, + 0.4276204928710755, + -0.4765839747178407, + 0.29094332302941817, + 0.4870174459734894, + -0.6896376408818339, + -0.4839264802438931, + -0.07754047377195206, + 0.24875411525518765, + -0.005581163205594986, + -0.7737732292848877, + -0.8556256379931827, + -0.5279982412403534, + -0.16862803377619207, + -0.5047622939908627, + 0.4095901253806363, + 0.1246134397813018, + 0.1165948598781208, + -0.4623237116261544, + -0.6034055404443166, + 0.13643783349319005, + -0.4175763715143793, + -0.13954572833948042, + -0.5397986119258984, + 0.6068878262933471, + 0.23438713688766988, + 0.2691130561906977, + -0.7348349791312754, + -0.5453757941060855, + 0.6428889268188703, + -0.17711072930431093, + -0.26679599213824656, + -0.6623819518719128, + 0.11944139924773389, + 0.4683013435079316, + -0.7761772538421639, + 0.5772786149794188, + -0.562353518974245, + -0.6112493093390934, + -0.027588129672320827, + 0.44610468926314695, + -0.6179321989321117, + -0.22898912019308304, + -0.5419559761930498, + 0.579599960840785, + -0.70759212634978, + -0.2545037781142422, + -0.1435764566700568, + -0.39149565201628816, + -0.13977423080829532, + -0.8553045507507594, + 0.015775772003931654, + 0.4497670622061337, + -0.6856592907999108, + -0.22619364587520185, + 0.5024667299338809, + 0.5780266970128939, + -0.6627910375424367, + -0.011125665452432987, + 0.22467516606045346, + 0.11074818900313788, + 0.22627850980182906, + -0.6812972163615906, + -0.6197671110700931, + 0.11717628251177392, + -0.557800228604957, + 0.21816973269080153, + -0.006972957737124252, + 0.01816414145256373, + -0.4316257032305805, + -0.4619856965505849, + 0.1656732922569487, + 0.3742419199953432, + -0.8265260787175118, + -0.7442038636858626, + -0.1877913558164297, + -0.5133631566765566, + 0.5879517308170784, + 0.6653688720667411, + -0.35591782118920623, + -0.05474569267913487, + -0.7444398594656648, + -0.2821070785233556, + -0.1500171368243184, + 0.5588645533961333, + 0.5711755381133882, + -0.3091085923248228, + -0.5550995822072615, + 0.5140889528438267, + -0.43118873835230087, + -0.44288199457466515, + -0.8649508879420775, + -0.5491772568500661, + -0.7267732202098828, + 0.19976833036576214, + -0.6167007715596277, + -0.6712432443932066, + 0.6768494618852597, + 0.22042593199123195, + -0.6723746946489729, + -0.28218743624806786, + 0.3320179491523053, + -0.7933011897737638, + 0.22119513933242996, + -0.3202425272185333, + -0.5039712231799689, + -0.8437961327212962, + 0.6791919898340434, + -0.5397502504341416, + 0.25558913576168074, + 0.5720376298245448, + -0.5352523592361962, + 0.29835693551829856, + -0.31374136591791, + 0.4784480842018447, + 0.6338590854684117, + -0.4626930890557515, + 0.657225647286014, + 0.48857656143065975, + 0.09555827684952334, + -0.06736966916435239, + 0.505047890573444, + 0.33593509170431657, + -0.07668686034768368, + -0.020835426467784246, + -0.6990248253290716, + -0.7180260161360181, + 0.3245291140961527, + 0.5787542234415916, + 0.35926796982735854, + -0.3764833710607403, + -0.19683690011616517, + -0.7519104752112677, + 0.41632738460323193, + -0.25717762780829545, + 0.11748017528253674, + 0.5515685263119353, + -0.8215027300356716, + -0.6480585021454159, + 0.23211442562003926, + -0.7250910593166925, + 0.15305460007166116, + 0.6793973840953552, + -0.28582120815431644, + -0.2662656508603307, + 0.620178656621874, + 0.2599645406969583, + 0.3721590505551974, + -0.6157915495690823, + 0.6053138905676639, + -0.35631974336799754, + 0.156991324013544, + -0.48324274767004993, + 0.12638636025680405, + 0.6592357533231631, + 0.6570642980659712, + 0.02218030299261642, + -0.38974756229560126, + 0.17551251391237443, + 0.3384884566734866, + -0.3582458106332116, + 0.6135129474622544, + -0.39875596347323894, + 0.07194913648306767, + -0.43586949795342017, + 0.2964181440069472, + -0.7510444604525071, + 0.20182397746452396, + 0.15860078614777995, + -0.8010515946501922, + 0.3104905867793236, + -0.5708758556337606, + -0.18959525918744513, + -0.2650040794908599, + 0.4548912484354849, + -0.047720964773216856, + -0.1684578436480645, + 0.6016500330021316, + 0.6699347281465601, + -0.0700704052340757, + -0.07339652950429665, + -0.5637203727050928, + -0.46048505213710966, + 0.26463895007918115, + 0.14339572893869568, + -0.3939271689924202, + -0.13176518794654357, + -0.34184008992012693, + -0.4606843638149725, + -0.674092346693738, + -0.5878477844703266, + 0.3573657489590284, + -0.0517251908674633, + 0.654185266628888, + -0.0639825285438107, + -0.5421667116491986, + 0.2602492506586035, + -0.2922279011878154, + -0.2057696665355162, + -0.6977667935363101, + 0.008385579701338464, + 0.2451864296596339, + -0.7885753760906083, + 0.19809775373335492, + -0.599806923224908, + -0.33230452762212825, + -0.386896793390091, + -0.3961289846140635, + 0.18073312674644637, + 0.17074040642161592, + 0.6037086898763332, + 0.2608107260333531, + 0.37649477021735633, + -0.22945196698238202, + -0.4490160952703499, + -0.13098091012760982, + -0.8413649382259557, + -0.7845975768329936, + -0.14193586023870142, + 0.00810915814911728, + 0.2421702114198011, + -0.03844809396708726, + 0.11409153038369557, + -0.41041297565694596, + 0.6666451435517758, + -0.25913734717289794, + -0.28046718601768916, + -0.5144582576327945, + -0.7635190600730664, + -0.8069543734175585, + 0.4106454724960674, + -0.2894144750639287, + -0.1262261954148748, + 0.33765787910666456, + -0.7931039879006432, + -0.3024476172693995, + -0.6839200011527966, + -0.07259210667466276, + 0.29757697424082774, + 0.21318807283936925, + 0.5729609260150786, + -0.6736914205144258, + -0.10631982803821427, + 0.007640092414996413, + 0.3328067233702833, + 0.29058352113117614, + -0.8290996940355331, + 0.4631819820847566, + -0.2789458121060655, + 0.30145380562388546, + 0.3340117379777253, + -0.1596375475528462, + 0.44117654105978155, + 0.02955578990860941, + -0.1332324429679329, + 0.5687512182709943, + 0.46167409514979874, + -0.4687730795646092, + 0.5206965464919192, + -0.24563112041944157, + -0.6660917909156544, + 0.20376370437178604, + 0.6073252957824234, + -0.1519093173175463, + -0.17983288210060677, + -0.21650851710979002, + 0.5241279981581967, + -0.7912683426323833, + 0.08839480826712598, + -0.5818021674731635, + -0.712216344972617, + 0.5689525344320338, + -0.8053270922699723, + 0.657094491368294, + 0.6191614440816747, + -0.4832379182250948, + -0.6048577926237153, + -0.539871237000956, + -0.24738720623296429, + -0.6270442467654633, + -0.33799177320591056, + -0.1541370306127522, + 0.42880651038323603, + -0.3741232014367429, + -0.722955148266765, + -0.5673709464190657, + -0.40334680648687327, + 0.32688376036180744, + 0.05667623480363082, + 0.07608345992930943, + 0.6154897058684065, + 0.3287519156339903, + -0.826131620873227, + -0.6570283496731554, + -0.6065449230120938, + 0.015183113464200426, + -0.548049502132973, + -0.6245495094607623, + -0.16975248226298467, + 0.06697093943107346, + 0.4783701308921916, + -0.17587394415364843, + 0.5608074523458345, + 0.25325881981227905, + -0.798890542696443, + 0.42916245248692786, + -0.5713031263639381, + 0.12372597577251654, + -0.06992039708839237, + 0.24203017353025558, + -0.31184354064276054, + -0.041508271409379516, + -0.46948386582541096, + 0.5035937503870825, + 0.6843277500979891, + 0.04245674391732923, + -0.041432537989605, + -0.10860649087715168, + -0.5232574811308759, + -0.6172655217365255, + 0.5409767343571724, + 0.2577613816438119, + -0.7767337502260936, + 0.10538417997255622, + 0.2179337715946198, + -0.12097359671616403, + 0.2866817232394999, + 0.3078941031972019, + 0.4233363474296771, + -0.8070993845105207, + 0.23652428526309166, + -0.03248515314231104, + -0.3680166796762476, + -0.11531704041003077, + -0.6419273092029035, + -0.4005045107558087, + 0.30556710511793084, + -0.10468053804016353, + 0.41808698449694226, + -0.5847571607507447, + -0.22737612474673852, + 0.12498114758426448, + 0.2042586485320511, + -0.4332141989060744, + 0.675509167375761, + -0.29882019499907353, + 0.3299532217624793, + -0.4668899359183519, + -0.3633974374829322, + -0.2647712830933975, + -0.21866185770990854, + -0.8265593602076993, + 0.20609178783411275, + 0.15470440000110963, + -0.21107755318381338, + 0.5168787727740066, + -0.5176501214250622, + -0.587255921105668, + 0.2193209825895831, + 0.31601555515314217, + 0.3919727733714643, + 0.23751351895594797, + -0.5245358147078243, + -0.5752196292934826, + 0.07748745272382351, + -0.37492619751868095, + -0.4387704540695876, + -0.6114755994728944, + -0.26725348140506067, + 0.3596750189283958, + 0.28547744684270515, + 0.21926152087455264, + 0.0828134471974048, + -0.2508035785406344, + -0.22647316457803113, + 0.2004024699036452, + 0.3321601394875585, + -0.564674340445735, + -0.5380674775613876, + 0.4002972476707046, + -0.4066167378475618, + 0.13010208107790067, + 0.13154803055679587, + 0.01070611786287845, + 0.1631621814632872, + -0.8624118530738634, + 0.10180934967233823, + 0.6311062326421649, + 0.6348763192807202, + -0.3268243883785359, + 0.22912241401757105, + -0.3620037196572873, + -0.5500606910166767, + -0.765296643237885, + -0.5122505858177415, + 0.33059972735814414, + 0.4680214257901568, + 0.3711711116145785, + 0.3006540601148041, + 0.3280769060657861, + -0.22770543909188234, + -0.38181925487700374, + 0.16328128651949003, + -0.4055520042252994, + -0.30833810121556005, + 0.24467668870206516, + -0.8242223330631173, + -0.5955213497631442, + 0.028388200807944464, + 0.3983458108167376, + 0.16051993714199753, + 0.4080046518084758, + -0.42061612716996905, + -0.2870968286798806, + -0.5539259142256007, + -0.12288928367766472, + 0.5921020861817233, + 0.13615129620948718, + 0.2818532536776094, + -0.3057796130123429, + 0.14945578735313758, + -0.5791344708082324, + -0.7627236611965591, + 0.27770155184367706, + -0.394727672780881, + 0.0565517027052207, + 0.6848144420114112, + -0.22160124149667337, + 0.46749440217214666, + -0.23732633207188147, + -0.08591421848026626, + 0.03452308972917373, + 0.25716911883852045, + 0.33320519602233534, + -0.07948455664264809, + 0.1603342242739888, + 0.5938318003887558, + -0.2781476332356788, + -0.4581348761112876, + -0.6576082103034978, + -0.23676839310266407, + -0.3113345524999158, + -0.40689310326807854, + -0.12515815259893137, + 0.3558913515632597, + 0.15178701101133674, + -0.0734864509199743, + 0.3186570135166812, + -0.20237615857852942, + -0.4364593003692408, + 0.48820580440827543, + 0.07328320602275129, + 0.048654332217310636, + 0.4202679412374005, + 0.535282326064289, + -0.816872048235382, + 0.547929104231864, + -0.4216549861822491, + 0.28304373582489084, + -0.6625866776673855, + -0.1759416338816604, + 0.2904875939705166, + -0.35280491651173596, + 0.6724113980770355, + -0.5906578247583658, + -0.4621839820834452, + -0.7099359620807886, + -0.30443439731868727, + 0.20462479630226216, + -0.7834284478083047, + -0.1351463778652252, + -0.37379575622475975, + 0.2339389448973851, + -0.5944392538200634, + 0.17613530216377737, + -0.5981635668270875, + 0.549024352232078, + -0.6440176999654783, + 0.6265966162295379, + 0.3066234666972917, + 0.28154177820625337, + -0.3189320915663749, + -0.11081742415197005, + 0.49623831703611254, + -0.25117581221371, + 0.2208515104322929, + 0.2562687343314193, + 0.06692605744552516, + 0.6738630068618455, + -0.4094136828733374, + 0.3191723517860795, + -0.7184392856543781, + 0.06705772029244639, + -0.777581346211635, + -0.4142478812641078, + -0.6760853279689931, + 0.1301106742176329, + -0.38554852209386464, + 0.4156722285166198, + -0.6997629041473211, + -0.22415312432306433, + -0.1068312347502729, + -0.7500583789415296, + 0.31685951103935783, + 0.3570521003536512, + -0.5966665072580462, + 0.561731051511151, + -0.025434883830634636, + -0.8038148080269767, + 0.1439414723471989, + 0.10371198158751771, + -0.4626879154921461, + 0.48300576595617517, + 0.45042739677643373, + 0.5189747974346745, + 0.383081235291881, + -0.6113218357174107, + 0.1207983938660594, + -0.21063557547392175, + -0.15070054871098548, + -0.6887134832955769, + 0.3842547657452179, + -0.3929318037562234, + -0.7362937740922016, + -0.03607220191333116, + -0.4362400832651674, + -0.3854310125832294, + 0.2546515899588363, + -0.276828967944292, + 0.4302110389040984, + -0.7892429503994121, + 0.5535501415976934, + 0.6663673071727331, + -0.6246381892267578, + -0.5747921848579897, + 0.3659838541259318, + -0.35818701140855735, + 0.27231942828698086, + -0.026901654747470416, + 0.24564306749089815, + 0.42501387606408436, + -0.6815611976050124, + 0.6255851758375276, + 0.18003807200322453, + -0.3650921276150654, + 0.6433928541078108, + 0.14287011180880727, + 0.1031004835449193, + -0.4793323747828982, + -0.712617435507023, + 0.6537592808129448, + 0.28404215586002624, + 0.12573857278941825, + 0.1615270744762466, + -0.5971389944830708, + 0.3379390350578252, + -0.18284477467586135, + -0.7216621648592533, + -0.3669250857752868, + 0.5548720683450282, + 0.6178921443247541, + 0.466231911967827, + -0.8198180321098045, + -0.35406537598655896, + -0.7445978425973491, + 0.5238977191431927, + -0.23064436283804501, + 0.22970025906709368, + -0.8380151589642842, + -0.1679567947115802, + 0.2464475781623524, + 0.5624885382159336, + -0.678834621065167, + 0.3488271516588096, + -0.7375790066182528, + 0.4814298547184169, + -0.5987875325087051, + -0.8507865710980913, + 0.6411829965053563, + -0.14190996453645233, + -0.756572229885417, + 0.5536662468334125, + 0.2559554342103888, + 0.2642476658041192, + 0.5298794148912706, + -0.6956429578574996, + -0.2054726384715274, + 0.14327296055059235, + 0.3410726918241501, + 0.1695984532004403, + -0.3557034945003251, + 0.38915824250002784, + -0.42406396682883823, + -0.6618911401638076, + -0.8016240347292386, + -0.2170751160995411, + 0.4131810109766746, + -0.14438832109157484, + 0.32168974786484916, + -0.006361788448420835, + -0.03151674517988645, + 0.07898509075036286, + 0.6243115902915831, + -0.049930067177622606, + -0.216104095331914, + 0.22391132400210434, + 0.35897899862290494, + 0.5650851612578783, + 0.3494986666984833, + 0.49804217707122855, + 0.17966633513855046, + 0.5069478903107844, + 0.14486349395399178, + -0.8015329191559892, + 0.1494938805546865, + -0.35178271729811894, + 0.5228616808823846, + -0.10790719434210339, + -0.24935850763819978, + 0.3203615475485545, + -0.0285408353790898, + -0.2589968491863357, + 0.4200268484948694, + -0.30568903234494016, + 0.32891439915158494, + 0.35812194606222725, + -0.20038886795026312, + -0.24842118886939923, + -0.14694751440122833, + 0.562656382656226, + 0.049352059925559244, + 0.5487526458638176, + -0.6749958074986693, + -0.5704441206753048, + -0.7749244644790438, + -0.13193312825494896, + 0.593268023982111, + -0.6657926667146816, + 0.18258896704790628, + -0.5191348933783894, + 0.2817267978245871, + -0.21157124209155598, + 0.2973824428762081, + 0.3548154374913789, + -0.5722969472099335, + -0.49052615352162016, + -0.3298893027596471, + -0.5986001949357141, + -0.6441879114956179, + -0.18780594687859575, + 0.08091935124157146, + -0.12331263431475037, + 0.29192447713236425, + -0.10229969715677067, + -0.43599240010651036, + -0.49912032660637673, + 0.0718181937767639, + 0.16917764317878714, + -0.3788215348750181, + 0.4446096351409733, + -0.4032695950156712, + -0.6192119374021878, + -0.6295617931153313, + 0.3323952946270864, + -0.1042005105927376, + -0.05953615217886776, + -0.14467863101103517, + -0.3774075166995485, + 0.24077415899652388, + 0.10023456990309532, + 0.03003904508803512, + 0.33677305210448016, + 0.34593373936896266, + 0.4665029850246444, + 0.5790474880405411, + -0.6674595779926955, + -0.22795395288965004, + 0.34021825509983017, + 0.2782761241732462, + -0.0957762526585072, + 0.6755404530372214, + 0.2958768772632826, + -0.23219697083620994, + 0.13311708446873138, + -0.6987093616574874, + 0.6507914319191962, + 0.4395424455957816, + -0.7579227701164679, + -0.04570855019721831, + 0.14774166021612556, + -0.5690482512460613, + -0.3637598893250177, + -0.7989856120587878, + -0.8259616937846759, + 0.1273932247773123, + -0.45168997046579384, + -0.0908906522535542, + -0.46716109123008015, + -0.40901267199287933, + -0.025876647139788544, + 0.6660365036216161, + -0.1519131278098984, + 0.42901801038872633, + -0.21017885757698296, + -0.25875977219436697, + 0.18128773694908762, + 0.4678586367441452, + -0.46237849481291937, + 0.26581593599204967, + -0.31622583083801525, + -0.003746745021409592, + -0.5388762587617912, + 0.15105061175598722, + -0.04124573810188459, + 0.6092078602107173, + -0.6653510284287125, + -0.296724321123096, + -0.696206428418596, + 0.04205326348198768, + -0.4057284292801064, + -0.5126142210746807, + -0.6889435245733283, + 0.17678144501041493, + -0.10425193549957967, + -0.3167445413308544, + -0.8407173342625784, + -0.024472505206598716, + 0.6327207375189955, + -0.7935950639013504, + -0.8489084369198729, + 0.48188239299652047, + -0.0888842644665585, + 0.4058970537934642, + 0.4488867980338106, + -0.12542694482305083, + -0.4363631538726049, + -0.5459445470238447, + -0.3637811783441147, + -0.5763856130135434, + 0.09779848310868333, + -0.5618834360365675, + -0.6764221773001464, + -0.2036718526492617, + 0.31162673028351306, + 0.18553644946708714, + 0.06395333788582092, + -0.6473499188960987, + -0.1889571459911924, + -0.4415135767670429, + -0.6856527871559297, + 0.12842638722021205, + 0.5698163668380224, + -0.6489885057665468, + 0.20098959828468665, + 0.21752225324746666, + 0.6178000902771551, + 0.6537900428097306, + -0.08842934237046796, + 0.46515813845719156, + -0.6031303834242363, + 0.48471578794636405, + 0.2870576947311717, + -0.6279730518153261, + -0.7052899083266313, + 0.37232051948683276, + 0.30655444422383515, + -0.7936204474638227, + 0.03772979029627366, + -0.4951263169285505, + -0.7144410577574327, + -0.4664562456007798, + 0.6691304904896066, + -0.2822487876254004, + 0.3916514062081303, + -0.4788405010963781, + 0.6623071046155936, + 0.4659628520694926, + -0.37935943109734244, + 0.4113096360856151, + -0.5436258056373462, + 0.12461364859186275, + 0.6127645273998946, + 0.5526875791393789, + -0.6826244258592814, + -0.07482031010095458, + -0.07528565092536033, + 0.03615489414617268, + -0.2169690878852355, + -0.30974137151924375, + -0.2803956084031344, + -0.5484318403804377, + 0.14056501895135687, + -0.677245488478427, + 0.617816825729654, + -0.5204020605948504, + 0.5207139561179442, + -0.7016207225528394, + 0.07066370784097353, + -0.6433584118982827, + 0.12823655707411896, + -0.567856168965482, + -0.2547873078292616, + -0.6687505947033038, + -0.3751284197021626, + -0.31119692718537195, + -0.7366313766199103, + -0.8064592062299634, + -0.7647596935322689, + 0.07791083779227981, + -0.43051647556501277, + 0.2703307307112791, + 0.2677961627856139, + 0.3052529609629445, + -0.7995808982719803, + -0.6268562353465336, + 0.6807602862011805, + 0.6048176111188454, + 0.05352300062662696, + 0.5366853260516397, + 0.04243593219449737, + 0.533560127145236, + 0.40681143395314645, + -0.050086477191259915, + -0.8591578669353234, + 0.1923892251351299, + -0.7725936205864113, + -0.36425613653623157, + -0.811766760268636, + -0.2896262137143929, + -0.6761860650748794, + 0.6114756350495568, + 0.6498840565607192, + -0.7677699121716843, + -0.5734947407708137, + -0.027430355458529787, + 0.14616290908835416, + -0.26141426865757034, + -0.04158861831767924, + -0.310026965066987, + 0.25315929558086714, + -0.3464948002200713, + -0.42359423356689574, + -0.22527574580278698, + -0.07350667084979479, + 0.45748237882370557, + 0.17317813674481186, + -0.6025756097793422, + -0.7083578084126864, + 0.2903262036200246, + 0.5160575672865421, + -0.2774085033361844, + -0.508906885600292, + -0.025932279495308075, + 0.6502582956535256, + -0.5141785414450019, + -0.7079630178262266, + 0.24735368138557934, + 0.3817190458461531, + -0.5996690782221925, + -0.4596826221964821, + -0.5795977843151698, + 0.639626875664321, + 0.29241188687072717, + -0.23287581053896378, + 0.6490948925404626, + -0.049700885287069285, + -0.03742529799779848, + 0.3131424923994942, + -0.828925097125076, + 0.5784421516937389, + 0.508883197333632, + 0.3272298563631716, + 0.6768300496165683, + -0.10403872732237052, + -0.7752149585367597, + -0.6587347339541793, + 0.5772430290248972, + 0.3963192818949549, + -0.29443776046768666, + 0.23579541285257932, + -0.5248915620161934, + -0.05856342342693732, + -0.5265916549870059, + 0.6175484149285951, + -0.20463650179466364, + -0.689896794980475, + -0.21385326551568784, + -0.18727497013938676, + -0.493099651352161, + -0.7440220997384596, + -0.6465747546167826, + -0.4234994933016237, + -0.12802156753271354, + 0.4998017799953268, + 0.28839214577399475, + 0.20986813749949118, + 0.12704987018070957, + -0.7163856574644129, + 0.32945752408787266, + 0.3613673699633725, + 0.42877686259327585, + -0.26905712129213943, + 0.6406704249917768, + 0.0518714635127866, + 0.17209303629400774, + -0.5650343844657144, + -0.7014184049315296, + -0.7234741178804937, + 0.5720095695594308, + -0.3601366866447274, + -0.13094527640501608, + -0.5217752506973127, + -0.3511364739362739, + -0.5993214723791234, + 0.2424120622913145, + -0.05464095865985952, + -0.033697779316474996, + 0.1661074561115815, + 0.23375010231860383, + -0.5838585796173974, + 0.0525466203239664, + -0.35585989511209815, + -0.4647194045155413, + -0.7836246937636013, + -0.5034609678177424, + -0.6234878079485769, + -0.052543616005033655, + -0.4338004557561288, + 0.048486610096675764, + 0.43461698392128867, + 0.46204666868734534, + -0.515943794321469, + 0.544956681820229, + -0.11985086449925586, + 0.4459562999167025, + 0.14706325281701804, + -0.8536533402576596, + -0.2893598785648066, + -0.6235579450592998, + -0.816099251589642, + -0.800062301886361, + -0.8605157699728565, + -0.5592254544799815, + 0.3671222399726849, + -0.040503901552198185, + -0.7719014809656713, + -0.1757007129601026, + 0.29192284926830203, + 0.048892987896678175, + -0.38329144191704084, + -0.2429169313250099, + 0.25049842595831284, + 0.15850382995711676, + 0.5934125026107407, + 0.23518902997570634, + 0.666329716773368, + -0.4428174766290479, + -0.7147515941041592, + -0.2500605128606975, + 0.33987096325188004, + 0.13806290473433547, + 0.058387165598234425, + -0.0923065567208936, + -0.8503197987413875, + 0.5756028586903782, + 0.633071550148287, + -0.5465932077436955, + -0.6806860266943833, + -0.7532134113920974, + -0.2822840371555063, + -0.1128677462946247, + -0.6731288192077652, + 0.12693052671125737, + 0.4511904227464215, + -0.7128352730545252, + 0.5323962591987487, + -0.6166479354364767, + 0.02150661756881289, + -0.17105482064798117, + -0.0013576410378461912, + -0.7123757891475493, + 0.3669666518039748, + 0.673559855351399, + 0.4820955005090245, + 0.06964237195994627, + -0.5586028455398941, + 0.6489934703105976, + 0.2894274335602839, + -0.3964197561996548, + 0.39646235421405385, + -0.04456846547888815, + 0.26934434559866627, + 0.0594164180335901, + -0.10456361132216896, + 0.3749058708793166, + -0.4227805788514967, + 0.13847444777906237, + -5.580807324565562E-4, + 0.6438311768265027, + -0.32005886219419644, + 0.05531361304558413, + -0.669036587561233, + 0.4012480899736036, + -0.43033514607740964, + -0.1975444377408624, + -0.7520407079780933, + -0.01312455264396839, + -0.8071340007855787, + 0.40378283435939755, + -0.015418094839988239, + 0.07934541054413857, + 0.5325894025774044, + 0.1282713501101701, + -0.0729211105148524, + 0.4941381827024057, + 0.3692739113546796, + -0.7538667901306115, + 0.361270343916145, + -0.31044068151773363, + 0.11676871407737388, + -0.05615269213557594, + 0.487550548714378, + -0.5471105108737455, + -0.6281586332218975, + 0.31178320184856545, + 0.4271534647008354, + -0.49379836546720873, + -0.531953206694894, + -0.26886869227830734, + 0.4526138949486499, + -0.40100746640941065, + -0.029247423037323306, + 0.4028942424218377, + 0.5476399621319344, + -0.7779576428215672, + 0.5189737567664184, + 0.42360193808589697, + -0.5123696350563287, + -0.33519650376248644, + -0.03988636747731711, + -0.799842366684112, + -0.07203517053820185, + 0.5804329786703036, + 0.4093075911998446, + 0.6521102957176058, + -0.12037651971312091, + -0.5837242076302873, + -0.7018214957981501, + 0.6453334166061094, + -0.2910174175170612, + -0.7062938269759361, + -0.2073279213212179, + -0.8404829891139243, + -0.6617438840809134, + 0.1137769047715863, + -0.5312065240989371, + -0.5982016457831705, + -0.1424078086229762, + -0.8664731520898663, + 0.39864428501377447, + -0.2931332091373918, + 0.5486863857824503, + 0.34421517646692024, + -0.07493822773228098, + -0.29318004736744974, + -0.8162425942191148, + -0.6702393536320138, + 0.08635536310214109, + -0.4502558971320245, + -0.6428175393992612, + 0.057664574166626736, + -0.298376301568978, + -0.7267863387813017, + 0.3763521404268494, + 0.18222168601353694, + 0.46984057318706995, + -0.2524536791351907, + -0.006228805677038762, + 0.3788981893598894, + -0.7598528971676228, + -0.6573297041829946, + -0.4763383448954552, + 0.4046027924532022, + -0.28396795746000647, + -0.13844060657025758, + -0.1690605835268345, + 0.1159190111212387, + -0.4076030325222388, + 0.060526070898598294, + -0.2916740958894355, + -0.7290481799118097, + 0.45868917310518287, + -0.32156168888235637, + 0.4034668538957512, + -0.6757180656980404, + 0.4209488614595819, + -0.708630332973292, + 0.1229338815245512, + 0.07275011472034099, + 0.06613573540478423, + -0.6099803651101242, + -0.28109031511688765, + -0.02055923847805774, + -0.6132677169532537, + 0.2336591203104349, + -0.06195186732993763, + -0.560338724594978, + 0.06476245717824558, + 0.2599932767136205, + -0.31730451288913863, + -0.58845817665681, + 0.630833511415987, + 0.5145676070082287, + 0.36530998677487936, + 0.6529795429621673, + 0.0820791632218878, + 0.5244510401805281, + 0.08815340055408827, + -0.5254620762002618, + -0.5438069306710214, + -0.6818165758480638, + -0.6069449418537491, + -0.48205443518696206, + 0.06541255611461294, + 0.3402729999201263, + -0.620366490426216, + -0.7110665459026433, + 0.005882295048585728, + -0.6233786241369148, + 0.5749700788704332, + -0.44571240156093617, + 0.6396412270668438, + 0.6746060451724903, + 0.6300492259500591, + 0.016135372144796323, + -0.3414486499440217, + 0.5928117607671651, + -0.8476391732637734, + -0.801300038766076, + 0.27520001478080036, + 0.48348058491913093, + 0.3172733771650095, + -0.24597703868054344, + 0.4279440642515785, + 0.07649913313748158, + -0.5477832113018494, + -0.326768970024263, + 0.024114257475406076, + -0.21911841853625402, + -0.3545124165981506, + -0.5381946318540607, + 0.47258708840543673, + -0.8151921060823258, + 0.38501197879395976, + -0.04747607894223149, + -0.656945100716162, + -0.44568313067220167, + 0.20534422672872854, + 0.3113406296330562, + 0.20542479322220497, + -0.6433853599991959, + 0.30751271900569843, + -0.8572152958859942, + 0.5682764811783815, + -0.5496902573746114, + -0.7243575686771961, + 0.1458376508434408, + -0.6606208413746733, + -0.44422507886755463, + -0.643488507525492, + 0.20436363936367308, + -0.6890281865678097, + -0.4233669064962545, + 0.1243628488530445, + -0.7117522727994001, + 0.5764470978241781, + -0.34350016674270023, + -0.011741724794935404, + -0.8262810246746202, + -0.7219837066717724, + 0.177433460036437, + -0.3336189842955528, + -0.3310725017554109, + -0.7502457442083454, + 0.11387720278434776, + -0.6807962397810732, + -0.7808333339564588, + -0.7910200657910966, + -0.31107328959376157, + -0.17112441177068782, + -0.2816735654200694, + -0.8627125497830387, + -0.01902732639960303, + -0.5340846072196958, + 0.4750821532215782, + 0.1383372049631385, + 0.33032364012767046, + -0.6259650305920886, + 0.1339870230469956, + -0.015299439076993715, + 0.30467596486576387, + -0.39495305666287894, + 0.6241350087110545, + 0.5862135265841161, + -0.354029731065035, + 0.6823401713535796, + -0.7215443566857014, + -0.5071174160576393, + -0.25650795108367364, + 0.43947445916754024, + -0.022958022258595334, + -0.1372877954217674, + 0.2351183589856879, + 0.682497823770298, + -0.39596522140608414, + 0.3885789548641684, + -0.670513217035057, + 0.19354398243640103, + -0.8646097978352754, + 0.15414557126109363, + 0.4169594272631204, + -0.8114975734761773, + -0.06005850395768886, + -0.44077760543008704, + 0.025840675265671686, + 0.05812869255974684, + -0.24224827136994798, + -0.38708665409045595, + -0.6251175669930782, + 0.5484534453934929, + 0.41806391503198903, + -0.7307486056204098, + -0.17029212271733785, + -0.5707095775504634, + 0.02067354757456019, + -0.1099068297506941, + -0.18472930610309946, + 0.33015841821220737, + -0.6097471356882936, + -0.1208807932291881, + -0.09652140816619559, + 0.24071170368908235, + -0.04322373819678216, + -0.502012833380926, + 0.6128923205953772, + 0.46934026322542255, + 0.4545390338808063, + -0.7185700775814019, + -0.2351893571732705, + 0.1648056837561348, + 0.26053376878196943, + -0.44001488387508975, + 0.5623599165449792, + 0.09241052362530067, + -0.8569383353608047, + -0.6665414490776813, + 0.11446896904765069, + 0.32538453244161236, + -0.12711621099385917, + -0.6325847654198571, + 0.11963135457447349, + -0.08696192887285914, + 0.40102563157458293, + 0.11403198712809781, + 0.49712632520891564, + 0.2516218702305951, + 0.11847439277020899, + 0.22225869824817635, + -0.5846450917208741, + -0.46212220953212385, + -0.608289672954613, + -0.4897253678387544, + -0.660973431421433, + 0.4038416582550933, + 0.40152331510997563, + -0.37245841349311654, + -0.406961560586933, + -0.745619968713618, + 0.5334372921542455, + 0.5161494646613048, + 0.4931479025141917, + -0.7887421689480658, + 0.04631505051507423, + -0.38424502869901367, + 0.19282072254764804, + -0.4972227217398, + 0.39404963784989644, + 0.07895143467306998, + -0.26196834877523334, + -0.09590168828043943, + -0.013014309548858627, + 0.10991086459930433, + -0.517003496927787, + -0.0286750035022707, + -0.0406510820094631, + 0.2366086878257162, + -0.8213352887429689, + -0.8397854516010274, + -0.45551777178885094, + 0.4255166719319411, + -0.536304950805397, + -0.7217361300870775, + -0.40086834579166225, + 0.47332554834746465, + -0.6501440384852462, + -0.23026186910617374, + -0.6372575189463044, + 0.6057946890173208, + -0.6835991168853448, + -0.8333888479933645, + 0.08874799507239539, + 0.24669430198647901, + -0.44687464309767755, + 0.5257762526854076, + -0.6590540547802364, + -0.7856718144398545, + -0.5829223775578016, + 0.24514203983704042, + 0.5522516872306441, + 0.05065078898990716, + 0.590579185538377, + -0.37771281007042556, + 0.26164373801410823, + -0.5129394079791125, + -0.10964908840648191, + -0.5319516885909008, + 0.19510061978452786, + 0.6709342518841391, + -0.049939611169475984, + -0.8162058589918157, + -0.8394053935635327, + -0.269173999812528, + -0.3485050396783178, + -0.7258821108603635, + -0.7622352856338478, + 0.6315708671587895, + -0.1596384833618255, + 0.13163000445244422, + 0.4613167261856771, + -0.20927727082728054, + -0.0048120337433598115, + 0.4116498414013302, + 0.2396020777320712, + -0.1254713660960648, + -0.08323384996760275, + 0.3422412440374897, + 0.26726319966262435, + 0.06912793755908264, + 0.02813575588073569, + -0.485185472355187, + -0.5587981468988237, + 0.042870729727164436, + 0.4281744431137723, + 0.14752759192026155, + -0.012726462852192921, + 0.4492156322722257, + -0.8390608612442679, + 0.23412348302735564, + 0.5884031703690601, + 0.6659202019827929, + -0.4802380221466548, + 0.09214137989751325, + 0.24026076794655815, + -0.6983588505996339, + -0.5884792469593922, + -0.5557923689113186, + 0.45982309613708583, + 0.4442651989843004, + -0.5619498302322392, + 0.6509450826933488, + -0.691677742779266, + 0.6004359302311916, + 0.2282173728935596, + -0.696422591373704, + -0.7175360606611814, + -0.509863112024267, + -0.540258004448121, + 0.2699692688648724, + -0.28271965420411804, + 0.4664822771957423, + 0.13144515619851782, + -0.5883159826676299, + 0.31546713481550903, + -0.18287116839675777, + -0.47236009897071557, + -0.03615130795992039, + -0.6432397668024131, + -0.7482106050482369, + 0.6612723257137841, + 0.5771996634244178, + 0.37585503249496466, + 0.15894496918738443, + 0.1402179314820723, + -0.448518223882325, + 0.028443267164176556, + -0.6911196141824504, + 0.6612987097709825, + 0.5793879656675872, + -0.029787578276512572, + -0.09803217998240565, + 0.6121365594663998, + 0.11380739834116915, + -0.08242385719686562, + -0.3350910029583495, + 0.49211946539215423, + 0.549296260710522, + -0.2235965817949329, + -0.7548953179628032, + -0.7475086636243282, + -0.7983577772038346, + -0.48804648811393986, + 0.5831148625672241, + -0.2066026530811047, + -0.5046800795612576, + 0.009090376801748734, + -0.4176916494191058, + -0.828665377633441, + -0.776470178965218, + 0.45380809197409755, + 0.4620776852589844, + -0.535457492783364, + 0.008239235777658283, + -0.7741374919000817, + 0.6209400957150663, + -0.33367312973330676, + 0.6821075303372165, + 0.3539733485170221, + -0.4838458935805039, + -0.6812311848612961, + -0.5753920336781321, + 0.2739287996359848, + 0.23876715886385103, + -0.7590609250081847, + 0.5345478869661381, + -0.1920221833193687, + 0.21863875533158972, + -0.30320883145891864, + -0.2597852280281412, + -0.7566610401766135, + 0.321540801295248, + -0.7330337093052026, + 0.543882809787889, + -0.7669356105219088, + -0.7973122806829225, + 0.10352276902012947, + -0.7766476635131714, + -0.16914285884103353, + 0.23800560678362348, + -0.05023827429140737, + 0.12447056281353452, + 0.4752721818826159, + -0.34036502054198514, + 0.3346892164049119, + -0.039122286030252584, + 0.11800938358837243, + -0.061561916687300156, + -0.5712107757700399, + -0.8506568569778207, + 0.6622514911209575, + -0.048415042472039205, + -0.5592420107414702, + -0.25084384638579404, + -0.597250146774229, + -0.8052128244662459, + 0.15821833555983178, + -0.846114252743969, + 0.5594368281368124, + 0.4289005541272496, + -0.6014589027600676, + -0.45234458104703007, + 0.05967592083705198, + -0.10364370987272031, + 0.11497040455665997, + 0.39010519107971675, + -0.44800766302721623, + -0.5945907223309648, + -0.045540808466504656, + -0.19174855442409056, + -0.20553221961611, + 0.5060003384472914, + -0.49224902389231945, + 0.4448262192326643, + 0.525832120639827, + -0.14589104618609017, + -0.5176621044562599, + -0.022624899471405446, + -0.7520048392040409, + -0.3914430909630252, + -0.4614752650406212, + -0.015713519630522477, + -0.16143139839158882, + -0.05486434861311784, + -0.6710364095576759, + -0.3536342579218615, + -0.6729577866017995, + -0.028176758424362625, + -0.020955638125895737, + -0.0493579228344424, + -0.21416917133356883, + -0.7620682956439507, + 0.058383978145786775, + -0.40130317825129824, + -0.45503296336712656, + -0.7093367985688827, + 0.032293865975555835, + -0.40006812943955233, + -0.5414184585401652, + -0.45698141029461625, + -0.15626983500376246, + 0.009645480737095369, + -0.5195894852671685, + -0.2223376174609345, + 0.0649333019732915, + -0.6165166551090384, + -0.08186788655914656, + -0.7870309512562256, + -0.1270848379161712, + 0.02152429485298979, + -0.7742416690678444, + 0.1087248495848776, + -0.4871325178290515, + -0.508053557380414, + -0.0911422590366423, + -0.7481828801802217, + -0.6220618993883028, + -0.665149983314666, + -0.005978831387447481, + -0.12680218236989116, + -0.23942920377745225, + -0.018636806230244773, + -0.7346686496214786, + 0.04901947047179522, + -0.4705486501778592, + -0.43170796545205, + -0.7881601905528465, + -0.7044233323800092, + 0.1338174977940445, + -0.2928521214061993, + -0.39438768433279653, + -0.6072006110920034, + -0.4586412423032224, + -0.42261869045585426, + -0.4674581045353652, + -0.6516226475969333, + -0.21105915484530446, + 0.049787540804917096, + -0.11715033549454557, + -0.35025403513110315, + -0.41931319881130585, + -0.5964834320155707, + -0.1661694871900654, + -0.013928612527733142, + -0.08852796400150953, + -0.24795210010940794, + -0.6422594271469919, + -0.06588584146419285, + 0.022619153619743315, + 0.0715774552237951, + -0.776011221773874, + -0.16508163235783413, + -0.6439836809874752, + 0.0210454835380125, + -0.6020468036136792, + 0.06317262363030662, + 0.13498567220699753, + -0.5534363869439178, + -0.33708378183077525, + -0.4038354317249013, + -0.4852175962461013, + -0.3219965138060834, + -0.27272908044519195, + -0.09956561679795528, + -0.6814743310731346, + -0.7507670338100835, + 0.016722253529086406, + -0.2774526676125171, + -0.19741849140225476, + -0.46985374794800955, + -0.5803497999908775, + -0.5659675545132268, + 0.1342844753272162, + -0.30586032213943337, + -0.7010016242849136, + -0.09793124139991805, + -0.0770220909183198, + 0.054728300860267254, + -0.33657934427780367, + -0.8050963349524778, + -0.02489614153320996, + -0.42288668943316804, + -0.07785120619860952, + -0.7285542974263786, + 0.025522676471921413, + 0.03418687086377903, + -0.48549406555032176, + -0.08167955448055586, + -0.01136021092504591, + 0.10816921924904288, + -0.6457498948128534, + -0.6661890386243707, + -0.029482722447814913, + -0.40589623012686277, + 0.07533520813213412, + -0.3166267891878056, + -0.007994355883740534, + -0.42111715423259755, + -0.5542296534459905, + -0.03268845392369457, + -0.22134596753160096, + -0.29695428948523206, + -0.14956296911122624, + -0.5474096134292863, + -0.17966006920636401, + -0.7103671708692253, + 0.08626406017256005, + 0.050038778571669495, + -0.2648016002579704, + -0.044595911090080875, + -0.13521206636848115, + -0.7466596522996228, + -0.4468518261430207, + -0.6994752396974038, + -0.08585795333708979, + -0.6642527365158571, + -0.4923483014031934, + -0.10334264963772188, + -0.63388823576754, + -0.6624725792427728, + -0.647843119968194, + -0.011146696017293678, + -0.24667162232499984, + -0.5388314946884702, + -0.44236178646111357, + -0.5552676740869797, + -0.6309787472610932, + -0.7438598110714981, + -0.14150611016917758, + -0.4848242566372724, + 0.09749305613067216, + -0.5985006237851238, + -0.046313223542795545, + -0.08088121835121431, + -0.4988946633743226, + -0.3972778186893126, + -0.132046317450771, + -0.5615468067402778, + -0.7242366286648555, + -0.44501276747307966, + -0.2747447963982321, + -0.13587714577572396, + -0.506509436002018, + -0.25687904604698797, + -0.42803060654437125, + -0.7115543527081217, + -0.6580942455019921, + 0.09261261400305565, + -0.7989145594830743, + 0.1121961062288549, + 0.014379189483136656, + -0.4645462449268312, + 0.014287678082230748, + -0.305442784688582, + -0.7196941485934308, + -0.32118584438828424, + 0.012278835747632333, + -0.5081990213686152, + -0.28308512911684836, + -0.5186478806059455, + -0.4950788707783592, + -0.3331670174312087, + -0.33459515123338013, + -0.7916613849733043, + -0.31977272934844125, + -0.2390871903740005, + 0.134322326592204, + -0.6461231530841395, + -0.6568945368013178, + -0.35455219244407504, + -0.07095993268498646, + -0.5733321975332205, + -0.21705147617792453, + -0.4384452439252861, + -0.5176324786594836, + 0.1360180582739008, + -0.6861465476933304, + -0.5656763604530254, + -0.033548291655357665, + -0.12299431271822525, + 0.10313071788168471, + -0.34348017138252274, + -0.13578534472625226, + -0.18537661574425746, + -0.007637800600441946, + -0.7561716569956759, + -0.21399288192350163, + 0.07869674643498836, + -0.31174680552373, + -0.5585430629800479, + 0.010782090741869421, + 0.09561254652740558, + 0.03849945683084899, + -0.5024125359980256, + -0.06996451074575616, + -0.6765744787862855, + -0.03313772458568254, + -0.40459393757460005, + -0.4628941150902331, + 0.06823298524515942, + -0.7909251367864664, + -0.8116472176941671, + -0.011986045834330494, + -0.40247028117440803, + 0.07153962212034648, + -0.3197749909108508, + 0.03882494325416985, + -0.16869216297356127, + -0.11554477819292674, + -0.2611151836572233, + -0.14522170678442348, + 0.11332925531009319, + -0.21509135653914935, + -0.029555911111546096, + -0.7688906897101005, + -0.404773478394566, + -0.23397601560926318, + -0.8324351627134412, + -0.7260608002227273, + 0.1184990676387978, + -0.49661543734466923, + -0.5052886342378482, + -0.7452892005789579, + -0.454323548852476, + -0.114049695585563, + 0.019975454910369672, + -0.4891604214992296, + -0.4448128585972889, + -0.5717043843035099, + -0.08000419762607391, + -0.3385033778823472, + -0.04301210336523753, + -0.40418098819663223, + -0.3612422333558902, + -0.688514379771467, + -0.2635063972013816, + -0.12811582079728157, + 0.08517564847052761, + -0.06218145931398389, + -0.5582236554290951, + 0.033074718731560426, + -0.6160531258445032, + -0.078103187358323, + -0.5484284415317406, + -0.007559124886735713, + -0.8461555276468128, + -0.2685805666276374, + -0.3335271423756063, + 0.035041364983850465, + -0.24478702566448585, + -0.4791039327499313, + 0.12229641920213541, + -0.16340789906148534, + -0.5499917438031862, + -0.574865850937585, + -0.19097445161184723, + 0.10182983428045422, + -0.14272645896199332, + -0.40823264190713765, + 0.08554303329090196, + -0.23914207264836418, + -0.26550723124334785, + -0.20367357575923473, + 0.008540070122424082, + -0.23327553732501938, + -0.7041221535555008, + -0.6556190236684905, + -0.06580434264475299, + -0.4430509842479578, + -0.4191339055101826, + -0.21653790269057105, + -0.09014658393929742, + -0.21986421608893258, + -0.526142988177055, + -0.6836701915784257, + -0.6157073338977372, + -0.12588614327950298, + -0.08025033235432621, + -0.7172560543113813, + -0.4363067316544825, + -0.28677386335126265, + -0.5861364081322815, + -0.6864552650892959, + -0.19039487278114087, + -0.5721960710557661, + -0.05282989015817596, + -0.11454067568928039, + -0.19403845037990608, + -0.5240716538677721, + -0.6791228229402816, + 0.0770173740409783, + -0.5918189503068791, + -0.7671921801869223, + -0.7567271839728855, + -0.416915274611176, + 0.11305782967795763, + 0.07950568449145612, + -0.21513701787930417, + -0.6515704178326498, + -0.21015135818868813, + -0.6654493607657332, + -0.14771891577393104, + 0.10782530804090218, + -0.5477033254583292, + -0.21138322246988073, + -0.014660509189703963, + -0.3681083291284318, + -0.5502839057980721, + -0.07616810475958302, + -0.4413647786361548, + -0.2917430794289856, + 0.06544240306437998, + -0.0015687990445257816, + -0.7267375273206067, + -0.2993973422300782, + -0.06878804720936904, + -0.04035272016406144, + -0.6801615034038427, + -0.7958009967051815, + -0.11229484623162156, + -0.5691360247729789, + -0.058699078325133214, + 0.12149803351975197, + 0.12883608905380672, + -0.038236720391699786, + -0.5423131416409311, + -0.7846025249938323, + -0.7256656388716477, + 0.07897666040806617, + -0.5941547887926069, + -0.2614379101797589, + -0.598499783671384, + -0.28112401397960174, + 0.051153449740968804, + 0.09038924699159356, + -0.6047372599353189, + -0.0951786475736256, + -0.830689638640589, + -0.8328984457064024, + -0.5937659179358643, + -0.1805682111210365, + -0.3890034825623173, + -0.06590511908792085, + -0.6565452306561426, + -0.09613144533318163, + -0.10782678007166024, + -0.25279483661616464, + -0.5758516524145613, + -0.7092505494199806, + -0.7124837760771343, + -0.5508556350876538, + -0.11913750804401202, + -0.13277309092274514, + -0.5384990617916117, + 0.07512139550576669, + 0.06627022925369275, + 0.12629736229743405, + -0.7752993105855075, + 0.09335612082595035, + -0.5505237852335064, + 0.03303782859558202, + -0.3301355592922969, + -0.5603167355443979, + -0.39260161487917733, + -0.8119299291950126, + -0.5594732796493082, + 0.06673256999026156, + -0.6093440969897981, + -0.40805776788291487, + 0.044754662248890686, + -0.47721227611461464, + 0.14004056931129083, + -0.6738222373480762, + -0.04195872927371014, + -0.33064208680014096, + -0.3700342415383282, + -0.08217655058845696, + -0.39676348939457556, + -0.41950733112214766, + -0.5123666663839683, + -0.5432254631611009, + -0.281019215796495, + -0.372684883743677, + -0.2427230816195497, + -0.2136421947776581, + -0.07729738140254083, + 0.11491852604723019, + -0.19079153869617016, + -0.47237103705094297, + -0.3372945948651669, + -0.1093179472730037, + -0.8408270680161842, + 0.06514966641132625, + -0.4888977863977941, + -0.7127773955854227, + -0.8343986046075597, + 0.12919816088872715, + -0.7207629941466636, + -0.6364610381336628, + 0.033086357541388445, + -0.6518580427657517, + -0.2877302450255962, + -0.09284100127866879, + -0.8015342768654222, + -0.3373975230443119, + -0.16970381045142136, + 0.11147069967135637, + -0.39794399224567883, + -0.20885438363539988, + -0.5706031469436497, + -0.7219159391231479, + 0.06813583459100936, + 0.11209303306717522, + -0.7471374239431067, + -0.5914877980812359, + -0.05830206524546222, + -0.30300502702544085, + -0.2285704872275447, + -0.2586077788187757, + -0.15819159853700615, + 0.03487483472319508, + -0.4209194634547898, + -0.6935779724592233, + -0.5668850790157152, + 0.11885304807841746, + -0.5762898491183638, + 0.14103213454959307, + -0.16032538097640114, + -0.09396729509815949, + -0.5524391601546724, + -0.6929491123077274, + -0.4111172448106601, + -0.5401111614413127, + -0.5749240873444406, + -0.1572433965909661, + -0.5334512399118587, + -0.14869722568727584, + -0.001017077092106744, + -0.36222907668416515, + -0.5208645043902934, + -0.3402741909474991, + -0.20874803668379194, + -0.007147857324040552, + -0.25665590874307653, + -0.0073974203780693415, + -0.4288146092118986, + -0.01742795640991024, + -0.6825174569623027, + -0.6188867543594843, + -0.22107969224613977, + -0.04813436682675876, + -0.331967856823965, + -0.5808463670534296, + 0.03705643010862936, + -0.018883214143807003, + -0.7899542796403901, + -0.8064424420677119, + -0.5545201045371502, + 0.12801425172910386, + -0.37286340914968, + -0.42621218131599514, + -0.036750775911067346, + -0.6440189107891022, + -0.19592888864996105, + -0.0750789719736028, + -0.5325922608825384, + -0.4617833065176449, + 0.01009987223791442, + -0.8168611489086599, + -0.558509054077474, + -0.6584519461911525, + -0.2456494031627996, + -0.42477029982448733, + -0.34831520116655557, + -0.3951159541588604, + -0.21114903291262532, + -0.20232571087530704, + -0.2420623818861869, + -0.4583999328677917, + -0.5554169916717087, + -0.02517975846973486, + -0.788143365605175, + 0.039404418947861175, + -0.21452055396012137, + -0.01810340563339996, + 0.02120869257129676, + -0.0182193707469277, + 0.06988875014457907, + -0.46864583440375257, + -0.4534850613491236, + -0.19376132790548062, + -0.43434712586835394, + -0.5262058950189492, + 0.05490150034601904, + -0.7107149606913684, + -0.4103131932686307, + -0.6279558427969183, + -0.009437930397897754, + -0.5144142242471673, + -0.22123721330903523, + -0.7236698427818569, + -0.5786837587254972, + -0.12425270790063958, + -0.49697217149501655, + -0.03882316543076392, + -0.4515034701328345, + -0.7078695486101907, + -0.3837337850204658, + -0.34882967376717944, + -0.04044016387333493, + -0.43114503737070753, + -0.6045120653489533, + -0.2532073629281797, + -0.43119182312140963, + -0.793138048841762, + -0.1491207997800732, + -0.34498541917394987, + -0.4734887206021278, + 0.009618090698891857, + 0.11044205272496244, + -0.618894076295773, + -0.18243998089999203, + -0.7678118935527494, + -0.4767958214078278, + -0.4996754428901902, + -0.7802503643293034, + -0.12220849149014668, + -0.8175673480411336, + -0.03577177027973444, + -0.19901188066458386, + -0.06628824757593532, + -0.040341638026941684, + -0.7653569349621803, + -0.3928166462260719, + -0.2796398959592543, + -0.20786785214315262, + -0.15235328912509905, + -0.6360831706517303, + -0.023877281047611776, + -0.5998248091474774, + -0.7997045418219022, + -0.09744334850414749, + -0.026401494911682533, + -0.7633704097116032, + -0.6892456496880541, + -0.42634192868354803, + -0.12624242571995548, + -0.6104414833588182, + 0.03193568596089025, + -0.5028880066476766, + -0.7824317185765145, + -0.10275868413863076, + -0.5652931680479156, + 0.026423872139790583, + -0.8110220262824848, + -0.7830317201986999, + -0.5329623668854753, + -0.2209057555239472, + -0.19269049896107615, + -0.45353494520942644, + 0.09894182077517921, + -0.17323212657744558, + -0.34369004232917466, + -0.7673424435439955, + 0.07539502378230134, + -0.286386490303119, + 0.01452885007981708, + -0.6853706654599543, + -0.02557572681618936, + -0.7545465245979244, + -0.6236585152286984, + -0.38179135657149416, + -0.3383398718083298, + -0.3066702403293996, + -0.09566194751241353, + -0.809653094740129, + -0.7871484351183066, + -0.5606323789283038, + -0.6715329928378477, + -0.718418309279446, + -0.015237711608545479, + -0.7378840185735099, + -0.8443194492819824, + -0.06842848175583127, + 0.14825915854419724, + -0.8403251232718774, + -0.5486675767407334, + -0.5393000128115895, + -0.7826993750606611, + -0.4030188797646117, + -0.15346962448386126, + -0.2592199859662686, + -0.3274907131280096, + -0.8058903903724289, + -0.46297810675830475, + -0.5365743603099046, + -0.3900565771035646, + -0.14827914619494942, + -0.3140923961025964, + -0.40891796465778324, + -0.47264260682633147, + -0.6642151712450923, + 0.03243349095521553, + -0.8034016553829265, + -0.07619627842265886, + -0.7835301065044523, + -0.3021394047251481, + -0.13303606434751836, + -0.5064064167996247, + -0.7093396374948473, + -0.0295833062849169, + -0.49465150738115976, + -0.4541406992254902, + -0.38868619492185097, + -0.0010392491364896728, + 0.11463957377602796, + -0.8360663414330612, + -0.23976289304506648, + 0.12303632131153008, + -0.02248043859869331, + -0.5323380365177375, + 0.08650980373837902, + 0.07548580868563226, + 0.06963018597851145, + 0.024180904809999126, + -0.6262677340936286, + -0.4995541415001764, + -0.5515881407699166, + -0.7643838544659477, + 0.11085266449364639, + -0.8155897941544876, + -0.5711036246326954, + -0.5061548271533578, + -0.7559955243503216, + -0.8309870675460527, + -0.7955275253188575, + -0.251490416548525, + -0.7887602578470398, + -0.4913455742391808, + -0.5383776595937457, + -0.2701632446706804, + -0.23790672486975561, + -0.43425109830929676, + -0.5418422339562641, + 0.06880790077259857, + -0.32698344983393857, + -0.751389884616958, + -0.2423271995251035, + -0.2267711924469792, + -0.0407941208581839, + -0.18024303022579102, + -0.72702818488606, + -0.5788737625310415, + -0.502536318367192, + -0.4454776009237807, + -0.8324639476047221, + -0.23408109194115878, + -0.7593848574328337, + -0.8456217770899616, + -0.7802531543259202, + 0.018084591712137166, + -0.5356054116577136, + -0.7575387085666151, + 0.01884385398742172, + -0.4033555783508435, + 0.08547235085680749, + -0.3191339088585058, + -0.3884723533856725, + -0.42088511972246323, + 0.07568382065148216, + 0.0655392800732385, + -0.278775323317765, + -0.5135217789738651, + -0.5964757239861078, + -0.6395882064415808, + -0.2021278608352699, + -0.3788167152796156, + -0.029520395047288206, + -0.5730743910715999, + -0.4693657085440618, + 0.0377121151752684, + -0.4178954023698575, + -0.4939157443870322, + -0.5994282662757535, + -0.23334761545574512, + -0.795036098060813, + -0.34891553218095794, + -0.31163353101139235, + 0.08631961622417239, + 0.026046376124224557, + -0.5381859093252557, + -0.5822113690385922, + 0.02348847573869073, + -0.4537220432596637, + -0.004435071518192779, + -0.05601874664196027, + -0.6538913242523061, + -0.7926413686557162, + -0.6121631932894603, + -0.020230889798666718, + -0.26084432706080307, + -0.08804396740016573, + -0.7156365629987003, + -0.16191662620910985, + 0.09409249016892618, + -0.08955491690370232, + 0.06678090039263707, + -0.18208123315764158, + 0.0475423524442935, + -0.13097749573500284, + 0.054919205679421323, + -0.22756769177133684, + -0.5068855253229043, + -0.546851299087815, + -0.393675750974184, + -0.26977278125619286, + -0.7165609132497184, + -0.17769613924734318, + -0.8342380787235363, + -0.7485943468405223, + -0.5502485172604079, + -0.16707415919214808, + -0.740286574884918, + -0.37295725645347744, + 0.007904644351644619, + 0.02607604518597939, + -0.7859433929431452, + -0.3953534862378257, + 0.13140278781948755, + -0.23411406284999414, + -0.33286233393282216, + -0.4660640062488567, + -0.38457967333946375, + -0.7245674209236437, + -0.6306340486711991, + -0.1747768464421232, + 0.052341716162321084, + -0.6096165082582419, + 0.09000910104636406, + -0.2927502596491288, + 0.03565989486803145, + 0.04085316245278392, + 0.054386268133640336, + -0.6909705715680357, + -0.08947807184718282, + -0.5459352250102296, + 0.10176233695364312, + 0.12450252819975172, + -0.6928941246957079, + -0.550490438386064, + -0.6939013910000826, + -0.04471518851243006, + -0.04861833730547105, + -0.5416821292635564, + -0.13679877239215155, + -0.8011679515494696, + -0.3203748631390345, + -0.7995523646886256, + -0.5371904262238687, + -0.4324921146642474, + -0.2641678708461854, + 0.07875722479074876, + -0.0349611751324127, + -0.816779875987909, + -0.3863126136650083, + -0.8206731650830906, + -0.2066841385227839, + -0.8394524412485515, + -0.7218479919468824, + -0.7393981254462967, + -0.33750601140259906, + -0.07339816200976834, + -0.02386001846456287, + -0.3581002154864651, + 0.055593434282821264, + -0.7156122087719943, + -0.2692232848547188, + -0.3228355802119516, + -0.8281973237460988, + 0.012862920993669147, + -0.07549776965069255, + -0.1653338620841509, + -0.7012471427340152, + -0.20743308286300044, + -0.2502720052024976, + -0.5247369788430938, + 0.062108767349888794, + -0.26402592777259015, + -0.7100082465238148, + -0.807162382208245, + -0.13048390927705855, + -0.6950311726574874, + -0.4916586476208124, + -0.5954181152133182, + 0.07103780789035474, + -0.5188011338926735, + -0.10117581611524995, + -0.6221587461436267, + -0.7568279230908062, + -0.28208571489325807, + -0.6962575478898423, + -0.19800893633216632, + 0.09770462356556464, + -0.663746428009864, + -0.6372383655879433, + -0.5910417295691093, + -0.8067290394058089, + -0.7564254430359624, + -0.6137833285300891, + -0.30453708133308577, + -0.6670205775671267, + -0.4664110939345531, + -0.055536606438804315, + 0.1056735482450647, + -0.6015624213953492, + -0.6048714136654386, + -0.7272606997501181, + 0.005711830487260761, + -0.5618618340607688, + -0.2148765303745056, + -0.5159487759926518, + 0.06537418719759203, + -0.14469448592149647, + 0.04325733046393032, + -0.4567454234640476, + -0.1568245450713036, + -0.4168351504138496, + -0.5293310795815716, + -0.14784430647602775, + -0.7742048534642672, + -0.18250771416430933, + -0.7234831007698039, + 0.01244740240386999, + -0.4658683273803951, + 0.04953291683167238, + -0.31263161267421546, + -0.2526655325209831, + -0.32444153349575644, + -0.4860781546757548, + -0.7451516693321678, + -0.5996000318314856, + -0.2886867516304442, + -0.5180562167113415, + -0.4869098416582828, + -0.648321467773207, + -0.6673791170711135, + -0.6562271089220437, + -0.4822146501686591, + -0.15006558244809243, + 0.09756025419818037, + -0.7893762556350427, + 0.1106861216082009, + -0.23357909788204934, + -0.3769363193673261, + -0.39288463616071156, + -0.2230452674955804, + -0.7781435583343708, + -0.567924261917585, + -0.688701165595123, + -0.5158138310246653, + -0.21874105345402517, + -0.6399420995723574, + -0.5261191490823951, + -0.40800767800583376, + -0.47399337405294095, + -0.663510553215669, + -0.19983510896837908, + -0.7405809283177974, + -0.270271450313849, + -0.46003637186566626, + -0.35702823941117795, + -0.8458764469628034, + -0.423186568180395, + -0.7706997168779138, + 0.031010169803731058, + -0.771529191487596, + -0.5132188229193289, + 0.14816999390019747, + -0.14228149501426524, + -0.3015774543288665, + -0.6507039763498013, + -0.8139739101265725, + -0.432365449370945, + -0.33897312062119944, + -0.5108010262548163, + -0.7035876797730894, + -0.6316947255315323, + -0.7294214057782071, + -0.7403066379143066, + -0.053762813599249726, + -0.5168482443763835, + -0.6226336598131142, + -0.6324470966095798, + -0.0882563926507266, + 0.137493877393156, + -0.5695681156729692, + 0.018209206206812434, + -0.3301335166144739, + -0.4088659493259431, + -0.008818158035183488, + -0.12984405680880018, + -0.14412118925962125, + -0.11725533597267568, + -0.11618030211506536, + 0.13628446181632914, + -0.45922207122744585, + -0.6866787530006276, + -0.6219936196317946, + -0.5875420167434527, + -0.5622965560339035, + -0.4261392636501041, + -0.7528216995962111, + 0.10218733782735046, + 0.057103538116790475, + -0.33461550750097335, + 0.06739070685234616, + -0.0230438586845626, + -0.13215580602535382, + -0.790787906485241, + -0.5715157421496911, + -0.6157830781725582, + -0.2028088732714307, + -0.46961153117481025, + -0.51473712279189, + -0.0023642775507358715, + -0.6621260766499051, + -0.3982852583762392, + -0.5586148824808139, + -0.20222288535489574, + -0.7698521504021987, + 0.06389206694225502, + -0.47622942567760423, + -0.370343367111714, + -0.11062990254615968, + -0.21878519395173857, + -0.0956106402565362, + -0.028908089849628338, + -0.4228011665022967, + 0.12278595741484932, + -0.34085916596825083, + -0.7479983741626313, + -0.3347925398373801, + -0.03372295423719274, + -0.11787996380692267, + 0.001086653182245545, + -0.8265989321140632, + -0.7159647640286175, + -0.5050972470357105, + -0.6570620678976191, + -0.15198272932715584, + -0.6588800046577556, + 0.11521737112227182, + -0.4790640779260095, + -0.10780898431972763, + -0.2779471486245253, + -0.24775404071740137, + -0.7729441305454794, + -0.3831238565081862, + -0.336165129780708, + -0.32856534308059193, + -0.4155831714466292, + -0.44893395125492175, + -0.25895820931720415, + 0.02066170467046624, + -0.31439399956471115, + 0.09672027882489165, + -0.1601668124282477, + -0.48541645016727053, + 0.11273301688990811, + -0.6855622813841836, + -0.22602185765553695, + 0.011868109040768071, + 0.0030407655571359493, + -0.6571623649189402, + -0.2661871723026298, + -0.30782251512905257, + -0.5432455387893375, + -0.5398912256849073, + 0.13443303318179045, + 0.08508595850071643, + -0.5111503719892303, + -0.5013022131189083, + -0.059890813317492575, + -0.13234505681271358, + -0.16665121670751948, + 0.11520219082072258, + -0.2799866071282394, + -0.43992604051810325, + -0.15038632992317025, + -0.32185041123837266, + 0.0697533215343128, + -0.7273934365125033, + -0.30733941210479276, + -0.7518537653755855, + -0.45102353165488235, + 0.07246670977273417, + 0.09470342076261173, + 0.09606211166872869, + -0.730942587527828, + -0.1421645457852202, + 0.11421084543818061, + 0.020550238384076214, + -0.11698118659262602, + -0.5651503919050931, + -0.573345612640958, + 0.1362231729098491, + -0.48002209615969943, + -0.7150593280217037, + -0.43398454009498133, + -0.38517348887709996, + -0.020224654854942847, + -0.23611745177043086, + -0.006487159479738214, + -0.4258247982734469, + 0.015047703585755468, + -0.4310793848705261, + -0.6538770947867478, + -0.4551408052425444, + -0.7193995995825859, + -0.7167026405243202, + -0.48815475913405143, + 0.06384865952851271, + -0.3702631268191782, + -0.10305741869712459, + -0.513759392452583, + -0.7441683250537661, + 0.13195533878833177, + -0.0380629831297693, + -0.4797789473526486, + -0.2722332579601203, + 0.07592874148445194, + -0.23077900220337466, + -0.3959940427606212, + -0.3566947572637592, + -0.6905626975440164, + -0.1932574216368511, + -0.2769211145652217, + -0.7971412527246443, + -0.5647113516455943, + -0.6022522559470841, + -0.14686465591123943, + -0.8264166755710336, + -0.028807221374887226, + -0.6094338120565671, + 0.013250879866192777, + -0.2815606366792366, + -0.514946318181342, + -0.5602160811438154, + -0.29582779088291344, + -0.7411650097990485, + -0.3793173657118522, + -0.15372095632009142, + -0.3434369293948162, + -0.3772023555167962, + -0.5861642928605822, + -0.14012606390533233, + -0.5228417350402047, + -0.8238282372027085, + -0.29216860900534924, + -0.4150039169338255, + -0.16639289143017721, + -0.7680338806803508, + -0.7453255712878677, + 0.0847457968303803, + 0.0992284903096291, + -0.026337758067091155, + -0.4444129874153832, + -0.6343088832648337, + -0.037927130498371486, + 0.033510414093129826, + 0.08895359445603812, + -0.774335098099411, + -0.45680836182327916, + -0.8159813324395685, + -0.03811640954027329, + -0.5508061109384375, + -0.36883152782833534, + 0.03485799274610901, + 0.12564385700536296, + -0.6455864475111662, + -0.590993586442544, + 0.02546144656432381, + -0.2260396088878699, + -0.3039829138290936, + -0.006117198155457193, + -0.46253013063874754, + -0.731640219810137, + -0.557217800347906, + -0.27195563198718553, + -0.7764364631354915, + -0.6845955192646611, + -0.6732453506900365, + -0.3690239306724474, + -0.7645013494834231, + -0.7397538583421543, + -0.3557486969629605, + -0.04019280430518157, + -0.5517697587682453, + -0.5392990954521781, + -0.3776521638566539, + -0.6665813645897405, + -0.6421444613668512, + -0.809449686245657, + -0.2339008171028527, + -0.7333301761829075, + 0.11956338631139074, + -0.6333809896788145, + -0.8044905311952343, + -0.8411116476511394, + 0.1285389706379112, + -0.11967275725537563, + -0.16492458137709176, + -0.6980203904462187, + 0.06847466331872099, + -0.6194570569968947, + -0.49565495127364156, + 0.12781201183585955, + -0.30638863725762944, + 0.1459433471992333, + 0.047622175171488035, + -0.008525297011771071, + -0.451788158431649, + -0.7507563693877216, + -0.04106791675691257, + -0.5751006088798583, + -0.535603155513942, + 0.12147227901334734, + -0.8134488332663793, + -0.26875117551327143, + -0.7762905471481092, + -0.7339108623687245, + -0.5365212021195066, + -0.4125991038131087, + -0.7946491218307933, + -0.39005953424400797, + -0.6498709261931388, + -0.17897275946131452, + 0.09953922407122973, + -0.3391078417324348, + -0.5998345480802376, + -0.822982697387482, + -0.7850059003758186, + -0.6815366704617842, + -0.4407989054147615, + -0.05033082328031979, + -0.2367611820254033, + 0.08084921187713501, + -0.04905219203191602, + -0.32324492448873, + 0.033505851100363526, + 0.13354022839094548, + -0.574789934872028, + -0.12886147857794505, + -0.19745267634559716, + -0.02906704170743779, + -0.14570297905843665, + 0.06780023183009287, + -0.031342327395031844, + -0.7092233000256811, + -0.6257758133111977, + -0.5492833544390032, + -0.7295834384564424, + -0.8455116895798166, + -0.36677432544148536, + -0.2787916868690268, + -0.22323694850915476, + -0.5097684114940353, + -0.5272617038570524, + -0.24270163697253722, + 0.0489359362114965, + -0.5972809613076475, + -0.2356023644063645, + -0.05841950562888709, + -0.40708557825658326, + -0.5733068958508591, + 0.09450000590953012, + -0.66273506118149, + -0.42014912735077703, + -0.011046345890995735, + -0.33793406346899624, + -0.6787646313960035, + -0.7088899264285891, + -0.039288179148552205, + -0.26011259707908907, + -0.6789407436812884, + 0.04597072437557237, + -0.24938557119133442, + -0.21243114879695812, + -0.7439920567012197, + 0.059977263925316326, + -0.14947726252001148, + -0.37245690783101115, + -0.4578200594815655, + 0.04573823012218592, + -0.17192528105684968, + -0.5669483180353557, + -0.8291059313754582, + -0.8161582707681265, + -0.5268666924278518, + -0.5418575172532851, + -0.28579963481519033, + -0.6480650775139261, + -0.7709474295208051, + -0.14096733729232147, + -0.3261467119553777, + -0.2576575953186736, + -0.019798349017404737, + -0.18715241896673163, + -0.793277895700865, + -0.7594110417336891, + -0.7481957838068891, + 0.061949706969141705, + -0.13853844754029299, + -0.7634649489359377, + -0.14054370239752423, + -0.7230557498459996, + -0.7651661770347304, + -0.5677838296620347, + -0.1600056270903223, + -0.2830099243231835, + -0.7433330287042819, + 0.07514463407596805, + -0.8143093295418296, + -0.22806914878522677, + -0.02748431114049199, + -0.5758512642940823, + 0.05568606455706204, + -0.09433881946854772, + -0.7598114668649776, + -0.3689106851371698, + -0.49723602723649885, + -0.2622664005949804, + -0.1627808764954447, + -0.19005337716617388, + -0.3465317539163396, + -0.44234722046845953, + -0.08171378121539485, + -0.7774891075487196, + -0.39241229987768644, + -0.0130205683207123, + -0.5351896740345656, + -0.07477808735530067, + -0.46317276282628334, + -0.4889479180770148, + -0.1894676846986071, + -0.5253440520219274, + -0.48878985205051556, + -0.1453238143655462, + -0.19386073612306698, + -0.6143953125167738, + -0.5372203941690125, + 0.0679296859497307, + -0.5667822969914083, + -0.405821589353725, + -0.24577630815675922, + -0.4008713950456932, + -0.6942216764828978, + -0.423605282992465, + -0.5133136174094164, + -0.42121431560986505, + 0.007479536354733418, + -0.7132630360309177, + -0.7234193689475258, + -0.3633748085428124, + -0.7439570910509747, + 0.10831429704716466, + -0.36532023742735087, + -0.035594642724085856, + -0.6823123720989304, + 0.07472725304753636, + -0.27846084734123033, + -0.1900151094793664, + -0.6141981974783871, + -0.36438685853286107, + 0.012869721951778934, + -0.39152444233204803, + -0.8279933276465802, + -0.5294384352778764, + -0.7729411181620436, + -0.2634966338906767, + -0.04231619043042956, + -0.8052086736844664, + -0.26172599945263253, + 0.03707743801566454, + -0.42964627688465806, + -0.40199357383322376, + -0.05845332536684422, + -0.6520845508216675, + -0.773418240942172, + -0.35531766999882514, + 0.01659381996438225, + -0.06605328894421891, + -0.700866965124671, + -0.6641182930192515, + -0.7766985100639533, + -0.04423560462008136, + -0.40551286353864163, + -0.7635417480814378, + -0.10268560082887201, + -0.7790257561161138, + -0.5513134229925193, + -0.1402935208654289, + -0.3059340714549196, + -0.24485190479240282, + -0.32239728601368367, + -0.6514778083663035, + 0.06594662789214001, + -0.45322684231579313, + -0.1200977602283485, + 0.08942006377142597, + -0.5220650198080554, + -0.7214840187457412, + -0.1374498138082687, + 0.00967576272630244, + -0.3735068295765588, + -0.816654411931946, + -0.14707697760150074, + -0.7523314718277836, + -0.5173326197456434, + -0.18597095637682792, + 0.0627581892839022, + -0.7968467476367467, + -0.5967260037589606, + -0.7866711659221257, + -0.043090946649650075, + -0.20303223037095053, + -0.8287342063774187, + 0.12516196782561073, + -0.7044691762898698, + -0.3395787315728347, + -0.46031679460690955, + -0.4128325835923278, + -0.23104366295954493, + -0.6003605315252997, + -0.7593300492371838, + -0.2733720306882155, + -0.060013399709465065, + -0.16523290375629907, + -0.07144322024554917, + -0.34286864008404083, + 0.07857937051389541, + 0.07395938361484622, + -0.8448332561606035, + -0.39963315360415186, + -0.5286538157218935, + -0.8340887419289368, + -0.08660739215034341, + -0.42204469260065947, + -0.20790775502664627, + -0.20082844357866658, + -0.7199106952111405, + -0.09392435025496604, + -0.4964123271981698, + -0.6401078267066133, + -0.42394944917200783, + -0.0744956038956176, + -0.6180368965251865, + -0.06048196297956021, + -0.5377905352233079, + -0.19204830250521798, + 0.0022280269237484607, + 0.13542209382499337, + -0.4923748285619818, + -0.6262335903592331, + 0.13807462699079498, + -0.22041499328187308, + -0.5158817908246722, + -0.7586301915960657, + -0.10580160364062441, + -0.23620837624965474, + -0.5407412426981734, + -0.4384895950340164, + -0.0505070621240451, + -0.5799529676006856, + -0.2695344345633337, + -0.7455836359637444, + -0.7813440073354931, + -0.7592256149444263, + -0.7735841329288314, + -0.29144847608200797, + 0.08795162692506076, + -0.13821161538548066, + -0.5373245601963315, + -0.7878672568104506, + -0.7458344372917535, + 0.054950057635253846, + -0.040129126423742334, + -0.1023482530721389, + -0.1557519593504063, + -0.8005069186791528, + -0.17670796805283873, + -0.4425244148153696, + -0.33638591843836996, + -0.8423504802902744, + -0.43102620771152955, + -0.5651132189748844, + 0.06295276744357214, + -0.39432232394181976, + 0.1331973500398247, + -0.25685811907723943, + -0.6871353112314509, + -0.3698460197942351, + -0.787414763164929, + -0.2784933752003981, + -0.10378764309106436, + -0.1537701859878473, + -0.7929871869927166, + -0.712216660628675, + -0.6471228407480427, + -0.1269408004623599, + -0.16542097209081086, + -0.2406743690313251, + -0.31830699344027813, + -0.3965732783199497, + -0.40402090348884667, + -0.7401884900992707, + -0.6753722062741636, + -0.05392027491471607, + -0.5115125093060777, + -0.8459566922135544, + -0.5621114008158747, + -0.4215255038506987, + -0.0753512646150225, + -0.4235879177231702, + -0.5556850230312427, + -0.03822412244203932, + 0.14461209819984788, + -0.42753520467225375, + -0.6912810904863143, + -0.6205761709535904, + -0.1114254452870247, + -0.26169330006222113, + -0.7127582385027827, + -0.10620517934657558, + -0.03742846468876637, + -0.3968880439241209, + -0.11461508148704269, + -0.6551540620413109, + -0.6171861676845831, + -0.5069346878938956, + -0.09789832105918617, + -0.23336431928177637, + -0.6924664193374744, + -0.6464017741772029, + -0.20785521766807635, + 0.13928620593452146, + -0.15228172348684377, + -0.6589403757508636, + -0.7282419796703783, + -0.8448502482128049, + 0.07610004340227794, + 0.04486503298552724, + -0.5949892985985508, + -0.4602382754760634, + -0.42961991049160625, + -0.46887888553371115, + -0.5799007060494072, + -0.22743610836113048, + -0.64784806124991, + -0.12231195350049429, + 0.14439092362873907, + -0.4925081980202497, + -0.22144665164932165, + -0.3659377774918332, + -0.05794861586337652, + 0.06200456824416489, + -0.04938037576283749, + -0.36901378012648955, + -0.4172681779802261, + -0.7234611409271954, + -0.31701883063215075, + -0.7025201629134536, + 0.028119006486075127, + -0.016814759760862774, + -0.6049228207127226, + -0.17018873310369953, + -0.437683279720771, + -0.5163368691767264, + -0.832213920079426, + -0.15797492875931507, + -0.4868846321667685, + -0.6115872300824574, + -0.30466590386007886, + -0.7222704472869076, + 0.06002679718164117, + -0.7180643546600922, + -0.09605711834102182, + -0.5630300718924626, + -0.6768896952949784, + -0.5687268112005693, + -0.2759029460537342, + 0.12378213030783847, + -0.7972592304319182, + -0.8396009786146996, + -0.45992131240195344, + -0.732441767129484, + 0.09628521558576342, + -0.7895675780080692, + -0.1640722393223265, + -0.6160374871059959, + 0.07878510860098975, + -0.13744509682063355, + -0.6434178356135186, + -0.21394264719724032, + -0.22645534699917025, + -0.5144862037773219, + -0.48792151429266284, + -0.1042024114009622, + -0.15262191895572796, + -0.33332943773676005, + -0.788734798040273, + -0.2209965729457275, + -0.2772220545903512, + -0.09474861840885207, + -0.619011673218494, + -0.022227799751712518, + -0.41236457252468234, + -0.7461701498183784, + -0.6063448654528811, + -0.0017523770074875378, + -0.6256331448460041, + -0.4032224819378734, + -0.7392675473611916, + -0.43488992054157916, + -0.512780208527108, + -0.007737763764387617, + -0.5570263392410579, + -0.20339550160939412, + -0.5931793573477611, + -0.6856936963888579, + -0.17966643339835708, + -0.4948528237657791, + 0.10587316807741298, + -0.025631466505853573, + -0.002032519639819541, + -0.6758093511533732, + -0.4574630389682983, + -0.20091453984904784, + -0.753004556861372, + -0.19730915349277667, + -0.31925852820263134, + -0.0025597341745904334, + -0.33602247435757304, + -0.834919679733204, + -0.6001576933117057, + 0.010252871013211595, + -0.050189899897277956, + -0.019845168847713368, + -0.20330159658943658, + -0.4430468468954356, + -0.6643144406845518, + -0.10666468970689458, + -0.02961779071087267, + -0.3443040164305323, + -0.7959117340183667, + -0.6036470544986388, + -0.3653478559642681, + -0.3267582478525147, + -0.35156755521937044, + -0.7403235615169719, + -0.7910199909110343, + -0.59994275157012, + -0.4420584943244056, + -0.4888131288461573, + -0.14176049234856425, + -0.299403133067319, + -0.28520402635022035, + -0.8236994699458344, + -0.4107442070047195, + -0.8319328991694006, + -0.817757956695498, + -0.8325769076159508, + -0.24355718756753153, + -0.5220498321208619, + -0.12045856489542472, + -0.0368956648985459, + -0.47808994122537635, + -0.626211618137958, + -0.40091509499753986, + -0.5162751357758357, + -0.8235144900470457, + -0.1817143690483165, + -0.8055972875113784, + 0.07749356760916071, + -0.5348021093403883, + -0.10710966328797866, + -0.02135590261993836, + 0.02276470860756663, + 0.029609185900846158, + -0.32814125260732674, + -0.3281144420331218, + 0.3656499185009852, + 0.1630736684270776, + 0.2658782704995871, + 0.2880803711161235, + 0.2989056525032546, + 0.27214387387998284, + 0.2980611948642681, + 0.20090633076865821, + 0.20662442173936768, + 0.30087333601121147, + 0.33255837175131536, + 0.3524269050035948, + 0.19268855364325255, + 0.28863616761224564, + 0.357126477756995, + 0.2005185482823703, + 0.36395784553127547, + 0.2971021606495793, + 0.3250362613723031, + 0.1622265180645924, + 0.37540761343823914, + 0.20909348400794048, + 0.23848161797904355, + 0.2734132683596409, + 0.18034707521312426, + 0.3635000742206955, + 0.2668188601153306, + 0.22978272038562242, + 0.32562735977203516, + 0.20764584817530268, + 0.2971387390896001, + 0.24187489132118645, + 0.3350368371551917, + 0.23654503949024533, + 0.35607308170291907, + 0.3079788981843886, + 0.3532090361384499, + 0.2557227693972688, + 0.16668230771082745, + 0.390805220614955, + 0.16938472858243417, + 0.27858139693691014, + 0.17140609938167758, + 0.3298999092606184, + 0.2805568875539899, + 0.3796683514558068, + 0.1604752783806243, + 0.2530586096213566, + 0.3736223508458667, + 0.3932456946099391, + 0.24662636889630754, + 0.32442099842697836, + 0.26117044921551874, + 0.2380073462301111, + 0.28176302113580326, + 0.24491452028270466, + 0.38851223627962117, + 0.36872872393414535, + 0.2259621529633401, + 0.2733308677812183, + 0.2843854365325869, + 0.36119002713385784, + 0.27326103007239533, + 0.3124663433052068, + 0.20983311865311943, + 0.34793044655871663, + 0.26351312905421576, + 0.26846833663402897, + 0.31416564614255194, + 0.15663565535749113, + 0.2261937908435524, + 0.17845075947599615, + 0.3779988713685713, + 0.2988899308591621, + 0.2930658396681396, + 0.24722453328112556, + 0.28133103447201735, + 0.27059469801941904, + 0.30585602477212337, + 0.21200789391724306, + 0.3808662930680894, + 0.33789623890594456, + 0.1583925785922619, + 0.15827267379313922, + 0.2392534635073711, + 0.199316332717072, + 0.28390310012577225, + 0.1934589127867745, + 0.2979747840131365, + 0.2682485288541164, + 0.1896411455065421, + 0.28344125859579383, + 0.17129620653506203, + 0.22646928176404343, + 0.32089347629796244, + 0.2450816459197107, + 0.17880057993055978, + 0.3857339534486752, + 0.33578209320519825, + 0.2306157040453289, + 0.3842347250268064, + 0.27145571309874217, + 0.2934693382060891, + 0.3454261077624611, + 0.37343361087198235, + 0.3786861432644277, + 0.24821615917072753, + 0.2047651235235812, + 0.3859959184624251, + 0.3129030229331575, + 0.3651906126490732, + 0.3159330774894821, + 0.26759422915268016, + 0.20853535624150044, + 0.3278232648304566, + 0.39325822976961555, + 0.16036191433348368, + 0.1871495380540564, + 0.29150950302726364, + 0.35021756960271777, + 0.27687764359631195, + 0.37221462315645865, + 0.3010939315161068, + 0.3278369896645991, + 0.3869513324064344, + 0.33700959423810517, + 0.37991423377534306, + 0.21578724892151097, + 0.2813405417090734, + 0.2833256936064653, + 0.27840211355990474, + 0.39283802514630983, + 0.38020654149934285, + 0.18838576535359672, + 0.22630258329128697, + 0.27458725419427565, + 0.318424276581199, + 0.22780209188574982, + 0.31203993645362743, + 0.2656316273058219, + 0.20242765878367577, + 0.20325131263067092, + 0.30350585514779777, + 0.3530453950247628, + 0.2680020796849989, + 0.3177529568664562, + 0.17623584561877245, + 0.35995956243369864, + 0.3039267928129078, + 0.2686034722015876, + 0.32618384493768704, + 0.2700223345507072, + 0.17941685555451783, + 0.23895261597040984, + 0.3407255293572049, + 0.2593154537387099, + 0.16002255992876743, + 0.3227525456252055, + 0.18262888450819242, + 0.34934655522392344, + 0.2477969126823108, + 0.33239852624846217, + 0.26106526854708595, + 0.24858490090863766, + 0.1960394288363826, + 0.2167900423424468, + 0.21529516107174554, + 0.38147386407276873, + 0.2758847008510841, + 0.31012539131420536, + 0.26679260586493797, + 0.220850269295756, + 0.3458134758313765, + 0.254401123824712, + 0.35724676941242917, + 0.25944005108869705, + 0.16043692457295547, + 0.2728547447360322, + 0.15893653001790342, + 0.3222805125895694, + 0.3611184863732636, + 0.26460684820633323, + 0.3705493392263975, + 0.17383532415505207, + 0.39212711136403894, + 0.22986836510334702, + 0.1573125834607376, + 0.2548512620459238, + 0.2864981396239323, + 0.35616017101775155, + 0.3771446052149271, + 0.29272016333857753, + 0.15989690638493184, + 0.3390462464479965, + 0.38509256628240884, + 0.31726503353891433, + 0.2328174707617498, + 0.36922724439466503, + 0.36477694935141103, + 0.16035312776366825, + 0.3732267603426747, + 0.2600776072310578, + 0.17301268737365735, + 0.32834518502679966, + 0.19850177268460645, + 0.3635897113775436, + 0.2604864483836926, + 0.3523213439267049, + 0.3181425491841841, + 0.2520609911814185, + 0.31624228329563897, + 0.22974851252319417, + 0.3161997875412572, + 0.2892063430125634, + 0.27550064516736067, + 0.2769407923702412, + 0.34231139801734894, + 0.3332968720808206, + 0.3850626755077266, + 0.30534736784864874, + 0.20719311650129685, + 0.2891644979621588, + 0.3310535976118455, + 0.17061869897478874, + 0.2907835253535319, + 0.326075688884126, + 0.2254207740191867, + 0.23203368844673944, + 0.2723489400020375, + 0.29805322329774814, + 0.2322866885915943, + 0.3319500123754804, + 0.26274523160066066, + 0.2517249595295529, + 0.2621221970841941, + 0.29900216580271255, + 0.24035651972596475, + 0.26948587830202964, + 0.16250820209178576, + 0.3745960585167568, + 0.34847289851123914, + 0.18646658943264297, + 0.25781376490392494, + 0.34636864304608506, + 0.21436089790374252, + 0.26827460940327474, + 0.26164213255779695, + 0.3921131930592868, + 0.3256688395056786, + 0.37077729741125587, + 0.37204538327694986, + 0.39268757055550646, + 0.24539484310414703, + 0.210573765791165, + 0.3379551188714621, + 0.28751772172689505, + 0.1950255666104546, + 0.36579225882384314, + 0.38091671912763186, + 0.26472890324158305, + 0.25866435601740506, + 0.24486481148963973, + 0.3547942825571178, + 0.19678485157154502, + 0.29524565674506903, + 0.3902012418678972, + 0.2369647306612857, + 0.23885310391857223, + 0.38973737096295624, + 0.37124754254388026, + 0.18021168269049115, + 0.2170557077225642, + 0.15959916609106586, + 0.3359768431646145, + 0.26856241280350684, + 0.373816558130621, + 0.15885826007750725, + 0.3004449984346109, + 0.38228848964465123, + 0.36123154369554716, + 0.2080598003475059, + 0.2880163955668843, + 0.3668365480367394, + 0.20327323054690158, + 0.27501996841106136, + 0.1914983421347125, + 0.2772375185096419, + 0.39231076210668514, + 0.320672273228105, + 0.3273530646899563, + 0.16506272590430315, + 0.26015378114913906, + 0.38175569785881025, + 0.25695893101514344, + 0.37426171138963754, + 0.2913930268330045, + 0.22945850337065615, + 0.17554568411530647, + 0.2780919416530635, + 0.19728634443914214, + 0.2274959476898109, + 0.31090457777174296, + 0.2701880328701006, + 0.27348236106188717, + 0.29396820721462913, + 0.19328472913940903, + 0.2475247495964849, + 0.23156321730750007, + 0.30270992247062656, + 0.33059928429922136, + 0.3004255053367154, + 0.3784147838351965, + 0.2598268034112238, + 0.25086517901794075, + 0.24599676660086967, + 0.3379663890815547, + 0.2567228795873573, + 0.354783028573781, + 0.22240184932143395, + 0.29122420246095404, + 0.302896015413888, + 0.19548829294443318, + 0.3208891678412755, + 0.3717981526659775, + 0.16028459986004107, + 0.3886998162467346, + 0.1631587859786446, + 0.2747357821289006, + 0.29656015643377237, + 0.19381982883276389, + 0.32711830908386497, + 0.32621881020016674, + 0.18299687017545224, + 0.20739416970264557, + 0.2818900568513759, + 0.20066181983114106, + 0.2788643383064976, + 0.346529390284427, + 0.22212199160766144, + 0.32651442843926776, + 0.34971089329720184, + 0.294881835579754, + 0.17629642523516978, + 0.2299128069247569, + 0.3866918240001057, + 0.23635426225873213, + 0.3663516674689816, + 0.25833650571839956, + 0.2653088431652366, + 0.39150080552475824, + 0.3500465046014776, + 0.25144044923198905, + 0.345887536415329, + 0.18525158737530478, + 0.21668219300939792, + 0.3879662278533062, + 0.3900625969538941, + 0.29174370511319014, + 0.24593018733778454, + 0.37797860013299767, + 0.3018227848760777, + 0.3647884791771152, + 0.32953244216862926, + 0.35447591420080676, + 0.2000416359957444, + 0.20911894610020307, + 0.24769722168182456, + 0.22026358883964076, + 0.1631343072460617, + 0.23155018129725394, + 0.18194197979585322, + 0.391584878616853, + 0.382809048672088, + 0.2888989225942789, + 0.23149589851460098, + 0.3882763419607405, + 0.3430404786021325, + 0.37405542758338794, + 0.2896425968439096, + 0.2352112702621877, + 0.170378999052676, + 0.24539621919341026, + 0.37316076380463803, + 0.2125850107121575, + 0.23224899536962978, + 0.23885682268201605, + 0.21144370490411873, + 0.3628671038098319, + 0.37588119528397745, + 0.3704105141145848, + 0.17003445400046577, + 0.271388051457265, + 0.37638865270911137, + 0.24023075176120529, + 0.39328521522257176, + 0.34643940049141264, + 0.3725343984170671, + 0.32835418398610744, + 0.3192924147167303, + 0.28326038985157875, + 0.1816734453712041, + 0.19140822921282694, + 0.26637709384036223, + 0.32207330942080103, + 0.30589253927941823, + 0.37301230806786095, + 0.385074287491154, + 0.2263732945153158, + 0.36818630815765907, + 0.2816365065840858, + 0.17073642961306681, + 0.21502978718529958, + 0.26900254729998735, + 0.17826506595999028, + 0.2849484883881833, + 0.23181801362256418, + 0.2304196059537571, + 0.20803141400457625, + 0.20062294222730145, + 0.21519290015852444, + 0.2705584831214727, + 0.3144407400250565, + 0.31830710582577093, + 0.1840264410478816, + 0.22053118702471736, + 0.22369493430698267, + 0.36806613828015766, + 0.3010830440976401, + 0.301451176877788, + 0.20764238600886015, + 0.3465646580036936, + 0.28911696968592526, + 0.25415361614565635, + 0.3286284754621054, + 0.2663246767023578, + 0.3599382389072395, + 0.29089642985543906, + 0.3690770760542755, + 0.2741336409637504, + 0.19703921662191878, + 0.20335521560541742, + 0.19837738084259104, + 0.23580592736413297, + 0.34723227644801474, + 0.3746933743750608, + 0.38875179074226385, + 0.29040824578700686, + 0.1865919377620024, + 0.19104174678092434, + 0.37207111384147684, + 0.3641310062775547, + 0.3391963194954718, + 0.3704130182959281, + 0.193782230667305, + 0.313588474861396, + 0.3479167226785573, + 0.17555440957766158, + 0.20334249339750482, + 0.355468561043164, + 0.23957600514194777, + 0.25805410966460635, + 0.25453581866345587, + 0.2653028301370304, + 0.25368124556374627, + 0.3782368898640174, + 0.26437315607556117, + 0.37742036846195215, + 0.26857782860462864, + 0.3405380277215486, + 0.22003142231936823, + 0.1592155579175818, + 0.3541609649398424, + 0.27015685192170413, + 0.3285261352909373, + 0.20121037341455975, + 0.29420187590505276, + 0.1664064478695242, + 0.17228355468562825, + 0.389875310577679, + 0.20686821607531689, + 0.17037360687342937, + 0.3655972585418462, + 0.2300805485373279, + 0.36998379000064385, + 0.2541907325732535, + 0.2527893166374862, + 0.2798844118508946, + 0.3088947648582812, + 0.3521439267261686, + 0.21044813937803694, + 0.3771991619787589, + 0.3125347677367255, + 0.2436220688183014, + 0.19949919108637515, + 0.2304999796422208, + 0.2651011258222328, + 0.15718740035476583, + 0.3301287003660017, + 0.24958303923305586, + 0.23143970528638674, + 0.22480990717991953, + 0.20907613720025545, + 0.2942097927090582, + 0.19089338604411787, + 0.18657545948403526, + 0.3279907405020684, + 0.2828899624332115, + 0.19069326373123058, + 0.21725806680938003, + 0.2745232335555635, + 0.39082054935565136, + 0.27871117223118325, + 0.379329929219053, + 0.22224212942289243, + 0.284956558449036, + 0.3052092860661287, + 0.31003410071037596, + 0.22960477752269493, + 0.33845598582090086, + 0.2961425820463282, + 0.34627680985354875, + 0.3195865807852054, + 0.27605456085152724, + 0.22966044202275743, + 0.27622090138865146, + 0.23634996924171398, + 0.3340512670477269, + 0.3359352792857967, + 0.379713941370324, + 0.17978757919925673, + 0.25437965799070106, + 0.3824345423496744, + 0.20346894729324205, + 0.3040072402892524, + 0.30826571818330806, + 0.15811285087710764, + 0.3100590153045748, + 0.33057154493147956, + 0.30571363583450395, + 0.1894150565021394, + 0.25570674064165055, + 0.3932052934319098, + 0.31816725178122607, + 0.2005355644254816, + 0.26259215518073714, + 0.254419161038164, + 0.1925951863944049, + 0.36285591992584465, + 0.24614383655709376, + 0.2870345767775095, + 0.3452059852701833, + 0.25317457011795097, + 0.16438166169515359, + 0.24877414951823495, + 0.22538865867702743, + 0.18256376323241133, + 0.2788148720113431, + 0.31127443894036133, + 0.2981110080777961, + 0.250441056876246, + 0.2785252755409212, + 0.29008184844578744, + 0.17878922179466378, + 0.33865239636904043, + 0.18276509246557918, + 0.2979977557118002, + 0.35344284172495377, + 0.33842265430923163, + 0.359839261168328, + 0.32299893324971374, + 0.22382067113692783, + 0.3270112379866804, + 0.26804011782833104, + 0.3220454566255234, + 0.25644935017059267, + 0.3785096016103846, + 0.28510505479328946, + 0.2892185440566253, + 0.2736093880856945, + 0.26523948173760975, + 0.3137283352020904, + 0.2725189388899371, + 0.32796225810971624, + 0.38747303487856755, + 0.18592523980802783, + 0.37927873259934597, + 0.2859392500380301, + 0.30946405912404007, + 0.25965034382395513, + 0.29696996841461676, + 0.34728696266323694, + 0.3085384327962726, + 0.18571545487167987, + 0.29705082879205746, + 0.30482174577876286, + 0.26139791505978166, + 0.3777876811851625, + 0.3710650328913231, + 0.3649982470169111, + 0.3581941809719973, + 0.2303511072443371, + 0.1776536522625104, + 0.25825459982925403, + 0.15656877524560808, + 0.3838580620530663, + 0.15874833107191055, + 0.27902499634721306, + 0.3735870616322402, + 0.24906224777247715, + 0.3239354142693379, + 0.36344101282298713, + 0.31968431272224795, + 0.33951898392656354, + 0.3252813686850425, + 0.360147925184108, + 0.37469405452268373, + 0.23655208658653648, + 0.20157250015471587, + 0.3336845653786896, + 0.28767334851822857, + 0.3215780506971929, + 0.1631659974145519, + 0.28767002425986177, + 0.2152672517523564, + 0.3167799943976801, + 0.25732849529210583, + 0.3158322292857916, + 0.2286037098242375, + 0.18661783509329327, + 0.3147387978312024, + 0.3750757931835097, + 0.38343770272356503, + 0.37602027862185083, + 0.20634978085441472, + 0.23922799502623016, + 0.2255843996348758, + 0.16923413167844836, + 0.23542539307648988, + 0.21991297299240656, + 0.3005338876910365, + 0.18224866340983992, + 0.21105976437088284, + 0.2232189090240817, + 0.18983404907135307, + 0.1958968812928035, + 0.21288666465038797, + 0.3511527150610361, + 0.35198637100329655, + 0.3356726881935821, + 0.16984980821642817, + 0.1964059273528382, + 0.3310014193252063, + 0.2311543268050768, + 0.27006792716515626, + 0.23349225817106176, + 0.31895720483428974, + 0.21888401280569658, + 0.3727424545064526, + 0.38140343761376616, + 0.16802895573859522, + 0.388765755396952, + 0.37557312177929403, + 0.20723056065693723, + 0.16485524932146284, + 0.22925796032879897, + 0.2521901490691041, + 0.27153923218237025, + 0.3184673087347672, + 0.3450849029312454, + 0.2742950574456645, + 0.24506392886551098, + 0.3802758109332706, + 0.2247872909696365, + 0.2376724287872992, + 0.26181997309435534, + 0.2218035135856906, + 0.26328724649358437, + 0.17519346795410973, + 0.35847390914937427, + 0.31738375526149565, + 0.2895865092441895, + 0.23817376153362324, + 0.3362028516886514, + 0.3294816277872139, + 0.34641462918433136, + 0.24832366421482044, + 0.25374208963203637, + 0.19744223505908892, + 0.18224290207525573, + 0.18651987369400644, + 0.3865652566166972, + 0.17213180260552968, + 0.21381169773308406, + 0.2856069589156788, + 0.38803871889640934, + 0.2531408068331046, + 0.26692811418487994, + 0.17494838436504223, + 0.24093865527575542, + 0.3464489425503643, + 0.2432025494205251, + 0.19888713806341024, + 0.33725033625574663, + 0.22630540600863452, + 0.23698060796070003, + 0.29046232002962635, + 0.2934653191156421, + 0.24398479063094483, + 0.1745117934097369, + 0.17641453651394082, + 0.35705357788754144, + 0.2076936742948161, + 0.22412279504563046, + 0.3335759562025601, + 0.26993255893240325, + 0.23077206200911665, + 0.279765310111331, + 0.31438022162877344, + 0.35566541652837713, + 0.19673463167811528, + 0.3854675787294153, + 0.26036088754365927, + 0.17652554100343684, + 0.22676194317184348, + 0.2402072514992675, + 0.17814168354631366, + 0.33657161702884875, + 0.32697320055580925, + 0.28178616574679194, + 0.34037783276984945, + 0.15911624742065572, + 0.25777238802209024, + 0.30430483033254696, + 0.20644232897452414, + 0.17629242786920554, + 0.39156844164260596, + 0.1642823264469592, + 0.2769163591887524, + 0.3233416715260856, + 0.22597004113169938, + 0.38481346756009743, + 0.31381392185058465, + 0.3398586522361003, + 0.3463380088577016, + 0.21356530186645503, + 0.18955651402396642, + 0.32329610271633585, + 0.19433310922472202, + 0.31917053400543516, + 0.199401819729036, + 0.16798370784128488, + 0.15639604736671028, + 0.20587644069940528, + 0.2869198364304095, + 0.20479840136463442, + 0.3186025648698917, + 0.31458285693586097, + 0.3167988587479358, + 0.28713933660594093, + 0.2114648201484754, + 0.1603806363548241, + 0.21261166162314524, + 0.3244280751543127, + 0.3048895346884136, + 0.2784556741259043, + 0.2664344567653042, + 0.3678068818813332, + 0.3720500696495974, + 0.28699245876214685, + 0.2900213826728949, + 0.21554205286610453, + 0.23389840493771777, + 0.20883901567446356, + 0.3025487497834819, + 0.1876082421861702, + 0.22325054144743472, + 0.37437087651657774, + 0.37334795742367427, + 0.2735068274617135, + 0.3147978041987528, + 0.16774060880700448, + 0.213259956244228, + 0.17049781336352457, + 0.1633504208398174, + 0.3266132432649767, + 0.27075179354911616, + 0.36468168620122765, + 0.3516386375778773, + 0.3468426203395791, + 0.2982120755460387, + 0.2485173102851445, + 0.3541010674793308, + 0.3349179208213854, + 0.2316788684140731, + 0.2583389780749155, + 0.19644046898098497, + 0.21860631943250147, + 0.25315028284158514, + 0.30984454491544056, + 0.3051549380915863, + 0.3352367858151897, + 0.38670436468866143, + 0.22679189572777414, + 0.2776134341184557, + 0.30246843487541347, + 0.3261702367689988, + 0.3028984911347414, + 0.3293226015176785, + 0.1931798220763927, + 0.15854880961191478, + 0.2507406845007908, + 0.17143350513649314, + 0.31578670950995164, + 0.3448515550418757, + 0.29312028345851815, + 0.3751253025957897, + 0.1980325167634979, + 0.3721216749693601, + 0.21814151789919545, + 0.33035161614835695, + 0.1926331615790714, + 0.2515182134769442, + 0.2939096675855349, + 0.2991930488752858, + 0.160510986166676, + 0.31795783654704834, + 0.21074576638095732, + 0.2109509649891753, + 0.28701723818836267, + 0.19475446067227317, + 0.1793146975640941, + 0.27038727083594905, + 0.3543488235950061, + 0.2768790488015917, + 0.3262008029198388, + 0.38483834751585994, + 0.21882104041784162, + 0.19941226801323808, + 0.2459620289398806, + 0.25175077613634145, + 0.19362031826949105, + 0.2676998838272542, + 0.386585797843764, + 0.21657782508738302, + 0.2676171489448056, + 0.44947490995162537, + 0.5591609090068997, + 0.4512251161594112, + 0.6022668572687648, + 0.6289064238276637, + 0.40142989995633416, + 0.5696256042021006, + 0.6823571279410912, + 0.6161741749957503, + 0.6971485342601813, + 0.6312644394987591, + 0.4695021747311386, + 0.49189078991531027, + 0.5819625216175495, + 0.4726411322518219, + 0.40186875224321406, + 0.5335369011553159, + 0.6614419455797806, + 0.3991516135304827, + 0.5346948765745851, + 0.5478781826736647, + 0.6604940635259289, + 0.565575667380855, + 0.5842895267660978, + 0.6891093261442647, + 0.4560370214311059, + 0.4071470217114493, + 0.7097517299246855, + 0.440287176821705, + 0.668839978071039, + 0.5276898057962057, + 0.6867605133095795, + 0.5327093962037635, + 0.5554201691004736, + 0.41140491172014054, + 0.6182976177526252, + 0.5918801472606847, + 0.5365972464636941, + 0.4736186175127586, + 0.4839711727550435, + 0.6834844918395795, + 0.5705893109502786, + 0.4634260639211208, + 0.6821082706781397, + 0.5772222758766763, + 0.5508860761419743, + 0.5272830210125103, + 0.44334901872493915, + 0.5908179498534823, + 0.49326058018419067, + 0.42742484494223276, + 0.6894273870201801, + 0.6615200749698107, + 0.5677245505800758, + 0.5797376827072456, + 0.6810576341854881, + 0.6638765286103255, + 0.6629283890563611, + 0.45286014034125743, + 0.4322948039406841, + 0.7029567433555095, + 0.48806516996010707, + 0.6497598426237665, + 0.5561856171789313, + 0.42190359783440645, + 0.7134227645178497, + 0.4120504957662863, + 0.6291763938209083, + 0.6801220406117044, + 0.4272823909559493, + 0.639030312182473, + 0.5001545616121468, + 0.42418604274725286, + 0.42467341290990657, + 0.7156505118188439, + 0.40430726596841965, + 0.7079955659219375, + 0.42323136908612, + 0.5007637995841799, + 0.5060786132249315, + 0.3984194722541386, + 0.5317350365584397, + 0.504321534389612, + 0.5775251508887682, + 0.6013911463582547, + 0.4529199230221624, + 0.4589297217728195, + 0.4133809199137971, + 0.6256442215965026, + 0.4761954544083511, + 0.5858029253655195, + 0.4413783470095903, + 0.6208500178017827, + 0.6456836104205455, + 0.6813235549737258, + 0.6262714416708633, + 0.5340213479226078, + 0.5852211175279595, + 0.6868323973458574, + 0.4693561086696458, + 0.439494770332283, + 0.4540854882000879, + 0.5208807939681952, + 0.5177766268849695, + 0.7146602030053812, + 0.6752661658715393, + 0.5029316470818178, + 0.6148870893143848, + 0.3964672590923258, + 0.5173094382255445, + 0.5451642352187374, + 0.5537180142893531, + 0.486785558758239, + 0.4774270636440513, + 0.5803828481307851, + 0.45353306487716194, + 0.49080039756660204, + 0.41028751459297663, + 0.6221534559515846, + 0.6196171281679431, + 0.5938007968568193, + 0.6841109232152008, + 0.4316482733907302, + 0.5143138017009365, + 0.6810128339201258, + 0.6231381029718905, + 0.40249938838480304, + 0.4666016279286467, + 0.6066667375342083, + 0.6451527899120342, + 0.4586943199085084, + 0.502273971541784, + 0.7073321904767944, + 0.6695317139266806, + 0.6474071579493014, + 0.4349465716271802, + 0.6057546762224839, + 0.4401722075596667, + 0.4046559402444609, + 0.5339365119950445, + 0.5035856869909587, + 0.4178003833690501, + 0.4514142965792603, + 0.6958885739980261, + 0.6459519578120111, + 0.49647988745392424, + 0.4314922806842084, + 0.43725876312470435, + 0.4820706779535406, + 0.5929763021471892, + 0.7094813189599081, + 0.6097609977143543, + 0.6156707852293652, + 0.6292867256774927, + 0.5258998754071731, + 0.7011115093973981, + 0.6412738937232755, + 0.4468872531978568, + 0.48637679865448336, + 0.5242908122849039, + 0.5169367676915242, + 0.6327657436107508, + 0.6860580717945381, + 0.4130869824980044, + 0.46421892353214067, + 0.5122340792846338, + 0.5651105459294855, + 0.5467828623960378, + 0.46114250852395033, + 0.49416736973101794, + 0.5493934563887548, + 0.6599963916687159, + 0.4233038462483555, + 0.4618611791973517, + 0.45757412593382024, + 0.619585084062036, + 0.5209058712957351, + 0.7064061975121935, + 0.4818838874028891, + 0.4691890953528288, + 0.41049222258268886, + 0.5518594118538349, + 0.46148637397980874, + 0.6848209099746994, + 0.43127535099409564, + 0.7087857449507365, + 0.5180619286772945, + 0.5500902937780852, + 0.6477160115201758, + 0.5639255430931001, + 0.46621972532988076, + 0.6528057326286821, + 0.47800922244967214, + 0.6310369227981549, + 0.4512976203787316, + 0.43632149095380085, + 0.4275687772091572, + 0.6214699340639009, + 0.42993475007706466, + 0.5465141877983528, + 0.5806573405895895, + 0.617853868810441, + 0.529565611308054, + 0.5099644572505408, + 0.6201217047240281, + 0.6118275713955594, + 0.6915908513328297, + 0.44246291370401414, + 0.7075589513850595, + 0.5790291126162145, + 0.5400585295307696, + 0.6638989854664977, + 0.6018266088661488, + 0.710534881512412, + 0.6977184025600696, + 0.5930889183755229, + 0.5806871975700987, + 0.5458616189536665, + 0.5466648095508845, + 0.6487039081463881, + 0.6745893722594508, + 0.7022136081632885, + 0.40414995792160524, + 0.5097890729643131, + 0.5699896856747952, + 0.47951250563740144, + 0.4394409638181534, + 0.4202057320800722, + 0.5473899817175893, + 0.6975058334615472, + 0.7070470395289747, + 0.6175650275875317, + 0.5988684084385467, + 0.5207615408152834, + 0.5936074937695042, + 0.5204933197950735, + 0.4450726348045054, + 0.513742366791507, + 0.4463927336726016, + 0.7106461944245717, + 0.6666714464924917, + 0.49100111389455803, + 0.5857529411954137, + 0.5574157993904207, + 0.5376993150876198, + 0.6318084229082579, + 0.6724122842909428, + 0.43999461936634143, + 0.6096532858885285, + 0.5940872569011817, + 0.584926845297876, + 0.5489903189363265, + 0.6630869545390332, + 0.6300601077639902, + 0.7054685549036126, + 0.6021802794103465, + 0.454306374409995, + 0.5385161112719692, + 0.442851227344632, + 0.4949328344771222, + 0.6669965420309734, + 0.5226104484745957, + 0.5874435499212234, + 0.42304741807330176, + 0.5870818540038869, + 0.5720214007666715, + 0.7157718209230017, + 0.5306431935340286, + 0.4591219234221998, + 0.6132218846525878, + 0.6499388856085813, + 0.4217152617364599, + 0.5677521948824005, + 0.6455086420578564, + 0.629872648152794, + 0.6257455578146016, + 0.5054893714539292, + 0.6864986530237951, + 0.581644297084422, + 0.6077451242385874, + 0.5744534172452361, + 0.6990538909652502, + 0.5112043443979075, + 0.45739927962572174, + 0.5133459299901999, + 0.6820496425477098, + 0.5002482555756131, + 0.558000910958212, + 0.5936534060349853, + 0.43796882943094484, + 0.4352986646174859, + 0.6505568052596136, + 0.6428723804802239, + 0.550881659307026, + 0.5487687486322455, + 0.4977844226021937, + 0.6811339421955918, + 0.49371522834299375, + 0.5221764662010286, + 0.5240207110840116, + 0.39810556815079606, + 0.5263153484142609, + 0.5415564866162389, + 0.45154377818072483, + 0.4708169766001077, + 0.4971009439975731, + 0.4153751129612154, + 0.6724445600510189, + 0.4067099643607768, + 0.666107940509429, + 0.43155785715427813, + 0.4039590655415924, + 0.6998930022168117, + 0.5401708515529049, + 0.636152940593175, + 0.7133112442164784, + 0.531303819340117, + 0.591874212290335, + 0.6936865419105636, + 0.7014424980719549, + 0.39693420521526174, + 0.48568752838870294, + 0.42849941420729715, + 0.6015751879281552, + 0.6722468491923429, + 0.5568312014553103, + 0.6870506717774534, + 0.561264843810348, + 0.4089680322761353, + 0.5579955027321857, + 0.5298013059067621, + 0.5574656615622855, + 0.6713436242627624, + 0.47746375643337924, + 0.4103826656251715, + 0.4548327619944813, + 0.4130824207462302, + 0.5082341872317329, + 0.5758695147868413, + 0.566516679654997, + 0.6002950020913164, + 0.7099348697283616, + 0.580108521689847, + 0.5978281874064648, + 0.42853152349639956, + 0.5542353166119592, + 0.6580019807282187, + 0.6545492028504538, + 0.4312279372843846, + 0.41971902376805387, + 0.4774697529252618, + 0.5449494416978136, + 0.45419216805801077, + 0.48408834436167375, + 0.4617755752183541, + 0.5396234006943657, + 0.6765757336859182, + 0.40482918583776456, + 0.4525025671728369, + 0.6047668348987515, + 0.6717759475926002, + 0.4823478316686448, + 0.45493871790270374, + 0.5503619528526246, + 0.4064189828908995, + 0.49463311694058515, + 0.5911830869580648, + 0.6413702377880045, + 0.6566160590444658, + 0.4072961022260736, + 0.6133008939304667, + 0.5969452761175253, + 0.4462181060379007, + 0.6670554257410131, + 0.7148346391001634, + 0.613884143470564, + 0.4143619867718291, + 0.6397626668303221, + 0.6777197365045213, + 0.6930594673754261, + 0.5395050432868512, + 0.4364620904346789, + 0.644167251511654, + 0.6437440474491639, + 0.6284831894986016, + 0.5649148398354297, + 0.3989574525375489, + 0.6276842644582152, + 0.48334837280106246, + 0.5984665658186303, + 0.6098352711744552, + 0.640968422874308, + 0.49470653731964964, + 0.5155980220495899, + 0.6447257585474435, + 0.5031490040470481, + 0.5241823291645659, + 0.6811553284594838, + 0.6122903850487436, + 0.5111634127267949, + 0.675526024743003, + 0.6877158999282644, + 0.5043252621169627, + 0.5441120116654827, + 0.5766138525694984, + 0.4324555264169152, + 0.7029157821823, + 0.6146880198250669, + 0.6095762824095943, + 0.454614557126627, + 0.4127452528353851, + 0.6293428071274054, + 0.40800069256150245, + 0.3976145912624218, + 0.6384093253004592, + 0.6624710341660924, + 0.5350926105572095, + 0.4408323103029471, + 0.6307870932898341, + 0.666509078016772, + 0.5087724734644257, + 0.5073209188015815, + 0.48223418786815136, + 0.668003809913837, + 0.500663191624142, + 0.48806500501703787, + 0.4858990130166929, + 0.6326159082877396, + 0.6961964042057878, + 0.410435888116119, + 0.4347320460465639, + 0.5940176583645058, + 0.6238091616564779, + 0.6926165202144736, + 0.6058732755859165, + 0.6515315673071016, + 0.4238537045349452, + 0.46454152056058506, + 0.47988623174615685, + 0.6027975819375568, + 0.4104223481979623, + 0.5143988388319829, + 0.4831743197439597, + 0.4980832309632889, + 0.617897554824377, + 0.39627262353974946, + 0.6224973351858507, + 0.40144716992323226, + 0.6673423612035114, + 0.6021243161793206, + 0.47648236131256294, + 0.7093440073230833, + 0.5704971175375045, + 0.5750745290180266, + 0.606339252115618, + 0.49195823378976034, + 0.5442597967203218, + 0.6774360731305322, + 0.509446038415213, + 0.46122539415670705, + 0.4277045995611829, + 0.4071871855047354, + 0.5924558632920638, + 0.4908539669013738, + 0.6927777037074769, + 0.45916372456492055, + 0.5687194114173424, + 0.43580394800788075, + 0.6739547252503704, + 0.6920218963592493, + 0.49286512083346756, + 0.4887422553545062, + 0.39887312222336174, + 0.4026138372739265, + 0.6963889315585156, + 0.397764499216326, + 0.5269556727677694, + 0.40978521073317226, + 0.5589017399284142, + 0.6947180272497799, + 0.5719391948197924, + 0.5546625797013365, + 0.4491765484891208, + 0.637972159365281 ], "type": "scatter" }, @@ -62369,69 +62304,47 @@ "mode": "markers", "name": "Expectation", "x": [ - 0.5159507647804554 + -4.375528139159007E-5 ], "y": [ - -0.3701098465795569 + -0.058325846627932804 ], "type": "scatter" }, { "fill": "toself", - "mode": "lines+markers", + "mode": "lines", "name": "Mode", "x": [ - 0.44, - 0.6633025782322575, - 0.6633025782322575, - 0.44, - 0.44, - null, - 0.44, - 0.6633025782322575, - 0.6633025782322575, - 0.44, - 0.44, - null + 0.4178483805738874, + 0.4178483805738874, + 0.6762126815500766, + 0.6762126815500766, + 0.4178483805738874 ], "y": [ - -0.697788532493164, - -0.697788532493164, - -0.66, - -0.66, - -0.697788532493164, - null, - -0.697788532493164, - -0.697788532493164, - -0.66, - -0.66, - -0.697788532493164, - null + 0.15624896603640903, + 0.393362968645088, + 0.393362968645088, + 0.15624896603640903, + 0.15624896603640903 ], "type": "scatter" } ], "layout": { "title": { - "text": "Marginal View of relative x and y position with respect to the milk" + "text": "JPT" }, "xaxis": { "title": { "text": "relative_x" - }, - "range": [ - -1, - 1 - ] + } }, "yaxis": { "title": { "text": "relative_y" - }, - "range": [ - -1, - 1 - ] + } }, "template": { "data": { @@ -63263,86 +63176,21022 @@ "plotlyServerURL": "https://plot.ly" } }, - "text/html": "
" + "text/html": "
" }, "metadata": {}, "output_type": "display_data" } ], "source": [ - "grounded_model = fpa.ground_model()\n", - "p_xy = grounded_model.marginal([relative_x, relative_y]).simplify()\n", + "p_xy = model.marginal([relative_x, relative_y])\n", "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", - "fig.update_layout(title=\"Marginal View of relative x and y position with respect to the milk\",\n", - " xaxis_range=[-1, 1], yaxis_range=[-1, 1])\n", "fig.show()" ], "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2024-03-13T13:17:36.011305Z", - "start_time": "2024-03-13T13:17:32.910505Z" + "end_time": "2024-03-21T13:49:00.755911Z", + "start_time": "2024-03-21T13:48:59.575756Z" } }, - "id": "a36ee203bb45f8b1", - "execution_count": 25 + "id": "78161f8e4a14782e", + "execution_count": 12 }, { "cell_type": "markdown", "source": [ - "Finally, we observe our improved plan in action." + "Let's look at the density of the relative x and y position of the robot with respect to the milk. We can see that he would like to access the object from the right front area." ], "metadata": { "collapsed": false }, - "id": "bd4fd2fa3d469c8c" - }, - { - "cell_type": "code", - "outputs": [], - "source": [ - "from pycram.designators.actions.actions import ParkArmsActionPerformable\n", - "\n", - "world.reset_bullet_world()\n", - "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", - "with simulated_robot:\n", - " \n", - " MoveTorsoActionPerformable(0.3).perform()\n", - " for sample in fpa:\n", - " try:\n", - " ParkArmsActionPerformable(Arms.BOTH).perform()\n", - " sample.perform()\n", - " break\n", - " except PlanFailure as e:\n", - " time.sleep(0.1)\n", - " continue" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-13T13:17:56.209834Z", - "start_time": "2024-03-13T13:17:38.934340Z" - } - }, - "id": "ea57ad24b398e28f", - "execution_count": 26 + "id": "eaaf99db302255e0" }, { "cell_type": "code", - "outputs": [], - "source": [ - "# world.exit()\n", - "# viz_marker_publisher._stop_publishing()" - ], - "metadata": { - "collapsed": false, - "ExecuteTime": { - "end_time": "2024-03-13T13:15:50.287095Z", - "start_time": "2024-03-13T13:15:50.285792Z" - } - }, - "id": "62728fa8ed6e55bd", - "execution_count": 14 + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "data": [ + { + "hovertext": [ + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 0.7111846762867592", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 1.5599843084222236", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.2841215840198554", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.3196950565297552", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.2841215840198554", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.3196950565297552", + "Likelihood: 1.3196950565297552", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.2841215840198554", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.2841215840198554", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.2841215840198554", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.3196950565297552", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.2841215840198554", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 0.7111846762867594", + "Likelihood: 0.7111846762867594", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 0.7111846762867594", + "Likelihood: 2.1006911556372625", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.3196950565297552", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 4.30291638024209", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 1.5599843084222238", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 2.2841215840198554", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 4.30291638024209", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625", + "Likelihood: 1.389506479350503", + "Likelihood: 2.1006911556372625", + "Likelihood: 2.1006911556372625" + ], + "marker": { + "color": [ + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 0.7111846762867592, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 1.5599843084222236, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 2.2841215840198554, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.3196950565297552, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.2841215840198554, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.3196950565297552, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 0.7111846762867594, + 1.3196950565297552, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.3196950565297552, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 2.2841215840198554, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 2.2841215840198554, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.2841215840198554, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.3196950565297552, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 2.2841215840198554, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 1.3196950565297552, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.2841215840198554, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.3196950565297552, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.3196950565297552, + 1.3196950565297552, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.3196950565297552, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 1.3196950565297552, + 1.3196950565297552, + 1.3196950565297552, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 2.2841215840198554, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 2.2841215840198554, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.2841215840198554, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 1.3196950565297552, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 2.2841215840198554, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.3196950565297552, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 2.2841215840198554, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.3196950565297552, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 2.2841215840198554, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 2.2841215840198554, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 2.1006911556372625, + 1.5599843084222238, + 2.2841215840198554, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 0.7111846762867594, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 0.7111846762867594, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 2.1006911556372625, + 2.1006911556372625, + 4.30291638024209, + 1.5599843084222238, + 1.3196950565297552, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 0.7111846762867594, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 2.2841215840198554, + 1.3196950565297552, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 0.7111846762867594, + 1.5599843084222238, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 2.1006911556372625, + 1.5599843084222238, + 0.7111846762867594, + 0.7111846762867594, + 4.30291638024209, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 4.30291638024209, + 0.7111846762867594, + 2.1006911556372625, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.2841215840198554, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.3196950565297552, + 2.1006911556372625, + 1.5599843084222238, + 4.30291638024209, + 2.1006911556372625, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 1.5599843084222238, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 2.2841215840198554, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 4.30291638024209, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625, + 1.389506479350503, + 2.1006911556372625, + 2.1006911556372625 + ] + }, + "mode": "markers", + "name": "Samples", + "x": [ + 0.6283796051478613, + 0.4733941091531527, + 0.304361377162602, + 0.36284938416969975, + 0.6192935890618187, + 0.60569568825769, + 0.46209790585296506, + 0.4949180298869439, + 0.6082241880992127, + 0.6238732508162596, + 0.672419060525532, + 0.5015495966798355, + 0.489947673645203, + 0.5492221697091524, + 0.3342703944183883, + 0.447428846314081, + 0.5518460984334048, + 0.3762043560058192, + 0.38631403755468446, + 0.5731636866909333, + 0.6064380749373501, + 0.5581377601291668, + 0.34301083313043607, + 0.4041324880582714, + 0.46561065509360255, + 0.6607704969526416, + 0.5360423734844382, + 0.4396901444838215, + 0.3342659204991326, + 0.4508799168259236, + 0.7267501358565729, + 0.5774155344797809, + 0.4802995783278318, + 0.6259046039930717, + 0.5509234830387231, + 0.5979993309410865, + 0.3837501194179711, + 0.47724999649198996, + 0.5217503468772747, + 0.5911001664796485, + 0.7241855400914489, + 0.37652717615879083, + 0.6269403586596356, + 0.5190834700749936, + 0.7227155040316005, + 0.6980411624967708, + 0.6427659094601246, + 0.39129194192301037, + 0.6110548782975422, + 0.3578221939924544, + 0.5593612538329051, + 0.4242497680912969, + 0.33850502580537883, + 0.6624764140650907, + 0.5655498575234894, + 0.3513137342537306, + 0.5085605551150013, + 0.6795004868407264, + 0.7021650682569843, + 0.5464262028130219, + 0.3659137794140434, + 0.3035437484499797, + 0.621384755232, + 0.7127270505757348, + 0.5651482743737656, + 0.7172958782692103, + 0.4142258940645192, + 0.6283486257077753, + 0.5238753668814327, + 0.5224017091836275, + 0.654498842944883, + 0.31295824876444706, + 0.7032865644494084, + 0.5281808732843437, + 0.48237193543067824, + 0.5707346770253106, + 0.40073765327089156, + 0.5540192954764896, + 0.32424110743165807, + 0.6766238307374881, + 0.3552251801945203, + 0.5260888280230741, + 0.6003375145624322, + 0.31877983684677236, + 0.4849292440295056, + 0.500861419308714, + 0.6618628201514674, + 0.6245222795406817, + 0.3123254397986413, + 0.4460377450601758, + 0.32696165476038197, + 0.697428491997524, + 0.529329277241698, + 0.7158733454945663, + 0.47633915643367997, + 0.5416173216581522, + 0.5233908056901426, + 0.3203996744550525, + 0.3801845695589516, + 0.6670287839403085, + 0.3132663532849949, + 0.5955014052813781, + 0.4714887925132052, + 0.3275115131512901, + 0.6415961989581219, + 0.3148918732168174, + 0.35950163197893903, + 0.5400825294091965, + 0.5409142823337219, + 0.510884620356082, + 0.40843494021431215, + 0.6170885039370684, + 0.3184088588382493, + 0.34549853802720587, + 0.5009104270382855, + 0.630314078109385, + 0.5797826573171031, + 0.5981062464628402, + 0.7192849232273155, + 0.7048041011396435, + 0.6526676271347946, + 0.32480658725867756, + 0.6465195069131373, + 0.4287674544120826, + 0.5273009545488178, + 0.4131261688779221, + 0.5961979593463775, + 0.5977206271695695, + 0.6379850363365573, + 0.6510702071219862, + 0.3899024901566016, + 0.5903523026509128, + 0.5267174672574283, + 0.5025120386997262, + 0.4810441994654623, + 0.6535007580572905, + 0.358192775590812, + 0.5174375012912954, + 0.46296430725722476, + 0.5554631238623899, + 0.6419914456946771, + 0.38463659724407784, + 0.5914033397518752, + 0.44812267790590393, + 0.49089156494998054, + 0.4185962716569772, + 0.4229205330398457, + 0.4623104362414824, + 0.3424233609076441, + 0.3339719360703627, + 0.6902291092064361, + 0.7021906294431108, + 0.31361578139190127, + 0.5468603954558365, + 0.40880690638251915, + 0.4588205901853545, + 0.505964213088147, + 0.4236511205665603, + 0.37495689167758006, + 0.3040047769720844, + 0.6311074299729487, + 0.7065956391240829, + 0.44584395163192914, + 0.306491629355991, + 0.7260294224247383, + 0.5383033820125867, + 0.6870078685876879, + 0.5099232704826162, + 0.5492410510803237, + 0.7270461091493341, + 0.6867594129775483, + 0.6445230430876836, + 0.6059327796605836, + 0.47900075321983054, + 0.6763662997777012, + 0.38160731808943543, + 0.3407477501223138, + 0.5594795229003933, + 0.40432473180131945, + 0.5419093614808759, + 0.6122666351974309, + 0.6969620543382329, + 0.5233198963800162, + 0.6770887490764189, + 0.563653773728354, + 0.5743622918856718, + 0.6816575519919552, + 0.5661830051289992, + 0.5679186190078296, + 0.6109985479745175, + 0.5534668006831678, + 0.31139630606287005, + 0.5885885434050432, + 0.4532673389629965, + 0.3645037461398636, + 0.3973278943523142, + 0.354530449093353, + 0.4747795182905353, + 0.6213517101286439, + 0.5267572842853802, + 0.5276500210009093, + 0.49832823987881425, + 0.5190553606893737, + 0.633874032599939, + 0.4602054346676733, + 0.6500319677259623, + 0.6619274965491957, + 0.40922291501520885, + 0.5656487570348294, + 0.5150732906585561, + 0.6297927495272928, + 0.5038430739457092, + 0.7241831836769697, + 0.32259587532130823, + 0.6029698595052331, + 0.41247081235211625, + 0.689422326422999, + 0.32380105199830156, + 0.42917246007924026, + 0.5046409001510277, + 0.7221649175887925, + 0.6833312627852342, + 0.6653609053091462, + 0.3462606623135728, + 0.4229378690434816, + 0.38551270869930254, + 0.6262746513793682, + 0.4176376980973968, + 0.5599410522484581, + 0.39122592680267415, + 0.5208435463642249, + 0.604142496269586, + 0.4823654311142736, + 0.32615067922989005, + 0.45844687093758496, + 0.6970015859807508, + 0.43966400842521774, + 0.5606086507572204, + 0.4306204768619101, + 0.6297983391676569, + 0.7060330985251653, + 0.5497512038674017, + 0.4379363786805115, + 0.6919095195926468, + 0.4398408120373566, + 0.34107310109250133, + 0.4710481718033095, + 0.6902624528623372, + 0.47149238191054677, + 0.7073712325045667, + 0.41007785279872205, + 0.6813771015130272, + 0.689156090640948, + 0.42444101075788304, + 0.3983902751758033, + 0.33133242086105663, + 0.43143489164464144, + 0.6603533137811184, + 0.3971827866512632, + 0.6884596397822573, + 0.3386128177610371, + 0.46633874072655535, + 0.3039530018038552, + 0.701683403292688, + 0.5119862644623705, + 0.5868539398870433, + 0.6661159422506897, + 0.3573903959782653, + 0.7236631093973747, + 0.3956232717829736, + 0.320391818473174, + 0.6674961608973242, + 0.36061856188095703, + 0.6980586756494421, + 0.7073654337447988, + 0.4876723572953149, + 0.3709356370654626, + 0.7144926539367294, + 0.6298249030036835, + 0.5682918041701379, + 0.6355509607890755, + 0.6007885572961679, + 0.520014578282243, + 0.4359298474375825, + 0.4566018956651901, + 0.467933063816996, + 0.6029959785228813, + 0.3234403383640688, + 0.4984592116233576, + 0.4254974782247243, + 0.3895032329263608, + 0.46261420747622917, + 0.417954500372443, + 0.5267979380626389, + 0.6185754300952171, + 0.7028395941568784, + 0.5601627793712287, + 0.5106977430017323, + 0.6061639107185534, + 0.40583301205118316, + 0.4877842654212847, + 0.3560924542784373, + 0.6505160542896489, + 0.6612727587409887, + 0.5577267848008154, + 0.44967862148681065, + 0.6499736804413174, + 0.4646792575596459, + 0.30665928292734, + 0.3051754984588699, + 0.34005416341775413, + 0.421918406262349, + 0.371580524378551, + 0.3087258645363744, + 0.45703796625085436, + 0.5632576230548111, + 0.5342318981535477, + 0.3915610853056041, + 0.5905756545770827, + 0.5709043622195802, + 0.5297699866169563, + 0.7192767445297887, + 0.39645957008013316, + 0.6589632086708673, + 0.638629610430095, + 0.5903277817912345, + 0.4650966357709906, + 0.5173483048558812, + 0.4562587239080659, + 0.6702573061262282, + 0.505230432269204, + 0.5420268768709828, + 0.35210358755474286, + 0.49250246186480595, + 0.6048799065601089, + 0.6354850865697617, + 0.35630162812176314, + 0.7140168541260483, + 0.35663897352621016, + 0.3686061423197887, + 0.30497686179145655, + 0.45455480714795604, + 0.36871758658091336, + 0.4156997632776323, + 0.4183593735188326, + 0.6640053258897827, + 0.5086446960615851, + 0.6247755246246731, + 0.5411817779685021, + 0.4842300300338286, + 0.4606548163786671, + 0.5186913574109123, + 0.6192151655498841, + 0.5589808035215549, + 0.5622196328426435, + 0.5839507122576795, + 0.4376236695976157, + 0.578691275629837, + 0.4659718970927792, + 0.6184663738987715, + 0.5113988607038276, + 0.5445328079384409, + 0.6541140035045494, + 0.7262085982391857, + 0.6013049240009737, + 0.6082525469263866, + 0.508164542825417, + 0.46319604226440547, + 0.5260510279355417, + 0.48813195110547797, + 0.6200477024377651, + 0.32552257841431137, + 0.5887528410252281, + 0.6188650700926779, + 0.5844499758285964, + 0.724048238456035, + 0.4800421633146098, + 0.6089187052534117, + 0.3580051561467969, + 0.40853572095261526, + 0.4046707270656579, + 0.5177442029027796, + 0.5959445012916478, + 0.6321499436951448, + 0.5989908162398548, + 0.6837116545572856, + 0.4444290096851937, + 0.6149310867222517, + 0.30341107667805556, + 0.6838873138587567, + 0.6084286328176265, + 0.3682399511833895, + 0.4873082951423991, + 0.5140686109874819, + 0.5208507968162873, + 0.6332222577400335, + 0.5001339790109951, + 0.4101682379161794, + 0.38078020844088856, + 0.48346909663921644, + 0.33985859961729326, + 0.4077065571453853, + 0.5827474891208355, + 0.3577831357027577, + 0.7031409499389227, + 0.417443966312144, + 0.45521563878147575, + 0.41021513003009263, + 0.6004149207157532, + 0.6259454060416844, + 0.3645468210854622, + 0.36647900283328966, + 0.6898774221881663, + 0.4360544870007585, + 0.5017465870520186, + 0.5431177629605345, + 0.3030022800568823, + 0.5433895632745123, + 0.6949559492369004, + 0.572761882302244, + 0.35174763183801716, + 0.4358395579885442, + 0.33382431781918365, + 0.4236842800372269, + 0.5400348174179141, + 0.6073159886609243, + 0.49937804108002154, + 0.43703930625379306, + 0.4344502031515486, + 0.5030837354952916, + 0.44390687067117873, + 0.6312690527690877, + 0.3917912731311066, + 0.5820204768759425, + 0.6916000307909508, + 0.6554477404885675, + 0.561326404492038, + 0.48139690057563755, + 0.336987414314844, + 0.5006062557629332, + 0.4444737552600778, + 0.3329381016070724, + 0.5744941407795525, + 0.4943775855306687, + 0.6992931176663637, + 0.5026161378511266, + 0.6743801994163671, + 0.35898038030334445, + 0.3565514394996119, + 0.44631411899327356, + 0.3845640879270406, + 0.3351108592510633, + 0.6532378860393817, + 0.4371828490016898, + 0.4034925795124067, + 0.3674503702153532, + 0.3044280002060322, + 0.4218703606193476, + 0.5042449308690269, + 0.38564211027068523, + 0.6558231022903257, + 0.5560126680683741, + 0.3352563215537477, + 0.7205491524755758, + 0.3579527523957865, + 0.5766608857157854, + 0.4158760254905389, + 0.7254828660798414, + 0.4377450125978234, + 0.553865788554406, + 0.6026799653098628, + 0.44672772822227913, + 0.4299125919597402, + 0.44943594473254933, + 0.4058202081865294, + 0.4980013422999515, + 0.35004260221750827, + 0.6348704204681872, + 0.5392634171384282, + 0.36034790793798627, + 0.41754363792613725, + 0.5216591391302169, + 0.5558609441838249, + 0.3569756107502839, + 0.5939250351319384, + 0.41141581058398125, + 0.47878178628399803, + 0.4834364542683392, + 0.39697356309862997, + 0.47046464413206107, + 0.3113260758050484, + 0.5536538265483462, + 0.4709846143200984, + 0.5260336421209957, + 0.6267790156950703, + 0.6756082147044937, + 0.4588761067107302, + 0.6536603788145247, + 0.5075285332008663, + 0.34725463008416624, + 0.5886846022727898, + 0.6665305528531992, + 0.5408489554283811, + 0.6770047129425629, + 0.6759393508818384, + 0.3764886077840023, + 0.5455512400140748, + 0.3893455917648779, + 0.7183185846984927, + 0.4489341405107281, + 0.43152601611163915, + 0.3708401018804384, + 0.6971597444860147, + 0.3588343021068228, + 0.6481878195188715, + 0.6236154600446786, + 0.6581651777527904, + 0.6559630475406568, + 0.49608616536238836, + 0.4839834635055007, + 0.6236020552201537, + 0.6949551740096618, + 0.4894338135535844, + 0.5583221611042595, + 0.5695491523365515, + 0.3815106653105451, + 0.3609054247596117, + 0.46233603004118995, + 0.32924268717539434, + 0.6738760509745194, + 0.5908475338257169, + 0.5583959601165877, + 0.43646558987492956, + 0.6999658939630757, + 0.67781451787629, + 0.5452736046500408, + 0.5246587442708179, + 0.47089375933332633, + 0.6810735352767955, + 0.6799433578348617, + 0.7179342726248339, + 0.359862266175987, + 0.7048737893226014, + 0.6085933054040886, + 0.34038957758292643, + 0.7055886634303343, + 0.580625385705815, + 0.670503445897152, + 0.6712870848626615, + 0.6574237741536735, + 0.5211048311373343, + 0.5951479664195025, + 0.5731446608322368, + 0.492055339696243, + 0.31576918131915355, + 0.6382309508550541, + 0.7102150127425395, + 0.5062300071287669, + 0.5461431388695358, + 0.366735598591452, + 0.5796768754677205, + 0.44814101533875067, + 0.7072722691770561, + 0.3711799650374539, + 0.6358934364384226, + 0.32456115137653624, + 0.6481918035654637, + 0.43189203980929863, + 0.7115168172455448, + 0.6005225250048853, + 0.7153499089830384, + 0.4770842347954062, + 0.5760247996364849, + 0.514419240495073, + 0.5747594546402328, + 0.6418186355561335, + 0.3712909364375715, + 0.5582826959939814, + 0.5886157815200508, + 0.5022243514679431, + 0.37316024552371896, + 0.36356576213902747, + 0.5284391063549394, + 0.4144589754108895, + 0.6743923467348893, + 0.44636936950444744, + 0.3332960876035859, + 0.3083595913108275, + 0.38947706563720286, + 0.5863816530368449, + 0.4266415031175206, + 0.3061407609907423, + 0.36882588504554426, + 0.33056295261752955, + 0.603331018849461, + 0.6839652242145082, + 0.6587832179448988, + 0.6395388279938079, + 0.6299669779130854, + 0.7055115246158173, + 0.5018756870185179, + 0.5274106260303715, + 0.4467765574995587, + 0.5030948427080323, + 0.4454971253757688, + 0.5905479087573315, + 0.33409831052867367, + 0.5103031815860772, + 0.4248606710224661, + 0.39604757311824756, + 0.573887493444585, + 0.5276343863449808, + 0.4256528600264111, + 0.3282993740085136, + 0.4323001259450036, + 0.6081425510394991, + 0.41442976577404217, + 0.3113606828767387, + 0.34910387712092, + 0.6411652327478881, + 0.46200164593405674, + 0.6783391559492938, + 0.5937067818159403, + 0.6566034624287591, + 0.6946023706954061, + 0.3044514444365833, + 0.5696697783014106, + 0.6890188407927036, + 0.3318693719444405, + 0.34861360732840196, + 0.36327611366106416, + 0.6016815323598927, + 0.3438172081826617, + 0.6969577256266861, + 0.49904812333172216, + 0.4485061924555992, + 0.5963347423587984, + 0.5111272142010436, + 0.592781583582433, + 0.3529818525114483, + 0.36446595416317745, + 0.6515134331904607, + 0.6039863787967059, + 0.686379920039508, + 0.6640050733117391, + 0.6658862158944967, + 0.4443087413930883, + 0.5143388994511631, + 0.45409815609884735, + 0.4067703393824441, + 0.3163984227460437, + 0.4077965448270234, + 0.5634222038416996, + 0.621153757756524, + 0.6226490096407002, + 0.6370692718818224, + 0.3409619414503315, + 0.5225594070645009, + 0.3472857350002331, + 0.62094362417778, + 0.3911717459026043, + 0.548125468458203, + 0.5035582244768404, + 0.6856451519536151, + 0.40256120557207903, + 0.31501377329827857, + 0.7084372458254975, + 0.5712348045939447, + 0.5924683215559299, + 0.5799869382282803, + 0.3982093038393647, + 0.5318158824030951, + 0.34976846926983507, + 0.4266089614093609, + 0.411131290757622, + 0.5670503648663541, + 0.4903656940268436, + 0.44257953605430006, + 0.6217584451844562, + 0.3208552326223359, + 0.5985447600433582, + 0.31478451829482323, + 0.7256491659584081, + 0.7132645608506929, + 0.4703747296909979, + 0.5753049447745445, + 0.3615167102596069, + 0.568386095899952, + 0.609864118765197, + 0.3931712683326044, + 0.563092429185546, + 0.41575243628849134, + 0.36634030267783735, + 0.6617827633328844, + 0.5840767578142287, + 0.3268599547102886, + 0.47623572029249306, + 0.3422583096333222, + 0.6554969723236388, + 0.39369640396769756, + 0.6685454590137837, + 0.6091142942519547, + 0.5840922330795957, + 0.49171159349404836, + 0.3296793489787416, + 0.3707830379677336, + 0.45410448053714264, + 0.5996215103512152, + 0.5966153257516946, + 0.700048873406725, + 0.31149255503669027, + 0.7173222379394364, + 0.4923001545676179, + 0.6599558966022463, + 0.5136622114358893, + 0.6792195986237963, + 0.49474467062886607, + 0.35420320520463133, + 0.6634724215364742, + 0.7012593952416637, + 0.3456167961601936, + 0.67452456233174, + 0.34102539644042656, + 0.4229711594017956, + 0.3416642184675365, + 0.38294226393790487, + 0.48323105914997766, + 0.5175097555786304, + 0.7243126701491212, + 0.680527679802422, + 0.3163758687701694, + 0.710991967415564, + 0.4405420323535961, + 0.41640951644415986, + 0.6122362690451243, + 0.36474363177438607, + 0.3946336119710069, + 0.44955537477446894, + 0.3061131686380475, + 0.3807637489483983, + 0.5808379427055801, + 0.6156331717872123, + 0.30897693040945523, + 0.5818880470891714, + 0.684596427417492, + 0.6417794317171888, + 0.6911874602100249, + 0.5385495644845054, + 0.3102434601558278, + 0.6759914780298717, + 0.6075017271216836, + 0.47082729242350524, + 0.5560228407454662, + 0.5447846719125439, + 0.6277657541408659, + 0.33273154551756456, + 0.40585585359609444, + 0.4215312923168469, + 0.41887929284236947, + 0.42579354065251, + 0.4862045641584724, + 0.5646325303183963, + 0.44503933952501185, + 0.49326899755973996, + 0.45875989832666475, + 0.30440015270903614, + 0.5562041072777719, + 0.5377111714984584, + 0.43066269536669627, + 0.5138758515250403, + 0.4792863196019584, + 0.3903194195606087, + 0.35424478596564457, + 0.6128269744749535, + 0.6568687574319098, + 0.43677270430104587, + 0.5215765545871621, + 0.44889634366770637, + 0.32157371149169883, + 0.5022220644051346, + 0.5193572190830626, + 0.33860487518871984, + 0.5349608299517188, + 0.31210442339741906, + 0.547853730579269, + 0.6342284221249467, + 0.6273621201878021, + 0.3617147477657871, + 0.6562530637557724, + 0.3443109189094608, + 0.35865021056963803, + 0.34965262757341836, + 0.38620215973865624, + 0.4225735672548078, + 0.6021499845712514, + 0.3336461083980789, + 0.6345619073442783, + 0.4313369799339354, + 0.6225023669777479, + 0.49567535816893016, + 0.5800530218134756, + 0.6231450892556671, + 0.4655305101803466, + 0.301858576396887, + 0.471968891217053, + 0.5767162693220493, + 0.5253744462055852, + 0.5464621120430444, + 0.57072691045957, + 0.5667386814437012, + 0.6464134002155069, + 0.6175856269704971, + 0.5505265884027604, + 0.6536716786881794, + 0.42134344445794203, + 0.6154951018316878, + 0.5137316585653113, + 0.6346612819511648, + 0.4326171934305997, + 0.3478277878214576, + 0.5327935525509186, + 0.493975545182576, + 0.6111312381842142, + 0.3064533600074726, + 0.4666813654295421, + 0.423258196051624, + 0.36902474265882085, + 0.3082621714789178, + 0.6211014962609542, + 0.3549384902376631, + 0.570223991571535, + 0.3375842230222571, + 0.4503648651737172, + 0.3687835655579639, + 0.3170151104871518, + 0.4138159279211927, + 0.6055102000888304, + 0.5020094938703433, + 0.4661298816063416, + 0.34645534966070335, + 0.35115573743392925, + 0.6334605858846329, + 0.4851722401181461, + 0.3057158281026421, + 0.4374399361978888, + 0.595786351004401, + 0.4716063951507897, + 0.646609298845213, + 0.6276935130616625, + 0.6212945159681429, + 0.3809143606490723, + 0.36404496654710583, + 0.32855343899906353, + 0.49095809770433013, + 0.6317161958590489, + 0.48693033521702245, + 0.4717475807027287, + 0.38929967919111513, + 0.520781529741573, + 0.4657369948544968, + 0.5371495305700696, + 0.6235183261680808, + 0.6233501478352295, + 0.42343738392874963, + 0.5009412211665744, + 0.4332437321062428, + 0.3655937504162642, + 0.3952963201490231, + 0.6008299142945471, + 0.6106117662114741, + 0.5783987548930137, + 0.6105384394959277, + 0.4309448967643013, + 0.34966869447089866, + 0.570873856863353, + 0.3713986148829185, + 0.3025877486439014, + 0.4702038920621103, + 0.35712576760201364, + 0.49365587466381455, + 0.4065099907644202, + 0.41101772508080453, + 0.374152997853725, + 0.5898420203704571, + 0.4984790851216053, + 0.34336887241093045, + 0.6421901353322744, + 0.4297260205429778, + 0.4159547744698222, + 0.6362973355198577, + 0.39125548331056814, + 0.5835236877144434, + 0.4682279358486453, + 0.5593559786275801, + 0.5845989799807698, + 0.6380846700417986, + 0.49333259445989885, + 0.42648062483079335, + 0.37129196754274774, + 0.5340514943584347, + 0.4364377821487191, + 0.32115170550053634, + 0.4271595207579023, + 0.449817890464845, + 0.392459538308913, + 0.40840209398895755, + 0.309486087524166, + 0.6334958732759641, + 0.4162510758671128, + 0.3138238244215734, + 0.521068920325292, + 0.6523065522395013, + 0.6367566222799106, + 0.4145526557745183, + 0.428979527464241, + 0.6202501638438618, + 0.44435402685111686, + 0.40546554215386155, + 0.6495867464326659, + 0.6272227415900492, + 0.47607965658869034, + 0.4453086309464669, + 0.4614138716846712, + 0.5862762030991432, + 0.4232697465175091, + 0.4522774649550203, + 0.43165817905165016, + 0.39053810412013523, + 0.6329836559326658, + 0.3744933170938044, + 0.6178836601792472, + 0.629052991713291, + 0.434392346800513, + 0.4407967182020396, + 0.6294987391021407, + 0.3672314653221527, + 0.3196380911388805, + 0.3312284693213937, + 0.35277734605675837, + 0.5992794068634668, + 0.6503867551606769, + 0.5195000534714557, + 0.4542026061259374, + 0.3370941679116914, + 0.3705226675332478, + 0.36016222118883845, + 0.5532909965401682, + 0.31586488993301964, + 0.3656717219172802, + 0.5914032123709931, + 0.6342059420259845, + 0.3857474451674922, + 0.4816705565175815, + 0.3501944281806235, + 0.616015874322043, + 0.6496223494159477, + 0.5233983645255038, + 0.5035547307938414, + 0.35029332706480554, + 0.4268222355086707, + 0.324822698513646, + 0.45207674881781157, + 0.5534603736405255, + 0.30534906096430275, + 0.5578935398790574, + 0.434256728725987, + 0.30385613557709873, + 0.6050911762046511, + 0.6356919494326239, + 0.4459189391745299, + 0.6085889308107486, + 0.41212866345860527, + 0.5874503791281399, + 0.567998862220816, + 0.5006134900755423, + 0.4439992416008366, + 0.30849142829407783, + 0.5944356032672165, + 0.3144823819444969, + 0.6182898951222484, + 0.42759684525055, + 0.5851823345809533, + 0.4208530861374904, + 0.4910502480357962, + 0.3605598138911661, + 0.3177725531196574, + 0.3856024220016098, + 0.570905751223963, + 0.43645874086863423, + 0.46660497185384886, + 0.5896332971554862, + 0.5602520924437551, + 0.5035385977091452, + 0.5839397568892926, + 0.3539609191314304, + 0.44059885953810807, + 0.3180021460810522, + 0.31537842708972647, + 0.6490570954487218, + 0.40764845534488137, + 0.3378737781050523, + 0.5366870526596343, + 0.5033900425695353, + 0.40297142689445764, + 0.4526968339068015, + 0.34554297091289327, + 0.324648114843355, + 0.606705689647239, + 0.45505971878756024, + 0.3156482238308619, + 0.6105825954203371, + 0.41925108091163815, + 0.48068842017664926, + 0.4798584266927689, + 0.48014986032982265, + 0.32239911484579675, + 0.43505589556728225, + 0.6531598818612552, + 0.5254854193265507, + 0.30642391069596236, + 0.4965525899644022, + 0.5323511335026697, + 0.5608716168961002, + 0.44658888088173354, + 0.6249868650639068, + 0.35303707458467165, + 0.48253396162487294, + 0.46434887959420734, + 0.6251087463358412, + 0.6041047649795979, + 0.5892501089885624, + 0.5032295110196191, + 0.5659430315831655, + 0.5836661226566989, + 0.34207729607894566, + 0.41859295927219814, + 0.32437901054322055, + 0.42562480996060337, + 0.382032541811991, + 0.4825743983950713, + 0.38510176745455066, + 0.6327961540132919, + 0.6171833266671837, + 0.30541440032647815, + 0.6186600399162947, + 0.529867376204354, + 0.6487918556228018, + 0.5887438211464289, + 0.37341202451886973, + 0.48232740589758183, + 0.4080090383273004, + 0.5044048144902158, + 0.5253850280878399, + 0.6397829599056974, + 0.5919649580382229, + 0.3182512508096891, + 0.5536955519783777, + 0.552812807631426, + 0.5050930554071905, + 0.5420589460006285, + 0.5289466744764265, + 0.3571919976494685, + 0.5985961251825339, + 0.3623469141931732, + 0.5094936495009472, + 0.3499489218996035, + 0.5011187182238428, + 0.4464636807370349, + 0.6536520803875222, + 0.579093791098509, + 0.5567453751464919, + 0.4365852850711365, + 0.5760227095521024, + 0.6595146535383958, + 0.6197494805500985, + 0.46374290762636333, + 0.3801590850691457, + 0.34181403975519664, + 0.4174257605377968, + 0.6142799481344108, + 0.5868759930436465, + 0.6375862767568166, + 0.4495729043582818, + 0.33903947822851427, + 0.4146948541874349, + 0.5124076406214595, + 0.6371718405517782, + 0.3730915882385377, + 0.383183463537193, + 0.4421289562490336, + 0.488055238500648, + 0.6327293107738333, + 0.3028467242233654, + 0.6272008962997544, + 0.6278963483755047, + 0.5802705182233028, + 0.4115742751271808, + 0.62008015531005, + 0.5871088471684699, + 0.5200640349274726, + 0.3004851560442113, + 0.37604677397623293, + 0.61804932987228, + 0.5472196920937592, + 0.5837879780539615, + 0.30194200589150744, + 0.3528201900546326, + 0.6144667077911103, + 0.544469222200664, + 0.4262028633981116, + 0.5843276966395407, + 0.552139591053923, + 0.38211102849030126, + 0.40254524855879137, + 0.5735202888401247, + 0.5913238006725148, + 0.517136637690755, + 0.595197507987815, + 0.3327291783122316, + 0.4447487604618927, + 0.4725429936943639, + 0.45834614028944753, + 0.42081988086030714, + 0.31170105311844104, + 0.49454927867113835, + 0.3184711192345364, + 0.5946647178304256, + 0.5431787326129518, + 0.6481440444599602, + 0.5858023474460219, + 0.4572735459870899, + 0.4040523047180046, + 0.6173867689299278, + 0.4052010428155837, + 0.6057220604953035, + 0.5780503543844706, + 0.6269016744293048, + 0.49176727239238527, + 0.3923679932499368, + 0.3459934283075525, + 0.32577535421750997, + 0.6134215099033211, + 0.5932971529755675, + 0.5347821793555578, + 0.5908634764234612, + 0.6269299665799886, + 0.40621956013937854, + 0.4742454704577971, + 0.4941313998040797, + 0.5735512408306038, + 0.5630733628007674, + 0.5848570913532656, + 0.3387362772518724, + 0.3309586933094481, + 0.5639411994901391, + 0.34386136192180405, + 0.32462066779615406, + 0.6508727379069488, + 0.4772038991138341, + 0.4558122864736458, + 0.5513623835085705, + 0.6188297740418129, + 0.5461025929054024, + 0.3741932949771718, + 0.48379931870526216, + 0.43567257102893575, + 0.4737840365495971, + 0.6404025009255687, + 0.347113054091818, + 0.36354947635522944, + 0.4812017972067638, + 0.33562239795132354, + 0.4399847140716765, + 0.31076513332548383, + 0.40071331554248757, + 0.3155993842149972, + 0.30123674430666764, + 0.4185892523970484, + 0.35974480292781374, + 0.6458029122056756, + 0.5195818290157815, + 0.4004632278872437, + 0.48797119496795627, + 0.32444331704187535, + 0.5303736384938389, + 0.6431949262150722, + 0.44583236446903085, + 0.43022366645001453, + 0.4390200973025601, + 0.5452352917549437, + 0.3120902303599264, + 0.3253755453841242, + 0.41209690471950977, + 0.4569647665510965, + 0.3832204043784626, + 0.541607264256136, + 0.34306611923820535, + 0.6403177717147606, + 0.5611259665145347, + 0.5987990350293315, + 0.3115220796328142, + 0.36781755536947147, + 0.6002969386181679, + 0.5188725370636618, + 0.5597226015436485, + 0.5041050035835213, + 0.6213565106066807, + 0.36066946924393073, + 0.5740493163206408, + 0.5363805495850938, + 0.3552387025017052, + 0.5179803487137642, + 0.3852037521994845, + 0.6232859187405493, + 0.3225433775204136, + 0.45050981368865206, + 0.6288668590560234, + 0.6031484500027444, + 0.41919900494432016, + 0.44297891987935056, + 0.5048698551697419, + 0.5253583425089268, + 0.33432826604015486, + 0.5822760776081443, + 0.5508911987460334, + 0.35450311486129715, + 0.3055112233618789, + 0.37338031586230935, + 0.3006942678241796, + 0.5335103478795163, + 0.49064464689620124, + 0.42619306491614595, + 0.6595210011422368, + 0.3026447286574352, + 0.5956644340137063, + 0.4536050401174808, + 0.37569274895532223, + 0.5146039057210474, + 0.32674783601847146, + 0.5639853519576397, + 0.44318308374019133, + 0.38451929904519316, + 0.31229949361180076, + 0.5959235110964856, + 0.5968086287202823, + 0.3690274361819703, + 0.5125641084679884, + 0.3119453311560434, + 0.3111057759844188, + 0.6047825895616943, + 0.46452771627049133, + 0.58553381165687, + 0.5980001740472589, + 0.542327812410462, + 0.4793485837169884, + 0.38100419468001046, + 0.3191081005333039, + 0.43700685067418527, + 0.40336971152383666, + 0.4420240268062344, + 0.47426356601417075, + 0.6214263258383176, + 0.3628051358382306, + 0.41980498650519554, + 0.6431980217542848, + 0.5338576358038218, + 0.348865244206845, + 0.3120404803317741, + 0.48174914046189665, + 0.4567246988051316, + 0.42407190775501047, + 0.314871943061639, + 0.6481706406332854, + 0.3698553825256064, + 0.5550690231985913, + 0.3823556979559085, + 0.4809236227774012, + 0.5018905730134657, + 0.49033919958470923, + 0.6102375963533575, + 0.6258092595867839, + 0.37442891740306244, + 0.4509538215198835, + 0.5526464527403014, + 0.32248395509340316, + 0.3275072726183847, + 0.4348112232796069, + 0.3709719517964109, + 0.3513972980092003, + 0.577265788194547, + 0.3851208329785129, + 0.4743673457729021, + 0.48374544683988385, + 0.5690701357807191, + 0.6165280097724692, + 0.561465066546758, + 0.6523647929268603, + 0.643067354704275, + 0.4844443379524277, + 0.5019708574474071, + 0.605571604255702, + 0.6382518279134511, + 0.6448704859686039, + 0.459931928367509, + 0.49626859562957987, + 0.41825656021888374, + 0.6582196113001928, + 0.4239939909822735, + 0.3717223998838036, + 0.3771604670003206, + 0.45788540083918483, + 0.3639688050178628, + 0.6220724968000051, + 0.6542307445781622, + 0.6057937985409332, + 0.36689631892929225, + 0.613554966806191, + 0.3831472806692263, + 0.5259229692015993, + 0.5222658133690186, + 0.43590028203004283, + 0.3509208058245661, + 0.4260144915036601, + 0.426229943984274, + 0.5285313848036943, + 0.6478827876429574, + 0.5797921325161342, + 0.4658783455759627, + 0.5372662519428992, + 0.4559002087485263, + 0.5107443396419502, + 0.3774584267353918, + 0.6143306285888428, + 0.6117244139745402, + 0.39800106694236337, + 0.45529233367269917, + 0.46472337216403803, + 0.514725809218002, + 0.4698627394733151, + 0.4989247192557882, + 0.4953228073151813, + 0.41708643195037115, + 0.5928041371969022, + 0.535237113763627, + 0.477684269084175, + 0.3775088738632767, + 0.4097857651223362, + 0.4090246816527669, + 0.35584171175256113, + 0.4541784099520737, + 0.5418082299934528, + 0.45113616388473826, + 0.3578748562483164, + 0.6081391953086366, + 0.4378299682790767, + 0.609125909743493, + 0.33020610743819473, + 0.5005633471753539, + 0.32082982593766707, + 0.46160224724279963, + 0.4064463444913453, + 0.41401554532863394, + 0.4124127999433109, + 0.39678363495728175, + 0.3207671499562126, + 0.5241868880187468, + 0.4466218141196209, + 0.6531094979714555, + 0.5635213883778398, + 0.4903953567650411, + 0.5159904105949308, + 0.6244807796647553, + 0.5411135473372184, + 0.4679467913430482, + 0.45544261901019206, + 0.3016197089420546, + 0.48300379530868404, + 0.6431560209491585, + 0.5317012333375699, + 0.4127749524387625, + 0.4402205821990024, + 0.3205005223221719, + 0.3570598452275214, + 0.35435328487817086, + 0.3246452878041226, + 0.5635367903402398, + 0.5098591294476403, + 0.3573585195239652, + 0.4160021986246843, + 0.4991341478943885, + 0.31657413920697597, + 0.3415520662686969, + 0.5825785261642114, + 0.3352368119795151, + 0.582187892492751, + 0.34445271699405083, + 0.3241465550996861, + 0.43435847943740136, + 0.5001078880603467, + 0.6320240437569238, + 0.44670723238951415, + 0.32428780555703923, + 0.4168725606994062, + 0.6470830904626692, + 0.6184386133629282, + 0.47098025064915067, + 0.572410623799795, + 0.4689323691322512, + 0.7197834869927044, + 0.6316136315179945, + 0.4687060687684722, + 0.718350145305457, + 0.6210544200381978, + 0.4164560870702277, + 0.49660455843009227, + 0.42651259791277985, + 0.6366416605015804, + 0.41963255318956266, + 0.6815639405845236, + 0.4942458770923169, + 0.4457701199079257, + 0.4304656871959445, + 0.5726605311602486, + 0.5952342434325051, + 0.5334850560897563, + 0.712061659091562, + 0.4596354255367053, + 0.6481432009608036, + 0.4429806574675191, + 0.6936683749328715, + 0.4732765137455004, + 0.5107652719855185, + 0.4946944959272113, + 0.6197705371251389, + 0.5145686394766992, + 0.4123226891991845, + 0.6262704156503593, + 0.5502114982003901, + 0.6089622714220028, + 0.4208381871199702, + 0.50889496046486, + 0.5882408265388384, + 0.5018349117266481, + 0.5755694107713233, + 0.524633567657553, + 0.5894654516585807, + 0.45841324279123835, + 0.7262855936311863, + 0.49859273261469994, + 0.42332319027641774, + 0.713866535071107, + 0.43205676921911484, + 0.5229543297310608, + 0.4970715878453204, + 0.44689050595635704, + 0.4487788817504181, + 0.5119097229290483, + 0.6124760099924502, + 0.6992990528158575, + 0.6572069412585482, + 0.4937709453010411, + 0.5601770915651907, + 0.4286833570365185, + 0.7094959145054953, + 0.6890705019888392, + 0.5668520064683533, + 0.7248289633289096, + 0.6573379691850709, + 0.40710705978119055, + 0.6742309160911615, + 0.5162391534583356, + 0.47573820510376796, + 0.7178936853201172, + 0.519068988202345, + 0.6763070207250317, + 0.6952341896089019, + 0.41240736760412594, + 0.4463629713142131, + 0.4651658797020105, + 0.6019065794716125, + 0.6426493316953639, + 0.6295544305062699, + 0.5602354161281937, + 0.5920669428961444, + 0.601960722291391, + 0.6799619543937965, + 0.5253836892563345, + 0.5245313872416404, + 0.6949207441342642, + 0.5756208426497832, + 0.5884699041096879, + 0.46912326795661013, + 0.4181121788805962, + 0.6357033818634634, + 0.591907107777484, + 0.6536793266893888, + 0.707460648794008, + 0.46523017585939375, + 0.5440345050262176, + 0.7060333731892688, + 0.4613979775505949, + 0.6518375070174278, + 0.6554704029287515, + 0.48946537987575583, + 0.5019560035247468, + 0.5694207885140414, + 0.5959099927780799, + 0.6165964122832779, + 0.6500555667032312, + 0.47645422422410544, + 0.4050170464732677, + 0.546522971606198, + 0.48042325982817846, + 0.6314912353999629, + 0.6080838515197824, + 0.7144394066924811, + 0.5126817311961976, + 0.7143629440074974, + 0.5660588498006132, + 0.6714776017760689, + 0.6753418704362764, + 0.40040014610538904, + 0.4665932797838158, + 0.6727402699563753, + 0.7028774920817134, + 0.6232886823047772, + 0.5475432425378585, + 0.43009464810422277, + 0.49350032509074326, + 0.7146159932181151, + 0.48043292020396333, + 0.6518657492961231, + 0.5523805374812223, + 0.5675913935925546, + 0.5223641096248607, + 0.6085880388730782, + 0.46957317130061743, + 0.42706038032637633, + 0.4506462955044916, + 0.6204898719937951, + 0.5841610705447264, + 0.41907794481836164, + 0.6350764305885837, + 0.5156732262365857, + 0.5859597677604466, + 0.6902085197935259, + 0.6491726923040189, + 0.47202818979892436, + 0.6610810050686968, + 0.6902126817071319, + 0.5690339146185632, + 0.5168156344650957, + 0.6255338048373137, + 0.689356065047364, + 0.6573941664354706, + 0.6480429458956037, + 0.5940005105158144, + 0.6753843779133182, + 0.6177463385053678, + 0.6129567271996117, + 0.6508339688495697, + 0.7260224425147257, + 0.5301089746180845, + 0.5299221137436484, + 0.5373730863843508, + 0.4092212566040232, + 0.654784728272557, + 0.5485691498728045, + 0.6180705536513569, + 0.5042883402069099, + 0.6250116461883338, + 0.4087943673051093, + 0.6963506967502574, + 0.6450984150907078, + 0.6710565642112627, + 0.5138994609565714, + 0.6728745637038989, + 0.6140040678874927, + 0.6124735545984926, + 0.4023191469549778, + 0.7251025930578976, + 0.44472694418247594, + 0.4269434258159559, + 0.7145397147259149, + 0.6158454927053456, + 0.5026026978056019, + 0.6351386451466535, + 0.6326141526655852, + 0.685105041397038, + 0.6681528113069954, + 0.5117756166030557, + 0.6902158678850396, + 0.6076480340370837, + 0.4534739208322089, + 0.5811962120703589, + 0.6901046415077833, + 0.6841274354171167, + 0.49056279581674556, + 0.6908005569981508, + 0.4433466153562218, + 0.440914540165169, + 0.5385789608943915, + 0.5639408803569758, + 0.48852938334011997, + 0.6142840812094663, + 0.46735645376110124, + 0.582035002682348, + 0.4534090413120068, + 0.6243030026211065, + 0.5803186620395626, + 0.5126604679547758, + 0.4714031330459305, + 0.5957490771602858, + 0.44395495292877674, + 0.5360509788489827, + 0.44026550080361215, + 0.41255676794473795, + 0.5022670163729497, + 0.6868518253751315, + 0.7270510952335061, + 0.5692686741635848, + 0.587372929671657, + 0.40190066748260317, + 0.5779417619949474, + 0.6713533514908641, + 0.49924960155851156, + 0.631585231273026, + 0.7269992339062916, + 0.5223905650512098, + 0.692058938606886, + 0.666510185790488, + 0.5027791845612649, + 0.7077197500146972, + 0.6982775649980968, + 0.43982564417218334, + 0.5173951510748156, + 0.4601304877194853, + 0.4203530637213925, + 0.4058236302770923, + 0.5379156793199351, + 0.4494841161342137, + 0.5787472056654933, + 0.557346580203431, + 0.612120752611783, + 0.550854170443685, + 0.6471277899593189, + 0.6087147254323042, + 0.5730967048198603, + 0.4001435906447169, + 0.5193686339475748, + 0.6323234170439205, + 0.6513369194779772, + 0.6434402464542841, + 0.4230028911720501, + 0.45727003088860607, + 0.4644176261944458, + 0.5401340348837511, + 0.45764705678635126, + 0.6725242424723166, + 0.5451189830535077, + 0.6781270835558384, + 0.5031620234883163, + 0.6298827852383095, + 0.5720033286713136, + 0.4000693449677106, + 0.4057087712113597, + 0.42204098727197803, + 0.6590457734375734, + 0.4344829651218552, + 0.6293691222155546, + 0.7074079457510306, + 0.6953457912257228, + 0.6622703458856337, + 0.6619426667220114, + 0.6813367901563063, + 0.716569548097565, + 0.4668520546674594, + 0.5452112442110254, + 0.7135529961755336, + 0.4173814447363607, + 0.7055914663847287, + 0.5465516553525196, + 0.5243589744900058, + 0.47476662012493426, + 0.5475490917387563, + 0.4800632299283459, + 0.5458378900347058, + 0.5097661045194443, + 0.7261107653161366, + 0.6941486430542376, + 0.5310655058707794, + 0.415644028029298, + 0.49367309024408823, + 0.5162439709357783, + 0.4489492758415089, + 0.5316652102335748, + 0.5093525297923611, + 0.510517568689326, + 0.6158974317494399, + 0.47763760487697227, + 0.6727542940410356, + 0.7108706828081125, + 0.5356368741409279, + 0.5249253885976933, + 0.41936340066575567, + 0.5206337962888683, + 0.6499477281544885, + 0.7087894964144852, + 0.6400935553326621, + 0.4204569531238562, + 0.6700508799810572, + 0.4568435982764736, + 0.4756231597697755, + 0.7166207930993505, + 0.4704375836120589, + 0.6273688237442504, + 0.6236402251970392, + 0.6496141112649226, + 0.5155659865604727, + 0.7257395508634432, + 0.42495962676142857, + 0.4995303679794203, + 0.47770199152713994, + 0.6455648142197309, + 0.6197438855633046, + 0.5760017778741467, + 0.7064124141634323, + 0.5952894246384737, + 0.5426317255115262, + 0.6177567103296489, + 0.5309929412004104, + 0.5539452961753389, + 0.5383124929792538, + 0.5782933227925827, + 0.5532171375416454, + 0.6709790222483929, + 0.5977389157641557, + 0.535564717535628, + 0.7243968795406612, + 0.4218861078613222, + 0.401293695053836, + 0.575172297380878, + 0.5359233867872996, + 0.6492506893837728, + 0.6849005741125974, + 0.5912287835435809, + 0.5153276837486633, + 0.6167520098742191, + 0.46060099180936015, + 0.653931620689449, + 0.5787305630127745, + 0.40415212779792514, + 0.500427269401813, + 0.47533155655672354, + 0.6008711676464067, + 0.6531938143144096, + 0.5731903221445871, + 0.5833182684976805, + 0.5581883469389973, + 0.6883006445783593, + 0.4965259925471431, + 0.6350330812522669, + 0.4285897801751181, + 0.6126905045715119, + 0.49079360484762624, + 0.6548664126043668, + 0.5607838312668035, + 0.5231373105820407, + 0.6205404152676071, + 0.40890716530542287, + 0.6200561985459652, + 0.5735296581056278, + 0.5140507864529466, + 0.613177674193633, + 0.6198673528818213, + 0.5206310014090613, + 0.687436979991149, + 0.6084211838010833, + 0.6661569300373088, + 0.438840041883516, + 0.6602087436831393, + 0.6390301131974396, + 0.5390479047155025, + 0.5156044436021643, + 0.5171696522183485, + 0.4954997281718294, + 0.6599868293375564, + 0.561629102778199, + 0.7160204541558473, + 0.723448159229608, + 0.6665808035181517, + 0.5593480432729796, + 0.5896276958242563, + 0.5882251799449669, + 0.47780790927529493, + 0.5363459471917551, + 0.7082092299280326, + 0.450207407523733, + 0.4746981666745122, + 0.6173846287322698, + 0.46621648464431703, + 0.5942031031340906, + 0.43390418735059394, + 0.5669023021635455, + 0.5165173578354999, + 0.6460489775685752, + 0.4453840399959637, + 0.6572821593043314, + 0.7185278636777748, + 0.631625203730624, + 0.414745413793755, + 0.6909837028526306, + 0.5558263691741704, + 0.5760977877929498, + 0.625099766772646, + 0.5027928727248834, + 0.5571115367354825, + 0.6417916401430903, + 0.5231257550031646, + 0.5755754108850929, + 0.7113219341373611, + 0.6802041539525232, + 0.47064943329224146, + 0.4364868612489419, + 0.6500463142577353, + 0.5473030023532187, + 0.4525720454678631, + 0.4206324712010905, + 0.4082841864152971, + 0.4200889141808819, + 0.6455112403403958, + 0.7052443031462612, + 0.4297883006134099, + 0.4167837069105667, + 0.4423726686932946, + 0.5207522926919259, + 0.5602517222981142, + 0.6812905024361913, + 0.7247582669930479, + 0.5721678278412293, + 0.5400788518602024, + 0.6709783542834045, + 0.6828270550807026, + 0.6717961660252436, + 0.4884274149280591, + 0.5545331853208774, + 0.71685660558059, + 0.632604501268535, + 0.7252326338264424, + 0.6097050508966383, + 0.4151132085261964, + 0.7261165716799243, + 0.5769163390433321, + 0.5048053851270932, + 0.5776505882642242, + 0.4891767512579941, + 0.6437301599699847, + 0.6797905666389702, + 0.6254729905067826, + 0.5194475952370308, + 0.7100236914659049, + 0.43750246531847686, + 0.40032137087920133, + 0.5330415343227557, + 0.5019920647661898, + 0.6458388689666033, + 0.45974559555796224, + 0.5383368287260067, + 0.4524700276688782, + 0.5080641566504269, + 0.4592273612826011, + 0.47594964978791887, + 0.5231275559691149, + 0.655269300086448, + 0.5476840454497682, + 0.4440819377096666, + 0.40786561057865706, + 0.635517972062976, + 0.6906933604034553, + 0.4178055429610969, + 0.6141825479825689, + 0.6763278736121052, + 0.6952487653685686, + 0.4849715023193522, + 0.5275336342593584, + 0.5167818834376335, + 0.42242663929060453, + 0.6373653691395047, + 0.4325720471141161, + 0.5995417654473569, + 0.5976632525940264, + 0.6824933041459088, + 0.40919405650571444, + 0.5503412892380459, + 0.7249782809712398, + 0.6297507652666274, + 0.4269794607094019, + 0.49929580164731147, + 0.6231603519232011, + 0.6170568708116694, + 0.4152692095548012, + 0.6441077807246715, + 0.574841581878357, + 0.7251792539646047, + 0.6704744405389109, + 0.5224537390553128, + 0.5626984797033743, + 0.48314479147975836, + 0.5363743257095168, + 0.6096530526532637, + 0.6265704284821443, + 0.4227728396202452, + 0.6721148474569805, + 0.5954600817217537, + 0.49986202953395464, + 0.4458418823773215, + 0.7055626816009821, + 0.6159606308786638, + 0.5363068793316683, + 0.654791501057649, + 0.5117761735391819, + 0.463188951108517, + 0.7258819519207759, + 0.4877493417617016, + 0.681810501619456, + 0.5201965704760291, + 0.4175780546854469, + 0.5550519067610347, + 0.6453541250389149, + 0.4421285089737912, + 0.6558712876991808, + 0.43317067763578404, + 0.455675768558564, + 0.6471408827179798, + 0.719758878584056, + 0.5978179958364884, + 0.4189066825909029, + 0.5874356921140906, + 0.48307821042075333, + 0.40638748229989036, + 0.5284851386245722, + 0.7041139305532125, + 0.6156791881526344, + 0.4137371346751112, + 0.4132284426909691, + 0.4209004900351835, + 0.5966857447958254, + 0.704344002609382, + 0.7113052310091987, + 0.4813088641608674, + 0.46541688983416474, + 0.4008701051756629, + 0.5135468661781041, + 0.7194875780026433, + 0.412250344279006, + 0.4493475611165865, + 0.5280934510905901, + 0.5091596544047805, + 0.6741212157042916, + 0.6301820761230689, + 0.4193975426040414, + 0.6006300725832298, + 0.6281296441580948, + 0.6409537275113707, + 0.5842317492875457, + 0.6689033889606171, + 0.5165759373843724, + 0.61170317893946, + 0.5731989976597218, + 0.6696102018015517, + 0.5992811616158567, + 0.5759876799509691, + 0.5662461350957158, + 0.5327895983300144, + 0.6203699123339332, + 0.5623652897464301, + 0.7065640748238113, + 0.6135566418672145, + 0.4867001288975257, + 0.5836359954653818, + 0.5855920905174156, + 0.721154819240945, + 0.6139923936389076, + 0.44987789669208267, + 0.6956427363236091, + 0.5861786691368709, + 0.41320267426869745, + 0.41084731641402855, + 0.5197983056437353, + 0.6043967333543292, + 0.536984890904068, + 0.4729585301838772, + 0.4728639685916926, + 0.5411511938068296, + 0.6818699738284572, + 0.4129121283614525, + 0.6829491419469944, + 0.5486658307751844, + 0.6982578143865932, + 0.5366828825867126, + 0.5415089150894549, + 0.6266189798123297, + 0.7179600144996415, + 0.5389532668053743, + 0.6761610351080105, + 0.6714384874183985, + 0.5113687838089486, + 0.44872483794162177, + 0.6374489737441251, + 0.715205311587156, + 0.6434959013933572, + 0.7140749079042126, + 0.6160104752965481, + 0.6902867980436744, + 0.43906698552309514, + 0.5569454117466819, + 0.47750478280673936, + 0.5383503482496566, + 0.5080115573645583, + 0.5403976975712427, + 0.6478884112620085, + 0.533018096543207, + 0.5611913935127509, + 0.4245615692690531, + 0.707997144616024, + 0.5667796977975552, + 0.6416557614674885, + 0.6082288718055453, + 0.7242901034221417, + 0.6144708294367085, + 0.6242391444204564, + 0.6249889034854758, + 0.7155661650130227, + 0.4332181111787017, + 0.6895552445705087, + 0.5006528560987517, + 0.5388089418881519, + 0.555831570988957, + 0.4515046621267364, + 0.5255770778497836, + 0.46936423144692496, + 0.618300232442527, + 0.6505128150361288, + 0.5304460965046816, + 0.7057325386609115, + 0.5619904910109542, + 0.5661023265132585, + 0.5417395637103966, + 0.5822858315338123, + 0.46107375238616777, + 0.4264794011914284, + 0.43849576903312115, + 0.666653639416823, + 0.5537985571673644, + 0.5576702309498746, + 0.66392204568011, + 0.48126609151443855, + 0.46131190745139167, + 0.4919748959618164, + 0.717904682469548, + 0.597367397419093, + 0.6510402474816981, + 0.5262644602516288, + 0.47147175509503086, + 0.42423246951973403, + 0.4241640412030545, + 0.45399576470222863, + 0.4771402267112912, + 0.5831813306722519, + 0.4268438279216966, + 0.47267333766205616, + 0.4657493265648575, + 0.4534690774257083, + 0.49821094269066923, + 0.6534913217200762, + 0.5847004002190924, + 0.6529136199371431, + 0.4221399253204602, + 0.443360435405088, + 0.4563533540546499, + 0.6752880657174818, + 0.7209445845191833, + 0.5236539962400077, + 0.45130478830794785, + 0.4190754027552134, + 0.5863342139777077, + 0.6952325325974715, + 0.7119992993658559, + 0.6776948064838351, + 0.5354031418121219, + 0.6046719285681237, + 0.7151523084204873, + 0.5999339794355842, + 0.6246832398960482, + 0.6186437154068657, + 0.7126338067272258, + 0.42112990628579605, + 0.5302805070091605, + 0.4772813847263648, + 0.4785548019825619, + 0.5236647161346651, + 0.41938360530342456, + 0.6271886066089976, + 0.4144300560278827, + 0.5391223003719716, + 0.6351470900532941, + 0.6233298977212194, + 0.40162211514590745, + 0.6570811244025845, + 0.45674606558827036, + 0.5472432682801092, + 0.6984784614893961, + 0.472968530208544, + 0.5216218961514655, + 0.6898009882865046, + 0.5551346371003414, + 0.42507818326470515, + 0.4982518466125969, + 0.5856046373538031, + 0.5446624769899603, + 0.5382128974287614, + 0.5176132573855343, + 0.487787378133819, + 0.7105479627634399, + 0.7006557469267867, + 0.45577814792236865, + 0.6851460971382266, + 0.703617783270291, + 0.6453747846216382, + 0.6723515178715591, + 0.4043954888836961, + 0.41325019555430503, + 0.4114467702390985, + 0.4657656215005246, + 0.6205632494520635, + 0.653861013128249, + 0.4006420023815259, + 0.4221185770218215, + 0.717071256271558, + 0.6865537727356577, + 0.44117050369440464, + 0.43273116393509303, + 0.45178856031251124, + 0.6776042150271471, + 0.5555436303221393, + 0.5653921019072848, + 0.653232943381167, + 0.632166138908776, + 0.5621074738043288, + 0.47700535757063656, + 0.6137379986396485, + 0.4481928055386387, + 0.7050999490550993, + 0.47994391983767803, + 0.43251115044416005, + 0.47131987878526416, + 0.7178939331485092, + 0.703608303559205, + 0.6523264694606545, + 0.4628514908465152, + 0.6551343189682841, + 0.41701425169121203, + 0.6255082668510072, + 0.42636316047081385, + 0.6617073330940219, + 0.6892863499988325, + 0.4068209762269848, + 0.6990347625611235, + 0.6503888953980779, + 0.6300720117581503, + 0.6975946690512684, + 0.5718278888643811, + 0.6782237410235162, + 0.6530593899328014, + 0.6958235564649197, + 0.6621010355355577, + 0.45275528394121384, + 0.5865474171655255, + 0.586716795063611, + 0.6968608875440383, + 0.6339378186216411, + 0.6885641102685263, + 0.70109610838306, + 0.668235996034617, + 0.7124321869723127, + 0.6811754565098469, + 0.5191214128959654, + 0.5543609915501745, + 0.5181526358323152, + 0.4736039961195086, + 0.44921728709351083, + 0.5538844924035562, + 0.4440752725607888, + 0.6867934753223393, + 0.565977269514002, + 0.47652266540542165, + 0.6866095752336953, + 0.6173387993886688, + 0.46612549455321106, + 0.6546398740904702, + 0.4189535925431774, + 0.6518599798192204, + 0.4303868452107261, + 0.6133719544586819, + 0.4066917762990364, + 0.595616277049412, + 0.5986477392055306, + 0.7074239399470463, + 0.6442462400962975, + 0.5666125959335597, + 0.5159175718036176, + 0.4298103174068968, + 0.40237989016164205, + 0.5573716210656234, + 0.4496387945888264, + 0.6896799932864028, + 0.6126443566518532, + 0.7264337312117546, + 0.409641024244968, + 0.48312687744337485, + 0.5664980627157217, + 0.43532819495530856, + 0.5373291606307601, + 0.48747252916467565, + 0.41823060284845975, + 0.5016488711599231, + 0.6679868698596192, + 0.6026422573334544, + 0.4644243976372694, + 0.6546982738036226, + 0.5503125355285614, + 0.7264593231569356, + 0.664327425488894, + 0.43741720767776815, + 0.48920537084837284, + 0.42029251014585123, + 0.576033925702679, + 0.455184757630851, + 0.43748614508917494, + 0.6087545627872861, + 0.401617657429981, + 0.7158628082729731, + 0.5899308426543204, + 0.515350185744781, + 0.5862518649536115, + 0.6961066972646458, + 0.6526592155310497, + 0.617638631686051, + 0.46897802859763493, + 0.4088915254977389, + 0.4148217195949384, + 0.6649125018281795, + 0.601175467987554, + 0.6827757403362155, + 0.6405335116770654, + 0.45636843454955395, + 0.6912462366237, + 0.4439438521422107, + 0.6752245306784146, + 0.49186629162040735, + 0.6274289284551264, + 0.5231839872173405, + 0.6495980646948716, + 0.5658824172548523, + 0.4055642639077962, + 0.5872267291002973, + 0.6895140324052937, + 0.4318289252625331, + 0.5034706133827413, + 0.4687056998547624, + 0.47603097015650314, + 0.5675703316670719, + 0.5161179598113267, + 0.5489294174324713, + 0.6767870252740629, + 0.42152672843055145, + 0.6096627473878324, + 0.6612868978332902, + 0.4076304064412046, + 0.4450008472849717, + 0.5289772716548058, + 0.40112031317464264, + 0.4215961378866302, + 0.5592406430933472, + 0.713413286122262, + 0.4737367466624648, + 0.6039634090997081, + 0.7052279873137033, + 0.6968441302832067, + 0.6717632392311241, + 0.6371736948292631, + 0.6080395704965543, + 0.7132033248392864, + 0.6943835520228634, + 0.4591745265330334, + 0.5170495071532383, + 0.49740165926443, + 0.47585455760384315, + 0.6457446561682721, + 0.4707830566295035, + 0.5441379113873516, + 0.44628134142023956, + 0.5152556965201411, + 0.6604104399499844, + 0.5404103528638075, + 0.6375105105888176, + 0.5376642520975137, + 0.4261753220714098, + 0.4936387003967693, + 0.5827748798783091, + 0.4433055935468915, + 0.46861106797382135, + 0.6392024570121524, + 0.583543314685016, + 0.4335608522240492, + 0.6794903047653413, + 0.5183326710219917, + 0.5053907603475029, + 0.517103951022083, + 0.6295375101477272, + 0.4311354957639444, + 0.5654470132279484, + 0.4981706289560788, + 0.5307969266952591, + 0.653087522527607, + 0.6012379892453387, + 0.5814439323483648, + 0.4609110960761476, + 0.5030747347179433, + 0.5125358649839317, + 0.4936349734314984, + 0.6403611271096342, + 0.6545111156588586, + 0.5752369323456998, + 0.5876304857717114, + 0.673894884016802, + 0.5162902795903327, + 0.4565879563515173, + 0.5882577453813462, + 0.40665275181917687, + 0.6837654990656581, + 0.443167784285489, + 0.46456048668959093, + 0.6998690718636913, + 0.6260668079409449, + 0.5039856823101784, + 0.6801390739254543, + 0.5424297918371118, + 0.4626986108631884, + 0.685612392894929, + 0.594944709143918, + 0.5482234783451572, + 0.507748370088445, + 0.6847479016905805, + 0.5457154680317343, + 0.4687468868528556, + 0.44402761232888455, + 0.702980487210371, + 0.4602436251782695, + 0.44624156066853415, + 0.6902126005299993, + 0.4864928649099596, + 0.588782923582001, + 0.5751195115805777, + 0.5807466856738689, + 0.5275651623962339, + 0.4236054166841978, + 0.5876300817616241, + 0.5665939344252964, + 0.4102709936917224, + 0.43538180349923156, + 0.5111174145647122, + 0.6829584225225879, + 0.6842739919068195, + 0.5558931206588477, + 0.43294789707986653, + 0.552442548198554, + 0.6809564469013266, + 0.5295745622156686, + 0.5512539307579452, + 0.4013651715132158, + 0.49525026966585445, + 0.6465865359237442, + 0.5411528281814435, + 0.581624718205495, + 0.5969588773869997, + 0.5509570505894337, + 0.5304303836483, + 0.44229884051474966, + 0.5531765955201711, + 0.45683390908994176, + 0.6635080020059632, + 0.4175758530804021, + 0.6333542881702622, + 0.6186649247459707, + 0.7206149428872407, + 0.5263058211405458, + 0.42883172637389616, + 0.4891868608995578, + 0.481981512547775, + 0.720818319059757, + 0.7248238838392187, + 0.4492352612154196, + 0.5176551510800828, + 0.6233378892149942, + 0.510259395046295, + 0.5927173624145947, + 0.45327838589472946, + 0.5898677426131322, + 0.6345330800780141, + 0.5023945000869443, + 0.47588143721027787, + 0.6302175746478136, + 0.5353991823162211, + 0.6093405065866229, + 0.4488538816093861, + 0.5196419382375799, + 0.6684204965418636, + 0.4754685196602758, + 0.7142446568768253, + 0.5868140054492265, + 0.5530283759246069, + 0.5831669381905328, + 0.4759760319631825, + 0.5900548468813153, + 0.5819107300934969, + 0.5323869507033336, + 0.4494159284429817, + 0.4102789562305654, + 0.4891024816386411, + 0.49837496650470375, + 0.697705206005248, + 0.7048549154019703, + 0.722952971721257, + 0.5312353173672706, + 0.5058620653198383, + 0.4089644158063124, + 0.5096943743782606, + 0.6139647289146926, + 0.6058554897178329, + 0.6974638826587896, + 0.5287102253700738, + 0.4492147301446179, + 0.43686868789190103, + 0.6463830071699934, + 0.4658189160651792, + 0.4414685003588095, + 0.6299039619308752, + 0.6089180508809366, + 0.5253477302504737, + 0.46876839650785707, + 0.522885737885001, + 0.7270460040793952, + 0.40191072825328555, + 0.6905135166519678, + 0.5694602430547163, + 0.5606250377450421, + 0.6478325059092228, + 0.5335534218135202, + 0.4957802628251513, + 0.7214512442557792, + 0.6911315255418387, + 0.5510500783346745, + 0.5407702378813009, + 0.6502680875653553, + 0.42656216431182253, + 0.5707624472105637, + 0.48985475581800864, + 0.4016857609538194, + 0.5145945745552559, + 0.5767815952691516, + 0.6694572137055548, + 0.6712825427394487, + 0.5445735596791028, + 0.7187202491058979, + 0.5401791303841791, + 0.5416385303992002, + 0.6731769039950797, + 0.5771716665813507, + 0.4824644818810431, + 0.5384433641894675, + 0.6637949144230897, + 0.6774240298939378, + 0.7193300740858152, + 0.48593869127417655, + 0.703005737184693, + 0.5650070766186055, + 0.6511375723592353, + 0.5798594100324155, + 0.6343437528224476, + 0.7077347613232232, + 0.664116061936254, + 0.43434691618335763, + 0.5038556474589082, + 0.4146495576718123, + 0.6632776237378617, + 0.4770356167283348, + 0.425996329560935, + 0.47935074985311776, + 0.4971624131079573, + 0.52362160520167, + 0.48258774766443036, + 0.42732183592672063, + 0.7261421334871657, + 0.48064871041231244, + 0.6165426151163088, + 0.5907940477604833, + 0.641238891496446, + 0.4973066614167373, + 0.5069434625412996, + 0.4613502679550699, + 0.4650907080412108, + 0.5005988340557661, + 0.6640979276674402, + 0.6032405848057596, + 0.650853608861165, + 0.6342784465500015, + 0.7162655177464898, + 0.4547424777264968, + 0.48354298350732566, + 0.4764331336342098, + 0.59391931857626, + 0.6304865355623195, + 0.6079246782735758, + 0.5717600387430426, + 0.5178616293988079, + 0.5692653320207901, + 0.6418657270568721, + 0.42220681157710144, + 0.4573422358747409, + 0.4348785018624498, + 0.6757965690759052, + 0.5105163207517038, + 0.6472538825447044, + 0.40059465307175035, + 0.5507618051992414, + 0.4882666847536532, + 0.6492986622497323, + 0.5173456012233368, + 0.5139993443019116, + 0.4672932443927459, + 0.4781732961287617, + 0.5253250005037307, + 0.474482801689898, + 0.5530526409228408, + 0.6635478575226159, + 0.5164641644059131, + 0.5764165348170758, + 0.5908865326232763, + 0.4682307661157933, + 0.6969560414464336, + 0.5337077065459579, + 0.6582571203722987, + 0.513871209576529, + 0.6124847638169355, + 0.6567650853799982, + 0.6006382447065735, + 0.5089984195645985, + 0.7225207672409719, + 0.4261121639231001, + 0.5932103668004136, + 0.4793318256921878, + 0.7226873352570469, + 0.4548940585589247, + 0.6163547816902897, + 0.7073468263578984, + 0.5035476691178962, + 0.6479007918308086, + 0.43040146735075946, + 0.59599882331109, + 0.45142202437912804, + 0.5653502896406373, + 0.6034024152670383, + 0.5184543009529883, + 0.4182440689953747, + 0.5909060486969917, + 0.5492827344692287, + 0.5540512306542416, + 0.504661556569054, + 0.4280883363123325, + 0.7253731237393569, + 0.5279529581908259, + 0.6068979918533415, + 0.47082209301253686, + 0.6757204134072765, + 0.42517739982119057, + 0.4376336000336328, + 0.4288494612782382, + 0.6328772869618068, + 0.40480602688278666, + 0.716244329136748, + 0.5762263542039207, + 0.4829785728869611, + 0.5975717492657098, + 0.46009589638637066, + 0.5071048389306871, + 0.48617120305977046, + 0.4752348670408676, + 0.6919926420334357, + 0.6467873162316662, + 0.704477065834878, + 0.5953507589694115, + 0.46996564105808675, + 0.4840081327083677, + 0.5433323697273233, + 0.6744226846813568, + 0.4935098984312737, + 0.436579490119959, + 0.5184049332222274, + 0.5547353618827753, + 0.6785873077593901, + 0.487345554472419, + 0.552088795647166, + 0.5185168048913598, + 0.713173598680465, + 0.7068945531814059, + 0.537984097537089, + 0.652598335803899, + 0.4985336807883104, + 0.580871064061875, + 0.41486699688231876, + 0.4899820804852233, + 0.4972845556218465, + 0.5795211914642043, + 0.6778202406374392, + 0.6716520967316356, + 0.6008527675307724, + 0.6016985728980717, + 0.6062677378339456, + 0.681746235329759, + 0.6527529139054005, + 0.5117807845900504, + 0.47631729922448585, + 0.5588174115288728, + 0.5631577051662174, + 0.5723447938021089, + 0.590485562330798, + 0.6732820431119091, + 0.66716771932047, + 0.6083906805108639, + 0.5322042770774056, + 0.44135538450994904, + 0.5731495170789993, + 0.6081573432926339, + 0.5220167791849478, + 0.49808089173313963, + 0.40835055232606554, + 0.4110117695683997, + 0.44988973122092746, + 0.42452729021967084, + 0.6556279921413435, + 0.44484957667191977, + 0.64193964929236, + 0.7260752041324244, + 0.4629515201284684, + 0.49099689679371217, + 0.5461762164931631, + 0.4822335234689162, + 0.6549310470404883, + 0.4965106735622709, + 0.6924619787130168, + 0.682484915479812, + 0.5001257494741765, + 0.6408708547009532, + 0.5055997408813717, + 0.5366787308271265, + 0.5623859784983327, + 0.5067661438964589, + 0.7081323867146623, + 0.6164168157039912, + 0.5534550365649487, + 0.5076662645923985, + 0.46272138876700447, + 0.4364345409677805, + 0.48389665820909306, + 0.4113351046948784, + 0.4012515614945821, + 0.6207720800380874, + 0.5961513547378744, + 0.5708653270528634, + 0.5483787881495392, + 0.40780914702429105, + 0.618640131323588, + 0.6293227801393178, + 0.5366624727510629, + 0.5612815016216522, + 0.5752739683273256, + 0.4319656694925026, + 0.512568429622798, + 0.43294745239730825, + 0.48189996418048087, + 0.6077162174797164, + 0.46467304013277677, + 0.6162283932552663, + 0.41831516764947607, + 0.5398292215406648, + 0.48388742847477895, + 0.5234673127237562, + 0.464135053282446, + 0.5735752402952795, + 0.45163053409201187, + 0.6386316125271752, + 0.5716817267184622, + 0.46992539927830274, + 0.6368255739087946, + 0.5915977475969985, + 0.4869333508379078, + 0.4474536919444014, + 0.5072267481795428, + 0.4622044971575666, + 0.6400037060349231, + 0.5337432405657528, + 0.5771704834155441, + 0.6251573731419591, + 0.6071074994532331, + 0.5499464270377855, + 0.5783257691480232, + 0.6323959216359918, + 0.6299743021974435, + 0.6343377597052489, + 0.6012028675512113, + 0.649442380497861, + 0.47042151171370833, + 0.6367775571591908, + 0.5017560203584681, + 0.5237476419727898, + 0.594611765756906, + 0.6522048110652325, + 0.5880077161126656, + 0.5101207263053195, + 0.4355810669367769, + 0.5736628672317214, + 0.44991193852078804, + 0.4972190529418692, + 0.4553790129714437, + 0.6522353004498564, + 0.4889846831831124, + 0.6071448083726405, + 0.6116716225133615, + 0.6471835934568928, + 0.5922143577099509, + 0.5087543881189583, + 0.4077416483591938, + 0.5123242524652428, + 0.6521490935029612, + 0.5121072964829457, + 0.5928070823981054, + 0.4123423755767302, + 0.6396315602763438, + 0.598786892950782, + 0.6346358175707976, + 0.5558692099452586, + 0.41940099747313275, + 0.549236264251703, + 0.457155369806929, + 0.46768044077469456, + 0.5752691213751319, + 0.6063436880860669, + 0.46080114683209444, + 0.41628561549226556, + 0.586878042995265, + 0.40057104196552157, + 0.5500987629625038, + 0.48140640156015924, + 0.5460325650906033, + 0.5574981671023108, + 0.4973023880619814, + 0.46541266017591887, + 0.4986814804967506, + 0.4139698089696885, + 0.5486182217055481, + 0.4360394175988678, + 0.5084753050487986, + 0.5854231016597677, + 0.6158975497891761, + 0.42671566628190405, + 0.6171787511965658, + 0.40055696756925874, + 0.40093360679028706, + 0.518481046606757, + 0.6454545666068143, + 0.6299823581676112, + 0.5104955494047165, + 0.6422402825143452, + 0.6380769308287103, + 0.5932140597559574, + 0.515033406266093, + 0.6477781281058462, + 0.44477818303358646, + 0.5750185589219238, + 0.6460149202368703, + 0.4357432806262208, + 0.6138467588945533, + 0.441436545797242, + 0.44950907557997566, + 0.6048225400529006, + 0.5787204133797021, + 0.6536952688990205, + 0.5008921781036141, + 0.46913214896678307, + 0.45559624440476737, + 0.5593363497966823, + 0.560556643114336, + 0.5609793902196034, + 0.5184953944162378, + 0.4899926943129563, + 0.6545880951172638, + 0.48920648438696357, + 0.5513543721014339, + 0.5657819667755097, + 0.5803559890766095, + 0.47331509575675934, + 0.42744962487064686, + 0.4195089757913908, + 0.4855163856934827, + 0.6523250578830628, + 0.4545660423689727, + 0.5327962194924732, + 0.6230059043194983, + 0.5029984307671527, + 0.45032286463408977, + 0.5196921375195644, + 0.5436391850079063, + 0.42342411639713634, + 0.5804084123199116, + 0.5643855466014904, + 0.4767024209637876, + 0.535707461407084, + 0.6383805549973335, + 0.5282668698801886, + 0.435922736409369, + 0.5875448215258422, + 0.5598682533664909, + 0.5190529454921466, + 0.5815354582266474, + 0.46319020574952036, + 0.4235765446494151, + 0.6464894738039263, + 0.5707007414308338, + 0.5572614014309527, + 0.5454816957188213, + 0.5531063736458377, + 0.5044440854779821, + 0.6155749497271521, + 0.6078610820552387, + 0.4624476341541934, + 0.48863407173367274, + 0.5618201199929186, + 0.438023057358969, + 0.43123007183520373, + 0.4504703049562432, + 0.6073725135468728, + 0.4158359765866645, + 0.5608939237494288, + 0.41297251205661245, + 0.457716684938946, + 0.44421599334184014, + 0.4450741334997806, + 0.47347856920582826, + 0.5455143493685912, + 0.429037541460792, + 0.6068859893229335, + 0.4359298572080063, + 0.6144000570883643, + 0.47873253019047135, + 0.5500645460316145, + 0.6013322059881417, + 0.5990547437726306, + 0.6271294130973886, + 0.6056731256519923, + 0.513307023308659, + 0.4819813582388078, + 0.4775323861589369, + 0.5447048219302508, + 0.4848315893509241, + 0.6376053364652015, + 0.4764836989052056, + 0.4741996771228081, + 0.44019064330167273, + 0.48760610317428876, + 0.45955301580769303, + 0.5182784119525621, + 0.5364320157986044, + 0.4956519269873865, + 0.6539885526372, + 0.567198514168222, + 0.6307723269976804, + 0.4898974807390413, + 0.46506496882546855, + 0.46149039658697677, + 0.40920495046529654, + 0.6588284891555258, + 0.5544356601399891, + 0.5236408562560325, + 0.646250675486232, + 0.4051581135567612, + 0.5457924237880079, + 0.4024738485148646, + 0.5426822026758343, + 0.40228207128487814, + 0.4656389714495799, + 0.5668420475100542, + 0.5961615994615863, + 0.6053464687929706, + 0.5723689902605406, + 0.5000325077043523, + 0.5896601359967215, + 0.5909438731026624, + 0.43948765733235634, + 0.6399666538989331, + 0.4828202690451645, + 0.645407770916594, + 0.427897987982255, + 0.4352769803109064, + 0.56462607959784, + 0.49733075419021155, + 0.40312196962287766, + 0.5498606812113684, + 0.5469610018491142, + 0.5367432198425539, + 0.4332182607043163, + 0.4446447696610409, + 0.4551877845871206, + 0.5721663208843233, + 0.6336549365797642, + 0.6121960818792974, + 0.4868052716310646, + 0.4360809919207097, + 0.6052223684600854, + 0.566360909701438, + 0.48405593041236566, + 0.6028466173265246, + 0.41162647374094474, + 0.48078097325795793, + 0.5049607823199299, + 0.4483660233804919, + 0.4541665596277253, + 0.571752615417818, + 0.605483624769811, + 0.41535724950844577, + 0.5407634370202269, + 0.5257620847484973, + 0.6471083449201885, + 0.5077125278042915, + 0.4633592887993617, + 0.461068709953705, + 0.5243746641517235, + 0.6514109652246516, + 0.5505035766292172, + 0.5281615593531124, + 0.46378780152614746, + 0.44655153057339314, + 0.4981157493885614, + 0.6403869198123393, + 0.46416435023925984, + 0.410621250375388, + 0.6440451758912564, + 0.6282840727474069, + 0.6347530332932844, + 0.582830547620744, + 0.6489418199143658, + 0.4973296167979319, + 0.49048496892144766, + 0.4306570560148095, + 0.6398821990471807, + 0.5629683003972841, + 0.42552092178093387, + 0.40545322177018633, + 0.5636972405769208, + 0.6029332695308818, + 0.5882158283415386, + 0.5465642799205186, + 0.4638407243522922, + 0.572890834914369, + 0.4707383489376118, + 0.5747303588983329, + 0.643546671732264, + 0.5903462615958668, + 0.436358599799576, + 0.4693469021071932, + 0.6178975297283477, + 0.6068496470103117, + 0.5834306179358026, + 0.6155750357358664, + 0.5324840583572401, + 0.6358718477565177, + 0.5471357835581592, + 0.6480611879769194, + 0.572867590015565, + 0.600600596868158, + 0.4150925027891145, + 0.44076440206020284, + 0.6274333847312059, + 0.49672439609344043, + 0.6429017763711815, + 0.4049279136192041, + 0.6596460415195489, + 0.5793678653887642, + 0.6325341188479074, + 0.4832637697989492, + 0.4664450556565028, + 0.6056978138138153, + 0.5842828600956785, + 0.5033215825489696, + 0.5728760260565409, + 0.5174085634212143, + 0.5717790009661744, + 0.5639821425988465, + 0.4631276735011309, + 0.5632258048655526, + 0.6300517284955696, + 0.6358072544352944, + 0.505106273530319, + 0.5820599124747323, + 0.648101303446179, + 0.5838445734938056, + 0.6501104381594727, + 0.462144345917158, + 0.546579964945766, + 0.5787796293271681, + 0.5156040161383555, + 0.6273137200827746, + 0.5364459723876931, + 0.5464404490151411, + 0.530890124654465, + 0.6556483419300109, + 0.4689274138685841, + 0.46429721476669683, + 0.6371649336265313, + 0.6450222922935737, + 0.43964382675054814, + 0.6487687031878133, + 0.6189192672318741, + 0.4096633489975282, + 0.5050370419712974, + 0.4081010340506279, + 0.5124509023177971, + 0.46788012219326275, + 0.6010890411380999, + 0.4240310244606508, + 0.4879322210638348, + 0.5843606918417728, + 0.45392053992759496, + 0.47379418142028074, + 0.473930866278485, + 0.4458531712340127, + 0.49672382859818376, + 0.5424216337020509, + 0.4974691368689337, + 0.5320183745219033, + 0.5035635521897172, + 0.5305504964966994, + 0.5205870267262976, + 0.4629001781834452, + 0.46151312723593113, + 0.5831584535890524, + 0.6122389576862773, + 0.49618280238443346, + 0.6012055739750187, + 0.650446402652845, + 0.5263733935257224, + 0.6287156115017546, + 0.6429463474690869, + 0.5463605893110719, + 0.6410339880298933, + 0.5307380342766035, + 0.4687987212366419, + 0.5629450422877249, + 0.40380515474076123, + 0.5971169479170553, + 0.4506306639827594, + 0.4979448813981393, + 0.614346078392501, + 0.5332968021740876, + 0.6223742994920685, + 0.5090439102344612, + 0.5892310655690502, + 0.6580886911994808, + 0.5040439665338506, + 0.6156619477270301, + 0.5298023325187776, + 0.5937285237220136, + 0.5643812727900703, + 0.5822845795073602, + 0.6463556450597989, + 0.4301606519800736, + 0.5374671961683926, + 0.4927016412776436, + 0.5103326191146963, + 0.6427318562946907, + 0.6442471761035989, + 0.6348762792386162, + 0.5318136717315854, + 0.40266029625390487, + 0.5627279108295205, + 0.6305010092106391, + 0.5164740250707055, + 0.4858012052328648, + 0.4084430771509089, + 0.5962446349474523, + 0.4639308681127595, + 0.5736249419775283, + 0.5974706097814659, + 0.530656365703156, + 0.6351665947871005, + 0.45104169985017356, + 0.5085952662214055, + 0.5726063975763926, + 0.5061740050331773, + 0.5437015039620299, + 0.4075343036587966, + 0.5021522949595829, + 0.4264603837902778, + 0.5113221135388446, + 0.4964442799598707, + 0.5435597600192459, + 0.5796287172627786, + 0.43961762684838407, + 0.45227809697745525, + 0.4800814485915506, + 0.4234191008617116, + 0.4443805873307077, + 0.5391215095588682, + 0.6350085542838835, + 0.6041870919219567, + 0.5201223312017705, + 0.46609895269230217, + 0.6335633110270268, + 0.5483976564854491, + 0.4568454354116727, + 0.43383416738135483, + 0.4018931001541899, + 0.5656555831998052, + 0.6423546264105209, + 0.6183089196502182, + 0.5908135418060904, + 0.5341000844706856, + 0.593205094964126, + 0.5006255980248459, + 0.647846782972948, + 0.6568325390363818, + 0.5862585894957599, + 0.5449593148432165, + 0.5158422872605388, + 0.4953134581991899, + 0.4259178955363384, + 0.5804039421153552, + 0.556116524499544, + 0.49003561612638585, + 0.4038848941066572, + 0.5768093765667689, + 0.453051338237836, + 0.5803783484218947, + 0.6286809301497045, + 0.4858688724642324, + 0.43686244740523983, + 0.6456085055616426, + 0.5541010747136927, + 0.5491655094375817, + 0.5520836862020924, + 0.44213448358649654, + 0.5533373365950223, + 0.5036162895850591, + 0.4340764697367166, + 0.6143638963668624, + 0.637133959155418, + 0.631825819479559, + 0.5568473822589188, + 0.623332976058615, + 0.6503946136155863, + 0.44781624522359603, + 0.5373662461435986, + 0.6309142269872648, + 0.5543087357829548, + 0.6273438302668779, + 0.4602757527683205, + 0.5335411241976747, + 0.5885223116415561, + 0.4805842906318269, + 0.5422995508927312, + 0.627526947635203, + 0.4112766717888698, + 0.4820787810084398, + 0.4413764026690947, + 0.5069861563149011, + 0.5989168827775804, + 0.4549472453330533, + 0.6380504950280377, + 0.4423532527506609, + 0.4116289455867016, + 0.5027350895797852, + 0.4707723343170763, + 0.6323727170247521, + 0.48276144403965504, + 0.6592076994282596, + 0.4704760563534601, + 0.6389251376409114, + 0.6042995420260848, + 0.49564718821472503, + 0.44571439429150345, + 0.6237234848289868, + 0.655258832738134, + 0.6586296177682585, + 0.44796177701076706, + 0.4032642044349047, + 0.5868666343653569, + 0.40131298663445564, + 0.4430615568163212, + 0.443659413563159, + 0.523610983217624, + 0.45570183752967086, + 0.5544687238468554, + 0.46993259195741277, + 0.5275448487996509, + 0.41325477977737324, + 0.5884396979516803, + 0.5252251218258592, + 0.5150056973781693, + 0.49059553709950243, + 0.4489163377043396, + 0.40233771571850613, + 0.49034691185317847, + 0.5434573825031971, + 0.5635379503717719, + 0.6391102029980231, + 0.5808636362134735, + 0.5534998191078517, + 0.5682145484024066, + 0.6562790178131113, + 0.5825672460962058, + 0.5678683052851997, + 0.5357597805974732, + 0.6059104138546034, + 0.5617194556199133, + 0.5826109542112923, + 0.4580572083264981, + 0.4739612858681359, + 0.610220432406925, + 0.4291298269360288, + 0.5619530574778425, + 0.6263737963697418, + 0.44249393925201014, + 0.6473052230186249, + 0.4503981658626414, + 0.5687774823073413, + 0.4003586648222098, + 0.5133056248198039, + 0.6541532471105029, + 0.6570138326843886, + 0.5937476770879894, + 0.4333851015168719, + 0.48063428882955045, + 0.6583869020439117, + 0.6526649095287794, + 0.4016924636122446, + 0.6056656207264827, + 0.47834090648141214, + 0.6282322391696599, + 0.4724555273889177, + 0.5530461965417485, + 0.4688772539140993, + 0.45631066122917996, + 0.6075128727248614, + 0.44273642489941806, + 0.547608115901881, + 0.516012284217532, + 0.4746460636410013, + 0.5484337782982895, + 0.5576845031773455, + 0.6437876609810369, + 0.5411184036654377, + 0.5450740880699039, + 0.5543458809390877, + 0.6392220305692962, + 0.4922104259303519, + 0.5449190356953227, + 0.4698360828199552, + 0.6235399979917964, + 0.5167701957841768, + 0.45911205307079356, + 0.5019595853364736, + 0.6390297488095305, + 0.6281488069095245, + 0.47526041452312295, + 0.5314210703432511, + 0.47640176438717713, + 0.5962187947902282, + 0.6406547310961059, + 0.4075084403099539, + 0.5010950133073395, + 0.584995163995025, + 0.617538676545889, + 0.41715213611060964, + 0.41567466925182267, + 0.4081195256803564, + 0.415259696052004, + 0.4127561714894642, + 0.41384235717398793, + 0.40618016984354316, + 0.40774957461553596, + 0.40642865725535154, + 0.410909162199514, + 0.4025801810062359, + 0.4049553686815353, + 0.41733325934814397, + 0.40987194906525826, + 0.40316574293414026, + 0.4092789892119147, + 0.41558447514389574, + 0.4097478599295288, + 0.41656296465893694, + 0.40475907535144456, + 0.4054084949011248, + 0.4069318624614578, + 0.41232830318454067, + 0.4132520485410743, + 0.4063803876247479, + 0.4122607404584897, + 0.4108350513643708, + 0.4163473031456735, + 0.4092995473138185, + 0.4104936115604722, + 0.40452306368561847, + 0.4095935473080143, + 0.4040496705273514, + 0.4127648549070418, + 0.41519357777890425, + 0.41000851148010686, + 0.41289521558780184, + 0.40077751511579024, + 0.41317152659178696, + 0.41205817346589435, + 0.4160950932704991, + 0.4014814196845411, + 0.4073466191856013, + 0.405547917191715, + 0.41290887368111856, + 0.41365877627233516, + 0.4158407598301966, + 0.40834655174783213, + 0.6186637565916807, + 0.6658214961787039, + 0.6260463787740848, + 0.46830497966527695, + 0.4733657017986268, + 0.5050458657711117, + 0.6275143892657398, + 0.45664004041263384, + 0.46751900774473343, + 0.668468495892399, + 0.49014308311517885, + 0.49397214714646515, + 0.6023363533340425, + 0.5002192783674755, + 0.5791624629009748, + 0.5448779442918705, + 0.5129878791208068, + 0.6710352802599475, + 0.5735367426530219, + 0.5938652280318285, + 0.6536252079992941, + 0.536927144811494, + 0.6296797403387018, + 0.5018047763971802, + 0.5876697950285332, + 0.6539829342824764, + 0.5820849130477652, + 0.5626204223417804, + 0.5700150584044282, + 0.5166279909405074, + 0.6143590899105231, + 0.5750982296369369, + 0.6280643002383485, + 0.6168004250177805, + 0.6043857232280778, + 0.42751958434879356, + 0.5496690104076866, + 0.4370959908554541, + 0.44423776772653106, + 0.6279665816462515, + 0.6632479083626908, + 0.41844414363785887, + 0.6742851519546087, + 0.5197739294561196, + 0.5615944720474719, + 0.5797524757413925, + 0.442699851170146, + 0.4712140112428712, + 0.6162036196900753, + 0.47482837648456405, + 0.5622439102276048, + 0.42094473232562113, + 0.5788261208529526, + 0.5736105753060249, + 0.5489802624392789, + 0.5186302603841612, + 0.6122209931915774, + 0.495263504285981, + 0.6171953330956156, + 0.6160691882357137, + 0.5688221369111166, + 0.6475695609960295, + 0.6735013486032837, + 0.5934608294238715, + 0.5432862974302196, + 0.639901105525931, + 0.5058420622382138, + 0.5142854244924218, + 0.4485880670461578, + 0.5935863080741683, + 0.6003069124296949, + 0.5344324716645976, + 0.4555084458505755, + 0.4805386905503884, + 0.6628799917510739, + 0.6365522176722308, + 0.47411320904679877, + 0.4918592686373214, + 0.6027577309769714, + 0.4622589938393244, + 0.6511388445365329, + 0.5587991915258127, + 0.49037598264548327, + 0.6418871925947728, + 0.5022241809424575, + 0.5139927553577128, + 0.5659792619121191, + 0.4820597321775048, + 0.5840786972570535, + 0.499499704340124, + 0.6259647625481699, + 0.46800341071635726, + 0.5933749257558866, + 0.5724583278721074, + 0.6453328850568858, + 0.5014878460018638, + 0.6445240163233446, + 0.6560310500454434, + 0.5166733140678633, + 0.6236628132952294, + 0.482700797908143, + 0.6192884747255105, + 0.6676246844938001, + 0.4586887919912696, + 0.44048992373130663, + 0.4354915623588556, + 0.5626206418582683, + 0.4435407241344718, + 0.5451502772227782, + 0.6453932596364187, + 0.6149702350845138, + 0.449404672897951, + 0.6403502159732428, + 0.45387373931965197, + 0.6623411207334008, + 0.4644333097027678, + 0.6595830332579885, + 0.5368755611427354, + 0.4838580589489046, + 0.4184882519846429, + 0.6626038902622227, + 0.4315497765532917, + 0.44641628416424245, + 0.6510464644664149, + 0.4208694000232278, + 0.5525269580368244, + 0.6152964067551826, + 0.6140228632148464, + 0.5334864053652251, + 0.6036437119974788, + 0.5623778518056581, + 0.5710770236231749, + 0.5354446290796452, + 0.6327509191580178, + 0.5180992023805325, + 0.6005450267359768, + 0.47227319823062064, + 0.47556114392094717, + 0.6274801955858987, + 0.4418810320119001, + 0.5968921163234591, + 0.542780890317585, + 0.4857908180747811, + 0.6560917564755215, + 0.6741073206814161, + 0.5856835471089571, + 0.6401820284603188, + 0.5826038706895031, + 0.6037719789982001, + 0.527851590722697, + 0.4719844336857817, + 0.5494374390590825, + 0.5036046514582513, + 0.6091650778865884, + 0.5291011022260989, + 0.4465342108199755, + 0.4743077490427661, + 0.5093669749650672, + 0.6429961360322435, + 0.6061032730503517, + 0.6300792623602193, + 0.4333053990982793, + 0.42541490937476767, + 0.4588636292544824, + 0.6661290223195402, + 0.5602819505876193, + 0.6246733669102296, + 0.6313727161074643, + 0.5527047455254466, + 0.6236652329339458, + 0.5663257044991242, + 0.4178751739938489, + 0.5969002079614806, + 0.4652487956695667, + 0.5562649309103779, + 0.5290674766398449, + 0.5231930658568147, + 0.6493099313797918, + 0.5720159624884077, + 0.5296005021264805, + 0.6410735124095235, + 0.5031685560960558, + 0.6538758564863563, + 0.4963997230936588, + 0.428315562330616, + 0.4396436709997804, + 0.4325237282497374, + 0.42727512917130595, + 0.5663284361208947, + 0.48877671190782257, + 0.663831511086579, + 0.5095610234553268, + 0.5736984619929075, + 0.5044045723203884, + 0.42556490180012396, + 0.5452352666929086, + 0.6703836005132262, + 0.5254596510551122, + 0.44974896965638916, + 0.6127431982856013, + 0.5208441692689937, + 0.5727787041360132, + 0.5882211762462828, + 0.4696649882925092, + 0.6198329090109307, + 0.6598051273374933, + 0.472623981555314, + 0.4256660124347717, + 0.5275252575478494, + 0.5613420428623683, + 0.5177316290023202, + 0.6446208801243914, + 0.4198637965942361, + 0.5011759787151067, + 0.6285192650424437, + 0.6738710721847547, + 0.6565468486059718, + 0.5139447463369823, + 0.5618176013260285, + 0.4870741166379393, + 0.5108544021329618, + 0.4445603060891902, + 0.42246517381869064, + 0.6485527766010981, + 0.5569206798438465, + 0.5147669620850512, + 0.6141770831590854, + 0.5596763597587201, + 0.6530469725268343, + 0.6341700352057138, + 0.5088728758159722, + 0.539188641635253, + 0.6646998861969275, + 0.5900766135395288, + 0.6402922617267738, + 0.5335857780788268, + 0.5257450205935756, + 0.6009861995400703, + 0.43306228076720454, + 0.4724183064109975, + 0.4522001308353273, + 0.452128814717727, + 0.45162240875289655, + 0.6599172601595222, + 0.672781678496674, + 0.4385619074701898, + 0.6295975680444447, + 0.5099783978183313, + 0.6550681783288972, + 0.45731945225931436, + 0.630189788549893, + 0.43553364920351084, + 0.5531566208606844, + 0.4842927174794085, + 0.472214602413611, + 0.5415864665260591, + 0.6057672510520563, + 0.5635305833227353, + 0.6049021091578395, + 0.6076710972941849, + 0.5868005162012435, + 0.6384947433493431, + 0.5261436932977139, + 0.4517692856477109, + 0.6379305145044951, + 0.5617183866265407, + 0.42922629568339765, + 0.5297132974241568, + 0.6199275679891976, + 0.6028624113739511, + 0.6110289096749643, + 0.5683920136223413, + 0.5533598371872335, + 0.42004956252282016, + 0.5055245969859351, + 0.5431013695447988, + 0.51069828275399, + 0.4555634554744861, + 0.5293068586240174, + 0.5295406979880246, + 0.6385710041721991, + 0.5149590132886619, + 0.6735257697925201, + 0.656476631309893, + 0.4941214853351421, + 0.419549268473238, + 0.5605883986246747, + 0.5872130542949496, + 0.46735464818371336, + 0.6575943034671545, + 0.5682247592770637, + 0.5758652521271134, + 0.43316910678293175, + 0.4186578071657144, + 0.4524279823888852, + 0.4377663647822437, + 0.5780068727641376, + 0.5351304543630072, + 0.621482682158919, + 0.501234869076283, + 0.6292862113191577, + 0.4437540507392766, + 0.47538525849489827, + 0.567960404932031, + 0.41924587871126356, + 0.49189135867104045, + 0.48752792156848224, + 0.5406801451402393, + 0.5475501736011475, + 0.6411963679840172, + 0.4921241738796809, + 0.5411806179986013, + 0.5976952218508476, + 0.46961080180107506, + 0.4734623030039098, + 0.6162910775974662, + 0.6515470162865886, + 0.5402820677484286, + 0.6584615304174679, + 0.4496321756018056, + 0.5851470810409601, + 0.5846858053969799, + 0.6162425942344473, + 0.44177445966835804, + 0.6368853228109935, + 0.6345227807364637, + 0.49880598602589843, + 0.46417654792928265, + 0.49365758638629614, + 0.6021404954722136, + 0.545470468274503, + 0.5495305679186745, + 0.5519219494171448, + 0.4749966022943994, + 0.47412492227390846, + 0.672137909903481, + 0.4996233961250569, + 0.5628492969741627, + 0.48910080147096846, + 0.6571813182926496, + 0.5312782705106229, + 0.5693399802668421, + 0.6249813623245736, + 0.5493605187861549, + 0.5583558080947093, + 0.6202289341295663, + 0.6667825927576305, + 0.6404249544153029, + 0.5361597745365673, + 0.6221156468699925, + 0.5422891225837555, + 0.5945602572036308, + 0.5377660460246316, + 0.6642602651412424, + 0.5835855528728072, + 0.6577297891809901, + 0.6235219279555905, + 0.665072143892804, + 0.5092230298993623, + 0.6522569027939403, + 0.48511332345182334, + 0.4522267702181343, + 0.5857470570787461, + 0.5523752745957272, + 0.542372949220619, + 0.4415407608636265, + 0.515764758710309, + 0.566482765145498, + 0.5494312853850423, + 0.44304245740979387, + 0.5527813701265438, + 0.6377326741241712, + 0.4937561586053217, + 0.5456882762315907, + 0.5955968364334099, + 0.5592880490683303, + 0.6012674887013061, + 0.4839009924934923, + 0.6436578612187887, + 0.5859010507817054, + 0.5444764682400671, + 0.4212399820181285, + 0.5402197008871515, + 0.463893492575928, + 0.44282316341458466, + 0.6077839851231553, + 0.44782262342670764, + 0.596033866268329, + 0.47358260417099063, + 0.652165284607904, + 0.4891401544281598, + 0.4884382640289997, + 0.6322824943535681, + 0.5005117496688781, + 0.5116280012235664, + 0.488204485417408, + 0.5122667894293349, + 0.4339758763177964, + 0.6081640074032075, + 0.6092953304464968, + 0.5526203641392282, + 0.45257768677385557, + 0.6047011326200028, + 0.4962005285685325, + 0.49533655945769645, + 0.4347757486911363, + 0.5846586261174054, + 0.45432342800085335, + 0.48001722516523143, + 0.6409704415335606, + 0.4859482622465814, + 0.5450892861913625, + 0.6318245030614065, + 0.5419666770966015, + 0.43176876923911134, + 0.5886099887223875, + 0.6571181551765193, + 0.446505299881494, + 0.6752190145738031, + 0.47101296765141376, + 0.5807612312660688, + 0.43251822804127943, + 0.5283702830885456, + 0.6536622716457052, + 0.5680400172427887, + 0.598904579803651, + 0.49476383730219686, + 0.6393818794750392, + 0.6749314268766788, + 0.55674965301081, + 0.43488071618182783, + 0.6442618573047081, + 0.582665888336034, + 0.5870464549264336, + 0.5989751029886299, + 0.5668745197527779, + 0.6348844881055099, + 0.4187933008921511, + 0.5228149681086238, + 0.4732000913077427, + 0.5250127529265971, + 0.5476985847835315, + 0.6360812304605248, + 0.47956229869254574, + 0.5085972201563821, + 0.5528653680922497, + 0.5378607445847261, + 0.4320476226204505, + 0.49519368533010893, + 0.4317705231683043, + 0.44009562087330056, + 0.4367647485048963, + 0.5000001691813895, + 0.4378796916746941, + 0.4932362206360679, + 0.6684219089464984, + 0.6391066412325059, + 0.6243094785813236, + 0.42729287857248205, + 0.5622567648276499, + 0.4469449138010813, + 0.44255345962592957, + 0.6056175798414283, + 0.5977396269156028, + 0.4472499227985556, + 0.6260232874275055, + 0.6185773026322541, + 0.5476493028014249, + 0.5655955226690892, + 0.6207372844570105, + 0.5806971478739439, + 0.673193734557657, + 0.5358588707320849, + 0.4650918545092592, + 0.45119934728023936, + 0.47407149271119603, + 0.5124633413604796, + 0.6538444798680076, + 0.5469005711931535, + 0.4807725960215937, + 0.5458459733928552, + 0.45312306211539966, + 0.5745984533133206, + 0.6529797697331007, + 0.5041158630541326, + 0.42552223898286873, + 0.49678494144974206, + 0.426303444449098, + 0.5486850889302589, + 0.637643474768241, + 0.5885867418671331, + 0.6604801746120814, + 0.6177578907683516, + 0.43692314979021823, + 0.5634434080804025, + 0.6368424424011969, + 0.4840684240891794, + 0.6034848922318071, + 0.5256969965412744, + 0.4436264038406719, + 0.6543671906542151, + 0.6399719770290165, + 0.5596298722527621, + 0.5388295581184049, + 0.4479736592737353, + 0.5251154991895247, + 0.4212127531099962, + 0.6174296958398777, + 0.6682008831813349, + 0.6061008022956641, + 0.4414591775808399, + 0.5219308249233546, + 0.4397006083913717, + 0.6549175444920357, + 0.4956142518103546, + 0.6731628294936831, + 0.4672512890209819, + 0.646326990423463, + 0.6636012982427719, + 0.4998812175114761, + 0.4851278786141787, + 0.5842500646896425, + 0.4720559343130976, + 0.645523525712766, + 0.4917607904626151, + 0.5011869235208324, + 0.4607192880091755, + 0.6614999679672873, + 0.6012942920203168, + 0.6076271895898512, + 0.6208732040803406, + 0.6154666794152432, + 0.6725475565663033, + 0.46433810079190163, + 0.6097353466706292, + 0.4547631502541668, + 0.47287532413882577, + 0.489312872064836, + 0.5104322848113781, + 0.6499110147950776, + 0.561170926155263, + 0.41832180380981626, + 0.4915424592024694, + 0.4599742414606182, + 0.5717279035126892, + 0.45612667755125313, + 0.6726893972577894, + 0.58385960890337, + 0.6257651076467751, + 0.5359394451946294, + 0.4352347062627171, + 0.6103494956535177, + 0.6005890418349848, + 0.6041906279857178, + 0.5130637982124853, + 0.5176778997749076, + 0.4767805818002884, + 0.47698594573416797, + 0.5589953819581441, + 0.6659235437138485, + 0.6484624784986153, + 0.6325123900795082, + 0.5826376264516105, + 0.6624181030352422, + 0.49022570085521905, + 0.5636995687344764, + 0.5588082333555504, + 0.6413412794538171, + 0.6008055307666268, + 0.6427697128792778, + 0.6641311881230638, + 0.5092291371373243, + 0.566555968235819, + 0.5531158745064284, + 0.5046098807797456, + 0.5520111609104219, + 0.6304417693673972, + 0.505151519058036, + 0.4416020935134145, + 0.646107270868101, + 0.5297204665697003, + 0.4370190418674936, + 0.5672703314233557, + 0.48996856556356455, + 0.6630325622714122, + 0.657373757039599, + 0.580934138353937, + 0.4747809787449257, + 0.4241361644323903, + 0.43640039186373203, + 0.4843622697286114, + 0.4544243854605152, + 0.6577154690447992, + 0.639685305528052, + 0.6587557710526475, + 0.5306128199125757, + 0.6452947644990731, + 0.6357267716749293, + 0.6512078526650209, + 0.6698945814551295, + 0.6299315222741697, + 0.5725488884588212, + 0.5799893302172573, + 0.4693969322126539, + 0.5963519636130984, + 0.45285119809383745, + 0.4877468808898209, + 0.5474766767152183, + 0.4670707518028317, + 0.4272015052992463, + 0.6145498855624159, + 0.5207575117218303, + 0.6612267087410298, + 0.4528896183351633, + 0.5295068831726898, + 0.4941547831637422, + 0.5730361204173189, + 0.6571823337316527, + 0.6759721464718964, + 0.47926080006185734, + 0.5262904413070497, + 0.4642679156983115, + 0.43770142300554365, + 0.520122971212266, + 0.4451343661443298, + 0.42358505874778857, + 0.6146053530176067, + 0.5998849336484793, + 0.4789013654873786, + 0.6704423461945052, + 0.4253071054398781, + 0.6718960897776963, + 0.6382681855275456, + 0.4682248408161684, + 0.43194216987563183, + 0.5138850448557033, + 0.6098098168345143, + 0.5018441748717778, + 0.5319589017828005, + 0.626099558053375, + 0.5646894930749273, + 0.5078125963829955, + 0.6236378601508243, + 0.46906656178847417, + 0.49638092030424763, + 0.641166874718798, + 0.597663350546503, + 0.49918422415926283, + 0.4753699292673029, + 0.5479279915892143, + 0.5467064144451789, + 0.45848594384802216, + 0.5050006174687619, + 0.42278209905959024, + 0.5524511655993667, + 0.6690067711490187, + 0.4601545521144763, + 0.42448772281497676, + 0.4738416354985964, + 0.6019377780091062, + 0.5016601403582513, + 0.649542785483363, + 0.48901226223643623, + 0.5194696101020322, + 0.4449625833158787, + 0.6508870100329195, + 0.4902748908266815, + 0.587377799810794, + 0.5971774628633941, + 0.5513827696042237, + 0.48572390469315674, + 0.6122197396769073, + 0.6030423640464975, + 0.4489806057066333, + 0.5216830998474734, + 0.663559198605107, + 0.5855040429831501, + 0.5751283762463459, + 0.45342637720861595, + 0.5040502483337106, + 0.43940069959398587, + 0.6438617192025182, + 0.449935876787998, + 0.5268066977442892, + 0.43200487315019603, + 0.4308707033078556, + 0.5291570331193189, + 0.5638747385453204, + 0.5303259931884781, + 0.4293667987671472, + 0.4298463634868346, + 0.645908022977257, + 0.4616150551293596, + 0.5295571859601491, + 0.49226411638278744, + 0.4651857187364878, + 0.5175628779023452, + 0.6717375402334267, + 0.6193943324670412, + 0.6543086239643756, + 0.5947291266971952, + 0.567300555216746, + 0.4653847172157376, + 0.5232019071688474, + 0.5401662248804371, + 0.6169356740403316, + 0.558114720551196, + 0.6709036734642972, + 0.46420764460091823, + 0.6269702580676505, + 0.4756628600216278, + 0.43454138924550034, + 0.5511786255077191, + 0.5599807419900495, + 0.6100734279200468, + 0.5705932400591633, + 0.598076806507937, + 0.46683532604330685, + 0.5201893812204563, + 0.6188498402445479, + 0.5322627553912872, + 0.5626770507714963, + 0.5686588638009538, + 0.4283329020393113, + 0.48289886219028033, + 0.6123453418842592, + 0.5727520762190752, + 0.6506406451831679, + 0.4843431393525188, + 0.4712449180492902, + 0.626059096717345, + 0.46444556223131334, + 0.6622674463004574, + 0.5847215223149224, + 0.6635176951730459, + 0.44211645609921313, + 0.5812611715170566, + 0.5935015511030367, + 0.6723581535655567, + 0.5811996592880234, + 0.6051260217592425, + 0.5013212769779508, + 0.5747407297802682, + 0.5893632820482739, + 0.6752715355045844, + 0.5120855602655245, + 0.5959157544678947, + 0.6341078325395165, + 0.4796038143099947, + 0.5143740220338999, + 0.507940479133872, + 0.5504318323413937, + 0.43917226557999356, + 0.5803683053408988, + 0.5839019837110467, + 0.6391547741754122, + 0.4213278721014795, + 0.6506167167419604, + 0.48057559087130786, + 0.4589982186304581, + 0.6063292558841016, + 0.46640835557887117, + 0.5997102794048879, + 0.6429561835775335, + 0.43635024335349, + 0.5202947109776997, + 0.6204482975901258, + 0.6272470148031342, + 0.6114382885648084, + 0.600214836618274, + 0.6260491240216263, + 0.5471449747602166, + 0.483435053612012, + 0.44098449179463284, + 0.5276655305445258, + 0.5027416850512085, + 0.6663330275757455, + 0.4689910311457727, + 0.43343829316455373, + 0.4654772277516001, + 0.4878292390119595, + 0.45771757712107497, + 0.44113241935386116, + 0.5361759297183487, + 0.4320449592678545, + 0.5185808321255505, + 0.5222659290792272, + 0.5979957653932836, + 0.6458864276831328, + 0.4444388475657291, + 0.5087232837854605, + 0.5777054162275688, + 0.5110753800421013, + 0.6563102804975645, + 0.5641161982274984, + 0.633148875245892, + 0.5776176663314918, + 0.5295769898879016, + 0.4937347110090873, + 0.6042891160011343, + 0.6206414575978353, + 0.6576942811166779, + 0.4696725811815, + 0.6589932083091092, + 0.5678525912299092, + 0.5908502688898118, + 0.5441275604322948, + 0.66653167217061, + 0.4677679104890484, + 0.5688595138764243, + 0.5060107386556006, + 0.5827265194248104, + 0.596126572206028, + 0.49818523914105234, + 0.4982341029334998, + 0.46430523926438866, + 0.6252246423612321, + 0.5602278955723731, + 0.6597785186051324, + 0.4949156511442636, + 0.4305445277092178, + 0.500536246153343, + 0.6529708383963886, + 0.6756708562290121, + 0.4635134568913601, + 0.42066686158790184, + 0.5481191799165859, + 0.5138203526161884, + 0.6394441666449984, + 0.5156125741315041, + 0.5042526992528915, + 0.5957743411428282, + 0.4857537584581223, + 0.5254770345633826, + 0.44480495886484406, + 0.5055859987820908, + 0.5564093056666319, + 0.6287957573697326, + 0.6639847815837505, + 0.6099976449982817, + 0.6099981726560155, + 0.6438447337211566, + 0.561913586624349, + 0.6368837061016767, + 0.5705895168845608, + 0.5989722248021062, + 0.5747121354813229, + 0.43858993046493844, + 0.5386441562330112, + 0.6592513198093767, + 0.5168602688217628, + 0.5523727081674877, + 0.6091762315661171, + 0.5543408100669136, + 0.4298296188141463, + 0.6336872423796126, + 0.6501279412541047, + 0.5413340501468423, + 0.6343202858020961, + 0.63971845201489, + 0.5176003925160564, + 0.6325645960516729, + 0.5579512672466466, + 0.6142445566646662, + 0.5542726194218361, + 0.4674306218329813, + 0.6451304398424416, + 0.501423913297982, + 0.49547478051090366, + 0.44091315058639885, + 0.67612785107939, + 0.5077084071042915, + 0.567738744947256, + 0.6111882513597162, + 0.6567208198918738, + 0.6184597705078414, + 0.6633494014071144, + 0.6725262897471082, + 0.4807870033468508, + 0.5155401155300986, + 0.5991896241108634, + 0.6476244020177709, + 0.4256282159591093, + 0.6302100635701158, + 0.5699585996967419, + 0.5900002820518522, + 0.49000321695818627, + 0.48916164227894454, + 0.46842429149657877, + 0.5995220770368569, + 0.602844282212248, + 0.48714890738021754, + 0.5754771529036167, + 0.6251402661099685, + 0.6689397909509013, + 0.5392346957926715, + 0.615668358446007, + 0.5253080903775751, + 0.5466375532210562, + 0.44498427418670766, + 0.46508050056951616, + 0.607723127995853, + 0.449109380818582, + 0.4788019591261244, + 0.6390101623691643, + 0.45200313737958575, + 0.5530739672108212, + 0.4233524877990753, + 0.6438637604465965, + 0.5955448332479023, + 0.5423833858900065, + 0.44908558766074885, + 0.5311714392075653, + 0.4514007158486212, + 0.6161292686085192, + 0.516762799139641, + 0.618128536201714, + 0.4997598016993501, + 0.6695433575507317, + 0.5436005416044496, + 0.43568294373019295, + 0.5483429320551184, + 0.5678179852304454, + 0.6277294216356517, + 0.5323047200927394, + 0.5672290394513544, + 0.495106569181642, + 0.6182580077526791, + 0.5337376429104425, + 0.5741367286715391, + 0.5864315044872417, + 0.5160573425288094, + 0.6672788744843194, + 0.5430932223280925, + 0.6649310429458581, + 0.6606263725376855, + 0.5516723950423116, + 0.626969289302088, + 0.448945587646302, + 0.4949997170632518, + 0.48745044763444445, + 0.5674079061141981, + 0.4310005816419374, + 0.5998221782980577, + 0.6720817907123855, + 0.4970373612487736, + 0.616848700692135, + 0.4514854689646, + 0.5788225559910173, + 0.5139259475517826, + 0.6069316801187977, + 0.4930694536410664, + 0.4509350272929651, + 0.6391390039946321, + 0.4706105426320323, + 0.4308072238238336, + 0.5494920002707673, + 0.550567172842012, + 0.5064704670889415, + 0.6687571253126972, + 0.4252875630506553, + 0.6648981418164633, + 0.6373179226697653, + 0.5755645426075042, + 0.5247611099500463, + 0.6480683932228865, + 0.5268797989310661, + 0.4287631624932705, + 0.5019482346960547, + 0.5312391026363799, + 0.5419663958200224, + 0.6377767553920065, + 0.5077554055106928, + 0.6040129593482538, + 0.47296573480972454, + 0.6754773839739765, + 0.580106658745535, + 0.4276432373138483, + 0.629560946774607, + 0.5368240031999153, + 0.5514116121831939, + 0.6510125635438458, + 0.6105705106961907, + 0.6480246405311586, + 0.5975590024089117, + 0.6059101092482692, + 0.5873472905784402, + 0.5670098928174474, + 0.5475157506157041, + 0.6185801872363037, + 0.5501714090764107, + 0.6407974413387563, + 0.4650948836049771, + 0.6119148034359145, + 0.42366437900199483, + 0.5525950519190994, + 0.6125160701088854, + 0.6609902172068608, + 0.6014862887238526, + 0.6746754636933474, + 0.4982927573695073, + 0.6389145736710107, + 0.4728955896767261, + 0.6493583479083107, + 0.47402618932098906, + 0.4439964341983015, + 0.6027631461067285, + 0.44843274483855533, + 0.4486753320928862, + 0.5262284168538645, + 0.5700084071382785, + 0.5705814967531783, + 0.515570259499563, + 0.5614124187578313, + 0.45250900085078616, + 0.4656748718121697, + 0.5550184158341261, + 0.48313510299537754, + 0.49371946062905847, + 0.6716292560349615, + 0.6386527839314069, + 0.6317751141927562, + 0.5593568639707345, + 0.604976983931754, + 0.41808122767006123, + 0.5365149841640768, + 0.6020721513697708, + 0.5301725588857653, + 0.6102383370200692, + 0.6248363757608615, + 0.4383824749044205, + 0.5078260638993375, + 0.6164107201137121, + 0.4430416181109835, + 0.5583082238663108, + 0.5346398029475393, + 0.6625426320715848, + 0.5729009325908674, + 0.6548431380712706, + 0.4489218459317534, + 0.569764708215242, + 0.6597510313061401, + 0.46269701301258287, + 0.5656926994116224, + 0.43632007151012314, + 0.6533844400382396, + 0.6572008113168453, + 0.4486128613214948, + 0.515716407098676, + 0.4794804108422735, + 0.5663416789039835, + 0.6138596257352869, + 0.4702287761597685, + 0.4571967914763247, + 0.49095160644725, + 0.5117154260071345, + 0.631816959103217, + 0.5297002822560725, + 0.6221920615364369, + 0.501653658635791, + 0.5476545460108793, + 0.45086069858294153, + 0.44213149156256065, + 0.47047683663655515, + 0.6251854682941729, + 0.5685300420062118, + 0.6483900096425302, + 0.5552833497859515, + 0.4820711053819329, + 0.5880924880902882, + 0.4913115478013045, + 0.5202291118894559, + 0.5173481550539121, + 0.5611645662812318, + 0.5435917290998352, + 0.5458227121365733, + 0.4711399149027056, + 0.47884164541117086, + 0.586758335641432, + 0.4276342185976828, + 0.5441748774094058, + 0.5812586367884944, + 0.6057537700554095, + 0.49061455870483117, + 0.6455704010294107, + 0.6141948239194893, + 0.5369104526484658, + 0.4306212621219995, + 0.6604976064623688, + 0.5588487266425906, + 0.630993005593718, + 0.49201692108324324, + 0.6462217600086144, + 0.48689176022503855, + 0.5970820119993103, + 0.48673969282814594, + 0.48880392917379756, + 0.5196910522942285, + 0.6516639609672149, + 0.48413987382701185, + 0.6162746196919014, + 0.6686144037524479, + 0.5480007766850874, + 0.4616610649899745, + 0.4870627070781328, + 0.6330708253676587, + 0.47716768102227114, + 0.49504668446680694, + 0.643512659066177, + 0.609659169898014, + 0.6027256639770283, + 0.5749312701681735, + 0.6066567695612832, + 0.5936583754386671, + 0.4612976565162898, + 0.6726102374755618, + 0.4965430955190422, + 0.5957261523227756, + 0.5715683263041845, + 0.5897208275802562, + 0.5175287184294949, + 0.5086578401357429, + 0.5706975033123912, + 0.44737520347554444, + 0.46885113054247607, + 0.6312261001288324, + 0.5416869420350455, + 0.6246389069078677, + 0.5017781181884734, + 0.5156538494707956, + 0.5079534323796221, + 0.4403593478920036, + 0.6108580290577519, + 0.615883224225863, + 0.4728743671303, + 0.6549814034207883, + 0.6266212705713861, + 0.5025900197166882, + 0.4272047047369499, + 0.4939331488412162, + 0.5126655597010561, + 0.4581394385335203, + 0.4712228759503606, + 0.4237628663455971, + 0.6238586428429682, + 0.5850495394063926, + 0.5994577631872001, + 0.42717701249832296, + 0.6194655019677118, + 0.5225908557785321, + 0.6286505444230719, + 0.4201119373573504, + 0.5679516064796498, + 0.5903580652886612, + 0.6328799341536309, + 0.5053324459281825, + 0.6072195175128706, + 0.5946366516321991, + 0.48898499353442254, + 0.434580817004348, + 0.602723676797946, + 0.5329873530540066, + 0.48394845278596826, + 0.6372518819339373, + 0.48138445119609974, + 0.6517876095116626, + 0.6673339561064187, + 0.5347577598714708, + 0.4502870581743756, + 0.5439691117597175, + 0.4201118470775914, + 0.45429788401098575, + 0.5347747947678881, + 0.4634870986947889, + 0.5769956626962063, + 0.4296478670853194, + 0.5492912112054913, + 0.4727787774232313, + 0.6029351478565788, + 0.554063240153242, + 0.5647456726155315, + 0.4762428005415566, + 0.41922343208047086, + 0.6107370910173773, + 0.4588336943477205, + 0.5421538207586063, + 0.670069399628596, + 0.611867753846928, + 0.557213413688316, + 0.5063310019584979, + 0.5924880669308283, + 0.4794026074780565, + 0.6394034958681301, + 0.44022545751000364, + 0.6751687160703161, + 0.6644763769804207, + 0.4491439488403998, + 0.6055226058273186, + 0.45902314663746296, + 0.4985624699840063, + 0.5280519113552421, + 0.42513053894611313, + 0.5705044185085255, + 0.5938687034106451, + 0.4824991546437328, + 0.5201799761038169, + 0.6378588687280747, + 0.4221606927871152, + 0.4426130573038244, + 0.6265601276369537, + 0.5877299787556127, + 0.5876811407884568, + 0.6178419383180506, + 0.45505950695307357, + 0.5135016086596155, + 0.5860410079378181, + 0.49451622070518975, + 0.599025123440801, + 0.5577075768704607, + 0.4235901214232942, + 0.4951345858133218, + 0.5975954685282594, + 0.538515284764658, + 0.42207200649661986, + 0.672007301793079, + 0.46459142130737446, + 0.5761051031460621, + 0.43100582390339415, + 0.6239677585330582, + 0.4838616049466472, + 0.45470247486526627, + 0.4673929705819646, + 0.42463174775499757, + 0.5134102641931542, + 0.4880475796424375, + 0.5484534910974355, + 0.45524406544770024, + 0.5656469318259032, + 0.5918452711383174, + 0.6616984822703174, + 0.4388208919060523, + 0.513575244078001, + 0.549104537669757, + 0.4904813069147809, + 0.4277674890452796, + 0.49847767225768264, + 0.572813493639029, + 0.59109859747183, + 0.6135812975385405, + 0.5686482989269631, + 0.6714894211847762, + 0.5816139500621464, + 0.49136479392844695, + 0.6602524063941119, + 0.5084934337410273, + 0.5359078714149633, + 0.5748360205283813, + 0.5014726077765187, + 0.6334426206713405, + 0.5089059306534947, + 0.4792825460476288, + 0.515784409238169, + 0.6022318674679527, + 0.42724499553077994, + 0.60556909805696, + 0.5809755709704891, + 0.45246072460737075, + 0.6051551604686015, + 0.5168916549232311, + 0.6760061762579224, + 0.576429765741346, + 0.6139918930841151, + 0.5187206496881277, + 0.5513428921832595, + 0.5084298951867354, + 0.4297257065404693, + 0.6130519374512127, + 0.6098091763262727, + 0.47414114363953797, + 0.6229945297166168, + 0.47417948866952614, + 0.6237150528616181, + 0.6223083053284715, + 0.6650114575809266, + 0.548640058003776, + 0.6600423102842694, + 0.672198427944197, + 0.5909426419950528, + 0.6506507118732174, + 0.5798091064371749, + 0.5266205827892922, + 0.44346537097035843, + 0.55073138737864, + 0.5663650864893949, + 0.6671966639951631, + 0.6317367962406127, + 0.5942590917199208, + 0.4672236499771694, + 0.4793590070351424, + 0.6089107777747036, + 0.4666576992209707, + 0.6256273713086642, + 0.6699167780695945, + 0.6552340585993263, + 0.43420120803784673, + 0.5272864267508344, + 0.42120309383726934, + 0.6555820492245131, + 0.5155067906336123, + 0.43079578700320353, + 0.49885044363427977, + 0.631648282724498, + 0.55258150657046, + 0.5073527930688516, + 0.4617488266998429, + 0.42337274600729946, + 0.6215094591134338, + 0.519397941870058, + 0.5369302144633952, + 0.4328633136584435, + 0.5757012744713902, + 0.4849266211124019, + 0.5368090046712135, + 0.5066541127347344, + 0.5841786384589298, + 0.5038701489143311, + 0.5105035106709749, + 0.5691524171778579, + 0.6141488421026757, + 0.4483880311334529, + 0.6464554423764665, + 0.6184727307344038, + 0.6460829419789078, + 0.6622115093063914, + 0.5197896932740175, + 0.5262045797863589, + 0.6402678421929364, + 0.5420368929700314, + 0.4996859833131402, + 0.6156296226422884, + 0.5149507558072215, + 0.6195032941167082, + 0.6182827282906899, + 0.6739823169536806, + 0.4562154792085572, + 0.5957536739325099, + 0.4327704453335564, + 0.4312980106895355, + 0.609340848826688, + 0.46518656238267025, + 0.5224420472742266, + 0.5258092664663971, + 0.6020292475143797, + 0.4680710796690936, + 0.6566345868389716, + 0.43763611932226576, + 0.6008516535644058, + 0.4573800572416806, + 0.519033718345491, + 0.4766454652626074, + 0.597644549991845, + 0.597968585162079, + 0.4491471274615502, + 0.5836855113804296, + 0.48881272595212405, + 0.43063826160998586, + 0.4711069704214128, + 0.491332486145751, + 0.6369660614619388, + 0.5247410053787961, + 0.6533945892609101, + 0.47952817401879105, + 0.4571086970548646, + 0.486927033200762, + 0.4469335928661234, + 0.5787981910215672, + 0.586077371820191, + 0.6443496104666973, + 0.4713076440819153, + 0.47332034371590864, + 0.4380614232349029, + 0.4880018504127424, + 0.6456544826523392, + 0.6269720688939131, + 0.4382861016834727, + 0.5850182825206348, + 0.6209766187378735, + 0.5946714924777973, + 0.644328071860983, + 0.6610367510719928, + 0.4453795311062353, + 0.506818278789746, + 0.5997030359769215, + 0.564300502660684, + 0.5915721509900786, + 0.4870436620729171, + 0.4821373628175896, + 0.5283433340384645, + 0.5186381515589504, + 0.5411683461896506, + 0.45780868203224545, + 0.6707356165287726, + 0.5514131676544831, + 0.5338969947497376, + 0.6513389132729768, + 0.44886342660887574, + 0.4986069006395344, + 0.643524193391204, + 0.5482614639820292, + 0.5756349226820744, + 0.46419191202631555, + 0.5117635432788035, + 0.4414247294125777, + 0.6117387532332201, + 0.6297260912501168, + 0.5233042723443851, + 0.5202261967588463, + 0.5545507193700767, + 0.6611151446627456, + 0.4398696818906977, + 0.473054299737586, + 0.45495764883528883, + 0.5509555358889967, + 0.6514283169158246, + 0.5019715302926671, + 0.4519500330301265, + 0.498365415875194, + 0.4723799924910431, + 0.48754076126414087, + 0.5892977675382051, + 0.4414655846151482, + 0.4469935248052333, + 0.4414677157415759, + 0.6004109438822295, + 0.47322420777927954, + 0.4721474432607007, + 0.5106033199884509, + 0.6277671723480984, + 0.4969410082802199, + 0.653861291337887, + 0.5117172747653163, + 0.544367392495219, + 0.5175244116240957, + 0.5227026176680079, + 0.5146952310974495, + 0.4381112226620481, + 0.6163245885767891, + 0.6599614867396939, + 0.5674314015139748, + 0.573181595547409, + 0.6237148054786532, + 0.46795814073644787, + 0.47218465804269766, + 0.4524022244742728, + 0.5643623692908885, + 0.6538578926384873, + 0.5885855783295441, + 0.46807262222115104, + 0.5516725299109979, + 0.47082875329682355, + 0.644147791070851, + 0.43253680037091746, + 0.6186731931926011, + 0.45564298619777593, + 0.5007109816953412, + 0.639801390375888, + 0.44586269947433255, + 0.6397149530552425, + 0.6275433524996125, + 0.46030847337352715, + 0.4272007563626595, + 0.6586900983096114, + 0.4189031498205622, + 0.450794073459694, + 0.5214007015753314, + 0.42101627511549716, + 0.5938036049486581, + 0.6419773101210333, + 0.47939586266064355, + 0.5652778045758694, + 0.4338922307347185, + 0.662609141818618, + 0.5893522963052936, + 0.4183850293936286, + 0.5273898400321877, + 0.5871311389322329, + 0.6376943125711301, + 0.5804626355512543, + 0.6473223178406453, + 0.49273761870183763, + 0.6046834813584172, + 0.6072349854067787, + 0.5669968824371872, + 0.6016409669331728, + 0.6050393688315338, + 0.5704057425450002, + 0.48586232366978915, + 0.5405720528283163, + 0.47091001779276537, + 0.6173315607429576, + 0.41879679382950674, + 0.5565904809811377, + 0.47414384948138516, + 0.568346519991162, + 0.5541683403655372, + 0.5456371540794682, + 0.6657251685943771, + 0.5825857628007115, + 0.4734678165485151, + 0.47611247545932844, + 0.4338513371809838, + 0.672280883804744, + 0.4229627550219375, + 0.4497412349460643, + 0.6292509641246214, + 0.4206841158246909, + 0.4514802539239091, + 0.4390625080509076, + 0.62904447233078, + 0.5976771290346261, + 0.42174286239809494, + 0.537489846528018, + 0.47544052248659757, + 0.5631827359310672, + 0.4548830981327004, + 0.6756923955254392, + 0.5870911544323338, + 0.6500696989693584, + 0.4426434616118874, + 0.6509466282106549, + 0.5962525078274883, + 0.6648378677598582, + 0.5226021646437627, + 0.541797846462833, + 0.510861179395654, + 0.6630892586629401, + 0.5367778558990198, + 0.5375768772654325, + 0.4566236085213001, + 0.62594970257563, + 0.48810323298572755, + 0.4337475396312565, + 0.4258183924319848, + 0.5711234003045061, + 0.5168507878228732, + 0.6430349710165784, + 0.5386550746552407, + 0.46106714128987253, + 0.6279738668879626, + 0.49594190055541754, + 0.4901276161420879, + 0.6719272880777879, + 0.634314643710829, + 0.550076331304068, + 0.45565444659799964, + 0.43560187014279245, + 0.4648728722831941, + 0.5945951613811963, + 0.6062374589486895, + 0.46209884131010653, + 0.43816330048622176, + 0.6675080348893347, + 0.6295788552972336, + 0.6341767957658666, + 0.42974435010830875, + 0.47095117769120226, + 0.6203088114472908, + 0.6750487372473492, + 0.4713897009721311, + 0.5881730950610079, + 0.6259879275270464, + 0.4286429309659223, + 0.6648996324955361, + 0.4841220782054608, + 0.6682441264277641, + 0.5804390215688197, + 0.6360974761083393, + 0.48556084308642034, + 0.5274661530410496, + 0.47577169932604046, + 0.5329123778501766, + 0.5702533042291292, + 0.5562024698575198, + 0.49422496902961804, + 0.510112913807003, + 0.559641345976785, + 0.5363010400612845, + 0.5214989091228562, + 0.6432684065341269, + 0.6159410142334454, + 0.43849777697617753, + 0.629372817368506, + 0.47045728052342417, + 0.6382908689457731, + 0.6722081523435732, + 0.5479407689400406, + 0.6710205365929127, + 0.6377263045318525, + 0.6433020569017958, + 0.541623355088046, + 0.5172351930813528, + 0.4947934892329621, + 0.6013528552236516, + 0.6034948577806821, + 0.4279938822955963, + 0.6712777581592362, + 0.4345456486875733, + 0.5582745892783212, + 0.5164646525285719, + 0.4779787035213325, + 0.513443097918909, + 0.6427237715897787, + 0.5679735270299557, + 0.6102716763838884, + 0.5475826855736516, + 0.4263061003005549, + 0.45351257414412444, + 0.668952008266098, + 0.5062423570699076, + 0.42035880114296864, + 0.49042951586698047, + 0.46044116290109705, + 0.45037535092477315, + 0.5502148944023486, + 0.5251715573389579, + 0.6544952918240217, + 0.6377621368251094, + 0.47214832054760714, + 0.5851481290079082, + 0.5316710882020335, + 0.6094803489761836, + 0.4429843922719223, + 0.6102537834190163, + 0.5855085956630669, + 0.507512696184161, + 0.5108189826721767, + 0.4655045625250388, + 0.498604110135793, + 0.4623549733539597, + 0.6650933404971426, + 0.435716192655376, + 0.5608385808241656, + 0.5162429273436229, + 0.556672147449047, + 0.5399772499751657, + 0.5963641437123793, + 0.43957602306982346, + 0.6265208383409813, + 0.47407143313636774, + 0.5037537539316709, + 0.587318974049634, + 0.5246625811171158, + 0.6402333119696109, + 0.5187418539781387, + 0.5214806403898993, + 0.6625907176493491, + 0.5459300675887133, + 0.6418755782495633, + 0.5151437244364354, + 0.6232436560287475 + ], + "y": [ + -0.4432159655895651, + -0.5823871036951657, + -0.6321558040686575, + -0.6281293501807178, + -0.846375860256131, + -0.8087969783143467, + -0.82837213610394, + -0.7127313204853822, + -0.7188568048007147, + -0.44121826420015864, + -0.8489126200349311, + -0.7964617103126466, + -0.7632732017837138, + -0.537337123470387, + -0.84890069925948, + -0.5582211322645969, + -0.7367767552546433, + -0.6553224530197546, + -0.6983201899485597, + -0.7852659821986434, + -0.4676593717796288, + -0.7642026512174694, + -0.4595929894290875, + -0.7881300952004628, + -0.4074211518904701, + -0.7280019164156561, + -0.6790101071514786, + -0.6345124678609813, + -0.6487065646910061, + -0.4525976955267307, + -0.5754841629871728, + -0.516731468433036, + -0.8061159100733846, + -0.4107679840329321, + -0.8628321521529942, + -0.5571949092893782, + -0.5294156993034891, + -0.8057103471896616, + -0.8017401872828076, + -0.40921963915232085, + -0.6056740383747836, + -0.4521559914292026, + -0.7765096125420216, + -0.6031634504240942, + -0.7644423296741776, + -0.6355776155519656, + -0.7799716700671221, + -0.7952876133137988, + -0.8500986224894057, + -0.8142438400479478, + -0.5992219167735197, + -0.5644224710958516, + -0.48500039451516025, + -0.7577766997680461, + -0.5374542065252799, + -0.4046769062436991, + -0.5376207942014544, + -0.45189318019292846, + -0.5720724754792128, + -0.5140316788295471, + -0.568704206674379, + -0.43450814043083646, + -0.7034979307984688, + -0.7562803564959105, + -0.6815828644029427, + -0.7858775569101486, + -0.7429007724079684, + -0.798616047926944, + -0.6997606247085718, + -0.5811340980431859, + -0.7850860456369989, + -0.6097339816632485, + -0.7938393829556933, + -0.7206736137505965, + -0.6970551273246782, + -0.44710610981307625, + -0.814277704044462, + -0.5471126889163793, + -0.7964125866828744, + -0.6499119021077876, + -0.753988464202047, + -0.6102745534463474, + -0.6940825532322431, + -0.8287371445831021, + -0.7898146449910275, + -0.46734617505541903, + -0.8037819012637124, + -0.6186121250392125, + -0.44610809739264284, + -0.5005878525766311, + -0.8071363928152594, + -0.5503210987116924, + -0.8273874603059147, + -0.5855684802941814, + -0.6632250375716351, + -0.8547807028020109, + -0.7633194641727156, + -0.7855495369746052, + -0.4999995889994189, + -0.5720554719584929, + -0.7847393262637536, + -0.7857404954044234, + -0.8257440296557027, + -0.4757388815789973, + -0.7309644986145094, + -0.4505749309548344, + -0.7177053768941176, + -0.6945142124344441, + -0.7834744297753948, + -0.6428166067463894, + -0.808597171522588, + -0.5364172772543017, + -0.7353676270269176, + -0.5498894260552238, + -0.4794731052318494, + -0.6066552806657859, + -0.863847259353731, + -0.4689042644415654, + -0.5664333731845723, + -0.4155313324924204, + -0.49799529673699205, + -0.48107689088010125, + -0.4572148177709923, + -0.5683312772041946, + -0.6754619616809117, + -0.44095727891524383, + -0.5581372979057757, + -0.5148272659765123, + -0.8193039844658101, + -0.4059736870690929, + -0.747174810302052, + -0.6572300332552972, + -0.5831017186495411, + -0.7450587770906386, + -0.597560224693536, + -0.7720887844309521, + -0.6362149819401441, + -0.6946848323821884, + -0.5887611669377139, + -0.6812109093326907, + -0.863509293833139, + -0.7858372667530297, + -0.8649510336993825, + -0.8445141893332779, + -0.4413218274266901, + -0.5969452117937186, + -0.8177172645407418, + -0.4827485097178296, + -0.8638330324427624, + -0.42511783151292093, + -0.4966312074103702, + -0.8524892654749893, + -0.4132746534647103, + -0.564597940038267, + -0.5601095423058091, + -0.40502439846190214, + -0.6349707007214682, + -0.42455466761376526, + -0.700603182425749, + -0.8506166705227856, + -0.4810250741698295, + -0.6523484417886688, + -0.7557329672801689, + -0.6807370390160616, + -0.5878278175300156, + -0.5245248148797728, + -0.5178884939809951, + -0.5599322330137027, + -0.4181905743591252, + -0.7793806186808037, + -0.5303801530214607, + -0.8183483442650257, + -0.5588334231380349, + -0.638515564873561, + -0.8602831167715659, + -0.4054912106198001, + -0.707518044160148, + -0.5299310217311881, + -0.5339279732143564, + -0.7661795292453852, + -0.5333453046766674, + -0.7227426794931913, + -0.6802968646255843, + -0.7441513822257309, + -0.8039661040270487, + -0.6808761559655081, + -0.7760804417605938, + -0.6314903502227709, + -0.5085579633095061, + -0.5055720000037787, + -0.7849400750384817, + -0.6362823080681358, + -0.45904559412117385, + -0.4734645365564617, + -0.6164653670571295, + -0.8685681564948771, + -0.724242969206326, + -0.5797523682605142, + -0.7224476755874959, + -0.6214724643080327, + -0.8462251589192491, + -0.7722767007711386, + -0.6130901428445232, + -0.7738986715321894, + -0.7638754197923884, + -0.4218641355613504, + -0.5987882196930444, + -0.47590424715111496, + -0.5577348595419176, + -0.8266707654093459, + -0.4893338678444647, + -0.40237552485624273, + -0.7724436058711088, + -0.7742554327721767, + -0.5501495563207299, + -0.6464565319584006, + -0.6994338221787718, + -0.46344835061649725, + -0.5915272251774936, + -0.6615462260456488, + -0.6822075069512924, + -0.8066467170606627, + -0.6054268761622354, + -0.7000073563616221, + -0.4827925072938817, + -0.5248693810379181, + -0.5442972965258506, + -0.4991944892202273, + -0.5323572335808129, + -0.7722124549133623, + -0.5384876184436976, + -0.485096566867254, + -0.4481462292817784, + -0.42196399535020435, + -0.7504326139233417, + -0.5448933065449346, + -0.4027283850617709, + -0.5342087689069777, + -0.8001514779634641, + -0.8105810662716171, + -0.6050688141486831, + -0.7662014024527197, + -0.6655320525374024, + -0.8564183905129478, + -0.753066269395263, + -0.5346082212168605, + -0.4137242791124801, + -0.5677538719438624, + -0.6729019221383613, + -0.41115092661650665, + -0.49409100900233854, + -0.4395214664789197, + -0.7380043728029186, + -0.6444103531958606, + -0.42448646056048334, + -0.49432781775127116, + -0.6459793453046123, + -0.7507740260686205, + -0.6373210686920066, + -0.46179874813289884, + -0.5036049210495468, + -0.7898327943420403, + -0.8337758947604015, + -0.6896823672823083, + -0.5653056045684226, + -0.7110142194868597, + -0.5132807776996822, + -0.698024860064104, + -0.802922332969385, + -0.7126476767759755, + -0.4992858098098753, + -0.7140868038595749, + -0.7120136665261165, + -0.8154526942946705, + -0.7996878528661302, + -0.733423225347402, + -0.6136991455215113, + -0.5428585386055294, + -0.6732770141439716, + -0.7999203682630227, + -0.4530276670954914, + -0.8057402256631535, + -0.7642527190644577, + -0.828120745418977, + -0.5409826636800062, + -0.5206908061739373, + -0.8698038076534557, + -0.5937885500353377, + -0.8229128376006515, + -0.8018607820702218, + -0.5604714770676321, + -0.699819943004825, + -0.8099447395641873, + -0.7025308358048586, + -0.5901170234414246, + -0.4587196931347202, + -0.6476198528219038, + -0.8414690233562347, + -0.8702541137836438, + -0.8410603246561019, + -0.7195977315165142, + -0.601830408680055, + -0.777793218400794, + -0.8654075765551246, + -0.5086873577492872, + -0.8472476952058597, + -0.5193240548235076, + -0.8113770045844951, + -0.4673669640708452, + -0.4754017991780407, + -0.4739288636519005, + -0.7305935467674521, + -0.8393018235821829, + -0.6273776970121856, + -0.7664566788956074, + -0.7174934750940871, + -0.4898153715641652, + -0.8586688923725132, + -0.41560007232478346, + -0.48657367883769986, + -0.43221647444484024, + -0.49974547243934125, + -0.4681770152432479, + -0.45236949056066456, + -0.5179783816306989, + -0.6170343751003105, + -0.600077921478566, + -0.7794720926787703, + -0.7931267589731708, + -0.5121952212799534, + -0.6189407358397822, + -0.7114424133148234, + -0.41496021207186323, + -0.639330374594246, + -0.73272415130897, + -0.6725515578116227, + -0.776427471652628, + -0.6534273006787936, + -0.6509646745135079, + -0.8073166622687648, + -0.4228499880280803, + -0.6443607277084796, + -0.4291173848651825, + -0.43728576133994307, + -0.6253755652323926, + -0.6369000398268196, + -0.42956824601525756, + -0.6670754408847597, + -0.717597919423659, + -0.5925315830840714, + -0.7123845646836098, + -0.4779495422222953, + -0.6920617143121182, + -0.59575269624731, + -0.6025013801039687, + -0.45952633963053025, + -0.6713805319934161, + -0.4432369785848112, + -0.6703740553076722, + -0.5345186476074114, + -0.531609093349143, + -0.4029862534497126, + -0.864775588638802, + -0.4940213212764773, + -0.49998895127031834, + -0.8587194698756246, + -0.5735012570737156, + -0.6363663258415542, + -0.5737080670904913, + -0.44053138668595154, + -0.6040192422942501, + -0.6796803541582842, + -0.7452139949309172, + -0.5680481852424175, + -0.8504886717896631, + -0.783668723793881, + -0.45013813958516385, + -0.8268752846537356, + -0.4061409640980966, + -0.7306618721521939, + -0.48652766371361333, + -0.40577432892137016, + -0.8490035003809451, + -0.5629150963539655, + -0.41875289911670344, + -0.8711705198488663, + -0.8701479631024049, + -0.5733017821185211, + -0.7060606250012461, + -0.4279799484651052, + -0.4805652039674926, + -0.49967245072191596, + -0.5238791170513275, + -0.5976298181665645, + -0.4027484528653045, + -0.48808679472068617, + -0.7746413177771664, + -0.4418117791717887, + -0.65662837713664, + -0.7496025810079286, + -0.4682780213348825, + -0.618994799051632, + -0.854049620136222, + -0.4886181750712426, + -0.7818679472317033, + -0.632884319334172, + -0.6754177710740946, + -0.5489356195412401, + -0.7952859416058204, + -0.6320949741967412, + -0.7066189314274137, + -0.6721915440401035, + -0.47628642618078565, + -0.8657450058425876, + -0.5495102088199164, + -0.5365436216557229, + -0.5962935765703834, + -0.7425075793200697, + -0.7946684511867982, + -0.7942746401236842, + -0.5719592571798195, + -0.5666334065618821, + -0.5429972334584949, + -0.4637567407629953, + -0.7260501199846612, + -0.635618766910235, + -0.46133489344853706, + -0.40116074950880254, + -0.8548834149119388, + -0.5625509633617314, + -0.5208028882642624, + -0.436583342039863, + -0.4327998491621506, + -0.6392659136298633, + -0.7346925534308861, + -0.44239937676841656, + -0.7160406182840152, + -0.6461391977937319, + -0.5838278277698663, + -0.49774520084467894, + -0.637959330873831, + -0.68123662732079, + -0.6570259468949213, + -0.6978397857637406, + -0.5052377909562453, + -0.860691659561398, + -0.4064832391840769, + -0.8373673064904911, + -0.5233539502511143, + -0.6496623034438691, + -0.5177817065770389, + -0.5962140013089259, + -0.6433762269704854, + -0.5562106830636704, + -0.7932662493388379, + -0.7323732563661303, + -0.46017506724754437, + -0.7941152604757401, + -0.48058845110685705, + -0.42854904054705123, + -0.4216404086938426, + -0.7105724761115927, + -0.46672051514133145, + -0.8394650555575925, + -0.7834224356581319, + -0.7772311503837531, + -0.5273371398718972, + -0.5078956625789686, + -0.4343340651177126, + -0.8362440572434907, + -0.5612963213773152, + -0.5351435192878322, + -0.5146212328574586, + -0.6316534743893001, + -0.7671959691568554, + -0.4148970223075253, + -0.5620605444381601, + -0.5878271116534942, + -0.7700007199304547, + -0.5307489395093987, + -0.500742561223535, + -0.8230057801338753, + -0.6716863246567961, + -0.46733742096511743, + -0.4915892140370506, + -0.5210318409801447, + -0.5628791943840203, + -0.5188671977106645, + -0.6041834575586305, + -0.4389886562714444, + -0.48151922074261944, + -0.7216712641239038, + -0.43654248921250227, + -0.7063635916951514, + -0.5914152063422577, + -0.785387426063849, + -0.5209956130555937, + -0.7415402019640508, + -0.7608441826440919, + -0.4940619210958477, + -0.5869972788120652, + -0.40568769439590296, + -0.6951100458936299, + -0.5799415443981304, + -0.8636834947283658, + -0.6313155692534618, + -0.552290890165409, + -0.43070255109233657, + -0.43993655530712833, + -0.7088209352582059, + -0.603338507624961, + -0.800105804058593, + -0.7263283289361769, + -0.6006724851856795, + -0.4583661944931172, + -0.8023121384946077, + -0.866290059475949, + -0.45789910985039894, + -0.5024861426927616, + -0.45188373884383104, + -0.8536599280339172, + -0.6915676699321, + -0.8409784199400729, + -0.6192122044393402, + -0.427971606312836, + -0.777645301508147, + -0.5449696878090751, + -0.5894216279806477, + -0.7537170663089825, + -0.8362768346934308, + -0.46343717970248216, + -0.7229752008250564, + -0.5102858151009304, + -0.703013821302028, + -0.8690415427330125, + -0.6603728038539227, + -0.845242506198199, + -0.6121029874238704, + -0.8286632756062572, + -0.5184696220958895, + -0.5926367248685218, + -0.4533342195249507, + -0.7450673601024425, + -0.8138585777529966, + -0.770458788544943, + -0.8173094672815341, + -0.8638968551823921, + -0.4975021270087134, + -0.7046643890604731, + -0.6286009855372121, + -0.5489624939277508, + -0.7774481482052462, + -0.6202703710324393, + -0.500051528451326, + -0.8341646993516115, + -0.7198576044021218, + -0.6454618000143488, + -0.5926636431822064, + -0.6901562083794254, + -0.5345497577650122, + -0.6988303309669309, + -0.530577340094686, + -0.4336142191418199, + -0.7267276535105038, + -0.5501365076082874, + -0.5950986962135467, + -0.4819082416274903, + -0.7420640845846048, + -0.5118093674707765, + -0.49296822419323216, + -0.6498481422484861, + -0.8509351378815379, + -0.825111959306894, + -0.7138915501105554, + -0.6197042429917484, + -0.8082474988764967, + -0.7775655611505986, + -0.48679300427564753, + -0.4006182373091497, + -0.5808605877821195, + -0.5790015359569749, + -0.8624026787038684, + -0.821369549747865, + -0.6777560647084965, + -0.594375397125942, + -0.4005300511935751, + -0.5655033534578844, + -0.7838414613164829, + -0.5789571985490392, + -0.8338019446983833, + -0.45508762816165144, + -0.8397065447264761, + -0.5538228573451733, + -0.7787500536358575, + -0.7981962119627954, + -0.5592459833183274, + -0.6095072794307121, + -0.6820493484545872, + -0.5755536013705458, + -0.7690113056773216, + -0.5217325823889523, + -0.7426002299223042, + -0.5510429942542547, + -0.4865593976428821, + -0.5640488562054622, + -0.4978662600177292, + -0.5606823810916853, + -0.6602881319441275, + -0.7222537677466274, + -0.8356012104060547, + -0.46392583414973904, + -0.7836651882214591, + -0.6875386955964113, + -0.6309457120129416, + -0.774188280035211, + -0.4333483950509999, + -0.655558251005405, + -0.7261902550528565, + -0.47483423190680785, + -0.6819728011729349, + -0.6993831534343669, + -0.7121694853784488, + -0.6317093776564938, + -0.7989796369442229, + -0.45876874668006634, + -0.6923289421596406, + -0.7288046193631482, + -0.4257905246872736, + -0.40199411863620277, + -0.6604575344635607, + -0.6156727414648193, + -0.6499570953022543, + -0.7367206279781371, + -0.4234355824555912, + -0.5586741121711641, + -0.7322863313608539, + -0.5354863323188672, + -0.44021448031421306, + -0.43996274398575835, + -0.8228736519189832, + -0.45399214056194503, + -0.4837070805731702, + -0.6126176699547331, + -0.7490343031405523, + -0.558327750432106, + -0.4255277155506125, + -0.7456545495540647, + -0.587628806451443, + -0.7030453941631525, + -0.7715903079244973, + -0.41052353242601064, + -0.493699763948808, + -0.7961046346439987, + -0.48761062045194153, + -0.755390971623327, + -0.8523118764926239, + -0.4209921008005629, + -0.5421138085078607, + -0.5988306386373069, + -0.4381517500613288, + -0.6052457503036615, + -0.4622703363346808, + -0.6071233434565039, + -0.7701601485938183, + -0.5946872899237928, + -0.7676052413788431, + -0.6922087342995404, + -0.46715485617823854, + -0.6514515051300254, + -0.8590725516607911, + -0.7376583668959776, + -0.7671603207349725, + -0.5139511804241603, + -0.6569491481352536, + -0.536910260892173, + -0.779343822875701, + -0.610129985136374, + -0.605624898487992, + -0.7748111493177504, + -0.6947756832974905, + -0.7594182685443628, + -0.7414533027528522, + -0.8605077409109981, + -0.6118114047313827, + -0.7885357946552163, + -0.5552236421570644, + -0.5274877506835531, + -0.8158157655053353, + -0.867453789613318, + -0.6210717898343061, + -0.5462729311679788, + -0.513725128992546, + -0.4670023911725681, + -0.5667427512944857, + -0.6119242638093287, + -0.7842780952575998, + -0.6475426470117027, + -0.532552833989447, + -0.7726275847106108, + -0.597302478970037, + -0.5559182688925022, + -0.7750109431983286, + -0.6606949381971727, + -0.5416016558899679, + -0.5458641191336315, + -0.6871470097319259, + -0.4465315097171436, + -0.7531135907076248, + -0.4190947580934375, + -0.40009821710125404, + -0.6942134161086544, + -0.8314488579210209, + -0.4147746660896921, + -0.7425545204952531, + -0.773514069912632, + -0.8669401275926696, + -0.6028258395092452, + -0.5995991007257859, + -0.41570202864534006, + -0.8144641771690339, + -0.4384955125666474, + -0.8606709882220316, + -0.47638807535484706, + -0.470117450978309, + -0.6877203163712511, + -0.6584716762466977, + -0.7643840408350917, + -0.5061417803059173, + -0.5285871064940854, + -0.7167172036165025, + -0.6700076590400978, + -0.8205954019463528, + -0.42051751979072854, + -0.8179043552628757, + -0.7749083091914888, + -0.6865762864001898, + -0.4972921378420167, + -0.7016011075674987, + -0.4204023479749232, + -0.6850186306790823, + -0.43763784310999654, + -0.4311819833687963, + -0.6992177413119941, + -0.5611294714558961, + -0.47629479054141016, + -0.7426396921844249, + -0.7251732263983905, + -0.5181117424383035, + -0.6345707808105556, + -0.8006245344978717, + -0.6021383442490924, + -0.743093296282669, + -0.5148039324529579, + -0.7235067470078558, + -0.6128950851615839, + -0.6763142666884141, + -0.7468418035661772, + -0.5338138624894864, + -0.4495864504522282, + -0.7635510319318489, + -0.6661870752559295, + -0.5420817899986021, + -0.5397952909511634, + -0.5989894328956289, + -0.6386588927049655, + -0.7795418220289086, + -0.8120197933782294, + -0.7747368333693555, + -0.6413904739868055, + -0.42207046907017326, + -0.7377444736580385, + -0.49787925256733795, + -0.5997032608645197, + -0.42748110757207447, + -0.6816470643731829, + -0.5220664386618621, + -0.4338590905343063, + -0.5762177812779683, + -0.6279158223230534, + -0.6141227989882196, + -0.4197014831776678, + -0.6183336428205103, + -0.6504483238168104, + -0.596545974128093, + -0.7037329205159899, + -0.5226579890530731, + -0.4580787890390667, + -0.4980868466446821, + -0.7019668680947286, + -0.4795549471000241, + -0.5253940693880199, + -0.5067382368422896, + -0.7431636310821276, + -0.4554932306837373, + -0.7971706978591409, + -0.7291602490492507, + -0.556488426771955, + -0.5130162033759883, + -0.507064059247776, + -0.548377508727429, + -0.7556602878221329, + -0.49614723068767785, + -0.7460467838622384, + -0.43344906354855267, + -0.819981745788306, + -0.5354055772900512, + -0.6148685300954257, + -0.4548425487263872, + -0.7689824221668078, + -0.6242703901771469, + -0.7490075086691348, + -0.5342929701742326, + -0.5744662264733855, + -0.7973510838594287, + -0.5104150347352006, + -0.42734471809596836, + -0.7785901776382929, + -0.693979962166076, + -0.5881004089245583, + -0.7921290689777033, + -0.49407488120866166, + -0.5238062840480204, + -0.590707024886219, + -0.6742121347082513, + -0.43663486805177937, + -0.41692193859713245, + -0.42168324936743634, + -0.7166972348123732, + -0.473190839634086, + -0.5608601236034059, + -0.6214479279555837, + -0.616358926227054, + -0.7812903476492035, + -0.4315929698677523, + -0.6422078578568069, + -0.4460690284208533, + -0.7613021428815617, + -0.687789024060172, + -0.7192058005546531, + -0.7493107153965961, + -0.7279972317070117, + -0.5597080892057961, + -0.4424935633878055, + -0.8451601177874238, + -0.7783653853255048, + -0.6625361550586355, + -0.4445022883666946, + -0.7895671253959242, + -0.7378957054845555, + -0.81842302297279, + -0.5697070556545576, + -0.8438615396856316, + -0.7398001196216165, + -0.6582406256025793, + -0.5292525446337211, + -0.8343771438969615, + -0.4121884391289932, + -0.7304955000413721, + -0.5642588901407244, + -0.8270850065590253, + -0.746676218578131, + -0.4940836664758103, + -0.44697870639021586, + -0.6389412748041079, + -0.5366948944569678, + -0.8069461720433839, + -0.5865779167485078, + -0.40874042183977694, + -0.6035489971512153, + -0.6283007550555298, + -0.8314413137606167, + -0.5255548228449254, + -0.48491728279943197, + -0.7944103143148639, + -0.7027420951122184, + -0.5961737781533956, + -0.5119363453418879, + -0.5197815779327639, + -0.6898938139211311, + -0.46265161005761635, + -0.6115301172728609, + -0.45699608031075295, + -0.6328442611745101, + -0.7324432593340098, + -0.6962850423270001, + -0.8246960038017368, + -0.5950451959962176, + -0.6813226733781492, + -0.823209382656477, + -0.45432230776328103, + -0.7377318171680204, + -0.8360182145459938, + -0.5983490444952411, + -0.47135722776931244, + -0.7019831912386567, + -0.6895694756954559, + -0.6065187710236815, + -0.7574795719856279, + -0.426110677374744, + -0.6707898260165586, + -0.6400685594451385, + -0.6043600827297603, + -0.4145958312317746, + -0.8397453291736653, + -0.7144229510374824, + -0.5246190652708009, + -0.6801154547564139, + -0.8010239129691168, + -0.6293727457851086, + -0.5587511508455328, + -0.8344962103786387, + -0.6978119136711232, + -0.7524940718685782, + -0.4967460084245257, + -0.4453791878174632, + -0.5334509967420784, + -0.4469139050372823, + -0.6749121597025438, + -0.826895735076435, + -0.43450375733765195, + -0.6125300212059928, + -0.7850929270891486, + -0.8039933044388984, + -0.8422145539057495, + -0.6719330178627023, + -0.7304105211970028, + -0.5473655517054821, + -0.5885289937997383, + -0.5250793867633705, + -0.7045982774978623, + -0.6318284103742724, + -0.6272850379041768, + -0.5582458130390673, + -0.5701254513736245, + -0.5304120506861556, + -0.7758542397410498, + -0.5297039674002437, + -0.7506680322670011, + -0.6594178695580419, + -0.4499649364424546, + -0.400034676909116, + -0.6825151959855649, + -0.4435213764871082, + -0.821676245045807, + -0.5047529074786282, + -0.8275125992226458, + -0.7881891968363677, + -0.6103413184944346, + -0.532907255440281, + -0.6101310453991199, + -0.4551318622330162, + -0.6875782474957024, + -0.5626444201161739, + -0.7830553385999023, + -0.5406775060633685, + -0.6437442681603645, + -0.7496594860101123, + -0.49626637563505205, + -0.5048065639159098, + -0.42706216038354067, + -0.6060904151424094, + -0.8248884607466241, + -0.4302060396859006, + -0.8132412461672198, + -0.7518513673624013, + -0.6274297776902996, + -0.4888281160010689, + -0.6991318044866581, + -0.6351866420621555, + -0.4417288786623369, + -0.515787061426292, + -0.6454904352536814, + -0.43863959860768315, + -0.44252399007465254, + -0.8417618831147329, + -0.5582860724382452, + -0.8172697287001903, + -0.7510584110926943, + -0.7374632182806025, + -0.8197508492836627, + -0.5015159098444181, + -0.7883629331647785, + -0.6743146120910585, + -0.6425211623020723, + -0.5936282901280504, + -0.7851000324400909, + -0.40633882574363833, + -0.7843338964594352, + -0.45276317444225095, + -0.5570271790587603, + -0.524775695881976, + -0.8485803521775308, + -0.8084128118988726, + -0.4957268269609185, + -0.5815649582211088, + -0.6363447155345116, + -0.7918158274791595, + -0.5439760647615688, + -0.645837061710155, + -0.7906214263555092, + -0.5106114022106661, + -0.7251546045304802, + -0.5137196474745636, + -0.8061406266138336, + -0.5633114764317299, + -0.6079811386707996, + -0.717797809933226, + -0.556321912342011, + -0.8193118162995425, + -0.5308606114297749, + -0.6728222469378244, + -0.45760074645405496, + -0.5530010857048346, + -0.6482500885616249, + -0.5170239070883236, + -0.5702133652633025, + -0.5953431144849373, + -0.6728082430182116, + -0.4940396211268657, + -0.704945768068886, + -0.41345128563874267, + -0.5245773312161008, + -0.5387455269446118, + -0.7333357388896808, + -0.5592476323620229, + -0.46172585665889776, + -0.4842267717645162, + -0.49436382222485936, + -0.8166170530976984, + -0.7708873874549295, + -0.8223510586768047, + -0.5723781079569172, + -0.6757614378680125, + -0.40107482738084405, + -0.7121300962831376, + -0.47011814842669153, + -0.43353411377248907, + -0.5475470133294429, + -0.4472785512030653, + -0.6044113435343748, + -0.6802085723799919, + -0.5401962713178952, + -0.6675363847608368, + -0.6333391703229165, + -0.7450296542831525, + -0.6058614775604043, + -0.8146227271867327, + -0.7982645506432805, + -0.7752256273567066, + -0.5639059482663, + -0.5828677879063581, + -0.5331885435520346, + -0.6258757520499608, + -0.7686826134639021, + -0.6519429149729351, + -0.8150497518120713, + -0.5669525341685437, + -0.42293408591086284, + -0.5245974637224353, + -0.469054194797762, + -0.42221139324782236, + -0.653855048303782, + -0.6162770219034265, + -0.8299650652847279, + -0.45933521816901907, + -0.4727352589366061, + -0.7279851384967404, + -0.6958343911747642, + -0.5117275639520718, + -0.5519645825601706, + -0.5439896380511826, + -0.567608723851897, + -0.5497384275254249, + -0.7645368722698275, + -0.6279599388845433, + -0.7967253389755845, + -0.5157530720337361, + -0.7988658603523567, + -0.720693422520128, + -0.4252876098795307, + -0.46026075480072687, + -0.7210639853654608, + -0.8264685053071893, + -0.6699083071451746, + -0.5037463784265019, + -0.722620607588983, + -0.7179643990843315, + -0.5619057217404317, + -0.7992692680422753, + -0.537893172015814, + -0.5496455488605501, + -0.5275439260298309, + -0.5294818894083128, + -0.8320434177811115, + -0.5458658775193959, + -0.8413924341964811, + -0.5466590537325984, + -0.5031850083837046, + -0.7407558414268971, + -0.5003107727520977, + -0.5467046568602019, + -0.549923914660738, + -0.8466559362378494, + -0.5168195594078708, + -0.8470973205895106, + -0.46099554552201627, + -0.6145587000348827, + -0.7238715581369018, + -0.5129493477841907, + -0.6002353712427719, + -0.5535263286668488, + -0.7438051393270044, + -0.4448639811661602, + -0.8363020973887514, + -0.470259017266684, + -0.7829204181228636, + -0.5229646188292781, + -0.6255395441041709, + -0.4214877929698806, + -0.8134902591603245, + -0.8144403228664918, + -0.747467947460999, + -0.6159681358141085, + -0.532636527550919, + -0.5221301334808164, + -0.6791743700157741, + -0.4552865596399156, + -0.5371243739007618, + -0.7404134635224947, + -0.577418314409353, + -0.4593869362191912, + -0.40122793544568663, + -0.8370187847672368, + -0.6277562137802485, + -0.5006648209963185, + -0.7016375297840347, + -0.4542258350663746, + -0.5193060327963266, + -0.8260079504032307, + -0.5817621638828252, + -0.6299295056196349, + -0.603341081027052, + -0.5425928785243737, + -0.572165820587484, + -0.42841906587365725, + -0.6683420877783194, + -0.6559755931299951, + -0.5919546763775025, + -0.46773010882164767, + -0.6661902974906776, + -0.6379505951552354, + -0.682038904804448, + -0.523286074191958, + -0.6978425233256524, + -0.7385462084776812, + -0.602775407325234, + -0.7779492992606376, + -0.46543761796190775, + -0.5647693700439683, + -0.7551606401221119, + -0.73296923122076, + -0.7024639219077123, + -0.6840602423400965, + -0.8121380083430346, + -0.7416152771217663, + -0.43062745480279013, + -0.649655112658566, + -0.5014569546982877, + -0.5347048403754718, + -0.6858850998967676, + -0.46292580134323963, + -0.7658151573508563, + -0.44441501396987687, + -0.6880031479934066, + -0.6752076491234247, + -0.40308812697893004, + -0.4787058785747699, + -0.7942385884554305, + -0.6759916054850685, + -0.7909996853029232, + -0.6300373472590701, + -0.5745815833751011, + -0.8055169017899276, + -0.4284302384189549, + -0.5259057550396231, + -0.4442492267377186, + -0.45488798333149566, + -0.6225963962804621, + -0.8362670951695124, + -0.6873421900042069, + -0.47278973945685376, + -0.4911201880583373, + -0.4664620532814192, + -0.5469008378891498, + -0.5619450693845761, + -0.5967489571986164, + -0.6450503377206642, + -0.7493708598237878, + -0.5414511100593282, + -0.5506267212214582, + -0.7326144616475854, + -0.40439820020081846, + -0.5817467819595222, + -0.49427672996567273, + -0.5507855322566391, + -0.531404556629433, + -0.45496934419387486, + -0.4264993130262393, + -0.8218989453180197, + -0.5217954712017183, + -0.6263607576337359, + -0.7743332582653202, + -0.6850191449495245, + -0.41236642850095906, + -0.5194032212383647, + -0.5716303975120653, + -0.8268230989185344, + -0.7643003350208646, + -0.7267566104824773, + -0.4708337047924596, + -0.5942085351876928, + -0.5313044142881094, + -0.612237866493764, + -0.44002088327400957, + -0.6693942086539718, + -0.5649149321537501, + -0.8393603890932727, + -0.7063525943062712, + -0.6134528153792393, + -0.5201798911602713, + -0.41153178599573714, + -0.5143808983363334, + -0.813528488649012, + -0.8103520021979466, + -0.5517468070695837, + -0.5875251945669835, + -0.4720544498405985, + -0.5075635911910783, + -0.4271055802149259, + -0.7318885928308998, + -0.6633278368206843, + -0.4232617409065609, + -0.7115467200058561, + -0.43906251414071634, + -0.6996452621188823, + -0.5776590353858415, + -0.7691558940358486, + -0.5825580027373536, + -0.43263409428593935, + -0.44567978087110416, + -0.7391197638766378, + -0.7771530061442592, + -0.626592940461731, + -0.7719233355162467, + -0.41185352022182387, + -0.42045858637557715, + -0.8075585669955844, + -0.7540967276086067, + -0.7238566451339197, + -0.6229142122603837, + -0.6171149536973121, + -0.49816937365571606, + -0.6801382728328262, + -0.43191657634496794, + -0.6390213027113844, + -0.47560272728892833, + -0.48338552883074026, + -0.6509676504127192, + -0.4294746676145822, + -0.8014212738191927, + -0.6001219551284604, + -0.6374823787787444, + -0.7843930148619913, + -0.7531057964067825, + -0.4003215046378119, + -0.5581590343658832, + -0.6087270804022229, + -0.44335933340035183, + -0.506081024933025, + -0.4274182156805524, + -0.7212761073713412, + -0.6327859946670147, + -0.5701044028607467, + -0.6950229722017199, + -0.6034828260066448, + -0.5737806726071735, + -0.40133299217978696, + -0.572865719089995, + -0.5609168340771133, + -0.6234220036013294, + -0.48089025263791396, + -0.7517182784436981, + -0.6993321148980166, + -0.7257151384337408, + -0.6823952196470683, + -0.7546039978733691, + -0.6694810507982433, + -0.42324760976281856, + -0.8073302941538917, + -0.6607178232534401, + -0.8391094390590382, + -0.4361482121034068, + -0.6330114472676043, + -0.605676976175849, + -0.7368817976377398, + -0.4438870151533168, + -0.4910604027934833, + -0.6968943465973905, + -0.7375599604990924, + -0.7173713647338542, + -0.6219605858812551, + -0.7135972618680386, + -0.5691674124992312, + -0.5068765648801545, + -0.4953288561694925, + -0.43984828166020484, + -0.5146207508811976, + -0.7198093091762877, + -0.470993614457085, + -0.47310044966076975, + -0.6115543621957203, + -0.7596581225399066, + -0.6367512528643412, + -0.4352203698271209, + -0.8126433852705558, + -0.5024404762793937, + -0.5143158001298792, + -0.710584101254302, + -0.6316878819120892, + -0.5529841709355026, + -0.826819963876856, + -0.7318034703742525, + -0.5631354967177522, + -0.6260847125861311, + -0.5038796362550745, + -0.6072531235898608, + -0.4562087438976456, + -0.8008962216392517, + -0.6302123004503373, + -0.7620233584663977, + -0.7192657920990401, + -0.8318529228099405, + -0.5514885648740091, + -0.5179815211489145, + -0.5134371334535874, + -0.7555813140519895, + -0.7292183426549729, + -0.4259991921937277, + -0.8108101843853769, + -0.8028222654421902, + -0.7686147571829047, + -0.458949841877365, + -0.691665276061173, + -0.6001547556384301, + -0.7801988082418763, + -0.6324889790104331, + -0.7995644582081588, + -0.5074001208219776, + -0.6628722357956609, + -0.7558407977969591, + -0.572352273977053, + -0.6589537080726257, + -0.423555029736253, + -0.845585053590429, + -0.7440875962277995, + -0.6205591098157783, + -0.7286451288418503, + -0.6689714008862, + -0.6533584478726011, + -0.7218105144566935, + -0.6944542585438032, + -0.5543990865309047, + -0.8371735284924718, + -0.7274939281348235, + -0.6617282017714516, + -0.40190629277813655, + -0.5319449776352825, + -0.44419357457371894, + -0.6639267134726445, + -0.7562041121324701, + -0.7897172550775273, + -0.825390976696223, + -0.5431138910762254, + -0.7849720980189466, + -0.5402235731318973, + -0.822894947392818, + -0.4228872253507327, + -0.6103827077012187, + -0.4669433739632042, + -0.8387220390077937, + -0.7096372090058503, + -0.703660651792201, + -0.815078725377902, + -0.6074603309507589, + -0.8285167471303856, + -0.4331361191200299, + -0.6996927375792759, + -0.8322972214002753, + -0.8370640906061005, + -0.4738512189807194, + -0.7289092751228848, + -0.7550715488522829, + -0.5696346412961633, + 0.5483286662381058, + 0.0413912613673908, + 0.5707974139556965, + 0.03167865885589449, + 0.1739117123170023, + -0.0867303548508277, + 0.10567733957665193, + 0.4446648205771079, + 0.025291352451735805, + 0.2959632225652493, + 0.28691464498316754, + 0.665121535678432, + -0.27808318793213266, + -0.31391637050468135, + 0.14407710270037022, + 0.11980012783901317, + 0.39532842476866037, + -0.23268349055715573, + -0.36755983251470065, + -0.06552570296709398, + -0.19938969528054012, + 0.3023004397615746, + 0.4439635895614146, + 0.19146246586518478, + 0.304846069846605, + 0.15825458649843538, + 0.04681789245636442, + -0.21815078588725897, + 0.683975487079887, + 0.6129148477807459, + 0.05139479754612686, + -0.24243831469604224, + -0.36316853844589836, + 0.6558965418463504, + -0.31676851577462545, + 0.17485286032274627, + -0.18250721947577764, + -0.057083583354271494, + 0.09870380323766309, + 0.4152822488643131, + 0.12105563682746934, + -0.1831710796647729, + 0.06809777760534541, + 0.24716006770317278, + 0.08154386884818726, + 0.47562598419182467, + 0.4029300414088576, + 0.06584726084469117, + 0.6838732359880638, + -0.10091223399656785, + 0.29874488226978835, + 0.4268552689836591, + 0.6591558905341731, + 0.31990048342453326, + -0.08170134106316912, + 0.5765651792900074, + 0.6264846915981316, + 0.13393368043738718, + 0.6774536286918379, + 0.4682593389117242, + -0.2326008857791511, + 0.6026394235377074, + 0.08316621841842681, + -0.06121410524560533, + 0.05029754206138809, + 0.408326629391887, + 0.18549894813153944, + 0.2238947164503109, + 0.4920389443559219, + 0.459598059186448, + -0.24908678529722578, + -0.27619323946590446, + 0.5784966620001051, + 0.3239748692761134, + -0.17598880620388554, + 0.4198929437298471, + 0.4070361755743571, + 0.07747463978362784, + 0.3292065771235708, + -0.1930563277147425, + -0.2865446820106627, + -0.09388186280100486, + 0.1077091958142039, + -0.006435452298299227, + -0.09836171396411364, + 0.4127434857695482, + -0.265305384603161, + 0.3113235373916736, + 0.31396271686154176, + 0.3400786697816435, + 0.1544559503221694, + 0.04890695802388417, + 0.19997108432490107, + 0.12978664306286303, + -0.11136370035233978, + 0.5288113380403673, + 0.3049266506759619, + 0.20870611381190818, + -0.0302067076805817, + -0.021677144286178285, + -0.28147257652998575, + -0.10828324612681772, + 0.5151101000936816, + 0.5974425141348656, + 0.39047854711401886, + 0.04850868080917725, + 0.2518897173916741, + 0.5233415878420478, + 0.33234018872189053, + -0.0015024886570236817, + 0.43118101986327195, + -0.126746390811946, + 0.5041672871027489, + 0.5463419553288756, + -0.28446522374297223, + 0.4556111543455762, + 0.2811232542566354, + 0.072958807265805, + 0.6008589399360792, + 0.22241302617879977, + -0.014693385334985154, + 0.2697605874054204, + 0.42314114966138605, + -0.09380844511837438, + 0.06382939351519423, + -0.3940100347125687, + -0.35343328746382885, + 0.5582490519900529, + 0.23968870299176148, + -0.2897950642015437, + -0.23590525791657688, + 0.5582040021447574, + 0.0901921530558028, + 0.19096432540239106, + 0.5085413559331687, + -0.2819777016729769, + 0.6274351121133029, + 0.0803488619093804, + -0.03627288109381971, + 0.5267319012663372, + -0.32217299405779365, + 0.5577243525019806, + -0.21363119268906633, + 0.14024017063550098, + -0.09342043098175151, + 0.39311075611782476, + 0.12324023731817557, + 0.10554599636146711, + 0.5686503082510124, + -0.054895079425861304, + -0.03708273752732344, + -0.16878297569500972, + 0.6835634020949456, + 0.44226223581672175, + -0.065840437386112, + 0.535223562707779, + 0.20602393705441535, + 0.49942311766686487, + 0.4062884986935571, + 0.13137252004903965, + -0.15860024147162588, + 0.4450753698048978, + -0.01059900726551205, + 0.16953030307525763, + 0.22857386769404242, + 0.6750076207276324, + 0.36185197324549845, + -0.35531655659612804, + -0.015506030296920215, + 0.6247165293619813, + 0.09650927744405713, + -0.3283494319552957, + 0.4353583232060778, + -0.21146594690577716, + 0.27462032364735156, + 0.4983374285544414, + -0.02893251016662035, + 0.12138446582622697, + 0.2724859969239214, + 0.2732044803222038, + 0.29464091280019844, + 0.2515573555730283, + 0.539913985664312, + -0.3409131008300271, + 0.28251122902264003, + -0.1341377015615644, + -0.3414329565053121, + 0.12422816304646533, + 0.32081277155263077, + -0.30631678910027815, + 0.3903389767551282, + 0.038613592787616835, + -0.20527797304020579, + 0.3790226681963229, + 0.18366855105453594, + -0.016681624563813946, + 0.36042616306869246, + 0.10062239799609896, + -0.20422945431858916, + -0.3667380549150062, + 0.6176196305386906, + 0.4456409981481947, + -0.1765274021845721, + -0.006134617365650852, + 0.39924214151629034, + 0.6535766987457242, + -0.12489372906421953, + 0.1539631289346225, + -0.06691116776821515, + -0.03185942317268453, + 0.3307713004862859, + 0.07320167932330973, + 0.2567122381702531, + 0.15179128463901237, + -0.13289263470813523, + 0.1258746205239739, + 0.5148701475324763, + 0.021013839301173065, + 0.5734598654608045, + -0.013056417228834105, + -0.030122657824829535, + 0.22083123524410198, + 0.09661521599793932, + 0.25570420720186393, + -0.036301895242562, + 0.35789273878347827, + 0.30420215012949114, + -0.3119837762544203, + 0.0921624811416048, + -0.24352249535698822, + 0.4992819261749549, + 0.08851460229147556, + 0.5753784880653896, + 0.5565045047220563, + 0.3227790432568519, + -0.12444961200005944, + 0.06328793513534914, + 0.07505519390025994, + 0.509093863588136, + 0.25403920930683654, + -0.2129899646769929, + -0.21495347072709922, + 0.5677362941122993, + 0.4699031405514337, + 0.10094200975644418, + 0.1255248030655357, + -0.20511820027463543, + 0.44263268878863526, + 0.5183241171117136, + 0.47618942087181015, + 0.5010031071154347, + 0.13471038482500808, + 0.6413028418938879, + -0.3415441487806759, + 0.432298658928167, + 0.25749489719370255, + -0.07508279234199333, + -0.3811347270853453, + 0.45896961628831756, + 0.23223125313662818, + 0.3968745750112813, + 0.1403228740839949, + 0.5435102975331177, + 0.5342065451269443, + 0.4719488037127878, + 0.32985201864361524, + -0.04012196611562835, + -0.39403679844736994, + 0.39236165787966903, + 0.4233084424262882, + -0.252192731245116, + 0.5026432980942069, + 0.17054822776422918, + 0.5611858865248557, + -0.14971420530047297, + -0.12012839614357151, + -0.3231540787592665, + -0.08007639347540407, + 0.36140774381231067, + 0.5899293789465339, + 0.24015370765691801, + 0.6646034397519428, + 0.2185754786621822, + -0.07812600506698486, + 0.36086766355374345, + -0.02142033204449212, + 0.21336896904380787, + 0.5844807813147387, + 0.3031680675843855, + 0.5146834089048286, + 0.19664279576695642, + 0.6551266234300163, + -0.35272622066258147, + 0.6316012255230276, + 0.04845834639024643, + 0.2844755476342027, + 0.4388668962557757, + 0.23346298904508878, + 0.5806627353719577, + -0.022308658041518215, + 0.4226093851260131, + -0.2812337057322626, + 0.00874807385173837, + 0.15767212206232262, + 0.5412808466173324, + 0.5930126440083054, + 0.42726849300198655, + -0.37848686954380945, + 0.06605320473361909, + 0.14651210258355984, + -0.3669917445368271, + -0.0793733828924505, + -0.3263651891870024, + -0.3198399587740258, + -0.3523411850207987, + -0.38874817221583824, + -0.19292354137597553, + 0.4473668179317525, + 0.4312598667238079, + -0.05020498838344001, + -0.01849449135656772, + 0.20217774374736408, + 0.6000053951019634, + 0.5411853759358077, + -0.07052419321923059, + 0.3468009658230531, + 0.43630212210658315, + 0.6567294562618006, + -0.30606051541936885, + -0.3163550459320739, + 0.47418202104811313, + 0.5911113552606106, + 0.34774272904714476, + -0.3199697684582428, + 0.6768161272304601, + -0.10679915562329373, + 0.36989338613006184, + 0.35664180245646004, + 0.3510318692451748, + -0.023395406398904417, + -0.17456673059756858, + 0.6151323083188268, + 0.3714315259645755, + 0.6829315963402921, + 0.31793112719660477, + 0.39314467459546376, + 0.028235520726778707, + 0.17593769695730455, + -0.1041873001427362, + 0.2389440583192738, + -0.08513273598338922, + -0.22484386920645227, + 0.6507409216061287, + 0.5496012568835084, + 0.1826909937689094, + 0.2744175584233097, + -0.0885452914364967, + 0.6009741160158463, + 0.42344236859322937, + -0.019674750100237115, + 0.18464078811333695, + 0.5260421249437046, + 0.5992943230947216, + 0.5347861217003309, + 0.6623004673061655, + -0.13550013339985634, + -0.2636550920579988, + 0.5579446277560139, + -0.1992437960380505, + 0.5361412377126898, + 0.36500653548493733, + 0.054889454673632154, + 0.07652353020552488, + -0.39123247353357943, + 0.5513502995549472, + -0.15928634280391948, + -0.06130229980601404, + 0.22025075221554924, + 0.1397590320159534, + 0.18295346852066952, + 0.20433790028721988, + -0.15978883349859457, + 0.2620548369798984, + 0.4947390194349631, + 0.0948305134869743, + 0.13421558434468017, + 0.2720817642339487, + 0.5597791890548951, + 0.29152243690043533, + 0.367103408172773, + 0.3861540329996139, + 0.4644549948316331, + 0.15303230685039948, + -0.21501216662535938, + 0.03595968896943785, + 0.5736739696200186, + 0.2879931832445547, + 0.35254824734896706, + 0.029035431177581394, + -0.16035256114410146, + 0.6143711279997192, + 0.24954975262100376, + 0.24238848744898234, + 0.3041006733142725, + -0.17822628134062987, + 0.6040715896366374, + 0.07475319932003432, + 0.382880684557135, + -0.18653236839421633, + 0.30727020928574666, + -0.10617609880829332, + 0.5058586593165861, + 0.10908602032244064, + 0.27412960237088546, + 0.4286440473447103, + -0.31318533673793947, + -0.38004957501676173, + 0.14852806093232318, + 0.06547585982564069, + -0.16735674219959845, + 0.20973271641720526, + 0.5599630212358687, + -0.30566873358390584, + -0.09747532168353401, + -0.3207688927379211, + 0.607263268356455, + 0.6056238448601005, + 0.46747108790962577, + 0.026657665343333525, + 0.5224339401742286, + 0.327065237162084, + 0.4571797712941732, + -0.023356098004496395, + -0.2265306297549034, + 0.1193939421921163, + -0.16255546554433362, + -0.021036050242628057, + -0.3301176560003588, + -0.14095232971524302, + 0.057798954149350434, + -0.06222813430718599, + 0.29656150866481157, + 0.22331199258772805, + 0.2088588337190591, + -0.1897703636270331, + 0.13221275677041566, + 0.4735691771517456, + 0.4192271365534399, + -0.252332108612617, + 0.011125510333012234, + 0.1462187813364526, + 0.2688557658950691, + 0.2558049560610315, + -0.05743738965194173, + 0.43025463217626836, + 0.2408291849651708, + 0.0025488005864025554, + 0.14994483889477805, + -0.2731892334516846, + -0.1953933738988901, + -0.20766667858131907, + 0.36389495055563903, + -0.032607824130428065, + -0.03005752422383151, + 0.48272916358374407, + -0.17473568551903818, + 0.538613321164579, + 0.3360841239076835, + -0.12258838356998458, + -0.20435326772416632, + 0.11261740747161286, + 0.06415799163363872, + 0.34017801496674405, + 0.364155510297681, + 0.38107602417983966, + -0.06030543549635009, + -0.20178754621774972, + 0.5001777404954814, + -0.235703348571336, + 0.5432569849018076, + 0.13091014337197515, + 0.5080213228617149, + -0.04894364726799616, + -0.06191067204639694, + 0.5936036760936104, + 0.3827508929797673, + 0.3438686204718653, + 0.3726975445272708, + -0.34463219358241576, + -0.20624205470745385, + -0.07032600855719395, + -0.21677305681214643, + 0.005764062936258418, + 0.17915302542087497, + 0.5307368322642319, + -0.3973330097529477, + 0.6658838548336564, + 0.6575628690267544, + 0.3299594476104917, + -0.08652964915605793, + 0.49398735039547836, + 0.47644365179489234, + -0.21737668134404495, + -0.39941107398438047, + 0.5653962227166628, + -0.22610400597445182, + 0.5369773728323408, + 0.16324257663768993, + -0.108056428868817, + 0.5273196773753761, + -0.1290222561899972, + -0.03394055466256518, + 0.17749101527418765, + 0.5849958442009796, + 0.3765485804054689, + -0.007362923547789946, + -0.12646738293881393, + 0.3876214889514781, + 0.44754518377595676, + -0.2975814455937438, + -0.012964126214854432, + 0.2193615479003177, + -0.25685172284632907, + -0.3516860560607565, + -0.09060240701119449, + -0.1338974620920395, + -0.20042811167245306, + 0.24478877128860743, + 0.6445180562878786, + -0.038636009608433, + 0.019470415802647856, + -0.3934138908179244, + 0.3325812744631581, + 0.527379914959846, + 0.42416555725080685, + 0.3353214692006473, + -0.33260919224976193, + -0.3367727362122819, + 0.1629354114974222, + 0.07681556070958562, + 0.40254826478325956, + 0.6805477008788038, + 0.26049855381590126, + -0.28960339343051034, + 0.48423666845857005, + -0.3883285391989959, + -0.3861197736005596, + -0.29415621454185636, + -0.3119039085715304, + 0.44695199151883613, + 0.09422563996285827, + -0.22075002661240783, + -0.33789493669423576, + 0.39383673372781147, + 0.07286056822682474, + 0.16595971130105647, + -0.23391067016131126, + 0.04715942359721392, + 0.6246940232907995, + 0.28619470566706473, + -0.29536434320827, + 0.5178715504090599, + -0.2579589654916741, + 0.0706402136089509, + -0.20988341822434442, + -0.32014736053226783, + 0.4023572046109576, + -0.22095722941115623, + 0.07234912274151817, + 0.45515703027179455, + -0.21296707666720344, + 0.5288566048568571, + -0.3085600050041309, + 0.4975525517868289, + 0.08154877760316043, + 0.5975973779560186, + -0.18091992995754516, + 0.5084067522510496, + 0.03904428527772896, + -0.2130650020539943, + -0.32584386005399985, + 0.18532463045503467, + 0.3737987072685308, + -0.29946541484557665, + 0.46783800439639633, + 0.29624999116807993, + -0.3585195304832399, + -0.38692310138469505, + 0.35193185208271016, + -0.08077025713960295, + 0.28669826182352753, + -0.3651994045967508, + -0.24904983214831664, + 0.23002203517417352, + 0.15957629221720393, + 0.3895912035495337, + -0.35104812653782447, + 0.33897415466883063, + -0.24335781399977444, + 0.6632991605967983, + 0.003954236353345408, + 0.28463038037033883, + 0.1593116032658931, + -0.017665095765043992, + 0.21620580164126157, + -0.28804223361288633, + 0.4857428415595205, + -0.12909781191507635, + 0.30230802835374493, + 0.4912535735870518, + 0.440502641812175, + 0.18883396188700796, + 0.5018142705531831, + 0.5450617436876921, + 0.6792681688337391, + 0.508518161595955, + 0.2503779625378997, + 0.6190679625688248, + 0.2650072755878988, + -0.03482171271480733, + 0.5374641419281643, + -0.2008065277772143, + 0.24403018322101366, + -0.2586576795251028, + 0.27060507139831447, + -0.18107047182221514, + -0.13798394484167031, + 0.5185603795763968, + 0.4150954752742523, + -0.13481993443676327, + 0.32391848178703875, + 0.4381558697368123, + 0.6751778313656204, + 0.6717393529910777, + 0.6134578391001063, + -0.013065260388819833, + 0.23160074007175802, + 0.13776808222360137, + 0.35078277882207975, + -0.2386109878049118, + 0.6181514770335131, + -0.055647669845623304, + -0.1997488782079388, + 0.03457005356772663, + 0.29230281849507733, + 0.014841815716369777, + 0.3198842594672635, + 0.438964989591934, + 0.18471163424683945, + 0.5591301978618665, + 0.6838892447958874, + -0.068032527656891, + 0.30852253238976357, + 0.48269939909462245, + 0.6631425772552989, + 0.525855070815404, + 0.586769357056604, + 0.43319814401068, + -0.09924133916578287, + 0.1367807918924695, + -0.0709892226946729, + 0.30207195998317116, + 0.10273998688785113, + 0.4751450542980823, + 0.6645823436833748, + 0.39582642602968865, + -0.0409038606855433, + -0.14392444353816936, + -0.1608698767330516, + 0.24055609476816286, + -0.10786422801420587, + -0.20735570199407913, + 0.6494571313374785, + 0.367947464776046, + -0.3364833371245852, + 0.1243637934863282, + 0.6676151634537758, + 0.47818573356343097, + -0.25864890830005427, + -0.06551021835474247, + -0.27889287392856943, + 0.4288229175321736, + -0.011093975532778022, + -0.1220661937301184, + 0.30555284909991953, + 0.30643304308122576, + 0.3187841153810449, + 0.3902008574456802, + -0.35568359500726543, + -0.033009660903318805, + 0.638399876187001, + 0.5381949419650282, + 0.438703878851994, + -0.058516185329337334, + 0.17035451608950736, + 0.6568068981981042, + 0.15164501784877882, + -0.10812978265576273, + 0.5977873300410914, + 0.2535014047113153, + -0.0635131363648535, + 0.16975386789788383, + -0.10131603952133994, + 0.26349000423322433, + -0.25896117485116854, + 0.26913777454109733, + -0.3713777177791715, + 0.2243327421364093, + -0.06062920110638381, + -0.38734225742500444, + -0.2642133566848545, + 0.2481073072502079, + -0.066031497346979, + -0.38103535215000844, + 0.6629882609989447, + 0.5869092562953232, + 0.4264179161736552, + 0.5903447172053692, + -0.19166480059179256, + -0.26146033013098224, + 0.23546365682204085, + -0.26097145636669267, + -0.31182888629226635, + 0.21114193971592965, + -0.03606310504129745, + 0.5395413743725391, + 0.1476560681304866, + 0.4222538530292633, + 0.5994668342075413, + 0.5206903061264027, + 0.4428862532927901, + -0.33458534053624484, + -0.1297075932085694, + -0.19534988516534924, + -0.27074674734888593, + -0.2734742559179009, + -0.16287015098549387, + -0.16793015496878294, + 0.42952633288826636, + 0.10120957719590495, + 0.13168333870652738, + -0.11966214451524126, + 0.2775945568245143, + -0.23817591668877847, + -0.08760012922189514, + -0.1772351271555049, + 0.05622588440718901, + 0.04944654425572087, + 0.03390970119119785, + -0.03380178836739306, + 0.2113452788282809, + 0.2815710544014416, + 0.5956731480812829, + 0.07713585171771481, + -0.3914385899184187, + 0.2097409564696746, + -0.2589072008807016, + 0.6649340128070239, + -0.3392718274149841, + 0.04678612649602015, + -0.290789951586387, + 0.5283920779433784, + 0.2817952873632411, + 0.38893621842521076, + -0.1931342048505327, + -0.3081153532161005, + -0.34465357210562797, + -0.31568051232119293, + 0.630227847639352, + 0.5751553305071169, + -0.3988421254483325, + -0.012057234159418062, + 0.4451922719640232, + 0.5280335836840427, + 0.11706575805018149, + -0.07098684802270355, + 0.5603842703758407, + 0.3862221048209695, + -0.01832842975600607, + 0.3509772459757601, + -0.34636112267508457, + 0.6420195136774599, + -0.21544080184306558, + 0.6378610564722539, + -0.3248704952597652, + 0.6514475875079683, + -0.1369249514599341, + 0.5806342631139585, + 0.054122589387270825, + 0.0678326406798771, + 0.034689981914516055, + 0.26844486165493364, + 0.50283537062052, + -0.23972282098514713, + 0.43458908393945195, + -0.24417483550927488, + -0.039743842121988726, + -0.16187756170292303, + 0.5959508368718962, + 0.6238519362663247, + -0.06342559329034558, + 0.23919251974099964, + -0.3247908648344276, + 0.013328196593526853, + 0.38999809214998893, + -0.2028943409762142, + 0.11967405491516814, + -0.10314332357768363, + -0.09925283416068942, + 0.31328004032845913, + -0.32301725383442015, + 0.23322324620376056, + -0.13570408007126122, + 0.4526540340484472, + 0.06504855479369698, + 0.5447307058549141, + 0.5665504094390533, + 0.07394840935847274, + 0.24216667733592157, + 0.4960774880784288, + 0.0984760941231087, + 0.002628777111741254, + -0.22026106849626786, + 0.30784574038550394, + 0.5118141718983771, + -0.13894737655041994, + -0.2633452346789654, + 0.3584929296379332, + 0.3675651918135102, + 0.6600563999409946, + -0.005363747481940961, + 0.6530590531827279, + 0.036427675119895475, + 0.1436309088782053, + 0.5416803787643205, + -0.3400980197024867, + 0.5764884335046947, + 0.2904473134550086, + -0.3617570943585085, + -0.3370379714363625, + -0.13394157603378098, + -0.0559244439388949, + 0.42521902457212835, + -0.24194852491277638, + 0.33536575877639485, + -0.288403158585427, + -0.040691492957032394, + 0.4402816779755998, + -0.02862250438357733, + -0.2825557035163188, + -0.16970094837797967, + -0.20282020142212256, + 0.282100375469167, + 0.40559122595433883, + -0.2061011239970558, + -0.3680825117286251, + -0.14888493381104018, + -0.009984721797993867, + 0.2451614227549238, + 0.578933405468833, + -0.34868838626289295, + -0.30156670666852226, + -0.26073682662851533, + -0.35853624619936875, + 0.5983854289288315, + 0.36472036005587394, + -0.18238095234776244, + 0.4671918411347762, + -0.23317799723020474, + 0.5206692331270519, + -0.05193332160669539, + 0.1944925732827656, + 0.2322591231028559, + 0.5374970555680292, + 0.17115469662259986, + 0.08347831100636033, + -0.3622937748773045, + -0.27796258112789946, + -0.319235616037268, + 0.0026081949166855134, + 0.5769066976980437, + 0.16280026343322163, + -0.23469645356031435, + -0.24393540243656628, + 0.34362655549626087, + 0.2539847122504081, + 0.22171699515578747, + -0.042499745606004224, + 0.649803903863679, + 0.34617094649543445, + -0.3125058732472245, + 0.2133643793655794, + 0.08725903521681183, + -0.04444528643623613, + 0.5346939380411345, + 0.16077070578427444, + 0.023017340719697077, + 0.6028801985925173, + 0.622577948186774, + -0.02956895205258231, + -0.2886762929557327, + 0.5171724900947413, + 0.48627085928791947, + 0.4107714102068064, + 0.34887430054733237, + 0.04138241953761346, + -0.3383669743753164, + -0.001415981857402493, + 0.19298223025809746, + -0.04779591921331211, + 0.03407172027041849, + -0.38509038434140536, + 0.08007035252390826, + -0.20030733137776952, + 0.5523207886440736, + -0.2936085077161018, + 0.4868895416894151, + 0.09931461318691381, + 0.522862806690692, + 0.123721746573897, + -0.24711415563410333, + 0.4724102978508594, + -0.26815724900403676, + 0.6669136107638155, + 0.5207529705161384, + 0.34806829524246297, + 0.02809633026171765, + -0.2975040052894078, + -0.14517889091745517, + 0.10419605030576229, + 0.4116205524522366, + 0.4955604134982047, + 0.4733039234522186, + -0.07902292161751234, + 0.5588009581136765, + 0.20310909944413524, + 0.35106449158409414, + -0.17680988595119385, + -0.3311917523752067, + -0.12446269640557367, + -0.28768257854052126, + -0.36456648744768183, + -0.2968721698640424, + 0.10920015102309477, + 0.41688417583374515, + 0.484561386225283, + 0.007374294720740693, + 0.5236327197938454, + -0.11821914928268584, + 0.054326715390865477, + 0.4229077459469617, + 0.1063384431415535, + -0.24929827837180618, + 0.5177193044870426, + 0.19707072926771596, + 0.21920779083895792, + 0.3924942666307555, + -0.19400360109473158, + 0.1351053955870165, + 0.5583637085509675, + -0.08993993658574484, + -0.2758475394781604, + 0.13021359072987082, + -0.25724873612255295, + -0.22230588411881902, + 0.5300908910112142, + -0.33731554941313197, + 0.31365451555759927, + 0.26704636847726626, + 0.6112388407620873, + -0.053004441558967386, + 0.3793039080374093, + -0.08417059669802457, + 0.10005732572061654, + 0.43353540118862477, + -0.08526025946069088, + 0.0441079233283172, + -0.16846551706004873, + -0.23275317826583444, + 0.01829503764850432, + 0.3446110064848218, + 0.27826820074113756, + -0.33563142922047695, + 0.26480368692858136, + 0.5539904202732667, + 0.4699747474669813, + 0.5166994755667016, + 0.092892488699855, + 0.6678014984089892, + 0.4302362604261756, + 0.36136024665008515, + -0.18604639835840173, + -0.04337634278563107, + -0.2087659460256106, + 0.27727675075300584, + 0.5391424005090246, + -0.12970111791582212, + 0.3374744551956047, + 0.1711781766511754, + 0.4927781547968717, + 0.4346128135840823, + -0.2656298631475933, + 0.572525983813508, + -0.19310312640439958, + 0.43091332610075705, + 0.5240304363912869, + -0.06001543488630179, + -0.2900333812361362, + -0.2815917770945972, + 0.35373684006632244, + 0.24633111911723238, + -0.284709146495985, + 0.06641285008596148, + -0.20117178650933454, + 0.6700468626995574, + 0.38620318274262466, + 0.37625730667514257, + 0.4974448783582175, + -0.28873208182136423, + 0.30170530418587804, + -0.3539209893850555, + 0.07107931308134269, + -0.20916055851466134, + 0.3994372528098932, + 0.23068545056816592, + 0.17137506882723186, + -0.22960411167542616, + 0.23381114335760111, + 0.3860833799401958, + 0.08899983371266618, + -0.1679714438100401, + 0.06762920507189268, + -0.3728704000852847, + -0.1022086944299751, + -0.1047861867801877, + -0.015121540976805015, + -0.36069409647767947, + 0.16314625175889186, + 0.4039709056602795, + -0.1417131974016933, + -0.2991149022712807, + 0.004906853025837599, + 0.4696067754133515, + -0.007833200297122866, + 0.06114300475570772, + -0.3093195211920111, + 0.4460759197072576, + 0.21055678544780176, + 0.591657350162516, + 0.6721137041005193, + 0.31386282690059786, + 0.0750169973254376, + 0.6699041250794967, + -0.04928530998647246, + 0.0216115025773419, + 0.46681183842353935, + -0.21946116422079603, + -0.03944771773115824, + -0.175041734846715, + 0.40799711024831253, + -0.3827862844520079, + 0.4839722906782786, + -0.1547626534818411, + 0.5274988142521531, + -0.16135862552327943, + 0.11762011304557707, + 0.49869162497266395, + 0.5564527778495981, + 0.4640898507772705, + -0.0015637306051736743, + -0.06213780359701643, + -0.17681457927174585, + 3.961846204902919E-5, + -0.23007322575843475, + 0.053759047931581594, + 0.6154761034313886, + 0.24448574714122606, + 0.07004396259172913, + 0.6820018729934277, + 0.614663167046336, + 0.22789267809712177, + 0.1880608657636358, + 0.5125965883482262, + 0.4979997499019695, + 0.35393895086319094, + 0.44448971792278125, + -0.042475141265559124, + 0.5562367307950289, + 0.3498636316724645, + 0.2826350192818783, + -0.07163568749204963, + -0.3997359994063637, + -0.277275428308697, + 0.055510595161941734, + 0.6227503099595543, + 0.6716139668617541, + 0.04395779013190926, + -0.3830843645355501, + 0.2876174986163781, + -0.3011153303971205, + -0.16580981553928695, + -0.03665292290184108, + -0.04796741277047584, + 0.4500390808354561, + -0.30627210422115253, + -0.03178935504380198, + 0.30847813282904935, + 0.1052831004221193, + 0.5830031122534807, + -0.2359202705128193, + -0.08956998236185731, + -0.29513657222620465, + 0.09498690883344957, + 0.43788193668147146, + 0.23048746282968569, + -0.12054203698404864, + 0.6682200594430995, + 0.29134199874631017, + -0.04297543756157307, + -0.3240916543194854, + 0.5436946729095739, + 0.6395786252089924, + 0.22127261690963174, + -0.15895803893063526, + 0.27075952059024744, + 0.4210379340985062, + -0.3151109249462234, + 0.5044547356667994, + 0.14325340642745066, + 0.5400429729005196, + -0.2628750593453118, + 0.26281720875935677, + -0.3601212119415758, + -0.09939996725382394, + 0.6760723303743662, + -0.3163842315214105, + 0.21468246344490127, + 0.6749546864787613, + -0.19669159237196646, + -0.14267872413476362, + 0.14816406420944073, + 0.21868188202605043, + 0.4724727200355465, + -0.1227706489569213, + -0.36586659445771214, + 0.5080895869631294, + 0.514494857519356, + 0.41935066480277805, + -0.03790361856503066, + 0.4961164022397536, + -0.06089524731464818, + 0.2881998684060122, + -0.02401555530605526, + 0.5535243960298846, + 0.18234234111026382, + 0.25043699357350335, + 0.1949575256435383, + 0.6387069590077782, + -0.21630339275263052, + -0.16708310226477902, + 0.08017744796276127, + 0.6492697014145562, + 0.08231641678132806, + 0.29256065920853425, + 0.18602341659866817, + -0.040540847847441164, + 0.12212031075882379, + 0.4705200949210261, + -0.17039497538239246, + -0.33602110315027023, + 0.3941312329872756, + 0.19549513251828998, + 0.2328821642229021, + -0.09622822025531125, + 0.3451323055662393, + 0.3133001866273798, + 0.29387816266657185, + -0.2354977032949067, + 0.05729646727881099, + 0.2018892563583785, + 0.6795039307007925, + 0.13482623315215003, + -0.18274488514111914, + -0.37548382101208605, + -0.15236522265012373, + -0.14062833298849414, + -0.31493991896185514, + 0.1695964475581796, + 0.3463026449773533, + 0.5152547526706555, + 0.4668619178192148, + -0.26101932492322755, + 0.246815238164509, + 0.10943775973102265, + 0.2675910662364488, + 0.22764839268996373, + 0.4905802418805776, + 0.5805130708392398, + 0.30028930667894627, + 0.46962200166304735, + 0.5136570146310504, + 0.0867445613807118, + -0.36568763885826333, + 0.6819494409989725, + 0.22055354389507853, + 0.39725780694688795, + 0.4568068481815514, + 0.26482496496090946, + -0.3179420787238812, + -0.31152876704633786, + -0.3665463199499585, + -0.07271980755667429, + -0.13332273067132416, + 0.6052614438686569, + 0.5102740158655084, + 0.39212581448607353, + -0.07011457285877243, + 0.6821529725696512, + -0.22590730568553197, + -0.2890075024296509, + -0.11891244285016045, + -0.028038368010971926, + 0.08980923693449389, + 0.10986339313348514, + -0.21200962105278875, + 0.5579923830855625, + 0.08749929065522472, + -0.14005141980503572, + -0.3236254331787233, + -0.30473619179830413, + 0.6084059678568149, + 0.6565515662249589, + -0.07037722192864293, + -0.18832940591600308, + 0.3671097762834805, + 0.3128112253758051, + 0.15673983229699262, + 0.5317356786058139, + 0.11785174791670039, + 0.33640405661498707, + 0.2518749996837294, + 0.4848461698325922, + -0.31211907617507006, + 0.24452974590487353, + 0.4417515837528754, + 0.4552254543617523, + 0.1451762057116046, + 0.07480199259599862, + -0.17900550552182798, + -0.3081454587792817, + 0.24709593653794715, + 0.0032771602678058342, + 0.6225185400379575, + 0.20712870605593436, + 0.6795023568720678, + 0.4546511638525137, + -0.2292854943124712, + 0.41191686503953373, + -0.1574999798975972, + 0.29828605835913, + 0.37106981435834496, + 0.4353433274811078, + -0.04998292183865077, + 0.006855791746175566, + 0.22527159266430952, + 0.6081882160702964, + 0.4947418731525337, + 0.2023698107484847, + 0.6678143274972922, + -0.11566280895428716, + -0.19404135789323054, + -0.36592420039794643, + 0.13947413641645467, + 0.3819710613894076, + 0.41418728790120474, + 0.09370419990843676, + -0.16633092917685915, + -0.28916774060413175, + 0.6450592586637504, + 0.4407210135092705, + -0.20150463714648567, + 0.285289083936215, + 0.6635651714180285, + -0.3513512579850334, + -0.009734729626807048, + 0.08052742470671781, + -0.009330541283874116, + -0.25664062614424693, + -0.34157740784092316, + -0.14313028233494102, + -0.23050942171968644, + -0.3568681262404364, + -0.04343406123051746, + -0.06593583715713042, + -0.25406344934690395, + -0.3009681123305135, + -0.19016618431152404, + -0.23337153414554265, + -0.2952904400209858, + -0.307600054923524, + -0.3410440044358555, + -0.22584383602556474, + -0.33304894316089406, + -0.015557917441465396, + -0.3755010354240651, + 0.009698498036414649, + -0.03937270831301526, + 0.07738092625633158, + -0.09229145212678708, + -0.36130896525541856, + -0.22816848239385717, + -0.1642228012912292, + -0.08394551692436641, + -0.03638528037727551, + -0.27489486756914505, + -0.09785036982783901, + 0.11789981357356183, + 0.09701597632196302, + -0.009842550506290904, + 0.1258378705855261, + -0.30786032193680013, + -0.15086767198204018, + 0.03220869986131658, + -0.2698669332577102, + -0.24296179916418623, + 0.04161073827247819, + -0.21805409239499574, + 0.10211575931650763, + -0.27212852419500694, + 0.12463161447861293, + -0.08770691507000733, + -0.19204523810430893, + -0.2233125284447549, + -0.32393094213893964, + -0.09507397667807149, + -0.2081844633585609, + -0.05523270998920038, + -0.04069328371042186, + -0.3905757684203585, + -0.19226541137605738, + -0.3208139305902831, + -0.3079950062903219, + -0.061652081078608145, + -0.06418904461969666, + 0.02743017372340767, + -0.07468850362492441, + 0.06350944601041131, + -0.3749164938904359, + -0.29282275950088227, + -0.16624280717198459, + -0.16193294648171477, + 0.1039737937477565, + 0.10661532708059185, + -0.36213899373469927, + -0.22841099706943924, + -0.13884988097832118, + -0.1501148153750639, + -0.3080762381246741, + -0.07676233393145299, + -0.04572554871998158, + -0.2154866858947949, + -0.15846019850680948, + -0.0708094974542341, + 0.14119434876711356, + -0.03180813129550292, + -0.21869841069333273, + -0.3515817892425766, + -0.35725797826395544, + -0.2672508155669974, + -0.013316726973279291, + -0.3754057769010233, + -0.3483590311036638, + -0.23256730889515426, + -0.375645522891698, + -0.24512516774583917, + -0.3860702023798642, + -0.001400339140586182, + 0.045310972933552796, + -0.19437020894800922, + -0.15105780214081804, + -0.036779238398542746, + -0.0313886437565562, + -0.1803716358377623, + -0.05056733234604516, + -0.37361879821933913, + 0.13954960500456448, + -0.2714084780931347, + -0.06576152640739558, + -0.18742601336473866, + -0.2833509514086178, + -0.24377737987803377, + -0.17999698841716855, + -0.07718186560833096, + 0.01799220072004276, + -0.1368837490578984, + -0.15429939989026967, + -0.1206705680787627, + -0.20374739468532263, + -0.08960211599533646, + -0.025150794020565526, + -0.1371586948286368, + 0.14110157528891754, + 0.04313237341510939, + 0.07441957060659088, + 0.09843596446148672, + -0.021381724261349377, + 0.12990037325287684, + -0.3254818112262219, + -0.01585053043355089, + -0.05078550678890592, + -0.11335699096287888, + -0.320376190875746, + -0.20925162272676448, + 0.11647102000035403, + -0.3845343414571074, + -0.03241539604291882, + -0.37605360087164635, + -0.13158872866069776, + -0.15305856152121047, + 0.029498269946418187, + 0.10167452325068127, + -0.23458511965509624, + -0.38077449618042325, + -0.2920249604596945, + -0.07109597519874572, + -0.09958870160740163, + 0.05373180643561898, + -0.2916331945461399, + -0.3140845520904458, + -0.1940929771071691, + 0.06306713180632789, + 0.06020223859378643, + -0.07184509051284371, + -0.11082377051659809, + 0.14824310198776514, + 0.06591945585019987, + -0.3218286338341107, + -0.34322879026783226, + -0.2924596022228677, + 0.02886737594150579, + -0.21767147482190086, + -0.22820921433788796, + 0.09344457910559767, + -0.2271362649481167, + -0.1201935652469413, + -0.16284691505485416, + 0.08999509572974662, + -0.07272342505460788, + 0.0593028009315012, + -0.3417833039161612, + 0.008714527726037424, + -0.2091907936670941, + -0.3911956586206732, + 0.09468834603404708, + -0.23864639044449104, + -0.15617006064196437, + 0.14163978043651448, + -0.12869832019152366, + -0.32927307147201007, + -0.25831383878451936, + -0.23507883396542512, + -0.2510293053176314, + -0.1498584270763082, + -0.3554517365232802, + -0.23586685721509748, + -0.005820995014750918, + -0.33430545277772394, + -0.09809194206519967, + -0.3215260400182086, + 0.06333191006219252, + -0.2356375232039473, + -0.38665348210307066, + -0.3840800008571111, + -0.2950803616456345, + 0.09760946177998059, + -0.36451721674050297, + 0.11802614197976657, + 0.12476742594022061, + -0.3071413435922187, + -0.31804061568312864, + -0.18454718198077089, + -0.20385651880118946, + -0.0746756213982342, + -0.3802130025884744, + -0.08380734443659166, + -0.013610226437624384, + -0.011155265979860995, + -0.304008854840458, + -0.08249776096799638, + -0.13638659199283676, + -0.11965409037905422, + -0.2530241243504219, + -0.36576093226600814, + -0.17598350303319737, + -0.18886127589776014, + -0.2632996309796942, + -0.21291112775519955, + -0.05419858618804463, + 0.090206803432613, + 0.05946757291261423, + -0.13450234873984968, + 0.07435615191327555, + -0.3218264412858729, + -0.0700715223782391, + -0.1144740027760146, + -0.19512577611139403, + -0.15876077082155196, + 0.06956882726858926, + 0.0816076394533295, + -0.37021901317465544, + -0.009654351575266007, + -0.04131645811499146, + -0.02445048275691647, + -0.08340268628090236, + -0.04565136323367169, + -0.03904795951901846, + 0.08485409024383944, + -0.3603340422464829, + -0.3568500058428221, + 0.05278929794742854, + -0.1596367250315796, + -0.297471223742482, + -0.09676041573086064, + -0.21638358805460436, + -0.39886923960837495, + -0.35505520401265334, + -0.06280990895481897, + -0.22467705691709197, + 0.10641530527178422, + -0.03620514181666479, + -0.08567526078825838, + -0.19504571954775374, + -0.01992903684423275, + -0.2214489893474725, + -0.3487331616986315, + 0.06045575543907172, + -0.058142333804468704, + -0.20049760801988478, + -0.04050807592959388, + 0.1251919215977868, + -0.2309512404842129, + -0.0062978714965858384, + -0.33174969741737337, + -0.06980812102798506, + 0.07913024739631286, + -0.07128240160879756, + 0.10766089260382428, + 0.13111666398456046, + 0.009181272071221547, + -0.29748839796660875, + -0.1653223937529884, + 0.10766952239094585, + -0.05836856603892132, + -0.02635074900969553, + 0.029870520874065554, + -0.3656502925893865, + -0.19582706566651703, + 0.030288937622913237, + -0.08868175332862438, + 0.0347841998756202, + -0.3581234111012665, + -0.367701810404299, + -0.36181281005505433, + -0.01251133219133338, + 0.0035272213804031782, + -0.3000877011610621, + -0.28452127470464716, + 0.005886822949095871, + 0.14626252365479087, + 0.00415608235457221, + -0.18227518028541143, + 0.00237217103690196, + -0.3216416124634055, + -4.4703627620790165E-4, + -0.34221354227612855, + -0.19729691550186307, + -0.24728878065456453, + -0.059375337216053536, + -0.11136964075095768, + 0.13174344537039173, + 0.09755239825538448, + -0.1263829561283284, + -0.19914246290830823, + -0.08516341871752126, + -0.09150428728905008, + -0.2164423914045247, + -0.2321055848019958, + -0.304407061056625, + 0.12490366974244793, + -0.1786863328179365, + -0.08211048890713041, + -0.2517308273334066, + -0.0012730107309130712, + -0.17582622940066164, + -0.2830734529803968, + -0.1626197054393973, + -0.09818373074677222, + 0.09363135210540319, + -0.004517732309542277, + -0.060410915338940885, + 0.13856605690116375, + -0.11931405822220198, + -0.01836761694162209, + -0.2777696163562133, + -0.3236894535041825, + -0.33915102661408353, + 0.12226147112863595, + -0.20292359894153492, + 0.12665280480448093, + 0.0894169418710144, + 0.1290578995619056, + -0.3609068800040676, + -0.24830008267562734, + 0.09683515139206439, + -0.012629771793401634, + -0.10492155597861691, + -0.15216752994397753, + -0.38662617010340766, + -0.10006259854735045, + -0.2995053473109294, + -0.34361510111829385, + -0.05164792206115587, + -0.15806779121025166, + -0.28315288938507754, + -0.3038437394352643, + -0.028376741422662277, + 0.0960213782328766, + -0.20708303838448625, + -0.27019412618134137, + -0.3335794951050944, + -0.09948589561341298, + -0.16700323854289756, + 0.10793936233264956, + -0.3716108029678804, + -0.21603224015337028, + -0.04169038183962415, + -0.12836567259502052, + 0.00931324842847675, + -0.2648109248191536, + -0.2616109998532822, + 0.0762457860214944, + -0.11859242995974262, + -0.24198486353224785, + -0.1177838588172559, + 0.04189766063737277, + -0.25210164006541014, + -0.11933656280958505, + 9.612305231878615E-4, + -0.14294142590863063, + -0.3104581069983772, + -0.11637091066926991, + -0.1622246045719802, + -0.11869598328092346, + -0.01414807828117659, + 0.11556061216758062, + 0.13522911833629436, + -0.3442627304295064, + -0.1916864866857944, + 0.1018225124942922, + -0.2603657832040541, + -0.00392449646797105, + 0.03652834714792258, + -0.10754944167537367, + -0.3670882338370339, + -0.319380092545237, + -0.0614382763216717, + 0.09689795392028167, + -0.23143728028799018, + -0.3776602886170574, + 0.04776683418458705, + -0.3087145777696926, + 0.12776366412892637, + -0.368760825957009, + -0.031629282952340354, + -0.31064143463802374, + 0.08644769402839175, + 0.08154175292685728, + -0.0699918575764702, + 0.042203330775386405, + -0.16496532675585732, + -0.09923037259150558, + -0.36918280608099485, + 0.04968535511336469, + -0.0947907377208504, + -0.340944724172196, + -0.31298318335417996, + -0.2944471921380477, + -0.27686930426322565, + -0.22473707417779018, + -0.03323582553746901, + -0.04563170984654019, + -0.07551708407214763, + -0.3013496422829016, + -0.2047247247119197, + -0.2200367655054311, + -0.03623928972527246, + 0.06310553967150101, + 0.14240116936858171, + -0.013124965864777072, + -0.057407549595690555, + -0.22351548859232342, + -0.35726469519923965, + -0.326665968027854, + -0.3856829005111819, + -0.13861579921402434, + -0.37544899376670265, + -0.25691148953642723, + -0.15163723021904535, + -0.250095390474172, + -0.3036396051054132, + 0.07195003347325957, + -0.007490423011273339, + -0.20909022119204226, + 0.048743573589925315, + -0.09782686016875575, + -0.03835800300109343, + -0.21529844402130063, + -0.10029557728177424, + 0.13842485998306808, + -0.17588170215809845, + 0.025221747542349626, + -0.2760480905623021, + 0.13071944823504977, + 0.033553546164282855, + 0.0848818557137132, + -0.17111892584028762, + -0.2174564780442809, + -0.19089065560055415, + -0.2464082597085413, + -0.2844199760032776, + -0.34516406574764835, + -0.0594210720818516, + 0.01158354997154043, + -0.2228321594630035, + -0.2692809333820011, + -0.25481949021560285, + -0.33425026932817226, + -0.22276948798508037, + -0.14118415765630615, + -0.38020459191562245, + -0.19572875940882498, + 0.0077304020913813165, + -0.0903717120261246, + 0.06307888352181068, + 0.11708901905541791, + -0.14091330772180938, + -0.27172335130212755, + -0.257169584595362, + -0.10857445832654844, + -0.3544605983615056, + -0.10654504820692168, + -0.013249646341022991, + -0.09848169563464809, + -0.14916592353964397, + 0.03256080404274608, + -0.2038182888891027, + -0.3686685496404891, + 0.06910443010304163, + -0.30842332499656067, + -0.3144080837903868, + -0.34205103124624914, + 0.12103154216127177, + -0.09271611548244973, + 0.06210531976183037, + 0.03556818697307368, + -0.2358670780702004, + -0.20293787283544318, + -0.2085777880394763, + -0.37801568066424013, + -0.3229188640843085, + -0.29839554203473084, + -0.1788821146516375, + -0.11041887354736418, + 0.11143144549730921, + -0.10746217907778155, + 0.07774433886143833, + -0.22691116062575167, + -0.00805204239332108, + -0.005744662882244678, + -0.03006843740880283, + -0.31108415430337005, + -0.3433889892590601, + 0.08815141974292384, + 0.016182047039700942, + -0.11949728047218039, + 0.060309081420795, + -0.0329542437278032, + -0.17453660195893334, + -0.17290778475780308, + -0.37164173086719887, + -0.1909903762249377, + 0.04465397854586106, + 0.042651135687689856, + -0.3554188208595119, + 0.04847349229794895, + -0.013939978705131695, + -0.38590532033328645, + -0.36692702024224716, + -0.04330975177932661, + -0.0013972193329707117, + -0.1271231534819997, + -0.18918616609223707, + -0.24323427683280732, + 0.00396516654089063, + 0.007528847770099878, + 0.14787609693514803, + -0.10296074535058153, + -0.3685600100400799, + -0.06766291305478539, + -0.33564345907525844, + 0.010798592121962325, + -0.0854875569776708, + -0.3995499535322787, + -0.0477721440276524, + -0.21666356817913227, + -0.12754360158929745, + -0.3888824913030268, + -0.13041224573955845, + -0.3862938242310157, + -0.3984332697389422, + -0.30003548225143584, + 0.04090546780804977, + -0.2960715503550975, + 0.13508937283174627, + -0.2441364604527979, + -0.30837651844528696, + -0.05908990006418985, + 0.023031085563601228, + 0.11537178652894553, + -0.016854637103667247, + -0.08133983596169952, + -0.2633657743553448, + 0.1346070957310358, + -0.28553672654897977, + -0.1416942953790542, + 0.028774787381247446, + 0.019399503586071953, + -0.2029560494840044, + -0.17818071316938816, + -3.769230461240225E-4, + -0.026780344798254363, + -0.31688496318945714, + -0.0914160768986797, + -0.30995744750233056, + -0.10945055783719565, + -0.030994140608908705, + -0.2722729371006518, + 0.09811675475117765, + -0.25336733747372786, + -0.3837181040313048, + 0.022772681167910924, + -0.05362370690801943, + -0.3879761255618494, + 0.14225243685979572, + -0.2495226608576374, + 0.07437216877402064, + -0.3918570739890528, + -0.3312784960171862, + -0.05031257808423273, + -0.3488097365202535, + -0.15944277093323517, + -0.39385729843209133, + -0.1252702275140164, + -0.20165235265400258, + -0.12195613941897532, + -0.043189106850897885, + 0.005565387863875504, + -0.054203769115794, + -0.34879417942153856, + -0.1351210503129343, + -0.26547728158059236, + 0.023419909179857756, + -0.1163857586296686, + 0.0036998156174414265, + 0.0847659385484319, + 0.07252717426390098, + -0.19398163638878113, + 0.050286810680968685, + -0.01811553504348512, + 0.011345372987039137, + 0.06566725540342, + -0.15164502573725053, + -0.1133648890255356, + 0.04356555464344525, + -0.2847390352396056, + -0.13706248778024466, + -0.05560659674780305, + -0.1690596754941748, + 0.035661571759571964, + 0.29616568741486293, + 0.1645542871628964, + 0.37264486159297716, + 0.36332794920576983, + 0.38375917422805605, + 0.21043950051945567, + 0.21567983799685186, + 0.16996154407598607, + 0.38047953255714806, + 0.3277884384052842, + 0.15807258604930927, + 0.27970392944796496, + 0.19191342938104056, + 0.3858936814305683, + 0.3833298279297457, + 0.27024037341409823, + 0.1692155473640982, + 0.16102348983493162, + 0.3490311550084596, + 0.256924747768988, + 0.22013449441629226, + 0.32936615259006563, + 0.3630667725697283, + 0.23575643523821782, + 0.24450526182503568, + 0.2760012061314161, + 0.2554440712503438, + 0.2509963433712131, + 0.1955671769644511, + 0.30519996527501575, + 0.3550736611769427, + 0.3216077932705956, + 0.25054218733198896, + 0.2972922546967175, + 0.2723840320393198, + 0.20169608260621272, + 0.3232818510495249, + 0.3632539368822537, + 0.21027814282246401, + 0.39080882580891985, + 0.2475729293836732, + 0.21052884380664855, + 0.27295724911004726, + 0.38117436569433394, + 0.17890587219298226, + 0.1803631456102814, + 0.38429637069338185, + 0.3662052854827318, + 0.169846081141677, + 0.3658572422223505, + 0.2933531490975376, + 0.34175515197323514, + 0.18280082704126274, + 0.20272226151136552, + 0.31761189408368795, + 0.3236029026677476, + 0.23976176847836508, + 0.2600782924816438, + 0.20518327503258246, + 0.2738330982189126, + 0.21295218300386462, + 0.3397929482219494, + 0.33491550579426216, + 0.19352185401111288, + 0.3242478282286748, + 0.39252354825772706, + 0.31449823184261577, + 0.282674255191514, + 0.3059903534761985, + 0.2477921389998624, + 0.34433526871445186, + 0.3736023284979839, + 0.19422037045972457, + 0.3901453387604304, + 0.3097616977866708, + 0.34122549096900223, + 0.2226042233986359, + 0.21366448547485492, + 0.21175572726190664, + 0.38740407208446437, + 0.2856439619632538, + 0.2654478305107489, + 0.2403767410612621, + 0.21847636387295863, + 0.19874764399479486, + 0.3376055893962727, + 0.37397372822370945, + 0.3707814505190358, + 0.2522627199134411, + 0.18385463895104207, + 0.35493830343281946, + 0.27313114371784125, + 0.2463695278853461, + 0.16698370727755033, + 0.21029806442831117, + 0.3515234987671986, + 0.20624275022400046, + 0.20176646029530043, + 0.32490954273607253, + 0.19038176201538232, + 0.30212022091517987, + 0.16114093911743652, + 0.3835552558582984, + 0.23540047279888968, + 0.39235079830926445, + 0.3773212386353935, + 0.3251969999319716, + 0.21587967975613512, + 0.16625363176431002, + 0.31136716984099155, + 0.2159117435221703, + 0.2793695567986849, + 0.24516198235813347, + 0.15667939662214825, + 0.18829414899412147, + 0.2751869638477742, + 0.3312110821763069, + 0.37727386524505613, + 0.21144791292422735, + 0.22738869874548023, + 0.36753995628929326, + 0.26620804034116996, + 0.24472705820961277, + 0.24020050501241294, + 0.24683460475864122, + 0.3560655874475111, + 0.18543621269541913, + 0.20087207606278745, + 0.3094830255070392, + 0.17527007697273717, + 0.37273891475775844, + 0.25228630883030734, + 0.3416920703671974, + 0.33662566379352055, + 0.20598733574947417, + 0.31765998598151235, + 0.2370189176917878, + 0.3404915688632575, + 0.1710747406349181, + 0.38995169297166954, + 0.18730905449695467, + 0.3407283148082756, + 0.3594835087921161, + 0.37993545421217234, + 0.24526625059667476, + 0.2980193725379807, + 0.3889534982018328, + 0.3920148898854444, + 0.28859061892507243, + 0.33022046064015886, + 0.22541417279242887, + 0.26413670417544327, + 0.2997057069197012, + 0.2966505148372524, + 0.2935180919368144, + 0.2215696086265114, + 0.36704665197004926, + 0.2966349674826395, + 0.2815813616722743, + 0.3077735846668578, + 0.32706279788349435, + 0.20680790752379546, + 0.20068323372519736, + 0.2616775382670411, + 0.30969277954621915, + 0.29178244867584346, + 0.3277707774686916, + 0.2798287621099004, + 0.3838456653160788, + 0.31651828650818986, + 0.3801900870131813, + 0.18448609863602908, + 0.3389454251362397, + 0.3496484936559188, + 0.3825532619680926, + 0.17593888587464482, + 0.23289442358545834, + 0.3267316015188119, + 0.3162950214599499, + 0.18430496733734125, + 0.20538194152943123, + 0.3676523397210526, + 0.23564876840491206, + 0.2581999752429913, + 0.2521569803834402, + 0.2331870014957202, + 0.3664493267866006, + 0.19146120101266956, + 0.31481085125317076, + 0.37627092019536945, + 0.2358728681238741, + 0.3028401110902007, + 0.2252646242629657, + 0.21212732612857194, + 0.16343391251333386, + 0.195251299740965, + 0.3132386753295749, + 0.29009069023514245, + 0.2550971527728266, + 0.2214479928905983, + 0.35390390665295596, + 0.30739500814908205, + 0.38690038217829414, + 0.3273792552175777, + 0.17746479928502046, + 0.2605282459880335, + 0.1834777657809768, + 0.3727180610455038, + 0.16423818959869024, + 0.359925225139366, + 0.21649578785557844, + 0.18609012197312128, + 0.3315012538723582, + 0.3387318651231735, + 0.18630242497243593, + 0.19323404501091487, + 0.32664266468733966, + 0.3179522067057027, + 0.217350702532964, + 0.2127918611471863, + 0.32875331812392306, + 0.3876778528421391, + 0.30476802416169274, + 0.18944962386261507, + 0.19987477097536568, + 0.2726619540051436, + 0.17263424663236498, + 0.33234024870711754, + 0.2107051380401433, + 0.292586728750985, + 0.3043423103671571, + 0.17878956486050956, + 0.2713525089831143, + 0.339511630768631, + 0.32124502070527183, + 0.2950124970204042, + 0.2805472181613006, + 0.3131342024727114, + 0.31145936728730395, + 0.33552821790384374, + 0.2802137029956411, + 0.28491968868474477, + 0.30626289959540076, + 0.3494655737802703, + 0.17863711271344943, + 0.3843688282714659, + 0.3180904534852057, + 0.2242993973608945, + 0.23917270005758678, + 0.28926733946876504, + 0.256018915482666, + 0.17913096721499755, + 0.2857769974036177, + 0.19071514584614307, + 0.36603389531278685, + 0.2840618262146498, + 0.37212061718157086, + 0.19589423182026272, + 0.29478784060909985, + 0.37817507069071665, + 0.25007490915931796, + 0.3770141233205814, + 0.25998019839701586, + 0.16274364953681067, + 0.21213262931983645, + 0.3913107282980776, + 0.30414072701468253, + 0.32461128138554896, + 0.23350463890490997, + 0.356852751164873, + 0.300187646876211, + 0.27353470098722976, + 0.16297850741099876, + 0.22503755316492552, + 0.1957284927215688, + 0.34755366046996705, + 0.38489029784700135, + 0.1932039994417193, + 0.37593766135964557, + 0.29244048403267947, + 0.29610776191628974, + 0.23961270796315784, + 0.37953797713566395, + 0.22097335092166726, + 0.1923377876797412, + 0.33886239502353116, + 0.33592750457500026, + 0.17091570683381263, + 0.1859270419999791, + 0.31986523383256826, + 0.305025656149335, + 0.17928053145475079, + 0.3329659519548833, + 0.23487210891465676, + 0.16419836119032688, + 0.3361396001255963, + 0.30580459500919566, + 0.30460716924327336, + 0.2641823483483075, + 0.36681286831769644, + 0.1588350335669442, + 0.3880810032933709, + 0.38647724923141236, + 0.16631184495621193, + 0.29805591160128253, + 0.3126366502416571, + 0.20695914741588745, + 0.37537746935311644, + 0.2376173300885236, + 0.343796218730488, + 0.19929205906648034, + 0.24861337430194858, + 0.3690606499885255, + 0.35374725621674463, + 0.37993757631201264, + 0.2768027216540898, + 0.2951695286525954, + 0.28908981199278294, + 0.21737632107124666, + 0.17281956309364885, + 0.3797763526880752, + 0.3446849114587546, + 0.22777485928234076, + 0.38089340684608153, + 0.15818600970112778, + 0.2713707377636015, + 0.35277282685349165, + 0.1584294244095367, + 0.18777117978546165, + 0.3594291941026477, + 0.3080445884797415, + 0.17764097773784213, + 0.2734852642297877, + 0.1649226792315333, + 0.24635755543889784, + 0.25957379064450126, + 0.2308889558068855, + 0.33763902896776965, + 0.21942446639227026, + 0.29803127026648535, + 0.2174705247545899, + 0.3690182662790866, + 0.19862329486590802, + 0.2752979963754169, + 0.19720358923360334, + 0.31038298834234457, + 0.2968004646710033, + 0.3517016857812053, + 0.34384174746901414, + 0.21511409794536993, + 0.26331320034008654, + 0.20726178820425747, + 0.37132585877814134, + 0.21111793411774252, + 0.3421359981769855, + 0.2800918652594643, + 0.21184494101249554, + 0.36454866040090766, + 0.24695954075311874, + 0.35775399022445653, + 0.23192239602376108, + 0.2491237696072448, + 0.24368492117665785, + 0.17337551623990785, + 0.3659245209385756, + 0.16730283279905123, + 0.19469740046206624, + 0.16332393623148242, + 0.34986194619781585, + 0.3584467617949286, + 0.2967242628269211, + 0.2779330362923675, + 0.31344571366956153, + 0.3234907856679011, + 0.35087964459603854, + 0.2843975355026477, + 0.23466530943952602, + 0.1738781916496543, + 0.26792620933441214, + 0.19541397976217845, + 0.3013386245897083, + 0.2661226399872765, + 0.15835154870887191, + 0.23972461538721537, + 0.29060599638743145, + 0.3170191683649488, + 0.36106149550564914, + 0.38556676887271246, + 0.1839153204334728, + 0.2463294905619597, + 0.2646936356351327, + 0.20048607600178692, + 0.32677321474452886, + 0.33361428708625085, + 0.370796803888926, + 0.22156979779637231, + 0.26633875128038664, + 0.2888101942764882, + 0.1991646248500692, + 0.37725122053885296, + 0.34887877181224664, + 0.31206902717750534, + 0.3035601602682384, + 0.15996084493785623, + 0.3762316032813641, + 0.29948946959274303, + 0.3328602625151591, + 0.19760211079266804, + 0.18372593243040586, + 0.34422694816418453, + 0.3756315048246147, + 0.17297186382378035, + 0.27825085708936925, + 0.32973280729225884, + 0.2261768773207044, + 0.20117786942176202, + 0.28278234056464135, + 0.29501317025614887, + 0.20469101979446666, + 0.281926317953884, + 0.21803954195078032, + 0.37977109865406034, + 0.18468656934880076, + 0.16435512774068525, + 0.24596030956490347, + 0.35069933510631324, + 0.2098982910469682, + 0.24103664986998322, + 0.31539285308085196, + 0.21273874915215346, + 0.22128466290790244, + 0.23555928548812038, + 0.2135668129995259, + 0.1698394907138801, + 0.33434242929324853, + 0.15828316527847147, + 0.1991373829371532, + 0.31787319299775973, + 0.3010572441208954, + 0.2483106524260572, + 0.20421808718420278, + 0.3350445704329006, + 0.19668814464475376, + 0.37118343070002424, + 0.2215395378724142, + 0.3146504924147388, + 0.24452238265809245, + 0.23359988851148022, + 0.17283197702540817, + 0.16230803349528847, + 0.29467388981014825, + 0.3608419690354765, + 0.17655230225966653, + 0.20946711421706393, + 0.38744840855021223, + 0.24012218762100318, + 0.34555345829800543, + 0.19118696031285742, + 0.27709171060277443, + 0.2858615490535372, + 0.2846067347262282, + 0.2401287976971193, + 0.2971118971460971, + 0.2882213470880477, + 0.17903749782978226, + 0.25096185175281605, + 0.22580810489426725, + 0.2226872587638454, + 0.3517789159480434, + 0.2015169149703778, + 0.16341989582680178, + 0.37468848660015985, + 0.19044831562496303, + 0.37569407870635585, + 0.2374592143649633, + 0.2980182563242627, + 0.20050344398925832, + 0.224904524032989, + 0.1861634025497832, + 0.33262519077111063, + 0.37556902895390154, + 0.2921141812678921, + 0.3228701767156479, + 0.16907429694322457, + 0.3846140822027396, + 0.2710735383351893, + 0.3536925234567813, + 0.2226078268746438, + 0.19128552242071944, + 0.3448535628725082, + 0.23523193566514083, + 0.34660857438411763, + 0.2359007815270328, + 0.21051514110927128, + 0.3427257631937208, + 0.2346950619755881, + 0.2934207390698601, + 0.22685991496011507, + 0.280960734374733, + 0.31537034415846166, + 0.18899048510848504, + 0.3805207821357939, + 0.37703311845654786, + 0.16900066843097375, + 0.2762958729039738, + 0.20768845351485865, + 0.22340387808378603, + 0.230879673925052, + 0.18503126764282318, + 0.292212318291564, + 0.38340601146484066, + 0.23714557713054243, + 0.2948706518656474, + 0.2183868214196822, + 0.24575097045061933, + 0.37933021718524373, + 0.3729808471749165, + 0.33984486305069644, + 0.354416766685973, + 0.2829933892890049, + 0.3639761606945471, + 0.35376526478513437, + 0.17027609588345585, + 0.18963858504005748, + 0.18569905755894164, + 0.3651739383858198, + 0.18515737459688242, + 0.2062534646432443, + 0.252801107244953, + 0.33492405918114326, + 0.23966166239357703, + 0.34784961099929523, + 0.3051895441075504, + 0.18548176701391883, + 0.1972311919133467, + 0.22860902684656167, + 0.20966745856821498, + 0.3178842275228416, + 0.23249671795142143, + 0.24340639059322516, + 0.3564863959710727, + 0.35294243350600585, + 0.36158220259885204, + 0.3093413866648653, + 0.3762968486277721, + 0.2302150251788494, + 0.16096824129217513, + 0.36376579120007424, + 0.19258335380098646, + 0.19088181731667042, + 0.2636424110053458, + 0.18466452880250617, + 0.3779875255734906, + 0.32070348398964504, + 0.27935087451397855, + 0.3562486135275075, + 0.21411713371895105, + 0.3285415661349516, + 0.19175502486077678, + 0.3626096693810305, + 0.3577746797083963, + 0.2841800161056245, + 0.3762773613523887, + 0.21946677196135828, + 0.39165768589143246, + 0.37869201389639173, + 0.18098716086021477, + 0.3554101107925791, + 0.374965618499459, + 0.375404078538109, + 0.32350153031291184, + 0.3032763580571216, + 0.17577142093990097, + 0.24842716159127867, + 0.37823815955390505, + 0.1948636388149231, + 0.21314152200099945, + 0.18487470313440607, + 0.31410269594820484, + 0.3329410122232993, + 0.30865807988774463, + 0.36989111006562425, + 0.25551541984375264, + 0.3822171144032711, + 0.3664358950866924, + 0.1619407254369991, + 0.3241773771491906, + 0.24114277571956005, + 0.2156398009182514, + 0.2824182325483434, + 0.3032818195263487, + 0.36692367112503266, + 0.20997105544242906, + 0.2734668140189386, + 0.25430992517779305, + 0.3263936345770305, + 0.26773279246309467, + 0.2803660850756614, + 0.36354596112874243, + 0.3072604572007198, + 0.322675602448213, + 0.36741903448028124, + 0.1615605464282488, + 0.2927764554008173, + 0.22402687853933503, + 0.2422674184918955, + 0.2424914762645604, + 0.21392969064698622, + 0.36187078730722466, + 0.26562169594680507, + 0.3066575884795266, + 0.2985435368773129, + 0.2887000935315549, + 0.3408927109360206, + 0.20846292892966586, + 0.3237706283644258, + 0.1812709317502118, + 0.25422778027181064, + 0.33520864974128806, + 0.3086834347447752, + 0.29330309822128364, + 0.23285907255661198, + 0.35996853144933516, + 0.22023469502901016, + 0.31853331612880553, + 0.2235415477606681, + 0.37906034050838555, + 0.19623695596425847, + 0.22507433411268524, + 0.19108921952330624, + 0.39237908340265093, + 0.16789461271108128, + 0.20537613205502517, + 0.3862378059020446, + 0.22257798978421134, + 0.3223262982955477, + 0.39221857218873324, + 0.3144460132429528, + 0.32528219326624164, + 0.38932365900598853, + 0.24850793189923584, + 0.2503890827979727, + 0.3868049358048271, + 0.2960233057881373, + 0.19593319669974435, + 0.22166994360672526, + 0.2904754177354803, + 0.24548257817723362, + 0.31185165738368587, + 0.24736596947901626, + 0.3681679634886751, + 0.37842275587967167, + 0.2204324873618162, + 0.38243850898025755, + 0.27785597199680423, + 0.26007050945584675, + 0.30313512935941406, + 0.17829211501960063, + 0.23788182328217478, + 0.24385882256296454, + 0.37311958114030924, + 0.3363875272700515, + 0.1806679362339836, + 0.26430410465879883, + 0.1883834350110381, + 0.24066657057224297, + 0.16794315769186582, + 0.2769127716532671, + 0.168053304845741, + 0.24600337900862634, + 0.2196171149745072, + 0.3548968824220664, + 0.3172588966732911, + 0.30671305801416693, + 0.28243801873393304, + 0.2264056474925363, + 0.351514263620501, + 0.3589680074366708, + 0.20603565090537862, + 0.227858380371468, + 0.34055181385285954, + 0.27318691220183317, + 0.33300004850460874, + 0.36852465623716346, + 0.31993006578732797, + 0.3761424761083917, + 0.3292891150493672, + 0.37042813298567556, + 0.3440020566705245, + 0.2904137463456022, + 0.28567872125604726, + 0.25480174375465675, + 0.21303375017074808, + 0.24442751930943002, + 0.33369856171596773, + 0.3606923133818952, + 0.20915950047472842, + 0.3758345565843514, + 0.1925357982078599, + 0.25650005860089703, + 0.365618550098068, + 0.2920388044154394, + 0.18808813765696425, + 0.30240759188870114, + 0.3413446789327411, + 0.385607392604563, + 0.24070143871341892, + 0.3190320476923229, + 0.23376029334353043, + 0.31398133181216825, + 0.37404534314478366, + 0.1624478117912243, + 0.19006096653915058, + 0.2807147267128845, + 0.3008925278264595, + 0.2655663635815922, + 0.15844229993281767, + 0.29914408529780995, + 0.21172618186469025, + 0.16790761322927136, + 0.30558111041515773, + 0.3283094511842478, + 0.2893711966120859, + 0.15712677403079364, + 0.3561031870363303, + 0.3399396975653984, + 0.17849204771638874, + 0.2905825757924573, + 0.22699097832384502, + 0.23333955536039525, + 0.3690477657817757, + 0.33659479750092947, + 0.24688181590451858, + 0.3431152389296208, + 0.2021774520952157, + 0.2838091743016239, + 0.37375070193251486, + 0.20108010981716898, + 0.2776883085538677, + 0.3149090941169343, + 0.34002713458359635, + 0.3299638832281895, + 0.37419959158093974, + 0.3283477902345494, + 0.39058408163723857, + 0.2875740939920909, + 0.31623987107926405, + 0.3907180688950669, + 0.23484879813234816, + 0.33019154190683203, + 0.39329031385831204, + 0.3390740373790333, + 0.30767439231334276, + 0.17910146419984319, + 0.33033887761535835, + 0.15999806340206765, + 0.22238076041321397, + 0.1843468644211311, + 0.22140030492382212, + 0.3327746336060612, + 0.3339079893744836, + 0.1951033516336383, + 0.20100296190288763, + 0.2815303256142474, + 0.16752402180733597, + 0.18668668846696876, + 0.3701979137137248, + 0.3582777636418799, + 0.24460192652861884, + 0.28538709828221276, + 0.24768849752010813, + 0.3024413815461001, + 0.36190397190660684, + 0.26205004728893055, + 0.1726544506735536, + 0.2575581675629553, + 0.29668975712489953, + 0.19140194829579088, + 0.3866650795551482, + 0.22123238733787493, + 0.19406539041469073, + 0.3454961940760109, + 0.1977454420164259, + 0.17436981645801083, + 0.17655517684034489, + 0.2095803087607051, + 0.17947507156513073, + 0.20680731384743303, + 0.1679408417683149, + 0.27759914711775135, + 0.33651637204458384, + 0.2178529083375983, + 0.34312872404285344, + 0.16764920626859095, + 0.18178936712377725, + 0.3246911729466798, + 0.33735036473537394, + 0.38740447719114024, + 0.2119194626337727, + 0.3898088791450125, + 0.28662523091355274, + 0.1724642919470968, + 0.3366578510043756, + 0.2003179530612233, + 0.17286313777296186, + 0.25595161366073477, + 0.2516732199246751, + 0.29367486696626993, + 0.1679282042886351, + 0.20804212290351057, + 0.21016368405324382, + 0.3448725699442977, + 0.2758251550082199, + 0.2144753006783662, + 0.2519679637397879, + 0.3625728179134361, + 0.18186865417065445, + 0.24048570476745967, + 0.38720343025241655, + 0.17493740191992618, + 0.21546288586105683, + 0.2641163589264888, + 0.22364781897484606, + 0.3326888244741735, + 0.35626263542272796, + 0.3124049452297796, + 0.2579596222471616, + 0.2331796966737278, + 0.2288086503189447, + 0.1658816775927772, + 0.2768851486335081, + 0.1982163926926304, + 0.24533755554047315, + 0.24293575846479296, + 0.21714959780694057, + 0.3623678578002604, + 0.38832079665804486, + 0.18840653625071907, + 0.2094804423417327, + 0.303269826675455, + 0.2927541315811469, + 0.349493494409327, + 0.3660399419919207, + 0.1974475576694038, + 0.19227781315264592, + 0.21750487496687143, + 0.3133221115527316, + 0.16278375635155581, + 0.25431087187105794, + 0.22314105445556898, + 0.214220265063494, + 0.29318126917790255, + 0.3687780105943481, + 0.199194167683365, + 0.2175728592633526, + 0.38984302151160766, + 0.35772763336772173, + 0.37405262850808446, + 0.32806116581031464, + 0.1666153780321018, + 0.35811426690285764, + 0.20935431380250746, + 0.26153402385684754, + 0.25920895322924353, + 0.21010198078468872, + 0.2724533303215884, + 0.15829853134527674, + 0.16899486837106376, + 0.22258596673394215, + 0.38204816293656185, + 0.3755024982358807, + 0.37791826726937705, + 0.2053806671599786, + 0.3302926788225955, + 0.3081247423227169, + 0.3312383175704722, + 0.3333396800645231, + 0.3693777302648657, + 0.3684032935296527, + 0.37507860470681686, + 0.32210130551452987, + 0.1681180143502013, + 0.25392017216292406, + 0.1734760241461332, + 0.3214427075066988, + 0.3746916179485791, + 0.2951836199236846, + 0.1614850616996995, + 0.1925418772847415, + 0.26384443762627274, + 0.2750181131266584, + 0.2961856239395332, + 0.2582508640157174, + 0.19402043916482709, + 0.1840658935436422, + 0.24375259561596574, + 0.27072740830968056, + 0.24230295304246197, + 0.37672398153216863, + 0.1896795773442467, + 0.27681680691284116, + 0.18038028204903236, + 0.20911905748723972, + 0.16307223215485447, + 0.21935550186984804, + 0.3345242203398374, + 0.26154709743968396, + 0.19752799754927486, + 0.20940906614853283, + 0.3711927626437894, + 0.3571046606569253, + 0.24852898040313115, + 0.1661893438116311, + 0.26586117495301304, + 0.39154084192434013, + 0.3447756222852849, + 0.2694216667252175, + 0.2068820089376377, + 0.25207313869165215, + 0.26338708187035065, + 0.3460408678642353, + 0.29226288647995796, + 0.3176633743852082, + 0.3030364799999126, + 0.3792970511903433, + 0.2566331793596535, + 0.33211196801235565, + 0.19525199547579478, + 0.36045188874425016, + 0.3693538839077043, + 0.34670224360371327, + 0.25616843907548426, + 0.21935106373042612, + 0.32823889693984576, + 0.17754562655400857, + 0.3459101509626023, + 0.3571434079314134, + 0.2971385366459246, + 0.21474745803091622, + 0.19917407367859827, + 0.21659520813384306, + 0.2682306281072209, + 0.36182698827929083, + 0.34526964692284023, + 0.2770643944125703, + 0.23507172127170206, + 0.17279078496060257, + 0.36317814943301696, + 0.2792604057209392, + 0.32197169793611125, + 0.2272751544902252, + 0.27311692564204965, + 0.20953122424104176, + 0.25075270279573353, + 0.2051187063860142, + 0.2526771169321052, + 0.3349732932776825, + 0.34025975612973847, + 0.24761914056120377, + 0.2565226219268527, + 0.20449104806543603, + 0.2342650419348402, + 0.21355590974944808, + 0.21915876612384305, + 0.24227464437550777, + 0.1816829843138127, + 0.17820258699374186, + 0.16702916582240265, + 0.21351369488538374, + 0.263447265499701, + 0.1821229098746753, + 0.1676937230608373, + 0.38710012660031484, + 0.17430189346155062, + 0.23187249438413843, + 0.35182037943724764, + 0.3605562476106271, + 0.28512998506370507, + 0.26557743556294067, + 0.2442192489385332, + 0.36266101377924814, + 0.3663591990978029, + 0.15951565980144164, + 0.27062495699161565, + 0.2427463837571926, + 0.1872393446740901, + 0.33302374945676005, + 0.21649016990372427, + 0.39287825343309407, + 0.2683151008537171, + 0.3265671221243743, + 0.22538376930916132, + 0.19243341026945507, + 0.23812265736822513, + 0.32198501079853015, + 0.19789588075508507, + 0.2702534975321306, + 0.1629602672821303, + 0.3578975106517338, + 0.2554903675178136, + 0.2331937792874207, + 0.16492036099143864, + 0.34646623767060614, + 0.3149781239128785, + 0.32988070028032157, + 0.3612988055450703, + 0.160928575219166, + 0.19718157809312317, + 0.38409661895684305, + 0.32385721159938535, + 0.20397645612020626, + 0.3795934764762401, + 0.21206903268098865, + 0.3286883026600943, + 0.19103039749088413, + 0.1795732974980744, + 0.28183786088272644, + 0.17112797092835264, + 0.26290581464922325, + 0.28076048863064185, + 0.2119767243181723, + 0.2516123875381441, + 0.3109636752043402, + 0.16893213758526487, + 0.2825989122510836, + 0.26407845523392254, + 0.31260400132621635, + 0.18592194255718497, + 0.2335095576901678, + 0.31549729792033593, + 0.2801070142149725, + 0.25556387068735453, + 0.28547534445244294, + 0.3846223197704387, + 0.308691818088805, + 0.34669426037347617, + 0.1789897303105384, + 0.36593690239494847, + 0.22314145719612302, + 0.3859694447473995, + 0.19193658042831985, + 0.28308866918277453, + 0.3475466343039554, + 0.28980696392386396, + 0.3005423653178126, + 0.2757409742426856, + 0.28107503613393314, + 0.2964739802981502, + 0.38688872612602226, + 0.17423707643793973, + 0.3294435900425132, + 0.19298526846807967, + 0.2881700984210902, + 0.3628378595343593, + 0.23827986815010227, + 0.2072855798952944, + 0.2215395177317899, + 0.2401949720429093, + 0.30063991138839835, + 0.34067829225839896, + 0.32199027162487037, + 0.36897911468450517, + 0.37690783631331326, + 0.22855930999206453, + 0.27986027754510456, + 0.2834013358162977, + 0.21217688123289935, + 0.29860662227416734, + 0.35117845525503677, + 0.28229741849145534, + 0.34193698711746046, + 0.2784156497875351, + 0.3134227449808751, + 0.21180121490098858, + 0.711962757813605, + 0.39815311415496873, + 0.44292046760452414, + 0.5768008109880305, + 0.7033290188598753, + 0.462326500097775, + 0.6009143044575174, + 0.6926878098947785, + 0.40097159608480726, + 0.45478684635840083, + 0.6010613401577611, + 0.7083475278602838, + 0.5877250480052306, + 0.4903215194462917, + 0.6702972200679044, + 0.46083805423231, + 0.5917125545734191, + 0.6039049477365644, + 0.497891076527091, + 0.6732794007512902, + 0.580218067394985, + 0.6356410164681873, + 0.4384105395021185, + 0.6061187612666489, + 0.5418075146160414, + 0.6920216467769131, + 0.5296890459387958, + 0.524505482008281, + 0.493532901229183, + 0.5069348601212728, + 0.4931019690741792, + 0.4127462051114675, + 0.6862369318642912, + 0.3992867827749434, + 0.6182775202064367, + 0.4923874182916165, + 0.6129371601583824, + 0.4876723676202689, + 0.41406911747025893, + 0.5867627924195378, + 0.47653259650267765, + 0.6464773141798149, + 0.4119813542049603, + 0.6166500805121151, + 0.403068372248438, + 0.5230822595153273, + 0.6939068229016099, + 0.4852540773967731, + 0.4674299953046227, + 0.5791896213994299, + 0.5672340393900775, + 0.39494905030377253, + 0.617469981323442, + 0.5227097938350032, + 0.5114480688505699, + 0.5589588869110595, + 0.45228366240912027, + 0.5886152080147398, + 0.5144332389314362, + 0.45337930341280497, + 0.5170283774824767, + 0.7103492509457714, + 0.4584289364200348, + 0.6687199528442566, + 0.6678282730015662, + 0.4491846911336971, + 0.44057740100555615, + 0.5417202304689096, + 0.6447103537654733, + 0.5909774034179112, + 0.5792443585817735, + 0.6199838604538931, + 0.5244440184586003, + 0.666558663967424, + 0.6147728111066595, + 0.708772400941591, + 0.6558796778464282, + 0.48642495200279123, + 0.48102739350062895, + 0.419511169229467, + 0.5478154067995329, + 0.49677471216019914, + 0.6201372974270869, + 0.6839439048353168, + 0.45540837195133205, + 0.4818231550917963, + 0.6220231358702435, + 0.5031023479335981, + 0.6102604046794599, + 0.45679205055844446, + 0.6587805547551189, + 0.6692178723459923, + 0.4438045975569266, + 0.5839254469962114, + 0.4999448224374055, + 0.5864116235907783, + 0.45055327914626564, + 0.6433423962298748, + 0.4970562409335306, + 0.407061779425151, + 0.4852102792984012, + 0.6663382578151473, + 0.4686690317339714, + 0.6970140445671968, + 0.4404082255883096, + 0.6643609161636244, + 0.5050783377880905, + 0.6980944265438744, + 0.5070854057232559, + 0.40724981743859734, + 0.4195438877535425, + 0.4630831862135333, + 0.6763871082747732, + 0.6119748808591626, + 0.5227511631145745, + 0.5729032312014803, + 0.6356713999361889, + 0.6811707916316445, + 0.6833006862756736, + 0.4749818335007447, + 0.6068364643289501, + 0.6058171592415011, + 0.5345663543282348, + 0.6797921380047451, + 0.7134489792052892, + 0.6348401182993568, + 0.5107115663639772, + 0.5899807403823627, + 0.6618449465476416, + 0.6044198098835072, + 0.42795994892077094, + 0.4366341076203042, + 0.5920413548845458, + 0.5747203529190272, + 0.518884267992845, + 0.6553601074800582, + 0.5522782171857559, + 0.5812425771702886, + 0.5188566928467463, + 0.43938988340427393, + 0.5904347694457215, + 0.6590473196520789, + 0.7038051314700527, + 0.7031828419179573, + 0.6190959204571592, + 0.47874301374089717, + 0.4349339092453788, + 0.5462935710533783, + 0.5149142941984725, + 0.5283519130195419, + 0.4246671343419862, + 0.4305215242815525, + 0.513097313262613, + 0.5117088703799203, + 0.4293892355480095, + 0.46080061498999286, + 0.49743613416085875, + 0.5309931815807153, + 0.6660056696389994, + 0.4488094972746772, + 0.5166096893658647, + 0.5882449824960373, + 0.4097963624557239, + 0.6123265459844238, + 0.632857815476312, + 0.5131182606714013, + 0.5941188888325492, + 0.44346260215922284, + 0.6759707223002797, + 0.6427940829966808, + 0.6533177547947908, + 0.6183672035331461, + 0.43187577978201247, + 0.4697382802289459, + 0.5042587176476276, + 0.6469666733909167, + 0.4877306742871255, + 0.6696552335834942, + 0.5039196793265777, + 0.609306749405845, + 0.7011968770974617, + 0.5566696104119744, + 0.3987921445626164, + 0.6500187356816818, + 0.5104061707756072, + 0.5282786409498476, + 0.5914821049416533, + 0.41371664573761097, + 0.5027914131558648, + 0.4989170048924323, + 0.6496438234898776, + 0.5005935179039264, + 0.3984907038239243, + 0.6263325635796174, + 0.5303873743536341, + 0.6039470208119304, + 0.5316047298841788, + 0.555653326523424, + 0.5397959474219562, + 0.4729667313697286, + 0.4702702141002456, + 0.5413508662015306, + 0.41180441671294293, + 0.4181677919032901, + 0.4446032218341824, + 0.6126476095391004, + 0.5849349635142738, + 0.5381397058965443, + 0.45648824561315693, + 0.5698735053959129, + 0.6631400538658948, + 0.436019220869814, + 0.6538220674929265, + 0.5200507921479117, + 0.5134752016334728, + 0.5242752526784109, + 0.7080406314471148, + 0.6798402242214365, + 0.5951691682006081, + 0.5060033502356611, + 0.6213449073490542, + 0.5654826490739211, + 0.46444850820655753, + 0.5194259198239838, + 0.5633495441793046, + 0.5514679681433389, + 0.5077013030094977, + 0.6127792824930988, + 0.706636292100824, + 0.570602183376504, + 0.6216645364428512, + 0.6936883910490428, + 0.43037174274898776, + 0.6964775263870293, + 0.5285076928136281, + 0.5758888633592366, + 0.5942999474428176, + 0.5336261926648287, + 0.3941968947207268, + 0.5086381182586743, + 0.5905923199279361, + 0.5279646325304657, + 0.6803705109476863, + 0.6561169359270214, + 0.4491780234668322, + 0.6044992010380432, + 0.6327137101517077, + 0.5900972837441649, + 0.5479276228352679, + 0.6935377989903508, + 0.68883600491109, + 0.6182291681083699, + 0.5364972804259742, + 0.4029616232779457, + 0.4185553611638994, + 0.620857924043035, + 0.48786970495038995, + 0.4241291930387523, + 0.7028867179969203, + 0.5841368564235132, + 0.6316830427904997, + 0.6919910956111806, + 0.39768623444669615, + 0.5112603994847797, + 0.5524596807849543, + 0.6035630338843816, + 0.6865826684910739, + 0.500470772008062, + 0.4109510221429117, + 0.6354714272691255, + 0.4703253719420525, + 0.47710484097803285, + 0.4058167282292378, + 0.494421352870279, + 0.7026531482868197, + 0.5174374840367824, + 0.44230791099097216, + 0.4976923082325452, + 0.5479838090128453, + 0.4786416117518284, + 0.7011440335923225, + 0.41471278765857056, + 0.607511076987083, + 0.4616088907730991, + 0.5410284580024868, + 0.6651454704976363, + 0.5164421580269817, + 0.569457148158764, + 0.5122448485373174, + 0.47452115281943774, + 0.49785562168792713, + 0.7097721099816737, + 0.6370586886051147, + 0.45908196640500953, + 0.4206945721375149, + 0.6620898244070043, + 0.5541928329601411, + 0.46172496049728784, + 0.6105445577372546, + 0.5033816382559141, + 0.606362865383502, + 0.4755743725507768, + 0.5909510672917728, + 0.652869171228466, + 0.4194296663268728, + 0.419780617319618, + 0.4150041526156384, + 0.554157706969425, + 0.6511881886090987, + 0.5424483958963496, + 0.40421978321879853, + 0.39438118915581644, + 0.5996588226528561, + 0.5726687042634084, + 0.43673954860820713, + 0.501418240111022, + 0.6917152383610561, + 0.5922281880774625, + 0.5291409206762938, + 0.40937635621970253, + 0.49092684000011005, + 0.6011157491176014, + 0.46792155712372785, + 0.5247583412354939, + 0.5354263298460167, + 0.41142675508304516, + 0.4567971633966736, + 0.4101714008758666, + 0.48962060543321345, + 0.6287706475444819, + 0.48601016325636387, + 0.42000514087334395, + 0.5873508035075334, + 0.49462225668471144, + 0.6846792266584254, + 0.6767559564629417, + 0.5211295669710305, + 0.45383436372513297, + 0.6254527570338038, + 0.7014324559533078, + 0.5908209858920584, + 0.6552371227271947, + 0.5471975255510084, + 0.401907613842104, + 0.3940988851527827, + 0.41118564247718153, + 0.4155635233122059, + 0.5881866790996094, + 0.5235593713836287, + 0.5110053489212206, + 0.7069588595078571, + 0.6001063305452567, + 0.6895786176075883, + 0.5447575450816875, + 0.4343283167298141, + 0.5258296219987123, + 0.5043270099255276, + 0.6943343578140002, + 0.4165226092249571, + 0.7088479312916749, + 0.6599922280624095, + 0.6999774797965107, + 0.4454606595208449, + 0.5606285702663785, + 0.5147278124059302, + 0.5852448014664361, + 0.45672618226207573, + 0.5447119969812344, + 0.6201402099201582, + 0.4190537174329982, + 0.592121634805794, + 0.6492557352068691, + 0.5855617287425616, + 0.5983685881014551, + 0.6512396364706718, + 0.48080487121892596, + 0.5072569460722686, + 0.6233654491568004, + 0.6620889124014488, + 0.548113804613509, + 0.4325435390886603, + 0.5849601205801223, + 0.49783189241094483, + 0.6906070717556729, + 0.5495575634938379, + 0.5718425696974205, + 0.635538576847613, + 0.7143773454764969, + 0.537913947609657, + 0.7020817995866242, + 0.5210328812001651, + 0.44437887223556016, + 0.7125854126890367, + 0.575759590081167, + 0.5166116245018237, + 0.5418638501605243, + 0.6863549822931128, + 0.551749778136972, + 0.396696383531449, + 0.5258638317745051, + 0.654956705455486, + 0.6297534701656669, + 0.5844938768773071, + 0.6506137715614804, + 0.6017936513297032, + 0.5975948320830823, + 0.47743095249847284, + 0.4969889735688867, + 0.6696776516085748, + 0.47798230630458827, + 0.40514333432744604, + 0.604478227488951, + 0.48386873415613857, + 0.6587588748965796, + 0.49246058327083514, + 0.7028309330559785, + 0.4200392595028487, + 0.5701312620924953, + 0.673872990010032, + 0.5441688057558004, + 0.6496054380188554, + 0.6331735011022274, + 0.6696194743702153, + 0.5229860411357092, + 0.5901206251969022, + 0.5633646242768569, + 0.48067891069377133, + 0.5019206780838119, + 0.6386806824181792, + 0.5068580992574296, + 0.4527311800430832, + 0.697842849515989, + 0.5347723423581131, + 0.41990194296940186, + 0.4821806682172247, + 0.642801469866938, + 0.47423891323911427, + 0.6770951729762045, + 0.6029199546437535, + 0.5414766113226164, + 0.5316280419791408, + 0.5754080159892239, + 0.4498250547371598, + 0.4796829775256669, + 0.6530111776489531, + 0.4615143081892326, + 0.6369686040951201, + 0.5586918878770812, + 0.5650726472638451, + 0.6524786448880111, + 0.5728944299824981, + 0.6612288933049202, + 0.5973777135252819, + 0.4395507291924551, + 0.4877236183381749, + 0.44245532767219137, + 0.5364409215909303, + 0.6879510226056141, + 0.7107724702153893, + 0.6231996167971611, + 0.5795392663302668, + 0.5249744914502672, + 0.47221489084416945, + 0.5877884833080051, + 0.48824367536196545, + 0.4561517212405387, + 0.6506123357096276, + 0.6441897474646094, + 0.5122937543954048, + 0.5292527273789344, + 0.42330486720313404, + 0.6282015340966691, + 0.572064471142192, + 0.6129446601749148, + 0.4836289137331772, + 0.6630412096577667, + 0.5574662163754142, + 0.5603952897616561, + 0.6417899140499703, + 0.6358738448723334, + 0.6212861540754707, + 0.42931239776853736, + 0.5908858847973001, + 0.40083311684666684, + 0.42692703593973963, + 0.6778874218670266, + 0.7039967647042549, + 0.6478948770867651, + 0.4366456219487328, + 0.5517499592412707, + 0.4513081239524787, + 0.46416054915834604, + 0.6649571664478269, + 0.6741598698560451, + 0.652834468502756, + 0.4633004681759674, + 0.6414494309889387, + 0.45032927783246596, + 0.4697007998246329, + 0.6620327185013504, + 0.41705394856604155, + 0.4398967707103367, + 0.5913409883343154, + 0.4875119632776497, + 0.4204386462732751, + 0.6794460614192366, + 0.49191818470651005, + 0.6092035542614986, + 0.4233056318647546, + 0.46978432977792434, + 0.5089138081262015, + 0.59091470168174, + 0.5889269051192079, + 0.5581302186254722, + 0.5033836102636637, + 0.474875837738481, + 0.6854242531757861, + 0.7027046742762378, + 0.4802457868181411, + 0.4570319256040039, + 0.4228283519401702, + 0.6344427609396895, + 0.48642863848085105, + 0.5607651503506909, + 0.5337065356401439, + 0.5881729613170801, + 0.445339611421861, + 0.42736598288665456, + 0.4359753863154801, + 0.5449090145324103, + 0.6777625181880983, + 0.6002082949102985, + 0.5599112523856377, + 0.5673828273773424, + 0.5861656719312751, + 0.48456667483354204, + 0.6225590230951801, + 0.5104525992299882, + 0.6842359879167492, + 0.63477314273042, + 0.4307422274242699, + 0.4758642861712374, + 0.47640180167741625, + 0.6276831685573012, + 0.5045703972035164, + 0.6599065028337288, + 0.44333318433811775, + 0.6871523168411047, + 0.5507136986936054, + 0.6519194862198708, + 0.615927517957735, + 0.48587952153799197, + 0.49092676591005086, + 0.6597955832205928, + 0.46580254002156196, + 0.5134089157399473, + 0.4423293796019698, + 0.6370615691859662, + 0.5512183401615391, + 0.6482636870650859, + 0.5451828832227467, + 0.5896308637740783, + 0.5221336670296579, + 0.6954960788368911, + 0.6254609800601086, + 0.4350734349858833, + 0.46900675113911505, + 0.5147580594122196, + 0.4984681877780196, + 0.500154683619607, + 0.6853185164931486, + 0.6145989551498843, + 0.414906080901187, + 0.6273437944120299, + 0.6161883627709921, + 0.5745992856253792, + 0.5347516641274731, + 0.4422418151586672, + 0.46179872861877486, + 0.5655184676399461, + 0.46971766161821243, + 0.5162779944600702, + 0.6947595108702095, + 0.4254184287904325, + 0.6224000502049263, + 0.5348603478712739, + 0.5334707606509118, + 0.6537938838140844, + 0.5281587413351672, + 0.578106877383572, + 0.6673020064178543, + 0.4913833687536658, + 0.496670000051071, + 0.4274753725190793, + 0.5847958907920836, + 0.676551993434623, + 0.6870826187359624, + 0.5578891062094579, + 0.6136536524972005, + 0.6346620422952325, + 0.5022351745552321, + 0.7106102618734005, + 0.6135516792241179, + 0.46427112422822137, + 0.6040551272936356, + 0.4238547979743983, + 0.47025503524134143, + 0.5839890777841227, + 0.6466707153828358, + 0.6123289910445529, + 0.4774983091271401, + 0.4144014702894539, + 0.6648779201576701, + 0.40730427560770127, + 0.6571738097022892, + 0.44669842592011744, + 0.4578804376440828, + 0.5359033090215639, + 0.5239434956359865, + 0.6011432278090295, + 0.6481178115420488, + 0.4971136865043413, + 0.5757776311791889, + 0.45384690812002537, + 0.702150702485456, + 0.471352288583422, + 0.4391373660643765, + 0.5219968611759536, + 0.7028692431932516, + 0.4567764773112989, + 0.4606434333092933, + 0.7039810925547345, + 0.41953842555233023, + 0.6554129177626637 + ], + "type": "scatter" + }, + { + "mode": "markers", + "name": "Expectation", + "x": [ + 0.5337653396715254 + ], + "y": [ + -0.027381306163016955 + ], + "type": "scatter" + }, + { + "fill": "toself", + "mode": "lines", + "name": "Mode", + "x": [ + 0.4178483805738874, + 0.4178483805738874, + 0.6762126815500766, + 0.6762126815500766, + 0.4178483805738874 + ], + "y": [ + 0.15624896603640903, + 0.393362968645088, + 0.393362968645088, + 0.15624896603640903, + 0.15624896603640903 + ], + "type": "scatter" + } + ], + "layout": { + "title": { + "text": "Marginal View of relative x and y position with respect to the milk" + }, + "xaxis": { + "title": { + "text": "relative_x" + }, + "range": [ + -1, + 1 + ] + }, + "yaxis": { + "title": { + "text": "relative_y" + }, + "range": [ + -1, + 1 + ] + }, + "template": { + "data": { + "histogram2dcontour": [ + { + "type": "histogram2dcontour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "choropleth": [ + { + "type": "choropleth", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "histogram2d": [ + { + "type": "histogram2d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmap": [ + { + "type": "heatmap", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "heatmapgl": [ + { + "type": "heatmapgl", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "contourcarpet": [ + { + "type": "contourcarpet", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "contour": [ + { + "type": "contour", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "surface": [ + { + "type": "surface", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ] + } + ], + "mesh3d": [ + { + "type": "mesh3d", + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + ], + "scatter": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scatter" + } + ], + "parcoords": [ + { + "type": "parcoords", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolargl": [ + { + "type": "scatterpolargl", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "bar": [ + { + "error_x": { + "color": "#f2f5fa" + }, + "error_y": { + "color": "#f2f5fa" + }, + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "scattergeo": [ + { + "type": "scattergeo", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterpolar": [ + { + "type": "scatterpolar", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "scattergl": [ + { + "marker": { + "line": { + "color": "#283442" + } + }, + "type": "scattergl" + } + ], + "scatter3d": [ + { + "type": "scatter3d", + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattermapbox": [ + { + "type": "scattermapbox", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scatterternary": [ + { + "type": "scatterternary", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "scattercarpet": [ + { + "type": "scattercarpet", + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + } + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "baxis": { + "endlinecolor": "#A2B1C6", + "gridcolor": "#506784", + "linecolor": "#506784", + "minorgridcolor": "#506784", + "startlinecolor": "#A2B1C6" + }, + "type": "carpet" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#506784" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "header": { + "fill": { + "color": "#2a3f5f" + }, + "line": { + "color": "rgb(17,17,17)" + } + }, + "type": "table" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "rgb(17,17,17)", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ] + }, + "layout": { + "autotypenumbers": "strict", + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#f2f5fa" + }, + "hovermode": "closest", + "hoverlabel": { + "align": "left" + }, + "paper_bgcolor": "rgb(17,17,17)", + "plot_bgcolor": "rgb(17,17,17)", + "polar": { + "bgcolor": "rgb(17,17,17)", + "angularaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "radialaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "ternary": { + "bgcolor": "rgb(17,17,17)", + "aaxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "baxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + }, + "caxis": { + "gridcolor": "#506784", + "linecolor": "#506784", + "ticks": "" + } + }, + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "sequential": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0.0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1.0, + "#f0f921" + ] + ], + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ] + }, + "xaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "yaxis": { + "gridcolor": "#283442", + "linecolor": "#506784", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "#283442", + "automargin": true, + "zerolinewidth": 2 + }, + "scene": { + "xaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "yaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + }, + "zaxis": { + "backgroundcolor": "rgb(17,17,17)", + "gridcolor": "#506784", + "linecolor": "#506784", + "showbackground": true, + "ticks": "", + "zerolinecolor": "#C8D4E3", + "gridwidth": 2 + } + }, + "shapedefaults": { + "line": { + "color": "#f2f5fa" + } + }, + "annotationdefaults": { + "arrowcolor": "#f2f5fa", + "arrowhead": 0, + "arrowwidth": 1 + }, + "geo": { + "bgcolor": "rgb(17,17,17)", + "landcolor": "rgb(17,17,17)", + "subunitcolor": "#506784", + "showland": true, + "showlakes": true, + "lakecolor": "rgb(17,17,17)" + }, + "title": { + "x": 0.05 + }, + "updatemenudefaults": { + "bgcolor": "#506784", + "borderwidth": 0 + }, + "sliderdefaults": { + "bgcolor": "#C8D4E3", + "borderwidth": 1, + "bordercolor": "rgb(17,17,17)", + "tickwidth": 0 + }, + "mapbox": { + "style": "dark" + } + } + } + }, + "config": { + "plotlyServerURL": "https://plot.ly" + } + }, + "text/html": "
" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "grounded_model = fpa.ground_model()\n", + "p_xy = grounded_model.marginal([relative_x, relative_y]).simplify()\n", + "fig = go.Figure(p_xy.root.plot_2d(), p_xy.root.plotly_layout())\n", + "fig.update_layout(title=\"Marginal View of relative x and y position with respect to the milk\",\n", + " xaxis_range=[-1, 1], yaxis_range=[-1, 1])\n", + "fig.show()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-21T13:49:03.412572Z", + "start_time": "2024-03-21T13:49:00.757156Z" + } + }, + "id": "a36ee203bb45f8b1", + "execution_count": 13 + }, + { + "cell_type": "markdown", + "source": [ + "Finally, we observe our improved plan in action." + ], + "metadata": { + "collapsed": false + }, + "id": "bd4fd2fa3d469c8c" + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "from pycram.designators.actions.actions import ParkArmsActionPerformable\n", + "\n", + "world.reset_bullet_world()\n", + "milk.set_pose(Pose([0.5, 3.15, 1.04]))\n", + "with simulated_robot:\n", + " \n", + " MoveTorsoActionPerformable(0.3).perform()\n", + " for sample in fpa:\n", + " try:\n", + " ParkArmsActionPerformable(Arms.BOTH).perform()\n", + " sample.perform()\n", + " break\n", + " except PlanFailure as e:\n", + " continue" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-21T13:49:04.597208Z", + "start_time": "2024-03-21T13:49:03.413811Z" + } + }, + "id": "ea57ad24b398e28f", + "execution_count": 14 + }, + { + "cell_type": "code", + "outputs": [], + "source": [ + "# world.exit()\n", + "# viz_marker_publisher._stop_publishing()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-03-21T13:49:04.599597Z", + "start_time": "2024-03-21T13:49:04.598003Z" + } + }, + "id": "62728fa8ed6e55bd", + "execution_count": 15 } ], "metadata": { diff --git a/requirements-resolver.txt b/requirements-resolver.txt new file mode 100644 index 000000000..ca5333345 --- /dev/null +++ b/requirements-resolver.txt @@ -0,0 +1,8 @@ +-r requirements.txt +plotly>=5.20.0 +portion>=2.4.2 +probabilistic_model>=4.0.6 +random_events>=2.0.6 +SQLAlchemy>=2.0.19 +tqdm>=4.66.1 +typing_extensions>=4.10.0 diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 09fbc0578..da6ba8bd5 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -29,6 +29,20 @@ class Rectangle: y_lower: float y_upper: float + def translate(self, x: float, y: float): + """Translate the rectangle by x and y""" + self.x_lower += x + self.x_upper += x + self.y_lower += y + self.y_upper += y + + def scale(self, x_factor: float, y_factor: float): + """Scale the rectangle by x_factor and y_factor""" + self.x_lower *= x_factor + self.x_upper *= x_factor + self.y_lower *= y_factor + self.y_upper *= y_factor + class Costmap: """ @@ -234,7 +248,7 @@ def partitioning_rectangles(self) -> List[Rectangle]: :return: A list containing the partitioning rectangles """ ocm_map = np.copy(self.map) - origin = np.array([self.height / 2, self.width / 2]) + origin = np.array([self.height / 2, self.width / 2]) * -1 rectangles = [] # for every index pair (i, j) in the occupancy costmap @@ -248,15 +262,19 @@ def partitioning_rectangles(self) -> List[Rectangle]: curr_height = self._find_max_box_height((i, j), curr_width, ocm_map) # calculate the rectangle in the costmap - x_lower = (curr_pose[0] - origin[0]) * self.resolution - x_upper = (curr_pose[0] + curr_width - origin[0]) * self.resolution - y_lower = (curr_pose[1] - origin[1]) * self.resolution - y_upper = (curr_pose[1] + curr_height - origin[1]) * self.resolution + x_lower = curr_pose[0] + x_upper = curr_pose[0] + curr_height + y_lower = curr_pose[1] + y_upper = curr_pose[1] + curr_width # mark the found rectangle as occupied ocm_map[i:i + curr_height, j:j + curr_width] = 0 - rectangles.append(Rectangle(x_lower, x_upper, y_lower, y_upper)) + # transform rectangle to map space + rectangle = Rectangle(x_lower, x_upper, y_lower, y_upper) + rectangle.translate(*origin) + rectangle.scale(self.resolution, self.resolution) + rectangles.append(rectangle) return rectangles diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index 01602391b..7570ded9c 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -5,7 +5,7 @@ from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution from probabilistic_model.probabilistic_circuit.probabilistic_circuit import ProbabilisticCircuit, \ DecomposableProductUnit, DeterministicSumUnit -from random_events.events import Event +from random_events.events import Event, ComplexEvent from random_events.variables import Symbolic, Continuous import tqdm from typing_extensions import Optional, List, Iterator @@ -20,6 +20,7 @@ from ...orm.action_designator import PickUpAction as ORMPickUpAction from ...plan_failures import ObjectUnreachable, PlanFailure from ...pose import Pose +import plotly.graph_objects as go class ProbabilisticAction: @@ -98,6 +99,13 @@ def __init__(self, distance_to_center: float = 0.2, variance: float = 0.5): self.distance_to_center = distance_to_center self.variance = variance + def center_event(self) -> Event: + """ + Create an event that describes the center of the map. + """ + return Event({self.relative_x: portion.open(-self.distance_to_center, self.distance_to_center), + self.relative_y: portion.open(-self.distance_to_center, self.distance_to_center)}) + def create_model_with_center(self) -> ProbabilisticCircuit: """ Create a fully factorized gaussian at the center of the map. @@ -105,6 +113,10 @@ def create_model_with_center(self) -> ProbabilisticCircuit: centered_model = DecomposableProductUnit() centered_model.add_subcircuit(GaussianDistribution(self.relative_x, 0., self.variance)) centered_model.add_subcircuit(GaussianDistribution(self.relative_y, 0., self.variance)) + centered_model.add_subcircuit(SymbolicDistribution(self.grasp, + [1/len(self.grasp.domain)] * len(self.grasp.domain))) + centered_model.add_subcircuit(SymbolicDistribution(self.arm, + [1/len(self.arm.domain)] * len(self.arm.domain))) return centered_model.probabilistic_circuit def create_model(self) -> ProbabilisticCircuit: @@ -114,30 +126,14 @@ def create_model(self) -> ProbabilisticCircuit: :return: The probabilistic circuit """ centered_model = self.create_model_with_center() - - region_model = DeterministicSumUnit() - - north_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), - self.relative_y: portion.closed(self.distance_to_center, float("inf"))}) - south_region = Event({self.relative_x: portion.closed(-self.distance_to_center, self.distance_to_center), - self.relative_y: portion.closed(-float("inf"), -self.distance_to_center)}) - east_region = Event({self.relative_x: portion.closed(self.distance_to_center, float("inf")), - self.relative_y: portion.open(-float("inf"), float("inf"))}) - west_region = Event({self.relative_x: portion.closed(-float("inf"), -self.distance_to_center), - self.relative_y: portion.open(-float("inf"), float("inf"))}) - - for region in [north_region, south_region, east_region, west_region]: - conditional, probability = centered_model.conditional(region) - region_model.add_subcircuit(conditional.root, probability) - - result = DecomposableProductUnit() - p_arms = SymbolicDistribution(self.arm, [1 / len(self.arm.domain) for _ in self.arm.domain]) - p_grasp = SymbolicDistribution(self.grasp, [1 / len(self.grasp.domain) for _ in self.grasp.domain]) - result.add_subcircuit(p_arms) - result.add_subcircuit(p_grasp) - result.add_subcircuit(region_model) - - return result.probabilistic_circuit + outer_event = self.center_event().complement() + limiting_event = Event({self.relative_x: portion.open(-2, 2), + self.relative_y: portion.open(-2, 2)}) + event = outer_event & limiting_event + # go.Figure(event.plot()).show() + result, _ = centered_model.conditional(event) + print(result) + return result class MoveAndPickUp(ActionDesignatorDescription, ProbabilisticAction): @@ -191,7 +187,7 @@ def sample_to_action(self, sample: List) -> MoveAndPickUpPerformable: action = MoveAndPickUpPerformable(standing_position, self.object_designator, arm, grasp) return action - def events_from_occupancy_and_visibility_costmap(self) -> List[Event]: + def events_from_occupancy_and_visibility_costmap(self) -> ComplexEvent: """ Create events from the occupancy and visibility costmap. @@ -199,10 +195,10 @@ def events_from_occupancy_and_visibility_costmap(self) -> List[Event]: """ # create occupancy and visibility costmap for the target object - ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.02, + ocm = OccupancyCostmap(distance_to_obstacle=0.3, from_ros=False, size=200, resolution=0.1, origin=self.object_designator.pose) vcm = VisibilityCostmap(min_height=1.27, max_height=1.69, - size=200, resolution=0.02, origin=self.object_designator.pose) + size=200, resolution=0.1, origin=self.object_designator.pose) mcm = ocm + vcm # convert rectangles to events @@ -211,35 +207,29 @@ def events_from_occupancy_and_visibility_costmap(self) -> List[Event]: event = Event({self.variables.relative_x: portion.open(rectangle.x_lower, rectangle.x_upper), self.variables.relative_y: portion.open(rectangle.y_lower, rectangle.y_upper)}) events.append(event) - return events + return ComplexEvent(events) def ground_model(self, model: Optional[ProbabilisticCircuit] = None, - events: Optional[List[Event]] = None) -> ProbabilisticCircuit: + event: Optional[ComplexEvent] = None) -> ProbabilisticCircuit: """ Ground the model to the current evidence. :param model: The model that should be grounded. If None, the policy is used. - :param events: The events that should be used as evidence. If None, the occupancy costmap is used. + :param event: The events that should be used as evidence. If None, the occupancy costmap is used. :return: The grounded model """ if model is None: model = self.policy - if events is None: - events = self.events_from_occupancy_and_visibility_costmap() - - result = DeterministicSumUnit() + if event is None: + event = self.events_from_occupancy_and_visibility_costmap() - for event in events: - conditional, probability = model.conditional(event) - if probability > 0: - result.add_subcircuit(conditional.root, probability) + result, probability = model.conditional(event) - if len(result.subcircuits) == 0: + if probability == 0: raise ObjectUnreachable("No possible locations found") - result.normalize() - return result.probabilistic_circuit + return result def iter_with_mode(self) -> Iterator[MoveAndPickUpPerformable]: """ @@ -282,7 +272,7 @@ def iterate_without_occupancy_costmap(self) -> Iterator[MoveAndPickUpPerformable def query_for_database(): query_context = PickUpWithContext() query = select(ORMPickUpAction.arm, ORMPickUpAction.grasp, - query_context.relative_x, query_context.relative_y).distinct() + query_context.relative_x, query_context.relative_y) query = query_context.join_statement(query).where(TaskTreeNode.status == TaskStatus.SUCCEEDED) return query diff --git a/test/__init__.py b/test/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 21801be30..2cbc18147 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -1,7 +1,14 @@ +import time + +import portion +from random_events.events import Event, ComplexEvent + from bullet_world_testcase import BulletWorldTestCase from pycram.costmaps import OccupancyCostmap from pycram.pose import Pose import numpy as np +from random_events.variables import Continuous +# import plotly.graph_objects as go class TestCostmapsCase(BulletWorldTestCase): @@ -24,6 +31,24 @@ def test_attachment_exclusion(self): def test_partition_into_rectangles(self): ocm = OccupancyCostmap(distance_to_obstacle=0.2, from_ros=False, size=200, resolution=0.02, - origin=Pose([0, 0, 0], [0, 0, 0, 1])) + origin=Pose([0, 0, 0], [0, 0, 0, 1])) rectangles = ocm.partitioning_rectangles() - self.assertEqual(len(rectangles), 10) + ocm.visualize() + + x = Continuous("x") + y = Continuous("y") + + events = [] + for rectangle in rectangles: + + event = Event({x: portion.open(rectangle.x_lower, rectangle.x_upper), + y: portion.open(rectangle.y_lower, rectangle.y_upper)}) + events.append(event) + + event = ComplexEvent(events) + # fig = go.Figure(event.plot(), event.plotly_layout()) + # fig.update_xaxes(range=[-2, 2]) + # fig.update_yaxes(range=[-2, 2]) + # fig.show() + self.assertTrue(event.are_events_disjoint()) + diff --git a/test/test_probabilistic_actions/test_database_resolver.py b/test/test_probabilistic_actions/test_database_resolver.py index 20d79de0d..78d702d05 100644 --- a/test/test_probabilistic_actions/test_database_resolver.py +++ b/test/test_probabilistic_actions/test_database_resolver.py @@ -133,6 +133,7 @@ def test_object_at_different_location(self): new_milk.remove() kitchen.remove() + @unittest.skip def test_multiple_objects(self): kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") new_milk = Object("new_milk", "milk", "../../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.9])) diff --git a/test/test_probabilistic_actions/test_move_and_pick_up.py b/test/test_probabilistic_actions/test_move_and_pick_up.py index e2bca18a0..ccead6d15 100644 --- a/test/test_probabilistic_actions/test_move_and_pick_up.py +++ b/test/test_probabilistic_actions/test_move_and_pick_up.py @@ -1,17 +1,30 @@ import random import unittest +import time import numpy as np +from random_events.events import Event from pycram.designator import ObjectDesignatorDescription from pycram.enums import ObjectType from pycram.plan_failures import PlanFailure from pycram.process_module import simulated_robot -from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp -from ..bullet_world_testcase import BulletWorldTestCase +from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp, GaussianCostmapModel +from bullet_world_testcase import BulletWorldTestCase import plotly.graph_objects as go +class GaussianCostmapModelTestCase(unittest.TestCase): + + def test_create_model(self): + gcm = GaussianCostmapModel() + model = gcm.create_model() + self.assertEqual(model.probability(gcm.center_event()), 0) + self.assertEqual(len(model.variables), 4) + # p_xy = model.marginal([gcm.relative_x, gcm.relative_y]) + # go.Figure(p_xy.plot(), p_xy.plotly_layout()).show() + + class MoveAndPickUpTestCase(BulletWorldTestCase): @classmethod @@ -25,12 +38,12 @@ def test_grounding(self): move_and_pick = MoveAndPickUp(object_designator, arms=["left", "right"], grasps=["front", "left", "right", "top"]) - # p_xy = move_and_pick.policy.marginal([move_and_pick.variables.relative_x, move_and_pick.variables.relative_y]) - # fig = go.Figure(p_xy.plot()) - # fig.show() model = move_and_pick.ground_model() + event = move_and_pick.events_from_occupancy_and_visibility_costmap() + self.assertTrue(event.are_events_disjoint()) self.assertIsNotNone(model) + def test_move_and_pick_up(self): object_designator = ObjectDesignatorDescription(types=[ObjectType.MILK]).resolve() move_and_pick = MoveAndPickUp(object_designator, arms=["left", "right"], From 37972fec253952b92b9c4cb310da52fd45a5d0e7 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 22 Mar 2024 11:04:22 +0100 Subject: [PATCH 139/195] [PyCRAMNEEMInterface] search online repository for meshes. --- src/pycram/description.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/description.py b/src/pycram/description.py index 0bd412e54..1bbf7fc52 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -530,7 +530,7 @@ class ObjectDescription(EntityDescription): A class that represents the description of an object. """ - mesh_extensions: Tuple[str] = (".obj", ".stl") + mesh_extensions: Tuple[str] = (".obj", ".stl", ".dae") """ The file extensions of the mesh files that can be used to generate a description file. """ From ea457387db17b7dd2d8efd466c0d788ec7e9166b Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Mon, 25 Mar 2024 09:55:54 +0100 Subject: [PATCH 140/195] [Requirements] Requirements are now less explicit. --- requirements-resolver.txt | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/requirements-resolver.txt b/requirements-resolver.txt index ca5333345..7c81de746 100644 --- a/requirements-resolver.txt +++ b/requirements-resolver.txt @@ -1,8 +1,5 @@ -r requirements.txt -plotly>=5.20.0 -portion>=2.4.2 -probabilistic_model>=4.0.6 -random_events>=2.0.6 -SQLAlchemy>=2.0.19 -tqdm>=4.66.1 -typing_extensions>=4.10.0 +probabilistic_model>=4.0.8 +random_events>=2.0.9 +SQLAlchemy +tqdm From e7fa320cccb401fa1a77f29467344dfc4e6c5c7c Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 25 Mar 2024 15:54:09 +0100 Subject: [PATCH 141/195] Added typing_extension with correct verison --- requirements.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index a86e66dac..4286972e9 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -gitpython>=3.1.37 +9gitpython>=3.1.37 pybullet~=3.2.5 rospkg~=1.4.0 roslibpy~=1.2.1 @@ -15,3 +15,4 @@ SQLAlchemy>=2.0.9 tqdm==4.66.1 psutil==5.9.7 lxml==4.9.1 +typing_extensions==4.9.0 From b3bba13d11b1f5dab1e67304c8b1554aaf15e52e Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 25 Mar 2024 15:56:48 +0100 Subject: [PATCH 142/195] [general] Fixed type in requirements --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 4286972e9..d40530f22 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -9gitpython>=3.1.37 +gitpython>=3.1.37 pybullet~=3.2.5 rospkg~=1.4.0 roslibpy~=1.2.1 From 6b237507a36c65443324b04e03cd7d0e787ff9b5 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 26 Mar 2024 08:38:53 +0100 Subject: [PATCH 143/195] [Test] Tests are now runnable from command line. --- .github/workflows/pycram-ci.yml | 1 + test/__init__.py | 0 .../test_database_resolver.py | 12 ++++++------ .../test_move_and_pick_up.py | 0 test/{test_orm => }/test_orm.py | 2 +- test/test_orm/__init__.py | 0 test/test_probabilistic_actions/__init__.py | 0 7 files changed, 8 insertions(+), 7 deletions(-) delete mode 100644 test/__init__.py rename test/{test_probabilistic_actions => }/test_database_resolver.py (93%) rename test/{test_probabilistic_actions => }/test_move_and_pick_up.py (100%) rename test/{test_orm => }/test_orm.py (99%) delete mode 100644 test/test_orm/__init__.py delete mode 100644 test/test_probabilistic_actions/__init__.py diff --git a/.github/workflows/pycram-ci.yml b/.github/workflows/pycram-ci.yml index 2c0e299c9..f77341e27 100644 --- a/.github/workflows/pycram-ci.yml +++ b/.github/workflows/pycram-ci.yml @@ -76,6 +76,7 @@ jobs: run: | cd $GITHUB_WORKSPACE/ros_ws/src/pycram sudo pip3 install -r requirements.txt + sudo pip3 install -r requirements-resolver.txt - name: install additional requirements run: | sudo pip3 install --ignore-installed pytest pyjpt mlflow diff --git a/test/__init__.py b/test/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/test/test_probabilistic_actions/test_database_resolver.py b/test/test_database_resolver.py similarity index 93% rename from test/test_probabilistic_actions/test_database_resolver.py rename to test/test_database_resolver.py index 78d702d05..54c91b651 100644 --- a/test/test_probabilistic_actions/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -36,7 +36,7 @@ class DatabaseResolverTestCase(unittest.TestCase,): def setUpClass(cls) -> None: global pycrorm_uri cls.world = BulletWorld("DIRECT") - cls.milk = Object("milk", "milk", "../../resources/milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.milk = Object("milk", "milk", "../resources/milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False cls.engine = sqlalchemy.create_engine(pycrorm_uri) @@ -84,7 +84,7 @@ def test_costmap_no_obstacles(self): grasp=sample.grasp).perform() def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") + kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "costmap_with_obstacles_test" pycram.task.task_tree.root.insert(self.session) @@ -106,14 +106,14 @@ def test_costmap_with_obstacles(self): kitchen.remove() def test_object_at_different_location(self): - kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") + kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "object_at_different_location_test" pycram.task.task_tree.root.insert(self.session) self.world.reset_bullet_world() - new_milk = Object("new_milk", "milk", "../../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + new_milk = Object("new_milk", "milk", "../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.95])) cml = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) sample = next(iter(cml)) @@ -135,8 +135,8 @@ def test_object_at_different_location(self): @unittest.skip def test_multiple_objects(self): - kitchen = Object("kitchen", "environment", "../../resources/kitchen.urdf") - new_milk = Object("new_milk", "milk", "../../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.9])) + kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") + new_milk = Object("new_milk", "milk", "../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.9])) object_description = ObjectDesignatorDescription(names=["milk"]) object_description_new_milk = ObjectDesignatorDescription(names=["new_milk"]) diff --git a/test/test_probabilistic_actions/test_move_and_pick_up.py b/test/test_move_and_pick_up.py similarity index 100% rename from test/test_probabilistic_actions/test_move_and_pick_up.py rename to test/test_move_and_pick_up.py diff --git a/test/test_orm/test_orm.py b/test/test_orm.py similarity index 99% rename from test/test_orm/test_orm.py rename to test/test_orm.py index c25257444..d73532150 100644 --- a/test/test_orm/test_orm.py +++ b/test/test_orm.py @@ -255,7 +255,7 @@ def test_setGripperAction(self): self.assertEqual(result[0].motion, "open") def test_open_and_closeAction(self): - apartment = Object("apartment", ObjectType.ENVIRONMENT, "../../resources/apartment.urdf") + apartment = Object("apartment", ObjectType.ENVIRONMENT, "../resources/apartment.urdf") apartment_desig = BelieveObject(names=["apartment"]).resolve() handle_desig = object_designator.ObjectPart(names=["handle_cab10_t"], part_of=apartment_desig).resolve() diff --git a/test/test_orm/__init__.py b/test/test_orm/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/test/test_probabilistic_actions/__init__.py b/test/test_probabilistic_actions/__init__.py deleted file mode 100644 index e69de29bb..000000000 From 03af0a2d2bccd7c79b5a613874e14561e50b6911 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 26 Mar 2024 08:43:16 +0100 Subject: [PATCH 144/195] [CI] Merged CI Changes. --- .github/workflows/new-pycram-ci.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 07678b99d..2eb158b77 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -60,6 +60,7 @@ jobs: pip3 install --upgrade pip --root-user-action=ignore cd /opt/ros/overlay_ws/src/pycram pip3 install -r requirements.txt + pip3 install -r requirements-resolver.txt - name: Install pytest, pyjpt & mlflow run: | From cefa36418b6a51ce4cfb5d73040d6246c3db27d3 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 26 Mar 2024 08:49:30 +0100 Subject: [PATCH 145/195] [CI] Updated CI requirements. --- .github/workflows/new-pycram-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index 2eb158b77..d618d87be 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -64,7 +64,7 @@ jobs: - name: Install pytest, pyjpt & mlflow run: | - pip3 install --ignore-installed pytest pyjpt mlflow + pip3 install --ignore-installed pytest pyjpt - name: Run tests run: | From 7f8ad1f02c7c48e493c113badc2cf777b151dcd6 Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 26 Mar 2024 08:58:03 +0100 Subject: [PATCH 146/195] [Test] Fixed bug in tests resource pathing. --- .github/workflows/new-pycram-ci.yml | 2 +- test/test_database_resolver.py | 12 ++++++------ test/test_orm.py | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/.github/workflows/new-pycram-ci.yml b/.github/workflows/new-pycram-ci.yml index d618d87be..1fa0f8839 100644 --- a/.github/workflows/new-pycram-ci.yml +++ b/.github/workflows/new-pycram-ci.yml @@ -62,7 +62,7 @@ jobs: pip3 install -r requirements.txt pip3 install -r requirements-resolver.txt - - name: Install pytest, pyjpt & mlflow + - name: Install pytest & pyjpt run: | pip3 install --ignore-installed pytest pyjpt diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 54c91b651..e415cd6e1 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -36,7 +36,7 @@ class DatabaseResolverTestCase(unittest.TestCase,): def setUpClass(cls) -> None: global pycrorm_uri cls.world = BulletWorld("DIRECT") - cls.milk = Object("milk", "milk", "../resources/milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False cls.engine = sqlalchemy.create_engine(pycrorm_uri) @@ -84,7 +84,7 @@ def test_costmap_no_obstacles(self): grasp=sample.grasp).perform() def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") + kitchen = Object("kitchen", "environment", "kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "costmap_with_obstacles_test" pycram.task.task_tree.root.insert(self.session) @@ -106,14 +106,14 @@ def test_costmap_with_obstacles(self): kitchen.remove() def test_object_at_different_location(self): - kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") + kitchen = Object("kitchen", "environment", "kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "object_at_different_location_test" pycram.task.task_tree.root.insert(self.session) self.world.reset_bullet_world() - new_milk = Object("new_milk", "milk", "../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) cml = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) sample = next(iter(cml)) @@ -135,8 +135,8 @@ def test_object_at_different_location(self): @unittest.skip def test_multiple_objects(self): - kitchen = Object("kitchen", "environment", "../resources/kitchen.urdf") - new_milk = Object("new_milk", "milk", "../resources/milk.stl", pose=Pose([-1.45, 2.5, 0.9])) + kitchen = Object("kitchen", "environment", "kitchen.urdf") + new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.9])) object_description = ObjectDesignatorDescription(names=["milk"]) object_description_new_milk = ObjectDesignatorDescription(names=["new_milk"]) diff --git a/test/test_orm.py b/test/test_orm.py index d73532150..23150b9be 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -255,7 +255,7 @@ def test_setGripperAction(self): self.assertEqual(result[0].motion, "open") def test_open_and_closeAction(self): - apartment = Object("apartment", ObjectType.ENVIRONMENT, "../resources/apartment.urdf") + apartment = Object("apartment", ObjectType.ENVIRONMENT, "apartment.urdf") apartment_desig = BelieveObject(names=["apartment"]).resolve() handle_desig = object_designator.ObjectPart(names=["handle_cab10_t"], part_of=apartment_desig).resolve() From 5d4adad8e4a2767476fadec97143c8594aee1a27 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Tue, 26 Mar 2024 09:06:32 +0100 Subject: [PATCH 147/195] [orm] improved orm insert performance --- src/pycram/designator.py | 21 ++++++-------- src/pycram/designators/actions/actions.py | 9 +++--- src/pycram/designators/motion_designator.py | 32 ++++++--------------- src/pycram/designators/object_designator.py | 14 ++++----- src/pycram/orm/base.py | 5 +--- src/pycram/orm/task.py | 14 ++++----- src/pycram/pose.py | 15 ++++------ src/pycram/task.py | 30 ++++++++++--------- 8 files changed, 57 insertions(+), 83 deletions(-) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index d91b18beb..4c53fab0a 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -25,7 +25,7 @@ from .orm.action_designator import (Action as ORMAction) from .orm.object_designator import (Object as ORMObjectDesignator) -from .orm.base import Quaternion, Position, Base, RobotState, ProcessMetaData +from .orm.base import RobotState, ProcessMetaData from .task import with_tree @@ -424,15 +424,15 @@ def insert(self, session: Session, *args, **kwargs) -> ORMAction: metadata = ProcessMetaData().insert(session) # create robot-state object - robot_state = RobotState(self.robot_torso_height, self.robot_type, pose.id) - robot_state.process_metadata_id = metadata.id + robot_state = RobotState(self.robot_torso_height, self.robot_type) + robot_state.pose = pose + robot_state.process_metadata = metadata session.add(robot_state) - session.commit() # create action action = self.to_sql() - action.process_metadata_id = metadata.id - action.robot_state_id = robot_state.id + action.process_metadata = metadata + action.robot_state = robot_state return action @@ -545,16 +545,13 @@ def insert(self, session: Session) -> ORMObjectDesignator: :return: The completely instanced ORM object """ metadata = ProcessMetaData().insert(session) + pose = self.pose.insert(session) # create object orm designator obj = self.to_sql() - obj.process_metadata_id = metadata.id - - pose = self.pose.insert(session) - obj.pose_id = pose.id - + obj.process_metadata = metadata + obj.pose = pose session.add(obj) - session.commit() return obj def frozen_copy(self) -> 'ObjectDesignatorDescription.Object': diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 71e781afc..5a39358b6 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -11,7 +11,7 @@ from ...bullet_world import BulletWorld from ...helper import multiply_quaternions from ...local_transformer import LocalTransformer -from ...orm.base import Base, Pose as ORMPose +from ...orm.base import Pose as ORMPose from ...orm.object_designator import Object as ORMObject, ObjectPart as ORMObjectPart from ...orm.action_designator import Action as ORMAction from ...plan_failures import ObjectUnfetchable, ReachabilityFailure @@ -90,12 +90,11 @@ def insert(self, session: Session, **kwargs) -> Action: if key not in orm_class_variables: variable = value.insert(session) if isinstance(variable, ORMObject): - action.object_id = variable.id + action.object = variable elif isinstance(variable, ORMPose): - action.pose_id = variable.id - + action.pose = variable session.add(action) - session.commit() + return action diff --git a/src/pycram/designators/motion_designator.py b/src/pycram/designators/motion_designator.py index b6779c300..b289f345d 100644 --- a/src/pycram/designators/motion_designator.py +++ b/src/pycram/designators/motion_designator.py @@ -54,7 +54,7 @@ def insert(self, session: Session, *args, **kwargs) -> ORMMotionDesignator: metadata = ProcessMetaData().insert(session) motion = self.to_sql() - motion.process_metadata_id = metadata.id + motion.process_metadata = metadata return motion @@ -108,12 +108,9 @@ def to_sql(self) -> ORMMoveMotion: def insert(self, session, *args, **kwargs) -> ORMMoveMotion: motion = super().insert(session) - pose = self.target.insert(session) - motion.pose_id = pose.id - + motion.pose = pose session.add(motion) - session.commit() return motion @@ -147,12 +144,9 @@ def to_sql(self) -> ORMMoveTCPMotion: def insert(self, session: Session, *args, **kwargs) -> ORMMoveTCPMotion: motion = super().insert(session) - pose = self.target.insert(session) - motion.pose_id = pose.id - + motion.pose = pose session.add(motion) - session.commit() return motion @@ -174,12 +168,9 @@ def to_sql(self) -> ORMLookingMotion: def insert(self, session: Session, *args, **kwargs) -> ORMLookingMotion: motion = super().insert(session) - pose = self.target.insert(session) - motion.pose_id = pose.id - + motion.pose = pose session.add(motion) - session.commit() return motion @@ -213,9 +204,8 @@ def to_sql(self) -> ORMMoveGripperMotion: def insert(self, session: Session, *args, **kwargs) -> ORMMoveGripperMotion: motion = super().insert(session) - session.add(motion) - session.commit() + return motion @@ -250,7 +240,7 @@ def to_sql(self) -> ORMDetectingMotion: def insert(self, session: Session, *args, **kwargs) -> ORMDetectingMotion: motion = super().insert(session) session.add(motion) - session.commit() + return motion @@ -353,12 +343,9 @@ def to_sql(self) -> ORMOpeningMotion: def insert(self, session: Session, *args, **kwargs) -> ORMOpeningMotion: motion = super().insert(session) - op = self.object_part.insert(session) - motion.object_id = op.id - + motion.object = op session.add(motion) - session.commit() return motion @@ -388,11 +375,8 @@ def to_sql(self) -> ORMClosingMotion: def insert(self, session: Session, *args, **kwargs) -> ORMClosingMotion: motion = super().insert(session) - op = self.object_part.insert(session) - motion.object_id = op.id - + motion.object = op session.add(motion) - session.commit() return motion diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index 02a58ef41..dbb3d8fbe 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -24,11 +24,11 @@ def to_sql(self) -> ORMBelieveObject: return ORMBelieveObject(self.type, self.name) def insert(self, session: sqlalchemy.orm.session.Session) -> ORMBelieveObject: + metadata = ProcessMetaData().insert(session) self_ = self.to_sql() + self_.process_metadata = metadata session.add(self_) - session.commit() - metadata = ProcessMetaData().insert(session) - self_.process_metadata_id = metadata.id + return self_ @@ -47,14 +47,12 @@ def to_sql(self) -> ORMObjectPart: return ORMObjectPart(self.type, self.name) def insert(self, session: sqlalchemy.orm.session.Session) -> ORMObjectPart: - obj = self.to_sql() metadata = ProcessMetaData().insert(session) - obj.process_metadata_id = metadata.id pose = self.part_pose.insert(session) - obj.pose_id = pose.id - + obj = self.to_sql() + obj.process_metadata = metadata + obj.pose = pose session.add(obj) - session.commit() return obj diff --git a/src/pycram/orm/base.py b/src/pycram/orm/base.py index 6bf7f55a9..d238dfff3 100644 --- a/src/pycram/orm/base.py +++ b/src/pycram/orm/base.py @@ -49,7 +49,7 @@ class Base(_Base): __abstract__ = True @declared_attr - def process_metadata_id(self) -> Mapped[Optional[int]]: + def process_metadata_id(self) -> Mapped[int]: return mapped_column(ForeignKey(f'{ProcessMetaData.__tablename__}.id'), default=None, init=False) """Related MetaData Object to store information about the context of this experiment.""" @@ -164,7 +164,6 @@ def insert(self, session: Session): """Insert this into the database using the session. Skipped if it already is inserted.""" if not self.committed(): session.add(self) - session.commit() return self @classmethod @@ -223,8 +222,6 @@ class Color(Base): class RobotState(PoseMixin, Base): """ORM Representation of a robots state.""" - pose_to_init = True - torso_height: Mapped[float] """The torso height of the robot.""" diff --git a/src/pycram/orm/task.py b/src/pycram/orm/task.py index 5d2152c1f..e2d5d3daf 100644 --- a/src/pycram/orm/task.py +++ b/src/pycram/orm/task.py @@ -15,14 +15,14 @@ class TaskTreeNode(Base): id: Mapped[int] = mapped_column(autoincrement=True, primary_key=True, init=False) """id overriden in order to be able to set the remote_side of the parent attribute""" - code_id: Mapped[int] = mapped_column(ForeignKey("Code.id"), default=None) + code_id: Mapped[int] = mapped_column(ForeignKey("Code.id"), init=False) code: Mapped["Code"] = relationship(init=False) - start_time: Mapped[datetime.datetime] = mapped_column(default=None) - end_time: Mapped[Optional[datetime.datetime]] = mapped_column(default=None) - status: Mapped[TaskStatus] = mapped_column(default=None) - reason: Mapped[Optional[str]] = mapped_column(default=None) - parent_id: Mapped[Optional[int]] = mapped_column(ForeignKey("TaskTreeNode.id"), default=None) - parent: Mapped["TaskTreeNode"] = relationship(foreign_keys=[parent_id], init=False, remote_side=[id]) + start_time: Mapped[datetime.datetime] + end_time: Mapped[Optional[datetime.datetime]] + status: Mapped[TaskStatus] + reason: Mapped[Optional[str]] + parent_id: Mapped[Optional[int]] = mapped_column(ForeignKey("TaskTreeNode.id"), init=False) + parent: Mapped[Optional["TaskTreeNode"]] = relationship(init=False, remote_side=[id]) class Code(Base): diff --git a/src/pycram/pose.py b/src/pycram/pose.py index 852f20967..dc45b4679 100644 --- a/src/pycram/pose.py +++ b/src/pycram/pose.py @@ -242,20 +242,17 @@ def insert(self, session: sqlalchemy.orm.Session) -> ORMPose: metadata = ProcessMetaData().insert(session) position = Position(*self.position_as_list()) - position.process_metadata_id = metadata.id + position.process_metadata = metadata orientation = Quaternion(*self.orientation_as_list()) - orientation.process_metadata_id = metadata.id - + orientation.process_metadata = metadata session.add(position) session.add(orientation) - session.commit() - pose = self.to_sql() - pose.process_metadata_id = metadata.id - pose.position_id = position.id - pose.orientation_id = orientation.id + pose = self.to_sql() + pose.process_metadata = metadata + pose.orientation = orientation + pose.position = position session.add(pose) - session.commit() return pose diff --git a/src/pycram/task.py b/src/pycram/task.py index e6323fd0c..8c477fa93 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -70,14 +70,13 @@ def insert(self, session: sqlalchemy.orm.session.Session) -> ORMCode: if self_ and getattr(self_, "insert", None): designator = self_.insert(session) - code.designator_id = designator.id + code.designator = designator # get and set metadata metadata = ProcessMetaData().insert(session) - code.process_metadata_id = metadata.id + code.process_metadata = metadata session.add(code) - session.commit() return code @@ -163,18 +162,17 @@ def to_sql(self) -> ORMTaskTreeNode: else: reason = None - return ORMTaskTreeNode(None, self.start_time, self.end_time, self.status.name, - reason, id(self.parent) if self.parent else None) + return ORMTaskTreeNode(self.start_time, self.end_time, self.status.name, reason) def insert(self, session: sqlalchemy.orm.session.Session, recursive: bool = True, - parent_id: Optional[int] = None, use_progress_bar: bool = True, + parent: Optional[TaskTreeNode] = None, use_progress_bar: bool = True, progress_bar: Optional[tqdm.tqdm] = None) -> ORMTaskTreeNode: """ Insert this node into the database. :param session: The current session with the database. :param recursive: Rather if the entire tree should be inserted or just this node, defaults to True - :param parent_id: The primary key of the parent node, defaults to None + :param parent: The parent node, defaults to None :param use_progress_bar: Rather to use a progressbar or not :param progress_bar: The progressbar to update. If a progress bar is desired and this is None, a new one will be created. @@ -191,27 +189,31 @@ def insert(self, session: sqlalchemy.orm.session.Session, recursive: bool = True # convert self to orm object node = self.to_sql() - node.code_id = code.id + node.code = code # get and set metadata metadata = ProcessMetaData().insert(session) - node.process_metadata_id = metadata.id + node.process_metadata = metadata - # set parent to id from constructor - node.parent_id = parent_id + # set node parent + node.parent = parent - # add the node to database to retrieve the new id + # add the node to the session; note that the instance is not yet committed to the db, but rather in a + # pending state session.add(node) - session.commit() if progress_bar: progress_bar.update() # if recursive, insert all children if recursive: - [child.insert(session, parent_id=node.id, use_progress_bar=use_progress_bar, progress_bar=progress_bar) + [child.insert(session, parent=node, use_progress_bar=use_progress_bar, progress_bar=progress_bar) for child in self.children] + # once recursion is done and the root node is reached again, commit the session to the database + if self.parent is None: + session.commit() + return node From dc9ae6c77b992da3d9f457d039a2466d9276c4aa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Tue, 26 Mar 2024 09:19:26 +0100 Subject: [PATCH 148/195] [orm] updated orm tests --- test/test_orm.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/test/test_orm.py b/test/test_orm.py index 4c5063fc7..f3bac54a3 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -10,7 +10,6 @@ import pycram.task import pycram.task from bullet_world_testcase import BulletWorldTestCase -import test_task_tree from pycram.bullet_world import Object from pycram.designators import action_designator, object_designator, motion_designator from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable, \ @@ -36,7 +35,6 @@ def setUp(self): super().setUp() pycram.orm.base.Base.metadata.create_all(self.engine) self.session = sqlalchemy.orm.Session(bind=self.engine) - self.session.commit() def tearDown(self): super().tearDown() @@ -205,7 +203,8 @@ def test_code_designator_type(self): action.perform() pycram.orm.base.ProcessMetaData().description = "code_designator_type_test" pycram.task.task_tree.root.insert(self.session) - result = self.session.scalars(select(pycram.orm.task.Code).where(pycram.orm.task.Code.function == "perform")).all() + result = (self.session.scalars(select(pycram.orm.task.Code).where(pycram.orm.task.Code.function == "perform")) + .all()) self.assertEqual(result[0].designator.dtype, action_designator.NavigateAction.__name__) self.assertEqual(result[1].designator.dtype, motion_designator.MoveMotion.__name__) From daeb98848ab7d337b4bd4656dfedab14699489a3 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 26 Mar 2024 16:34:54 +0100 Subject: [PATCH 149/195] [pose-gen] New class for pose generator and global orientation gen --- src/pycram/designators/location_designator.py | 12 +- src/pycram/pose_generator_and_validator.py | 248 ++++++++++-------- 2 files changed, 139 insertions(+), 121 deletions(-) diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index 100a233f8..72a95237b 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -11,8 +11,7 @@ from ..enums import JointType from ..helper import transform from ..plan_failures import EnvironmentManipulationImpossible -from ..pose_generator_and_validator import pose_generator, visibility_validator, reachability_validator, \ - generate_orientation +from ..pose_generator_and_validator import PoseGenerator, visibility_validator, reachability_validator from ..robot_description import ManipulatorDescription from ..pose import Pose @@ -183,8 +182,7 @@ def __iter__(self): test_robot = BulletWorld.current_bullet_world.get_shadow_object(robot_object) with Use_shadow_world(): - - for maybe_pose in pose_generator(final_map, number_of_samples=600): + for maybe_pose in PoseGenerator(final_map, number_of_samples=600): res = True arms = None if self.visible_for: @@ -276,8 +274,8 @@ def __iter__(self) -> Location: self.handle.name) with Use_shadow_world(): - for maybe_pose in pose_generator(final_map, number_of_samples=600, - orientation_generator=lambda p, o: generate_orientation(p, half_pose)): + for maybe_pose in PoseGenerator(final_map, number_of_samples=600, + orientation_generator=lambda p, o: PoseGenerator.generate_orientation(p, half_pose)): hand_links = [] for name, chain in robot_description.chains.items(): @@ -340,6 +338,6 @@ def __iter__(self): if self.for_object: min, max = self.for_object.bullet_world_object.get_AABB() height_offset = (max[2] - min[2]) / 2 - for maybe_pose in pose_generator(sem_costmap): + for maybe_pose in PoseGenerator(sem_costmap): maybe_pose.position.z += height_offset yield self.Location(maybe_pose) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index f959fd126..f9e05ba6c 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -7,6 +7,7 @@ from .bullet_world_reasoning import contact from .costmaps import Costmap from .pose import Pose, Transform +from .robot_description import ManipulatorDescription from .robot_descriptions import robot_description from .external_interfaces.ik import request_ik from .plan_failures import IKError @@ -14,65 +15,116 @@ from typing import Type, Tuple, List, Union, Dict, Iterable -def pose_generator(costmap: Costmap, number_of_samples=100, orientation_generator=None) -> Iterable: - """ - A generator that crates pose candidates from a given costmap. The generator - selects the highest 100 values and returns the corresponding positions. - Orientations are calculated such that the Robot faces the center of the costmap. - - :param costmap: The costmap from which poses should be sampled. - :param number_of_samples: The number of samples from the costmap that should be returned at max - :param orientation_generator: function that generates an orientation given a position and the origin of the costmap - :Yield: A tuple of position and orientation - """ - if not orientation_generator: - orientation_generator = generate_orientation - - # Determines how many positions should be sampled from the costmap - if number_of_samples == -1: - number_of_samples = costmap.map.flatten().shape[0] - indices = np.argpartition(costmap.map.flatten(), -number_of_samples)[-number_of_samples:] - indices = np.dstack(np.unravel_index(indices, costmap.map.shape)).reshape(number_of_samples, 2) - - height = costmap.map.shape[0] - width = costmap.map.shape[1] - center = np.array([height // 2, width // 2]) - for ind in indices: - if costmap.map[ind[0]][ind[1]] == 0: - continue - # The position is calculated by creating a vector from the 2D position in the costmap (given by x and y) - # and the center of the costmap (since this is the origin). This vector is then turned into a transformation - # and muiltiplied with the transformation of the origin. - vector_to_origin = (center - ind) * costmap.resolution - point_to_origin = Transform([*vector_to_origin, 0], frame="point", child_frame="origin") - origin_to_map = costmap.origin.to_transform("origin").invert() - point_to_map = point_to_origin * origin_to_map - map_to_point = point_to_map.invert() - - orientation = orientation_generator(map_to_point.translation_as_list(), costmap.origin) - yield Pose(map_to_point.translation_as_list(), orientation) - - -def height_generator() -> float: - pass - - -def generate_orientation(position: List[float], origin: Pose) -> List[float]: - """ - This method generates the orientation for a given position in a costmap. The - orientation is calculated such that the robot faces the origin of the costmap. - This generation is done by simply calculating the arctan between the position, - in the costmap, and the origin of the costmap. - - :param position: The position in the costmap. This position is already converted - to the world coordinate frame. - :param origin: The origin of the costmap. This is also the point which the - robot should face. - :return: A quaternion of the calculated orientation - """ - angle = np.arctan2(position[1]-origin.position.y, position[0]-origin.position.x) + np.pi - quaternion = list(tf.transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) - return quaternion +class PoseGenerator: + current_orientation_generator = None + + def __init__(self, costmap: Costmap, number_of_samples=100, orientation_generator=None): + """ + :param costmap: The costmap from which poses should be sampled. + :param number_of_samples: The number of samples from the costmap that should be returned at max + :param orientation_generator: function that generates an orientation given a position and the origin of the costmap + """ + + if not PoseGenerator.current_orientation_generator: + PoseGenerator.current_orientation_generator = PoseGenerator.generate_orientation + + self.costmap = costmap + self.number_of_samples = number_of_samples + self.orientation_generator = orientation_generator if orientation_generator else PoseGenerator.current_orientation_generator + + def __iter__(self) -> Iterable: + """ + A generator that crates pose candidates from a given costmap. The generator + selects the highest 100 values and returns the corresponding positions. + Orientations are calculated such that the Robot faces the center of the costmap. + + :Yield: A tuple of position and orientation + """ + + # Determines how many positions should be sampled from the costmap + if self.number_of_samples == -1: + self.number_of_samples = self.costmap.map.flatten().shape[0] + indices = np.argpartition(self.costmap.map.flatten(), -self.number_of_samples)[-self.number_of_samples:] + indices = np.dstack(np.unravel_index(indices, self.costmap.map.shape)).reshape(self.number_of_samples, 2) + + height = self.costmap.map.shape[0] + width = self.costmap.map.shape[1] + center = np.array([height // 2, width // 2]) + for ind in indices: + if self.costmap.map[ind[0]][ind[1]] == 0: + continue + # The position is calculated by creating a vector from the 2D position in the costmap (given by x and y) + # and the center of the costmap (since this is the origin). This vector is then turned into a transformation + # and muiltiplied with the transformation of the origin. + vector_to_origin = (center - ind) * self.costmap.resolution + point_to_origin = Transform([*vector_to_origin, 0], frame="point", child_frame="origin") + origin_to_map = self.costmap.origin.to_transform("origin").invert() + point_to_map = point_to_origin * origin_to_map + map_to_point = point_to_map.invert() + + orientation = self.orientation_generator(map_to_point.translation_as_list(), self.costmap.origin) + yield Pose(map_to_point.translation_as_list(), orientation) + + # @staticmethod + # def pose_generator(costmap: Costmap, number_of_samples=100, orientation_generator=None) -> Iterable: + # """ + # A generator that crates pose candidates from a given costmap. The generator + # selects the highest 100 values and returns the corresponding positions. + # Orientations are calculated such that the Robot faces the center of the costmap. + # + # :param costmap: The costmap from which poses should be sampled. + # :param number_of_samples: The number of samples from the costmap that should be returned at max + # :param orientation_generator: function that generates an orientation given a position and the origin of the costmap + # :Yield: A tuple of position and orientation + # """ + # if not orientation_generator: + # orientation_generator = PoseGenerator.current_orientation_generator + # + # # Determines how many positions should be sampled from the costmap + # if number_of_samples == -1: + # number_of_samples = costmap.map.flatten().shape[0] + # indices = np.argpartition(costmap.map.flatten(), -number_of_samples)[-number_of_samples:] + # indices = np.dstack(np.unravel_index(indices, costmap.map.shape)).reshape(number_of_samples, 2) + # + # height = costmap.map.shape[0] + # width = costmap.map.shape[1] + # center = np.array([height // 2, width // 2]) + # for ind in indices: + # if costmap.map[ind[0]][ind[1]] == 0: + # continue + # # The position is calculated by creating a vector from the 2D position in the costmap (given by x and y) + # # and the center of the costmap (since this is the origin). This vector is then turned into a transformation + # # and muiltiplied with the transformation of the origin. + # vector_to_origin = (center - ind) * costmap.resolution + # point_to_origin = Transform([*vector_to_origin, 0], frame="point", child_frame="origin") + # origin_to_map = costmap.origin.to_transform("origin").invert() + # point_to_map = point_to_origin * origin_to_map + # map_to_point = point_to_map.invert() + # + # orientation = orientation_generator(map_to_point.translation_as_list(), costmap.origin) + # yield Pose(map_to_point.translation_as_list(), orientation) + + @staticmethod + def height_generator() -> float: + pass + + @staticmethod + def generate_orientation(position: List[float], origin: Pose) -> List[float]: + """ + This method generates the orientation for a given position in a costmap. The + orientation is calculated such that the robot faces the origin of the costmap. + This generation is done by simply calculating the arctan between the position, + in the costmap, and the origin of the costmap. + + :param position: The position in the costmap. This position is already converted + to the world coordinate frame. + :param origin: The origin of the costmap. This is also the point which the + robot should face. + :return: A quaternion of the calculated orientation + """ + angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi + quaternion = list(tf.transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) + return quaternion def visibility_validator(pose: Pose, @@ -134,14 +186,9 @@ def reachability_validator(pose: Pose, target = target.get_pose() robot.set_pose(pose) + manipulator_descs = list( + filter(lambda chain: isinstance(chain[1], ManipulatorDescription), robot_description.chains.items())) - left_gripper = robot_description.get_tool_frame('left') - right_gripper = robot_description.get_tool_frame('right') - - # left_joints = robot_description._safely_access_chains('left').joints - left_joints = robot_description.chains['left'].joints - # right_joints = robot_description._safely_access_chains('right').joints - right_joints = robot_description.chains['right'].joints # TODO Make orientation adhere to grasping orientation res = False arms = [] @@ -151,57 +198,30 @@ def reachability_validator(pose: Pose, if robot in allowed_collision.keys(): allowed_robot_links = allowed_collision[robot] - joint_state_before_ik=robot._current_joint_states - try: - # resp = request_ik(base_link, end_effector, target_diff, robot, left_joints) - resp = request_ik(target, robot, left_joints, left_gripper) + for chain_name, chain in manipulator_descs: + joint_state_before_ik = robot._current_joint_states + try: + resp = request_ik(target, robot, chain.joints, chain.tool_frame) - _apply_ik(robot, resp, left_joints) - - for obj in BulletWorld.current_bullet_world.objects: - if obj.name == "floor": - continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] + _apply_ik(robot, resp, chain.joints) - if in_contact: - for link in contact_links: - - if link[0] in allowed_robot_links or link[1] in allowed_links: - in_contact = False - - if not in_contact: - arms.append("left") - res = True - except IKError: - pass - finally: - robot.set_joint_states(joint_state_before_ik) + for obj in BulletWorld.current_bullet_world.objects: + if obj.name == "floor": + continue + in_contact, contact_links = contact(robot, obj, return_links=True) + allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - try: - # resp = request_ik(base_link, end_effector, target_diff, robot, right_joints) - resp = request_ik(target, robot, right_joints, right_gripper) + if in_contact: + for link in contact_links: - _apply_ik(robot, resp, right_joints) - - for obj in BulletWorld.current_bullet_world.objects: - if obj.name == "floor": - continue - in_contact, contact_links = contact(robot, obj, return_links=True) - allowed_links = allowed_collision[obj] if obj in allowed_collision.keys() else [] - - if in_contact: - for link in contact_links: - - if link[0] in allowed_robot_links or link[1] in allowed_links: - in_contact = False - - if not in_contact: - arms.append("right") - res = True - except IKError: - pass - finally: - robot.set_joint_states(joint_state_before_ik) + if link[0] in allowed_robot_links or link[1] in allowed_links: + in_contact = False + if not in_contact: + arms.append(chain_name) + res = True + except IKError: + pass + finally: + robot.set_joint_states(joint_state_before_ik) return res, arms From 3de5a1c133a5e9ae167d8e8e4a319354a1a27c12 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 26 Mar 2024 16:35:35 +0100 Subject: [PATCH 150/195] [robot-description] Added orientation generator to description --- src/pycram/robot_descriptions/stretch_description.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index fedbbd55b..a8db7e11c 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -1,4 +1,6 @@ from ..robot_description import * +import numpy as np +import tf class StretchDescription(RobotDescription): @@ -28,8 +30,8 @@ def __init__(self): ["link_head_pan", "link_head_tilt"]) self.add_chain("neck", neck) - arm_joints = ['joint_arm_l4', 'joint_arm_l3', 'joint_arm_l2', 'joint_arm_l1', 'joint_arm_l0'] - arm_links = ['link_arm_l4', 'link_arm_l3', 'link_arm_l2', 'link_arm_l1', 'link_arm_l0'] + arm_joints = ['joint_lift','joint_arm_l3', 'joint_arm_l2', 'joint_arm_l1', 'joint_arm_l0', "joint_wrist_yaw"] + arm_links = ['link_lift', 'link_arm_l3', 'link_arm_l2', 'link_arm_l1', 'link_arm_l0', "link_wrist_yaw"] arm_chain_desc = ChainDescription("arm", arm_joints, arm_links) arm_inter_desc = InteractionDescription(arm_chain_desc, "link_wrist_yaw") @@ -59,3 +61,9 @@ def __init__(self): def get_camera_frame(self, name="color"): return super().get_camera_frame(name) + + @staticmethod + def stretch_orientation_generator(position, origin): + angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi + quaternion = list(tf.transformations.quaternion_from_euler(0, 0, angle + np.pi / 2, axes="sxyz")) + return quaternion From 741cb6141c05403e7d3f3957f13b1d3cf0ec685e Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:09:11 +0100 Subject: [PATCH 151/195] [robot-desc] New logging --- src/pycram/robot_description.py | 40 ++++++++++++++++----------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/pycram/robot_description.py b/src/pycram/robot_description.py index d8df6f5b8..18059f436 100644 --- a/src/pycram/robot_description.py +++ b/src/pycram/robot_description.py @@ -48,7 +48,7 @@ def add_static_joint_chains(self, static_joint_states: Dict[str, List[float]]) - """ for configuration, joint_states in static_joint_states.items(): if not self.add_static_joint_chain(configuration, joint_states): - logger.error("(robot_description) Could not add all static_joint_states for the chain %s.", self.name) + rospy.logerr("(robot_description) Could not add all static_joint_states for the chain %s.", self.name) break def add_static_joint_chain(self, configuration: str, static_joint_states: List[float]) -> Union[None, bool]: @@ -68,10 +68,10 @@ def add_static_joint_chain(self, configuration: str, static_joint_states: List[f self.static_joint_states[configuration] = static_joint_states return True else: - logger.warning("(robot_description) The chain %s already has static joint values " + rospy.logwarn("(robot_description) The chain %s already has static joint values " "for the config %s.", self.name, configuration) else: - logger.error("(robot_description) The number of the joint values does not equal the amount of the joints" + rospy.logerr("(robot_description) The number of the joint values does not equal the amount of the joints" "for the chain %s.", self.name) def get_static_joint_chain(self, configuration: str) -> Union[None, Dict[str, float]]: @@ -85,7 +85,7 @@ def get_static_joint_chain(self, configuration: str) -> Union[None, Dict[str, fl try: joint_values = self.static_joint_states[configuration] except KeyError: - logger.error("(robot_description) Configuration %s is unknown for the chain %s.", configuration, self.name) + rospy.logerr("(robot_description) Configuration %s is unknown for the chain %s.", configuration, self.name) return None return dict(zip(self.joints, joint_values)) @@ -260,8 +260,8 @@ def __init__(self, name: str, rospack = rospkg.RosPack() filename = rospack.get_path('pycram') + '/resources/' + name + '.urdf' with open(filename) as f: - with utils.suppress_stdout_stderr(): - self.robot_urdf = URDF.from_xml_string(f.read()) + # with utils.suppress_stdout_stderr(): + self.robot_urdf = URDF.from_xml_string(f.read()) def _safely_access_chains(self, chain_name: str, verbose: Optional[bool] = True) -> Union[None, ChainDescription]: """ @@ -272,7 +272,7 @@ def _safely_access_chains(self, chain_name: str, verbose: Optional[bool] = True) chain_description = self.chains[chain_name] except KeyError: if verbose: - logger.warning("(robot_description) Chain name %s is unknown.", chain_name) + rospy.logwarn("(robot_description) Chain name %s is unknown.", chain_name) return None return chain_description @@ -295,10 +295,10 @@ def _get_chain_description(self, chain_name: str, if type(chain_description) is description_type: return chain_description else: - logger.error("(robot_description) The chain %s is not of type %s, but of type %s.", + rospy.logerr("(robot_description) The chain %s is not of type %s, but of type %s.", chain_name, description_type, type(chain_description)) else: - logger.warning("(robot_description) Only subclasses of ChainDescription are allowed.") + rospy.logwarn("(robot_description) Only subclasses of ChainDescription are allowed.") def get_tool_frame(self, manipulator_name: str) -> Union[None, str]: """ @@ -310,7 +310,7 @@ def get_tool_frame(self, manipulator_name: str) -> Union[None, str]: if manipulator_description: return manipulator_description.tool_frame else: - logger.error("(robot_description) Could not get the tool frame of the manipulator %s.", manipulator_name) + rospy.logerr("(robot_description) Could not get the tool frame of the manipulator %s.", manipulator_name) def get_static_joint_chain(self, chain_name: str, configuration: str) -> Union[None, Dict[str, float]]: """ @@ -322,7 +322,7 @@ def get_static_joint_chain(self, chain_name: str, configuration: str) -> Union[N if chain_description: return chain_description.get_static_joint_chain(configuration) else: - logger.error("(robot_description) Could not get static joint chain called %s of the chain %s.", + rospy.logerr("(robot_description) Could not get static joint chain called %s of the chain %s.", configuration, chain_name) def get_static_tf(self, base_link: str, target_link: str): @@ -338,11 +338,11 @@ def add_chain(self, name: str, chain_description: ChainDescription) -> Union[Non """ if issubclass(type(chain_description), ChainDescription): if self._safely_access_chains(name, verbose=False): - logger.warning("(robot_description) Replacing the chain description of the name %s.", name) + rospy.logwarn("(robot_description) Replacing the chain description of the name %s.", name) self.chains[name] = chain_description return True else: - logger.error("(robot_description) Given chain_description object is no subclass of ChainDescription.") + rospy.logerr("(robot_description) Given chain_description object is no subclass of ChainDescription.") def add_chains(self, chains_dict: Dict[str, ChainDescription]) -> None: """ @@ -354,7 +354,7 @@ def add_chains(self, chains_dict: Dict[str, ChainDescription]) -> None: """ for name, chain in chains_dict.items(): if not self.add_chain(name, chain): - logger.error("(robot_description) Could not add the chain object of name %s.", name) + rospy.logerr("(robot_description) Could not add the chain object of name %s.", name) break def add_camera(self, name: str, camera_description: CameraDescription) -> Union[None, bool]: @@ -369,11 +369,11 @@ def add_camera(self, name: str, camera_description: CameraDescription) -> Union[ except KeyError: found = False if found: - logger.warning("(robot_description) Replacing the camera description of the name %s.", name) + rospy.logwarn("(robot_description) Replacing the camera description of the name %s.", name) self.cameras[name] = camera_description return True else: - logger.error("(robot_description) Given camera_description object is not of type CameraDescription.") + rospy.logerr("(robot_description) Given camera_description object is not of type CameraDescription.") def add_cameras(self, cameras_dict: Dict[str, CameraDescription]) -> None: """ @@ -385,7 +385,7 @@ def add_cameras(self, cameras_dict: Dict[str, CameraDescription]) -> None: """ for name, camera in cameras_dict.items(): if not self.add_camera(name, camera): - logger.error("(robot_description) Could not add the camera object of name %s.", name) + rospy.logerr("(robot_description) Could not add the camera object of name %s.", name) break def get_camera_frame(self, camera_name: str) -> Union[None, str]: @@ -397,7 +397,7 @@ def get_camera_frame(self, camera_name: str) -> Union[None, str]: try: camera_description = self.cameras[camera_name] except KeyError: - logger.error("(robot_description) Camera name %s is unknown.", camera_name) + rospy.logerr("(robot_description) Camera name %s is unknown.", camera_name) return None return camera_description.frame @@ -426,7 +426,7 @@ def add_static_joint_chains(self, chain_name: str, static_joint_states: Dict[str """ for configuration, joint_states in static_joint_states.items(): if not self.add_static_joint_chain(chain_name, configuration, joint_states): - logger.error("(robot_description) Could not add the static joint chain called %s for chain %s.", + rospy.logerr("(robot_description) Could not add the static joint chain called %s for chain %s.", configuration, chain_name) break @@ -456,7 +456,7 @@ def add_static_gripper_chains(self, manipulator_name: str, static_joint_states: """ for configuration, joint_states in static_joint_states.items(): if not self.add_static_gripper_chain(manipulator_name, configuration, joint_states): - logger.error("(robot_description) Could not add static gripper chain called %s for manipulator chain %s.", + rospy.logerr("(robot_description) Could not add static gripper chain called %s for manipulator chain %s.", configuration, manipulator_name) break From 4612f0c7ba9e476e1fe88e184de80bf05f82d32a Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:09:41 +0100 Subject: [PATCH 152/195] [stretch-description] Finished stretch description --- src/pycram/robot_descriptions/stretch_description.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index a8db7e11c..2c5c706ce 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -38,9 +38,8 @@ def __init__(self): gripper_links = ['link_gripper_finger_left', 'link_gripper_fingertip_left', 'link_gripper_finger_right', 'link_gripper_fingertip_right', 'link_grasp_center'] - gripper_joints = ['joint_gripper_finger_left', 'joint_gripper_fingertip_left', - 'joint_gripper_finger_right', 'joint_gripper_fingertip_right', 'joint_grasp_center'] - arm_gripper_desc = GripperDescription("gripper", gripper_links, gripper_joints, + gripper_joints = ['joint_gripper_finger_left', 'joint_gripper_finger_right'] + arm_gripper_desc = GripperDescription("arm", gripper_links, gripper_joints, gripper_meter_to_jnt_multiplier=5.0, gripper_minimal_position=0.013, gripper_convergence_delta=0.005) @@ -48,7 +47,7 @@ def __init__(self): arm_desc = ManipulatorDescription(arm_inter_desc, tool_frame="link_grasp_center", gripper_description=arm_gripper_desc) self.add_chain("arm", arm_desc) - arm_park = [0.0, 0.0, 0.0, 0.0, 0.0] + arm_park = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.add_static_joint_chain("arm", "park", arm_park) gripper_confs = {"open": [0.59, 0.59], "close": [0.0, 0.0]} From 29113075a56d3e865d250429df1ce43e58c5e42e Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:45:44 +0100 Subject: [PATCH 153/195] [stretch-description] Last fixes for arm name --- src/pycram/robot_descriptions/__init__.py | 4 ++-- src/pycram/robot_descriptions/stretch_description.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/pycram/robot_descriptions/__init__.py b/src/pycram/robot_descriptions/__init__.py index d32c9d37f..3385fab74 100644 --- a/src/pycram/robot_descriptions/__init__.py +++ b/src/pycram/robot_descriptions/__init__.py @@ -70,7 +70,7 @@ def update_robot_description(robot_name=None, from_ros=None): return InitializedRobotDescription(description) -with utils.suppress_stdout_stderr(): - update_robot_description(from_ros=True) # "ur5_robotiq")# # todo: put in ros init +# with utils.suppress_stdout_stderr(): +update_robot_description(from_ros=True) # "ur5_robotiq")# # todo: put in ros init robot_description = InitializedRobotDescription.i diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index 2c5c706ce..9bdf63717 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -45,7 +45,7 @@ def __init__(self): gripper_convergence_delta=0.005) arm_desc = ManipulatorDescription(arm_inter_desc, tool_frame="link_grasp_center", gripper_description=arm_gripper_desc) - self.add_chain("arm", arm_desc) + self.add_chains({"arm": arm_desc, "right": arm_desc, "left": arm_desc}) arm_park = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.add_static_joint_chain("arm", "park", arm_park) From 648d2b525ff13f8b682b83b82a1234259a3dacc3 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:46:07 +0100 Subject: [PATCH 154/195] [stretch-pms] Finished process modules for stretch simulated --- .../stretch_process_modules.py | 115 ++++++++++-------- 1 file changed, 65 insertions(+), 50 deletions(-) diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py index 106373601..1dc972859 100644 --- a/src/pycram/process_modules/stretch_process_modules.py +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -1,76 +1,55 @@ from threading import Lock from typing import Any -from ..external_interfaces.ik import request_ik from ..helper import _apply_ik -from ..pose import Pose -from ..process_module import ProcessModule, ProcessModuleManager -from ..robot_descriptions import robot_description -from ..bullet_world import BulletWorld, Object -from ..bullet_world_reasoning import visible +from .default_process_modules import * -class StretchNavigate(ProcessModule): - def _execute(self, designator) -> Any: - BulletWorld.robot.set_pose(designator.target) +class StretchNavigate(DefaultNavigation): + pass class StretchMoveHead(ProcessModule): def _execute(self, designator) -> Any: - pass + target = designator.target + robot = BulletWorld.robot + local_transformer = LocalTransformer() + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("link_head_pan")) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("link_head_tilt")) -class StretchMoveGripper(ProcessModule): - def _execute(self, designator) -> Any: - robot = BulletWorld.robot - gripper = designator.gripper - motion = designator.motion - for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): - robot.set_joint_state(joint, state) + new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) + new_tilt = np.arctan2(-pose_in_tilt.position.y, pose_in_tilt.position.z ** 2 + pose_in_tilt.position.x ** 2) * -1 + current_pan = robot.get_joint_state("joint_head_pan") + current_tilt = robot.get_joint_state("joint_head_tilt") -class StretchDetect(ProcessModule): - def _execute(self, designator) -> Any: - robot = BulletWorld.robot - object_type = designator.object_type - # Should be "wide_stereo_optical_frame" - cam_frame_name = robot_description.get_camera_frame() - # should be [0, 0, 1] - front_facing_axis = robot_description.front_facing_axis + robot.set_joint_state("joint_head_pan", new_pan + current_pan) + robot.set_joint_state("joint_head_tilt", new_tilt + current_tilt) - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) - for obj in objects: - if visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): - return obj +class StretchMoveGripper(DefaultMoveGripper): + pass -class StretchMoveTCP(ProcessModule): - def _execute(self, designator) -> Any: - target = designator.target - robot = BulletWorld.robot - _move_arm_tcp(target, robot, designator.arm) +class StretchDetecting(DefaultDetecting): + pass -class StretchMoveArmJoints(ProcessModule): - def _execute(self, designator) -> Any: - robot = BulletWorld.robot - if designator.right_arm_poses: - robot.set_joint_states(designator.right_arm_poses) - if designator.left_arm_poses: - robot.set_joint_states(designator.left_arm_poses) +class StretchMoveTCP(DefaultMoveTCP): + pass -class StretchMoveJoints(ProcessModule): - def _execute(self, designator) -> Any: - robot = BulletWorld.robot - robot.set_joint_states(dict(zip(designator.names, designator.positions))) +class StretchMoveArmJoints(DefaultMoveArmJoints): + pass -class StretchWorldStateDetecting(ProcessModule): - def _execute(self, designator) -> Any: - obj_type = designator.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] +class StretchMoveJoints(DefaultMoveJoints): + pass + + +class StretchWorldStateDetecting(DefaultWorldStateDetecting): + pass class StretchOpen(ProcessModule): @@ -108,4 +87,40 @@ def __init__(self): def navigate(self): if ProcessModuleManager.execution_type == "simulated": - return StretchNavigate() + return StretchNavigate(self._navigate_lock) + def looking(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchMoveHead(self._looking_lock) + + def detecting(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchDetecting(self._detecting_lock) + + def move_tcp(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchMoveTCP(self._move_tcp_lock) + + def move_arm_joints(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchMoveArmJoints(self._move_arm_joints_lock) + + def world_state_detecting(self): + if ProcessModuleManager.execution_type == "simulated" or ProcessModuleManager.execution_type == "real": + return StretchWorldStateDetecting(self._world_state_detecting_lock) + + def move_joints(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchMoveJoints(self._move_joints_lock) + + def move_gripper(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchMoveGripper(self._move_gripper_lock) + + def open(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchOpen(self._open_lock) + + def close(self): + if ProcessModuleManager.execution_type == "simulated": + return StretchClose(self._close_lock) + From 8e8750632dd8f02f0c31bf00b614115c218496a0 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:47:47 +0100 Subject: [PATCH 155/195] [launch] Changed default robot back to pr2 --- launch/ik_and_description.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/ik_and_description.launch b/launch/ik_and_description.launch index efe640395..0ae6d3098 100644 --- a/launch/ik_and_description.launch +++ b/launch/ik_and_description.launch @@ -1,5 +1,5 @@ - + From 7217e280f09e5d88bba7d7b19ddce58e5e143d48 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 28 Mar 2024 15:52:48 +0100 Subject: [PATCH 156/195] [pose-gen] removed old code --- src/pycram/pose_generator_and_validator.py | 39 ---------------------- 1 file changed, 39 deletions(-) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index f9e05ba6c..20495072e 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -65,45 +65,6 @@ def __iter__(self) -> Iterable: orientation = self.orientation_generator(map_to_point.translation_as_list(), self.costmap.origin) yield Pose(map_to_point.translation_as_list(), orientation) - # @staticmethod - # def pose_generator(costmap: Costmap, number_of_samples=100, orientation_generator=None) -> Iterable: - # """ - # A generator that crates pose candidates from a given costmap. The generator - # selects the highest 100 values and returns the corresponding positions. - # Orientations are calculated such that the Robot faces the center of the costmap. - # - # :param costmap: The costmap from which poses should be sampled. - # :param number_of_samples: The number of samples from the costmap that should be returned at max - # :param orientation_generator: function that generates an orientation given a position and the origin of the costmap - # :Yield: A tuple of position and orientation - # """ - # if not orientation_generator: - # orientation_generator = PoseGenerator.current_orientation_generator - # - # # Determines how many positions should be sampled from the costmap - # if number_of_samples == -1: - # number_of_samples = costmap.map.flatten().shape[0] - # indices = np.argpartition(costmap.map.flatten(), -number_of_samples)[-number_of_samples:] - # indices = np.dstack(np.unravel_index(indices, costmap.map.shape)).reshape(number_of_samples, 2) - # - # height = costmap.map.shape[0] - # width = costmap.map.shape[1] - # center = np.array([height // 2, width // 2]) - # for ind in indices: - # if costmap.map[ind[0]][ind[1]] == 0: - # continue - # # The position is calculated by creating a vector from the 2D position in the costmap (given by x and y) - # # and the center of the costmap (since this is the origin). This vector is then turned into a transformation - # # and muiltiplied with the transformation of the origin. - # vector_to_origin = (center - ind) * costmap.resolution - # point_to_origin = Transform([*vector_to_origin, 0], frame="point", child_frame="origin") - # origin_to_map = costmap.origin.to_transform("origin").invert() - # point_to_map = point_to_origin * origin_to_map - # map_to_point = point_to_map.invert() - # - # orientation = orientation_generator(map_to_point.translation_as_list(), costmap.origin) - # yield Pose(map_to_point.translation_as_list(), orientation) - @staticmethod def height_generator() -> float: pass From 2cdc22b333bcf2e76498b2544ce00bb9e8b78b8b Mon Sep 17 00:00:00 2001 From: Tom Schierenbeck Date: Tue, 2 Apr 2024 14:25:20 +0200 Subject: [PATCH 157/195] [Misc] added docstring, removed an unnecessary print, replaced function call. --- src/pycram/designators/actions/actions.py | 2 +- src/pycram/resolver/probabilistic/probabilistic_action.py | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 58ed1e716..27312d89f 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -553,7 +553,7 @@ def perform(self) -> None: orientation = list(transformations.quaternion_from_euler(0, 0, angle, axes="sxyz")) # create new robot pose - new_robot_pose = Pose(robot_position.to_list()[0], orientation) + new_robot_pose = Pose(robot_position.position_as_list(), orientation) # turn robot NavigateActionPerformable(new_robot_pose).perform() diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index 7570ded9c..f5feaaa32 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -132,7 +132,6 @@ def create_model(self) -> ProbabilisticCircuit: event = outer_event & limiting_event # go.Figure(event.plot()).show() result, _ = centered_model.conditional(event) - print(result) return result @@ -179,6 +178,11 @@ def default_policy(self) -> ProbabilisticCircuit: return GaussianCostmapModel().create_model() def sample_to_action(self, sample: List) -> MoveAndPickUpPerformable: + """ + Convert a sample from the underlying distribution to a performable action. + :param sample: The sample + :return: The action + """ arm, grasp, relative_x, relative_y = sample position = [relative_x, relative_y, 0.] pose = Pose(position, frame=self.object_designator.bullet_world_object.tf_frame) From 88b0421b8c40b37ecdfb07f726b874e06fb53bbb Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 2 Apr 2024 15:00:49 +0200 Subject: [PATCH 158/195] [demos] Small fixes to make demo work everywhere --- demos/pycram_bullet_world_demo/demo.py | 6 +----- src/pycram/process_modules/pr2_process_modules.py | 2 +- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/demos/pycram_bullet_world_demo/demo.py b/demos/pycram_bullet_world_demo/demo.py index c19ad349c..6886af5da 100644 --- a/demos/pycram_bullet_world_demo/demo.py +++ b/demos/pycram_bullet_world_demo/demo.py @@ -67,11 +67,7 @@ def move_and_detect(obj_type): pickup_arm = "left" if drawer_open_loc.arms[0] == "right" else "right" PickUpAction(spoon_desig, [pickup_arm], ["top"]).resolve().perform() - ParkArmsAction([Arms.BOTH]).resolve().perform() - - close_loc = drawer_open_loc.pose - close_loc.position.y += 0.1 - NavigateAction([close_loc]).resolve().perform() + ParkArmsAction([Arms.LEFT if pickup_arm == "left" else Arms.RIGHT]).resolve().perform() CloseAction(object_designator_description=handle_desig, arms=[drawer_open_loc.arms[0]]).resolve().perform() diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index e49427485..75846131e 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -176,7 +176,7 @@ def _execute(self, desig: OpeningMotion): desig.object_part.bullet_world_object.set_joint_state(container_joint, part_of_object.get_joint_limits( - container_joint)[1]) + container_joint)[1] - 0.05) class Pr2Close(ProcessModule): From 37de05480c69d7266df3467ec736e6fd30ec6989 Mon Sep 17 00:00:00 2001 From: Nils Leusmann Date: Wed, 3 Apr 2024 12:00:36 +0200 Subject: [PATCH 159/195] Adds documentation strings for new functions --- src/pycram/pose_generator_and_validator.py | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index e2fcf7aed..74366b6d3 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -140,7 +140,8 @@ def reachability_validator(pose: Pose, should be validated. :param target: The target position or object instance which should be the target for reachability. - :param allowed_collision: + :param allowed_collision: dict of objects with which the robot is allowed to collide each + object correlates to a list of links of which this object consists :return: True if the target is reachable for the robot and False in any other case. """ @@ -189,7 +190,22 @@ def reachability_validator(pose: Pose, return res, arms -def collision_check(robot, allowed_collision): +def collision_check(robot: Object, allowed_collision: list): + """ + This method checks if a given robot collides with any object within the world + which it is not allowed to collide with. + This is done checking iterating over every object within the world and checking + if the robot collides with it. Careful the floor will be ignored. + If there is a collision with an object that was not within the allowed collision + list the function returns True else it will return False + + :param robot: The robot object in the (Bullet)World where it should be checked if it collides + with something + :param allowed_collision: dict of objects with which the robot is allowed to collide each + object correlates to a list of links of which this object consists + :return: True if the target is reachable for the robot and False in any other + case. + """ in_contact = False allowed_robot_links = [] if robot in allowed_collision.keys(): From 7770e8beb77406a18f8a36cd78f6f073443b4fb2 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 3 Apr 2024 13:16:52 +0200 Subject: [PATCH 160/195] [stretch-desc] New and correct stretch urdf and description --- resources/stretch.urdf | 693 ++++++++++-------- .../robot_descriptions/stretch_description.py | 11 +- 2 files changed, 374 insertions(+), 330 deletions(-) diff --git a/resources/stretch.urdf b/resources/stretch.urdf index 044ee54e0..78df2173b 100644 --- a/resources/stretch.urdf +++ b/resources/stretch.urdf @@ -1,182 +1,256 @@ - - - - - - - - name="link_gripper"> - + + - - - + + + - + - + - + - + - + - - - - + + + - - + - + - - - + + + - + - + - + - + - + - - - - - - - - + + + + + + + + - - - + + + - + - + - + - + - + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + - + - + - + - + - - + + + - - + - + - + - + - + - + - + + - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - + + - - - - - + + + - + - + - + @@ -184,658 +258,626 @@ - - - + + + - + - + - + - + + - - + - - - + + + - + - + - + - + + - - + + + + + + + - - - - - 0 - 0 - 1.0 - 1.0 - - - - + - + - - - - - + + - - - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - - - + - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - + - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - + - + - - + - + + + + + + - - + - + - - - - - - - - + - + - - + - + - - + - + - - + - + @@ -845,108 +887,107 @@ - + - + - + - + - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - - - + + + - + - + - + - + + - - diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index 9bdf63717..9f1ba9899 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -30,8 +30,10 @@ def __init__(self): ["link_head_pan", "link_head_tilt"]) self.add_chain("neck", neck) - arm_joints = ['joint_lift','joint_arm_l3', 'joint_arm_l2', 'joint_arm_l1', 'joint_arm_l0', "joint_wrist_yaw"] - arm_links = ['link_lift', 'link_arm_l3', 'link_arm_l2', 'link_arm_l1', 'link_arm_l0', "link_wrist_yaw"] + arm_joints = ['joint_lift', 'joint_arm_l3', 'joint_arm_l2', 'joint_arm_l1', 'joint_arm_l0', "joint_wrist_yaw", + "joint_wrist_pitch", "joint_wrist_roll"] + arm_links = ['link_lift', 'link_arm_l3', 'link_arm_l2', 'link_arm_l1', 'link_arm_l0', "link_wrist_yaw", + "link_wrist_pitch", "link_wrist_roll"] arm_chain_desc = ChainDescription("arm", arm_joints, arm_links) arm_inter_desc = InteractionDescription(arm_chain_desc, "link_wrist_yaw") @@ -44,10 +46,11 @@ def __init__(self): gripper_minimal_position=0.013, gripper_convergence_delta=0.005) - arm_desc = ManipulatorDescription(arm_inter_desc, tool_frame="link_grasp_center", gripper_description=arm_gripper_desc) + arm_desc = ManipulatorDescription(arm_inter_desc, tool_frame="link_grasp_center", + gripper_description=arm_gripper_desc) self.add_chains({"arm": arm_desc, "right": arm_desc, "left": arm_desc}) - arm_park = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + arm_park = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.add_static_joint_chain("arm", "park", arm_park) gripper_confs = {"open": [0.59, 0.59], "close": [0.0, 0.0]} From 4da0a3190287e445e69c555245e109efa61d7ea6 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 3 Apr 2024 14:09:12 +0200 Subject: [PATCH 161/195] [bullet-world] Change initial cam pose --- src/pycram/bullet_world.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/pycram/bullet_world.py b/src/pycram/bullet_world.py index a60d72a35..fc60cb77c 100644 --- a/src/pycram/bullet_world.py +++ b/src/pycram/bullet_world.py @@ -528,8 +528,8 @@ def run(self): # Disable the side windows of the GUI p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) # Change the init camera pose - p.resetDebugVisualizerCamera(cameraDistance=1.5, cameraYaw=270.0, cameraPitch=-50, - cameraTargetPosition=[-2, 0, 1]) + p.resetDebugVisualizerCamera(cameraDistance=3, cameraYaw=90, cameraPitch=-41, + cameraTargetPosition=[3.12, 2.5, 1.2]) # Get the initial camera target location cameraTargetPosition = p.getDebugVisualizerCamera()[11] From 3a86b8bc9d943bc0582ac313b8d9ea30d5c7a949 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 3 Apr 2024 15:44:50 +0200 Subject: [PATCH 162/195] [PoseGen] Added override orientation generator to PoseGenerator --- src/pycram/pose_generator_and_validator.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 20495072e..3d9be0c86 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -17,6 +17,13 @@ class PoseGenerator: current_orientation_generator = None + """ + If no orientation generator is given, this generator is used to generate the orientation of the robot. + """ + override_orientation_generator = None + """ + Override the orientation generator with a custom generator, which will be used regardless of the current_orientation_generator. + """ def __init__(self, costmap: Costmap, number_of_samples=100, orientation_generator=None): """ @@ -31,6 +38,8 @@ def __init__(self, costmap: Costmap, number_of_samples=100, orientation_generato self.costmap = costmap self.number_of_samples = number_of_samples self.orientation_generator = orientation_generator if orientation_generator else PoseGenerator.current_orientation_generator + if PoseGenerator.override_orientation_generator: + self.orientation_generator = PoseGenerator.override_orientation_generator def __iter__(self) -> Iterable: """ From 94a9ba68df76b7667e5e537ba617239a2f822087 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 3 Apr 2024 15:45:41 +0200 Subject: [PATCH 163/195] [stretch] Process moduiles for open and close --- .../stretch_process_modules.py | 31 ++++++++++++++++--- .../robot_descriptions/stretch_description.py | 2 +- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py index 1dc972859..60ac47e32 100644 --- a/src/pycram/process_modules/stretch_process_modules.py +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -53,13 +53,35 @@ class StretchWorldStateDetecting(DefaultWorldStateDetecting): class StretchOpen(ProcessModule): - def _execute(self, designator) -> Any: - pass + def _execute(self, desig: OpeningMotion): + part_of_object = desig.object_part.bullet_world_object + + container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + + goal_pose = btr.link_pose_for_joint_config(part_of_object, { + container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) + + _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + + desig.object_part.bullet_world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( + container_joint)[1] - 0.05) class StretchClose(ProcessModule): - def _execute(self, designator) -> Any: - pass + def _execute(self, desig: ClosingMotion): + part_of_object = desig.object_part.bullet_world_object + + container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + + goal_pose = btr.link_pose_for_joint_config(part_of_object, { + container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) + + _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + + desig.object_part.bullet_world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( + container_joint)[0]) def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: @@ -88,6 +110,7 @@ def __init__(self): def navigate(self): if ProcessModuleManager.execution_type == "simulated": return StretchNavigate(self._navigate_lock) + def looking(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveHead(self._looking_lock) diff --git a/src/pycram/robot_descriptions/stretch_description.py b/src/pycram/robot_descriptions/stretch_description.py index 9f1ba9899..503df6ede 100644 --- a/src/pycram/robot_descriptions/stretch_description.py +++ b/src/pycram/robot_descriptions/stretch_description.py @@ -66,6 +66,6 @@ def get_camera_frame(self, name="color"): @staticmethod def stretch_orientation_generator(position, origin): - angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi + angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi + np.pi / 16 quaternion = list(tf.transformations.quaternion_from_euler(0, 0, angle + np.pi / 2, axes="sxyz")) return quaternion From ca162d8a77b9a631c8c348f92ce711e2920bfba6 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 4 Apr 2024 09:29:00 +0200 Subject: [PATCH 164/195] [stretch-pms] Added process modules for the real stretch --- .../stretch_process_modules.py | 194 ++++++++++++++++++ 1 file changed, 194 insertions(+) diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py index 60ac47e32..1aecce643 100644 --- a/src/pycram/process_modules/stretch_process_modules.py +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -1,15 +1,25 @@ from threading import Lock from typing import Any +import rospy + +from ..external_interfaces.robokudo import query from ..helper import _apply_ik +from ..external_interfaces import giskard from .default_process_modules import * class StretchNavigate(DefaultNavigation): + """ + Process module for the simulated Stretch that sends a cartesian goal to the robot to move the robot base + """ pass class StretchMoveHead(ProcessModule): + """ + Process module for the simulated Stretch that moves the head such that it looks at the given position + """ def _execute(self, designator) -> Any: target = designator.target robot = BulletWorld.robot @@ -29,30 +39,51 @@ def _execute(self, designator) -> Any: class StretchMoveGripper(DefaultMoveGripper): + """ + Process module for the simulated Stretch that opens or closes the gripper + """ pass class StretchDetecting(DefaultDetecting): + """ + Process Module for the simulated Stretch that tries to detect an object fitting the given object description + """ pass class StretchMoveTCP(DefaultMoveTCP): + """ + Process module for the simulated Stretch that moves the tool center point of the robot + """ pass class StretchMoveArmJoints(DefaultMoveArmJoints): + """ + Process module for the simulated Stretch that moves the arm joints of the robot + """ pass class StretchMoveJoints(DefaultMoveJoints): + """ + Process module for the simulated Stretch that moves any joint of the robot + """ pass class StretchWorldStateDetecting(DefaultWorldStateDetecting): + """ + Process Module for the simulated Stretch that tries to detect an object using the world state + """ pass class StretchOpen(ProcessModule): + """ + Process module for the simulated Stretch that opens an already grasped container + """ def _execute(self, desig: OpeningMotion): part_of_object = desig.object_part.bullet_world_object @@ -69,6 +100,10 @@ def _execute(self, desig: OpeningMotion): class StretchClose(ProcessModule): + """ + Process module for the simulated Stretch that closes an already grasped container + Process module for the simulated Stretch that closes an already grasped container + """ def _execute(self, desig: ClosingMotion): part_of_object = desig.object_part.bullet_world_object @@ -93,6 +128,147 @@ def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: _apply_ik(robot, inv, joints) +########################################################### +########## Process Modules for the Real Stretch ########### +########################################################### + + +class StretchNavigationReal(ProcessModule): + """ + Process module for the real Stretch that sends a cartesian goal to giskard to move the robot base + """ + + def _execute(self, designator: MoveMotion) -> Any: + rospy.logdebug(f"Sending goal to giskard to Move the robot") + giskard.achieve_cartesian_goal(designator.target, robot_description.base_link, "map") + + +class StretchMoveHeadReal(ProcessModule): + """ + Process module for the real robot to move that such that it looks at the given position. Uses the same calculation + as the simulated one + """ + + def _execute(self, desig: LookingMotion): + target = desig.target + robot = BulletWorld.robot + + local_transformer = LocalTransformer() + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) + + new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) + new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 + + current_pan = robot.get_joint_state("head_pan_joint") + current_tilt = robot.get_joint_state("head_tilt_joint") + + giskard.avoid_all_collisions() + giskard.achieve_joint_goal({"head_pan_joint": new_pan + current_pan, + "head_tilt_joint": new_tilt + current_tilt}) + + +class StretchDetectingReal(ProcessModule): + """ + Process Module for the real Stretch that tries to detect an object fitting the given object description. Uses Robokudo + for perception of the environment. + """ + + def _execute(self, designator: DetectingMotion) -> Any: + query_result = query(ObjectDesignatorDescription(types=[designator.object_type])) + # print(query_result) + obj_pose = query_result["ClusterPoseBBAnnotator"] + + lt = LocalTransformer() + obj_pose = lt.transform_pose(obj_pose, BulletWorld.robot.get_link_tf_frame("torso_lift_link")) + obj_pose.orientation = [0, 0, 0, 1] + obj_pose.position.x += 0.05 + + bullet_obj = BulletWorld.current_bullet_world.get_objects_by_type(designator.object_type) + if bullet_obj: + bullet_obj[0].set_pose(obj_pose) + return bullet_obj[0] + elif designator.object_type == ObjectType.JEROEN_CUP: + cup = Object("cup", ObjectType.JEROEN_CUP, "jeroen_cup.stl", pose=obj_pose) + return cup + elif designator.object_type == ObjectType.BOWL: + bowl = Object("bowl", ObjectType.BOWL, "bowl.stl", pose=obj_pose) + return bowl + + return bullet_obj[0] + + +class StretchMoveTCPReal(ProcessModule): + """ + Moves the tool center point of the real Stretch while avoiding all collisions + """ + + def _execute(self, designator: MoveTCPMotion) -> Any: + lt = LocalTransformer() + pose_in_map = lt.transform_pose(designator.target, "map") + + if designator.allow_gripper_collision: + giskard.allow_gripper_collision(designator.arm) + giskard.achieve_cartesian_goal(pose_in_map, robot_description.get_tool_frame(designator.arm), + robot_description.base_link) + + +class StretchMoveArmJointsReal(ProcessModule): + """ + Moves the arm joints of the real Stretch to the given configuration while avoiding all collisions + """ + + def _execute(self, designator: MoveArmJointsMotion) -> Any: + joint_goals = {} + if designator.left_arm_poses: + joint_goals.update(designator.left_arm_poses) + if designator.right_arm_poses: + joint_goals.update(designator.right_arm_poses) + giskard.avoid_all_collisions() + giskard.achieve_joint_goal(joint_goals) + + +class StretchMoveJointsReal(ProcessModule): + """ + Moves any joint using giskard, avoids all collisions while doint this. + """ + + def _execute(self, designator: MoveJointsMotion) -> Any: + name_to_position = dict(zip(designator.names, designator.positions)) + giskard.avoid_all_collisions() + giskard.achieve_joint_goal(name_to_position) + + +class StretchMoveGripperReal(ProcessModule): + """ + Opens or closes the gripper of the real Stretch, gripper uses an action server for this instead of giskard + """ + + def _execute(self, designator: MoveGripperMotion) -> Any: + chain = robot_description.chains[designator.gripper].gripper.get_static_joint_chain(designator.motion) + giskard.achieve_joint_goal(chain) + + +class StretchOpenReal(ProcessModule): + """ + Tries to open an already grasped container + """ + + def _execute(self, designator: OpeningMotion) -> Any: + giskard.achieve_open_container_goal(robot_description.get_tool_frame(designator.arm), + designator.object_part.name) + + +class StretchCloseReal(ProcessModule): + """ + Tries to close an already grasped container + """ + + def _execute(self, designator: ClosingMotion) -> Any: + giskard.achieve_close_container_goal(robot_description.get_tool_frame(designator.arm), + designator.object_part.name) + + class StretchManager(ProcessModuleManager): def __init__(self): super().__init__("stretch") @@ -110,22 +286,32 @@ def __init__(self): def navigate(self): if ProcessModuleManager.execution_type == "simulated": return StretchNavigate(self._navigate_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchNavigationReal(self._navigate_lock) def looking(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveHead(self._looking_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchMoveHeadReal(self._looking_lock) def detecting(self): if ProcessModuleManager.execution_type == "simulated": return StretchDetecting(self._detecting_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchDetectingReal(self._detecting_lock) def move_tcp(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveTCP(self._move_tcp_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchMoveTCPReal(self._move_tcp_lock) def move_arm_joints(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveArmJoints(self._move_arm_joints_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchMoveArmJointsReal(self._move_arm_joints_lock) def world_state_detecting(self): if ProcessModuleManager.execution_type == "simulated" or ProcessModuleManager.execution_type == "real": @@ -134,16 +320,24 @@ def world_state_detecting(self): def move_joints(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveJoints(self._move_joints_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchMoveJointsReal(self._move_joints_lock) def move_gripper(self): if ProcessModuleManager.execution_type == "simulated": return StretchMoveGripper(self._move_gripper_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchMoveGripperReal(self._move_gripper_lock) def open(self): if ProcessModuleManager.execution_type == "simulated": return StretchOpen(self._open_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchOpenReal(self._open_lock) def close(self): if ProcessModuleManager.execution_type == "simulated": return StretchClose(self._close_lock) + elif ProcessModuleManager.execution_type == "real": + return StretchCloseReal(self._close_lock) From 8c19ce0007445c9d8a23a523c1ce3216ae07b582 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 4 Apr 2024 11:31:33 +0200 Subject: [PATCH 165/195] [stretch] Chanegs from comment in PR --- src/pycram/pose_generator_and_validator.py | 6 ++++++ src/pycram/process_modules/stretch_process_modules.py | 1 - 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 3d9be0c86..8dd704ec8 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -16,6 +16,12 @@ class PoseGenerator: + """ + Crates pose candidates from a given costmap. The generator + selects the highest values, amount is given by number_of_sample, and returns the corresponding positions. + Orientations are calculated such that the Robot faces the center of the costmap. + """ + current_orientation_generator = None """ If no orientation generator is given, this generator is used to generate the orientation of the robot. diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py index 1aecce643..2ca0bdec5 100644 --- a/src/pycram/process_modules/stretch_process_modules.py +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -102,7 +102,6 @@ def _execute(self, desig: OpeningMotion): class StretchClose(ProcessModule): """ Process module for the simulated Stretch that closes an already grasped container - Process module for the simulated Stretch that closes an already grasped container """ def _execute(self, desig: ClosingMotion): part_of_object = desig.object_part.bullet_world_object From 7f614f28ba4d15203578a3c6edad234c9ea88363 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Fri, 5 Apr 2024 14:37:14 +0200 Subject: [PATCH 166/195] [general] Fixed imports after merge --- src/pycram/designator.py | 6 +-- src/pycram/designators/action_designator.py | 14 ------ src/pycram/designators/actions/actions.py | 29 +++++------ src/pycram/pose_generator_and_validator.py | 2 +- src/pycram/process_module.py | 1 - .../process_modules/boxy_process_modules.py | 28 +++++------ .../default_process_modules.py | 48 +++++++++++------- .../process_modules/donbot_process_modules.py | 19 ++----- .../process_modules/hsr_process_modules.py | 49 ++++++++++--------- .../process_modules/pr2_process_modules.py | 38 +++----------- src/pycram/ros/viz_marker_publisher.py | 2 +- src/pycram/task.py | 2 +- 12 files changed, 103 insertions(+), 135 deletions(-) diff --git a/src/pycram/designator.py b/src/pycram/designator.py index d3a504fd0..6ce66f970 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -8,9 +8,9 @@ from sqlalchemy.orm.session import Session import rospy -from ..world import World -from ..world_concepts.world_object import Object as WorldObject -from .enums import ObjectType +from .world import World +from .world_concepts.world_object import Object as WorldObject +from .datastructures.enums import ObjectType from .helper import GeneratorList, bcolors from threading import Lock from time import time diff --git a/src/pycram/designators/action_designator.py b/src/pycram/designators/action_designator.py index dfc85fa28..f22fa75dc 100644 --- a/src/pycram/designators/action_designator.py +++ b/src/pycram/designators/action_designator.py @@ -1,22 +1,10 @@ import itertools from typing_extensions import List, Union, Callable -from .object_designator import ObjectDesignatorDescription, ObjectPart -from ..enums import Arms from typing_extensions import Any, Union -import sqlalchemy.orm - -from .location_designator import CostmapLocation -from .motion_designator import * from .object_designator import ObjectDesignatorDescription, BelieveObject, ObjectPart -from ..datastructures.local_transformer import LocalTransformer -from ..orm.base import Base -from ..plan_failures import ObjectUnfetchable, ReachabilityFailure -from ..robot_descriptions import robot_description -from ..task import with_tree from ..datastructures.enums import Arms from ..designator import ActionDesignatorDescription -from ..pose import Pose from .actions.actions import (ParkArmsActionPerformable, MoveTorsoActionPerformable, SetGripperActionPerformable, GripActionPerformable, PlaceActionPerformable, PickUpActionPerformable, @@ -24,9 +12,7 @@ LookAtActionPerformable, DetectActionPerformable, OpenActionPerformable, CloseActionPerformable, GraspingActionPerformable, ReleaseActionPerformable) -from ..world import World from ..datastructures.pose import Pose -from ..helper import multiply_quaternions class MoveTorsoAction(ActionDesignatorDescription): diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 16175592a..7a538a765 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -6,14 +6,15 @@ from typing_extensions import Union, Type from pycram.designator import ActionDesignatorDescription from pycram.designators.motion_designator import * -from pycram.enums import Arms, Grasp +from ...datastructures.pose import Pose +from ...datastructures.enums import Arms, Grasp from pycram.task import with_tree from dataclasses import dataclass, field from ..location_designator import CostmapLocation from ..object_designator import BelieveObject -from ...bullet_world import BulletWorld +# from ...bullet_world import BulletWorld from ...helper import multiply_quaternions -from ...local_transformer import LocalTransformer +from ...datastructures.local_transformer import LocalTransformer from ...orm.base import Pose as ORMPose from ...orm.object_designator import Object as ORMObject, ObjectPart as ORMObjectPart from ...orm.action_designator import Action as ORMAction @@ -237,7 +238,7 @@ class PickUpActionPerformable(ActionAbstract): def perform(self) -> None: # Store the object's data copy at execution self.object_at_execution = self.object_designator.frozen_copy() - robot = BulletWorld.robot + robot = World.robot # Retrieve object and robot from designators object = self.object_designator.bullet_world_object # Get grasp orientation and target pose @@ -280,12 +281,12 @@ def perform(self) -> None: prepose = object.local_transformer.transform_pose(oTg, "map") # Perform the motion with the prepose and open gripper - BulletWorld.current_bullet_world.add_vis_axis(prepose) + World.current_world.add_vis_axis(prepose) MoveTCPMotion(prepose, self.arm, allow_gripper_collision=True).perform() MoveGripperMotion(motion="open", gripper=self.arm).perform() # Perform the motion with the adjusted pose -> actual grasp and close gripper - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + World.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm, allow_gripper_collision=True).perform() adjusted_oTm.pose.position.z += 0.03 MoveGripperMotion(motion="close", gripper=self.arm).perform() @@ -293,11 +294,11 @@ def perform(self) -> None: robot.attach(object, tool_frame) # Lift object - BulletWorld.current_bullet_world.add_vis_axis(adjusted_oTm) + World.current_world.add_vis_axis(adjusted_oTm) MoveTCPMotion(adjusted_oTm, self.arm, allow_gripper_collision=True).perform() # Remove the vis axis from the world - BulletWorld.current_bullet_world.remove_vis_axis() + World.current_world.remove_vis_axis() @dataclass @@ -322,20 +323,20 @@ class PlaceActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - object_pose = self.object_designator.bullet_world_object.get_pose() + object_pose = self.object_designator.world_object.get_pose() local_tf = LocalTransformer() # Transformations such that the target position is the position of the object and not the tcp tcp_to_object = local_tf.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame( + World.robot.get_link_tf_frame( robot_description.get_tool_frame(self.arm))) target_diff = self.target_location.to_transform("target").inverse_times( tcp_to_object.to_transform("object")).to_pose() MoveTCPMotion(target_diff, self.arm).perform() MoveGripperMotion("open", self.arm).perform() - BulletWorld.robot.detach(self.object_designator.bullet_world_object) - retract_pose = local_tf.transform_pose(target_diff, BulletWorld.robot.get_link_tf_frame( + World.robot.detach(self.object_designator.world_object) + retract_pose = local_tf.transform_pose(target_diff, World.robot.get_link_tf_frame( robot_description.get_tool_frame(self.arm))) retract_pose.position.x -= 0.07 MoveTCPMotion(retract_pose, self.arm).perform() @@ -516,7 +517,7 @@ def perform(self) -> None: gripper_name = robot_description.get_tool_frame(self.arm) object_pose_in_gripper = lt.transform_pose(object_pose, - BulletWorld.robot.get_link_tf_frame(gripper_name)) + World.robot.get_link_tf_frame(gripper_name)) pre_grasp = object_pose_in_gripper.copy() pre_grasp.pose.position.x -= 0.1 @@ -544,7 +545,7 @@ class FaceAtPerformable(ActionAbstract): @with_tree def perform(self) -> None: # get the robot position - robot_position = BulletWorld.robot.pose + robot_position = World.robot.pose # calculate orientation for robot to face the object angle = np.arctan2(robot_position.position.y - self.pose.position.y, diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index cc412f0db..970924ec6 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -6,7 +6,7 @@ from .world_reasoning import contact from .world_concepts.costmaps import Costmap from .datastructures.local_transformer import LocalTransformer -from .pose import Pose, Transform +from .datastructures.pose import Pose, Transform from .robot_description import ManipulatorDescription from .robot_descriptions import robot_description from .external_interfaces.ik import request_ik diff --git a/src/pycram/process_module.py b/src/pycram/process_module.py index 3e368997a..16eff4a77 100644 --- a/src/pycram/process_module.py +++ b/src/pycram/process_module.py @@ -13,7 +13,6 @@ import rospy -from .designator import MotionDesignatorDescription from .language import Language from .robot_descriptions import robot_description from typing_extensions import TYPE_CHECKING diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 1a1778872..0f133e773 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -1,11 +1,11 @@ from threading import Lock import numpy as np -import pycram.bullet_world_reasoning as btr +from .. import world_reasoning as btr import pycram.helper as helper from ..designators.motion_designator import * -from ..enums import JointType +from ..datastructures.enums import JointType from ..external_interfaces.ik import request_ik -from ..local_transformer import LocalTransformer +from ..datastructures.local_transformer import LocalTransformer from ..world import World from ..datastructures.local_transformer import LocalTransformer @@ -20,7 +20,7 @@ def _park_arms(arm): :return: None """ - robot = BulletWorld.robot + robot = World.robot if arm == "right": for joint, pose in robot_description.get_static_joint_chain("right", "park").items(): robot.set_joint_state(joint, pose) @@ -35,7 +35,7 @@ class BoxyNavigation(ProcessModule): """ def _execute(self, desig: MoveMotion): - robot = BulletWorld.robot + robot = World.robot robot.set_pose(desig.target) @@ -52,7 +52,7 @@ def _execute(self, desig: OpeningMotion): goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) desig.object_part.bullet_world_object.set_joint_state(container_joint, part_of_object.get_joint_limits( @@ -71,7 +71,7 @@ def _execute(self, desig: ClosingMotion): goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) desig.object_part.bullet_world_object.set_joint_state(container_joint, part_of_object.get_joint_limits( @@ -141,14 +141,14 @@ class BoxyDetecting(ProcessModule): """ def _execute(self, desig): - robot = BulletWorld.robot + robot = World.robot object_type = desig.object_type # Should be "wide_stereo_optical_frame" cam_frame_name = robot_description.get_camera_frame() # should be [0, 0, 1] front_facing_axis = robot_description.front_facing_axis - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = World.current_world.get_object_by_type(object_type) for obj in objects: if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): return obj @@ -161,7 +161,7 @@ class BoxyMoveTCP(ProcessModule): def _execute(self, desig: MoveTCPMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot _move_arm_tcp(target, robot, desig.arm) @@ -174,11 +174,11 @@ class BoxyMoveArmJoints(ProcessModule): def _execute(self, desig: MoveArmJointsMotion): - robot = BulletWorld.robot + robot = World.robot if desig.right_arm_poses: - robot.set_joint_states(desig.right_arm_poses) + robot.set_joint_positions(desig.right_arm_poses) if desig.left_arm_poses: - robot.set_joint_states(desig.left_arm_poses) + robot.set_joint_positions(desig.left_arm_poses) class BoxyWorldStateDetecting(ProcessModule): @@ -188,7 +188,7 @@ class BoxyWorldStateDetecting(ProcessModule): def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, World.current_bullet_world.objects))[0] def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index f68c8fc8d..588b5661d 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -2,6 +2,9 @@ import numpy as np +from ..datastructures.enums import JointType +from ..external_interfaces.ik import request_ik +from ..helper import _apply_ik from ..process_module import ProcessModule, ProcessModuleManager # from ..process_modules.pr2_process_modules import Pr2Navigation as DefaultNavigation, Pr2PickUp as DefaultPickUp, \ # Pr2Place as DefaultPlace, Pr2WorldStateDetecting as DefaultWorldStateDetecting, Pr2Open as DefaultOpen, \ @@ -10,8 +13,17 @@ from ..robot_descriptions import robot_description from ..world import World from ..datastructures.local_transformer import LocalTransformer -from ..designators.motion_designator import LookingMotion, MoveArmJointsMotion, MoveJointsMotion +from ..designators.motion_designator import * +from ..world_reasoning import visible, link_pose_for_joint_config +class DefaultNavigation(ProcessModule): + """ + The process module to move the robot from one position to another. + """ + + def _execute(self, desig: MoveMotion): + robot = World.robot + robot.set_pose(desig.target) class DefaultMoveHead(ProcessModule): """ @@ -50,7 +62,7 @@ class DefaultMoveGripper(ProcessModule): """ def _execute(self, desig: MoveGripperMotion): - robot = BulletWorld.robot + robot = World.robot gripper = desig.gripper motion = desig.motion for joint, state in robot_description.get_static_gripper_chain(gripper, motion).items(): @@ -64,16 +76,16 @@ class DefaultDetecting(ProcessModule): """ def _execute(self, desig: DetectingMotion): - robot = BulletWorld.robot + robot = World.robot object_type = desig.object_type # Should be "wide_stereo_optical_frame" cam_frame_name = robot_description.get_camera_frame() # should be [0, 0, 1] front_facing_axis = robot_description.front_facing_axis - objects = BulletWorld.current_bullet_world.get_objects_by_type(object_type) + objects = World.current_world.get_object_by_type(object_type) for obj in objects: - if btr.visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): + if visible(obj, robot.get_link_pose(cam_frame_name), front_facing_axis): return obj @@ -84,7 +96,7 @@ class DefaultMoveTCP(ProcessModule): def _execute(self, desig: MoveTCPMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot _move_arm_tcp(target, robot, desig.arm) @@ -115,12 +127,12 @@ def _execute(self, desig: MoveJointsMotion): class DefaultWorldStateDetecting(ProcessModule): """ - This process module detectes an object even if it is not in the field of view of the robot. + This process moduledetectes an object even if it is not in the field of view of the robot. """ def _execute(self, desig: WorldStateDetectingMotion): obj_type = desig.object_type - return list(filter(lambda obj: obj.type == obj_type, BulletWorld.current_bullet_world.objects))[0] + return list(filter(lambda obj: obj.type == obj_type, World.current_world.objects))[0] class DefaultOpen(ProcessModule): @@ -129,16 +141,16 @@ class DefaultOpen(ProcessModule): """ def _execute(self, desig: OpeningMotion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) - goal_pose = btr.link_pose_for_joint_config(part_of_object, { + goal_pose = link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, + desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits( container_joint)[1]) @@ -148,16 +160,16 @@ class DefaultClose(ProcessModule): Low-level implementation that lets the robot close a grasped container, in simulation """ def _execute(self, desig: ClosingMotion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) - goal_pose = btr.link_pose_for_joint_config(part_of_object, { + goal_pose = link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, + desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits( container_joint)[0]) diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 6f31372f1..337318a2a 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -3,12 +3,12 @@ import numpy as np from typing_extensions import Optional -from pycram.worlds.bullet_world import World +from ..worlds.bullet_world import World from ..designators.motion_designator import MoveArmJointsMotion, WorldStateDetectingMotion -from pycram.datastructures.local_transformer import LocalTransformer +from ..datastructures.local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description -from ..process_modules.pr2_process_modules import Pr2PickUp, Pr2Detecting as DonbotDetecting, _move_arm_tcp +from ..process_modules.pr2_process_modules import Pr2Detecting as DonbotDetecting, _move_arm_tcp def _park_arms(arm): @@ -34,15 +34,6 @@ def _execute(self, desig): robot.set_pose(desig.target) -class DonbotPickUp(Pr2PickUp): - """ - This process module is for picking up a given object. - The object has to be reachable for this process module to succeed. - """ - def _execute(self, desig, used_arm: Optional[str] = "left"): - super()._execute(desig, "left") - - class DonbotPlace(ProcessModule): """ This process module places an object at the given position in world coordinate frame. @@ -161,10 +152,6 @@ def navigate(self): if ProcessModuleManager.execution_type == "simulated": return DonbotNavigation(self._navigate_lock) - def pick_up(self): - if ProcessModuleManager.execution_type == "simulated": - return DonbotPickUp(self._pick_up_lock) - def place(self): if ProcessModuleManager.execution_type == "simulated": return DonbotPlace(self._place_lock) diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index de8703087..52846d20a 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -1,8 +1,11 @@ -from threading import Lock +import numpy as np +import rospy from threading import Lock from typing import Any from typing_extensions import Optional + +from ..datastructures.enums import JointType from ..robot_descriptions import robot_description from ..process_module import ProcessModule, ProcessModuleManager from ..world import World @@ -13,6 +16,8 @@ import logging import time from ..datastructures.local_transformer import LocalTransformer +from ..designators.motion_designator import * +from ..external_interfaces import giskard @@ -48,7 +53,7 @@ class HSRBNavigation(ProcessModule): """ def _execute(self, desig: MoveMotion): - robot = BulletWorld.robot + robot = World.robot robot.set_pose(desig.target) @@ -60,7 +65,7 @@ class HSRBMoveHead(ProcessModule): def _execute(self, desig: LookingMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) @@ -69,11 +74,11 @@ def _execute(self, desig: LookingMotion): new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = robot.get_joint_state("head_pan_joint") - current_tilt = robot.get_joint_state("head_tilt_joint") + current_pan = robot.get_joint_position("head_pan_joint") + current_tilt = robot.get_joint_position("head_tilt_joint") - robot.set_joint_state("head_pan_joint", new_pan + current_pan) - robot.set_joint_state("head_tilt_joint", new_tilt + current_tilt) + robot.set_joint_position("head_pan_joint", new_pan + current_pan) + robot.set_joint_position("head_tilt_joint", new_tilt + current_tilt) class HSRBMoveGripper(ProcessModule): @@ -137,7 +142,7 @@ class HSRBMoveTCP(ProcessModule): def _execute(self, desig: MoveTCPMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot _move_arm_tcp(target, robot, desig.arm) @@ -152,9 +157,9 @@ def _execute(self, desig: MoveArmJointsMotion): robot = World.robot if desig.right_arm_poses: - robot.set_joint_states(desig.right_arm_poses) + robot.set_joint_positions(desig.right_arm_poses) if desig.left_arm_poses: - robot.set_joint_states(desig.left_arm_poses) + robot.set_joint_positions(desig.left_arm_poses) class HSRBMoveJoints(ProcessModule): @@ -163,8 +168,8 @@ class HSRBMoveJoints(ProcessModule): """ def _execute(self, desig: MoveJointsMotion): - robot = BulletWorld.robot - robot.set_joint_states(dict(zip(desig.names, desig.positions))) + robot = World.robot + robot.set_joint_positions(dict(zip(desig.names, desig.positions))) class HSRBWorldStateDetecting(ProcessModule): @@ -183,16 +188,16 @@ class HSRBOpen(ProcessModule): """ def _execute(self, desig: OpeningMotion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, + desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits(container_joint)[1]) @@ -202,16 +207,16 @@ class HSRBClose(ProcessModule): """ def _execute(self, desig: ClosingMotion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object - container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) + container_joint = part_of_object.find_joint_above_link(desig.object_part.name, JointType.PRISMATIC) goal_pose = btr.link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, + desig.object_part.world_object.set_joint_position(container_joint, part_of_object.get_joint_limits(container_joint)[0]) @@ -259,7 +264,7 @@ class HSRBMoveHeadReal(ProcessModule): def _execute(self, desig: LookingMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) @@ -358,7 +363,7 @@ def extract_xyz_values(input_string): size = (x, z / 2, y) size_box = (x / 2, z / 2, y / 2) hard_size = (0.02, 0.02, 0.03) - id = BulletWorld.current_bullet_world.add_rigid_box(obj_pose, hard_size, color) + id = World.current_world.add_rigid_box(obj_pose, hard_size, color) box_object = Object(obj_type + "_" + str(rospy.get_time()), obj_type, pose=obj_pose, color=color, id=id, customGeom={"size": [hard_size[0], hard_size[1], hard_size[2]]}) box_object.set_pose(obj_pose) diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index dae6eef07..66acaecce 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -14,9 +14,9 @@ from ..helper import _apply_ik from pycram.datastructures.local_transformer import LocalTransformer from ..designators.object_designator import ObjectDesignatorDescription -from ..designators.motion_designator import MoveMotion, PickUpMotion, PlaceMotion, LookingMotion, \ +from ..designators.motion_designator import MoveMotion, LookingMotion, \ DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ - MoveGripperMotion, OpeningMotion, ClosingMotion, MotionDesignatorDescription + MoveGripperMotion, OpeningMotion, ClosingMotion from ..robot_descriptions import robot_description from pycram.world import World from pycram.world_concepts.world_object import Object @@ -62,12 +62,9 @@ class Pr2MoveHead(ProcessModule): This process module moves the head to look at a specific point in the world coordinate frame. This point can either be a position or an object. """ - def __init__(self, lock: Lock): - super().__init__(lock) - self.robot: Object = World.robot - def _execute(self, desig: LookingMotion): target = desig.target + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, self.robot.get_link_tf_frame("head_pan_link")) @@ -79,27 +76,8 @@ def _execute(self, desig: LookingMotion): current_pan = self.robot.get_joint_position("head_pan_joint") current_tilt = self.robot.get_joint_position("head_tilt_joint") - return new_pan + current_pan, new_tilt + current_tilt - - @abstractmethod - def _execute(self, designator: LookingMotion.Motion) -> None: - pass - - -class Pr2MoveHead(_Pr2MoveHead): - """ - This process module moves the head to look at a specific point in the world coordinate frame. - This point can either be a position or an object. - """ - - def _execute(self, desig: LookingMotion.Motion): - """ - Moves the head to look at the given position. - :param desig: The looking motion designator - """ - pan_goal, tilt_goal = self.get_pan_and_tilt_goals(desig) - self.robot.set_joint_position("head_pan_joint", pan_goal) - self.robot.set_joint_position("head_tilt_joint", tilt_goal) + robot.set_joint_position("head_pan_joint", new_pan + current_pan) + robot.set_joint_position("head_tilt_joint", new_tilt + current_tilt) class Pr2MoveGripper(ProcessModule): @@ -254,7 +232,7 @@ class Pr2MoveHeadReal(ProcessModule): def _execute(self, desig: LookingMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) @@ -267,8 +245,8 @@ def _execute(self, desig: LookingMotion): current_tilt = robot.get_joint_state("head_tilt_joint") giskard.avoid_all_collisions() - giskard.achieve_joint_goal({"head_pan_joint": pan_goal, - "head_tilt_joint": tilt_goal}) + giskard.achieve_joint_goal({"head_pan_joint": new_pan + current_pan, + "head_tilt_joint": new_tilt + current_tilt}) class Pr2DetectingReal(ProcessModule): diff --git a/src/pycram/ros/viz_marker_publisher.py b/src/pycram/ros/viz_marker_publisher.py index 9e12516d7..fc33f5f6e 100644 --- a/src/pycram/ros/viz_marker_publisher.py +++ b/src/pycram/ros/viz_marker_publisher.py @@ -33,7 +33,7 @@ def __init__(self, topic_name="/pycram/viz_marker", interval=0.1): self.thread = threading.Thread(target=self._publish) self.kill_event = threading.Event() - self.main_world = World.current_world if not World.current_world.is_prospection_world elseWorld.current_world.world_sync.world + self.main_world = World.current_world if not World.current_world.is_prospection_world else World.current_world.world_sync.world self.thread.start() atexit.register(self._stop_publishing) diff --git a/src/pycram/task.py b/src/pycram/task.py index 5540c4e88..d26d63d11 100644 --- a/src/pycram/task.py +++ b/src/pycram/task.py @@ -15,7 +15,7 @@ import sqlalchemy.orm.session import tqdm -from ..world import World +from .world import World from .orm.task import TaskTreeNode as ORMTaskTreeNode from .orm.base import ProcessMetaData from .plan_failures import PlanFailure From 686563a907c93690d3888b43ab05bc18eff9c2c9 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Fri, 5 Apr 2024 14:51:02 +0200 Subject: [PATCH 167/195] [tets] fixed test imports --- src/pycram/resolver/location/database_location.py | 4 ++-- .../resolver/probabilistic/probabilistic_action.py | 10 +++++----- test/bullet_world_testcase.py | 1 - test/test_action_designator.py | 2 +- test/test_move_and_pick_up.py | 2 +- test/test_orm.py | 4 ++-- 6 files changed, 11 insertions(+), 12 deletions(-) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index f005a95ab..d84625e9d 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -6,14 +6,14 @@ from sqlalchemy import select, Select from typing_extensions import List -from ...costmaps import Rectangle, OccupancyCostmap +from ...world_concepts.costmaps import Rectangle, OccupancyCostmap from ...designator import LocationDesignatorDescription from ...designators.location_designator import CostmapLocation from ...orm.action_designator import PickUpAction from ...orm.base import RobotState, Quaternion from ...orm.object_designator import Object from ...orm.task import TaskTreeNode -from ...datastructures.Pose import Pose +from ...datastructures.pose import Pose from ...orm.queries.queries import PickUpWithContext diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index f5feaaa32..8506d8c3e 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -9,17 +9,17 @@ from random_events.variables import Symbolic, Continuous import tqdm from typing_extensions import Optional, List, Iterator -from ...bullet_world import BulletWorld -from ...costmaps import OccupancyCostmap, VisibilityCostmap +from ...world import World +from ...world_concepts.costmaps import OccupancyCostmap, VisibilityCostmap from ...designator import ActionDesignatorDescription, ObjectDesignatorDescription from ...designators.actions.actions import MoveAndPickUpPerformable, ActionAbstract -from ...enums import Arms, Grasp, TaskStatus -from ...local_transformer import LocalTransformer +from ...datastructures.enums import Arms, Grasp, TaskStatus +from ...datastructures.local_transformer import LocalTransformer from ...orm.queries.queries import PickUpWithContext from ...orm.task import TaskTreeNode from ...orm.action_designator import PickUpAction as ORMPickUpAction from ...plan_failures import ObjectUnreachable, PlanFailure -from ...pose import Pose +from ...datastructures.pose import Pose import plotly.graph_objects as go diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 47c9e8562..04637ca68 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -9,7 +9,6 @@ from pycram.process_module import ProcessModule from pycram.datastructures.enums import ObjectType, WorldMode from pycram.object_descriptors.urdf import ObjectDescription -from pycram.enums import ObjectType from pycram.ros.viz_marker_publisher import VizMarkerPublisher diff --git a/test/test_action_designator.py b/test/test_action_designator.py index af5708b09..af915b4cf 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -2,7 +2,7 @@ from pycram.designators import action_designator, object_designator from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ NavigateActionPerformable, FaceAtPerformable -from pycram.local_transformer import LocalTransformer +from pycram.datastructures.local_transformer import LocalTransformer from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot from pycram.datastructures.pose import Pose diff --git a/test/test_move_and_pick_up.py b/test/test_move_and_pick_up.py index ccead6d15..dd0872979 100644 --- a/test/test_move_and_pick_up.py +++ b/test/test_move_and_pick_up.py @@ -6,7 +6,7 @@ from random_events.events import Event from pycram.designator import ObjectDesignatorDescription -from pycram.enums import ObjectType +from pycram.datastructures.enums import ObjectType from pycram.plan_failures import PlanFailure from pycram.process_module import simulated_robot from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp, GaussianCostmapModel diff --git a/test/test_orm.py b/test/test_orm.py index d2a0693f7..4516f7b27 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -9,13 +9,13 @@ import pycram.task import pycram.task from bullet_world_testcase import BulletWorldTestCase -from pycram.bullet_world import Object +from pycram.world_concepts.world_object import Object from pycram.designators import action_designator, object_designator, motion_designator from pycram.designators.actions.actions import ParkArmsActionPerformable, MoveTorsoActionPerformable, \ SetGripperActionPerformable, PickUpActionPerformable, NavigateActionPerformable, TransportActionPerformable, \ OpenActionPerformable, CloseActionPerformable, DetectActionPerformable, LookAtActionPerformable from pycram.designators.object_designator import BelieveObject -from pycram.enums import ObjectType +from pycram.datastructures.enums import ObjectType from pycram.datastructures.pose import Pose from pycram.process_module import simulated_robot from pycram.task import with_tree From f9a6cc9eef0717cf665acc2286be524bc89493c4 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Fri, 5 Apr 2024 16:39:01 +0200 Subject: [PATCH 168/195] [general] fixing everything else --- requirements-resolver.txt | 1 - src/pycram/datastructures/local_transformer.py | 17 +++++++++++++++++ src/pycram/designators/actions/actions.py | 9 +++++---- src/pycram/pose_generator_and_validator.py | 3 ++- .../process_modules/pr2_process_modules.py | 8 ++++---- .../probabilistic/probabilistic_action.py | 4 ++-- src/pycram/world_concepts/world_object.py | 8 ++++++++ test/bullet_world_testcase.py | 1 + test/test_bullet_world.py | 1 + test/test_costmaps.py | 2 ++ test/test_move_and_pick_up.py | 2 ++ test/test_orm.py | 6 +++--- 12 files changed, 47 insertions(+), 15 deletions(-) diff --git a/requirements-resolver.txt b/requirements-resolver.txt index 7c81de746..0425b4650 100644 --- a/requirements-resolver.txt +++ b/requirements-resolver.txt @@ -1,5 +1,4 @@ -r requirements.txt probabilistic_model>=4.0.8 random_events>=2.0.9 -SQLAlchemy tqdm diff --git a/src/pycram/datastructures/local_transformer.py b/src/pycram/datastructures/local_transformer.py index 59a9f594d..11408a956 100644 --- a/src/pycram/datastructures/local_transformer.py +++ b/src/pycram/datastructures/local_transformer.py @@ -55,6 +55,23 @@ def __init__(self): # If the singelton was already initialized self._initialized = True + def transform_to_object_frame(self, pose: Pose, + world_object: 'world_concepts.world_object.Object', link_name: str = None) -> Union[Pose, None]: + """ + Transforms the given pose to the coordinate frame of the given World object. If no link name is given the + base frame of the Object is used, otherwise the link frame is used as target for the transformation. + + :param pose: Pose that should be transformed + :param world_object: BulletWorld Object in which frame the pose should be transformed + :param link_name: A link of the BulletWorld Object which will be used as target coordinate frame instead + :return: The new pose the in coordinate frame of the object + """ + if link_name: + target_frame = world_object.get_link_tf_frame(link_name) + else: + target_frame = world_object.tf_frame + return self.transform_pose(pose, target_frame) + def transform_pose(self, pose: Pose, target_frame: str) -> Union[Pose, None]: """ Transforms a given pose to the target frame after updating the transforms for all objects in the current world. diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 7a538a765..6ad3262bf 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -1,5 +1,6 @@ import abc import inspect +import time import numpy as np from tf import transformations @@ -240,7 +241,7 @@ def perform(self) -> None: self.object_at_execution = self.object_designator.frozen_copy() robot = World.robot # Retrieve object and robot from designators - object = self.object_designator.bullet_world_object + object = self.object_designator.world_object # Get grasp orientation and target pose grasp = robot_description.grasps.get_orientation_for_grasp(self.grasp) # oTm = Object Pose in Frame map @@ -440,7 +441,7 @@ class DetectActionPerformable(ActionAbstract): @with_tree def perform(self) -> None: - return DetectingMotion(object_type=self.object_designator.type).perform() + return DetectingMotion(object_type=self.object_designator.obj_type).perform() @dataclass @@ -512,7 +513,7 @@ def perform(self) -> None: if isinstance(self.object_desig, ObjectPart.Object): object_pose = self.object_desig.part_pose else: - object_pose = self.object_desig.bullet_world_object.get_pose() + object_pose = self.object_desig.world_object.get_pose() lt = LocalTransformer() gripper_name = robot_description.get_tool_frame(self.arm) @@ -591,4 +592,4 @@ class MoveAndPickUpPerformable(ActionAbstract): def perform(self): NavigateActionPerformable(self.standing_position).perform() FaceAtPerformable(self.object_designator.pose).perform() - PickUpActionPerformable(self.object_designator, self.arm, self.grasp).perform() \ No newline at end of file + PickUpActionPerformable(self.object_designator, self.arm, self.grasp).perform() diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 970924ec6..95bb205af 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -143,6 +143,7 @@ def _in_contact(robot: Object, obj: Object, allowed_collision: Dict[Object, List allowed_robot_links: List[str]) -> bool: """ This method checks if a given robot is in contact with a given object. + :param robot: The robot object that should be checked for contact. :param obj: The object that should be checked for contact with the robot. :param allowed_collision: A dictionary that contains the allowed collisions for links of each object in the world. @@ -220,7 +221,7 @@ def reachability_validator(pose: Pose, except IKError: pass finally: - robot.set_joint_states(joint_state_before_ik) + robot.set_joint_positions(joint_state_before_ik) if arms: res = True return res, arms diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 66acaecce..29dcd41fe 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -67,14 +67,14 @@ def _execute(self, desig: LookingMotion): robot = World.robot local_transformer = LocalTransformer() - pose_in_pan = local_transformer.transform_pose(target, self.robot.get_link_tf_frame("head_pan_link")) - pose_in_tilt = local_transformer.transform_pose(target, self.robot.get_link_tf_frame("head_tilt_link")) + pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) + pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_tilt_link")) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) new_tilt = np.arctan2(pose_in_tilt.position.z, pose_in_tilt.position.x ** 2 + pose_in_tilt.position.y ** 2) * -1 - current_pan = self.robot.get_joint_position("head_pan_joint") - current_tilt = self.robot.get_joint_position("head_tilt_joint") + current_pan = robot.get_joint_position("head_pan_joint") + current_tilt = robot.get_joint_position("head_tilt_joint") robot.set_joint_position("head_pan_joint", new_pan + current_pan) robot.set_joint_position("head_tilt_joint", new_tilt + current_tilt) diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index 8506d8c3e..428232bbe 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -185,7 +185,7 @@ def sample_to_action(self, sample: List) -> MoveAndPickUpPerformable: """ arm, grasp, relative_x, relative_y = sample position = [relative_x, relative_y, 0.] - pose = Pose(position, frame=self.object_designator.bullet_world_object.tf_frame) + pose = Pose(position, frame=self.object_designator.world_object.tf_frame) standing_position = LocalTransformer().transform_pose(pose, "map") standing_position.position.z = 0 action = MoveAndPickUpPerformable(standing_position, self.object_designator, arm, grasp) @@ -306,4 +306,4 @@ def batch_rollout(self): progress_bar.set_postfix({"Success Probability": successful_tries / total_tries}) # reset world - BulletWorld.current_bullet_world.reset_bullet_world() + World.current_world.reset_current_world() diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index 54a80f8ae..2d8cda257 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -96,6 +96,14 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, self.world.objects.append(self) + @property + def pose(self): + return self.get_pose() + + @pose.setter + def pose(self, pose: Pose): + self.set_pose(pose) + def _load_object_and_get_id(self, path: Optional[str] = None, ignore_cached_files: Optional[bool] = False) -> Tuple[int, Union[str, None]]: """ diff --git a/test/bullet_world_testcase.py b/test/bullet_world_testcase.py index 04637ca68..e82620c66 100644 --- a/test/bullet_world_testcase.py +++ b/test/bullet_world_testcase.py @@ -44,6 +44,7 @@ def tearDown(self): @classmethod def tearDownClass(cls): + cls.viz_marker_publisher._stop_publishing() cls.world.exit() diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index bf0c5d75e..d9b927525 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -95,6 +95,7 @@ def test_step_simulation(self): self.world.simulate(1) self.assertTrue(self.milk.get_position().z < 2) + @unittest.skip def test_set_real_time_simulation(self): self.milk.set_position(Pose([100, 0, 2])) curr_time = time.time() diff --git a/test/test_costmaps.py b/test/test_costmaps.py index 9f3ea7dae..b46f1fede 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -1,6 +1,8 @@ import numpy as np from random_events.variables import Continuous # import plotly.graph_objects as go +import portion +from random_events.events import Event, ComplexEvent from bullet_world_testcase import BulletWorldTestCase from pycram.world_concepts.costmaps import OccupancyCostmap diff --git a/test/test_move_and_pick_up.py b/test/test_move_and_pick_up.py index dd0872979..e4161e12d 100644 --- a/test/test_move_and_pick_up.py +++ b/test/test_move_and_pick_up.py @@ -7,6 +7,7 @@ from pycram.designator import ObjectDesignatorDescription from pycram.datastructures.enums import ObjectType +from pycram.designators.actions.actions import MoveTorsoActionPerformable from pycram.plan_failures import PlanFailure from pycram.process_module import simulated_robot from pycram.resolver.probabilistic.probabilistic_action import MoveAndPickUp, GaussianCostmapModel @@ -51,6 +52,7 @@ def test_move_and_pick_up(self): with simulated_robot: for action in move_and_pick: try: + MoveTorsoActionPerformable(0.3).perform() action.perform() return # Success except PlanFailure as e: diff --git a/test/test_orm.py b/test/test_orm.py index 4516f7b27..4766636a8 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -204,7 +204,7 @@ def test_code_designator_type(self): self.assertEqual(result[1].action.dtype, motion_designator.MoveMotion.__name__) def test_parkArmsAction(self): - action = ParkArmsActionPerformable(pycram.enums.Arms.BOTH) + action = ParkArmsActionPerformable(pycram.datastructures.enums.Arms.BOTH) with simulated_robot: action.perform() pycram.orm.base.ProcessMetaData().description = "parkArmsAction_test" @@ -230,7 +230,7 @@ def test_lookAt_and_detectAction(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) action = DetectActionPerformable(object_description.resolve()) with simulated_robot: - ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform() + ParkArmsActionPerformable(pycram.datastructures.enums.Arms.BOTH).perform() NavigateActionPerformable(Pose([0, 1, 0], [0, 0, 0, 1])).perform() LookAtActionPerformable(object_description.resolve().pose).perform() action.perform() @@ -257,7 +257,7 @@ def test_open_and_closeAction(self): self.kitchen.set_pose(Pose([20, 20, 0], [0, 0, 0, 1])) with simulated_robot: - ParkArmsActionPerformable(pycram.enums.Arms.BOTH).perform() + ParkArmsActionPerformable(pycram.datastructures.enums.Arms.BOTH).perform() NavigateActionPerformable(Pose([1.81, 1.73, 0.0], [0.0, 0.0, 0.594, 0.804])).perform() OpenActionPerformable(handle_desig, arm="left").perform() From 1382bc12dc1d12ca0db352093084789fc9125d04 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 8 Apr 2024 11:23:28 +0200 Subject: [PATCH 169/195] [general] Fixed Documentation --- doc/source/conf.py | 2 +- doc/source/examples.rst | 4 +- doc/source/index.rst | 2 +- doc/source/resolvers.rst | 2 +- examples/bullet_world.ipynb | 44 +--------- src/pycram/cache_manager.py | 9 ++- src/pycram/datastructures/dataclasses.py | 10 +-- .../datastructures/local_transformer.py | 11 +-- src/pycram/datastructures/pose.py | 2 +- src/pycram/description.py | 40 ++++++++-- src/pycram/designator.py | 6 +- src/pycram/external_interfaces/ik.py | 5 +- src/pycram/failure_handling.py | 28 +++---- src/pycram/fluent.py | 13 +-- src/pycram/language.py | 3 +- src/pycram/object_descriptors/urdf.py | 2 +- src/pycram/pose_generator_and_validator.py | 38 ++++----- .../stretch_process_modules.py | 35 ++++---- src/pycram/ros/joint_state_publisher.py | 3 +- src/pycram/ros/robot_state_updater.py | 5 +- src/pycram/world.py | 77 +++++++++++------- src/pycram/world_concepts/constraints.py | 8 +- src/pycram/world_concepts/costmaps.py | 14 ++-- src/pycram/world_concepts/world_object.py | 80 ++++++++++++------- src/pycram/world_reasoning.py | 17 ++-- src/pycram/worlds/bullet_world.py | 28 +++---- 26 files changed, 246 insertions(+), 242 deletions(-) diff --git a/doc/source/conf.py b/doc/source/conf.py index 3bfd0f09c..177109f8b 100644 --- a/doc/source/conf.py +++ b/doc/source/conf.py @@ -210,7 +210,7 @@ autosectionlabel_prefix_document = True -# autoapi_keep_files = True +autoapi_keep_files = True suppress_warnings = [] diff --git a/doc/source/examples.rst b/doc/source/examples.rst index 111a96eee..f4cc7bc1d 100644 --- a/doc/source/examples.rst +++ b/doc/source/examples.rst @@ -58,8 +58,8 @@ seen in :meth:`pycram.task.TaskTreeNode.to_sql` and :meth:`pycram.task.TaskTreeN When using the ORM to record the experiments a MetaData instance is created. For a clean data management it is important to fill out the description. For this, check the documentation of :meth:`pycram.orm.base.ProcessMetaData`. -Examples --------- +ORM Examples +------------ .. nbgallery:: diff --git a/doc/source/index.rst b/doc/source/index.rst index 65293c4a4..fb1161d2d 100644 --- a/doc/source/index.rst +++ b/doc/source/index.rst @@ -1,4 +1,4 @@ - ================================== +================================== Welcome to pycram's documentation! ================================== diff --git a/doc/source/resolvers.rst b/doc/source/resolvers.rst index 844c74804..0303fa7cb 100644 --- a/doc/source/resolvers.rst +++ b/doc/source/resolvers.rst @@ -15,4 +15,4 @@ Tutorial A tutorial for custom resolver creation is found in the notebook below. .. nbgallery:: - notebooks/custom_resolver \ No newline at end of file + notebooks/improving_actions \ No newline at end of file diff --git a/examples/bullet_world.ipynb b/examples/bullet_world.ipynb index 33a3da4d7..80623bbfd 100644 --- a/examples/bullet_world.ipynb +++ b/examples/bullet_world.ipynb @@ -2,7 +2,6 @@ "cells": [ { "cell_type": "markdown", - "id": "8d2d6a94", "metadata": {}, "source": [ "# Bullet World\n", @@ -14,7 +13,6 @@ { "cell_type": "code", "execution_count": 1, - "id": "23bbba35", "metadata": { "ExecuteTime": { "end_time": "2024-02-01T16:28:16.307401805Z", @@ -46,7 +44,6 @@ }, { "cell_type": "markdown", - "id": "dccaf6ff", "metadata": {}, "source": [ "This new window is the BulletWorld, PyCRAMs internal physics simulation. You can use the mouse to move the camera around:\n", @@ -61,7 +58,6 @@ }, { "cell_type": "markdown", - "id": "4403bf9c", "metadata": {}, "source": [ "To close the BulletWorld again please use the ```exit``` method since it will also terminate threads running in the background" @@ -70,7 +66,6 @@ { "cell_type": "code", "execution_count": 7, - "id": "b1e6ed82", "metadata": {}, "outputs": [], "source": [ @@ -79,7 +74,6 @@ }, { "cell_type": "markdown", - "id": "e0fc7086", "metadata": {}, "source": [ "To spawn new things in the BulletWorld we need to import the Object class and create and instance of it. " @@ -88,7 +82,6 @@ { "cell_type": "code", "execution_count": 2, - "id": "48a3aed2", "metadata": { "ExecuteTime": { "end_time": "2024-02-01T16:14:50.629562309Z", @@ -104,7 +97,6 @@ }, { "cell_type": "markdown", - "id": "8a754f12", "metadata": {}, "source": [ "As you can see this spawns a milk floating in the air. What we did here was create a new Object which has the name \"milk\" as well as the type ```ObjectType.MILK ``` , is spawned from the file \"milk.stl\" and is at the position [0, 0, 1]. \n", @@ -123,7 +115,6 @@ { "cell_type": "code", "execution_count": 3, - "id": "4ae2bc42", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:29:23.208599020Z", @@ -138,7 +129,6 @@ { "cell_type": "code", "execution_count": 4, - "id": "4adc7b11", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:29:23.675871190Z", @@ -153,7 +143,6 @@ { "cell_type": "code", "execution_count": 5, - "id": "f91d1809", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:29:24.180713247Z", @@ -167,7 +156,6 @@ }, { "cell_type": "markdown", - "id": "5805be38", "metadata": {}, "source": [ "In the same sense as setting the position or orientation, you can also get the position and orientation." @@ -176,7 +164,6 @@ { "cell_type": "code", "execution_count": 6, - "id": "1db2aa78", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:29:58.869360443Z", @@ -227,7 +214,6 @@ }, { "cell_type": "markdown", - "id": "68c02db9", "metadata": {}, "source": [ "## Attachments\n", @@ -239,7 +225,6 @@ { "cell_type": "code", "execution_count": 7, - "id": "10a493b1", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:02.056106044Z", @@ -254,7 +239,6 @@ { "cell_type": "code", "execution_count": 8, - "id": "275372e3", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:03.288290549Z", @@ -268,7 +252,6 @@ }, { "cell_type": "markdown", - "id": "5577c567", "metadata": {}, "source": [ "Now since they are attached to each other, if we move one of them the other will move in conjunction." @@ -277,7 +260,6 @@ { "cell_type": "code", "execution_count": 9, - "id": "dff85834", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:05.029258354Z", @@ -291,7 +273,6 @@ }, { "cell_type": "markdown", - "id": "196bd705", "metadata": {}, "source": [ "In the same way the Object can also be detached, just call the detach method on one of the two attached Objects." @@ -300,7 +281,6 @@ { "cell_type": "code", "execution_count": 10, - "id": "b0bba145", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:06.737363899Z", @@ -322,7 +302,6 @@ }, { "cell_type": "markdown", - "id": "e5e44a67", "metadata": {}, "source": [ "## Links and Joints\n", @@ -334,7 +313,6 @@ { "cell_type": "code", "execution_count": 11, - "id": "edf5cb72", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:13.548802172Z", @@ -355,18 +333,8 @@ "print(pr2.links)" ] }, - { - "cell_type": "code", - "outputs": [], - "source": [], - "metadata": { - "collapsed": false - }, - "id": "e896223230860878" - }, { "cell_type": "markdown", - "id": "e157eb6f", "metadata": {}, "source": [ "For links there are similar methods available as for the pose. However, you can only **get** the position and orientation of a link. " @@ -375,7 +343,6 @@ { "cell_type": "code", "execution_count": 12, - "id": "51b59ffd", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:26.283263579Z", @@ -426,7 +393,6 @@ }, { "cell_type": "markdown", - "id": "ecd9c4a3", "metadata": {}, "source": [ "Methods available for joints are:\n", @@ -441,7 +407,6 @@ { "cell_type": "code", "execution_count": 13, - "id": "38a8aef4", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:51.633276335Z", @@ -471,7 +436,6 @@ }, { "cell_type": "markdown", - "id": "6d4ee70a", "metadata": {}, "source": [ "## Misc Methods\n", @@ -481,7 +445,6 @@ { "cell_type": "code", "execution_count": 14, - "id": "5eee9b8a", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:57.200886492Z", @@ -504,7 +467,6 @@ { "cell_type": "code", "execution_count": 15, - "id": "07aa1c3f", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:30:59.531448130Z", @@ -518,7 +480,6 @@ }, { "cell_type": "markdown", - "id": "ce5d910b", "metadata": {}, "source": [ "Lastly, there is ```get_AABB```, AABB stands for *A*xis *A*ligned *B*ounding *B*ox. This method returns two points in world coordinates which span a rectangle representing the AABB." @@ -527,7 +488,6 @@ { "cell_type": "code", "execution_count": 16, - "id": "2a78715b", "metadata": { "ExecuteTime": { "end_time": "2024-01-25T18:31:05.700993547Z", @@ -537,7 +497,9 @@ "outputs": [ { "data": { - "text/plain": "AxisAlignedBoundingBox(min_x=-0.0015000000000000005, min_y=-0.0015000000000000005, min_z=0.06949999999999999, max_x=0.0015000000000000005, max_y=0.0015000000000000005, max_z=0.0725)" + "text/plain": [ + "AxisAlignedBoundingBox(min_x=-0.0015000000000000005, min_y=-0.0015000000000000005, min_z=0.06949999999999999, max_x=0.0015000000000000005, max_y=0.0015000000000000005, max_z=0.0725)" + ] }, "execution_count": 16, "metadata": {}, diff --git a/src/pycram/cache_manager.py b/src/pycram/cache_manager.py index a8995636b..29191db9e 100644 --- a/src/pycram/cache_manager.py +++ b/src/pycram/cache_manager.py @@ -4,7 +4,7 @@ from typing_extensions import List, TYPE_CHECKING if TYPE_CHECKING: - from pycram.description import ObjectDescription + from .description import ObjectDescription class CacheManager: @@ -21,6 +21,7 @@ class CacheManager: def __init__(self, cache_dir: str, data_directory: List[str]): """ Initializes the CacheManager. + :param cache_dir: The directory where the cached files are stored. :param data_directory: The directory where all resource files are stored. """ @@ -31,6 +32,7 @@ def update_cache_dir_with_object(self, path: str, ignore_cached_files: bool, object_description: 'ObjectDescription', object_name: str) -> str: """ Checks if the file is already in the cache directory, if not it will be preprocessed and saved in the cache. + :param path: The path of the file to preprocess and save in the cache directory. :param ignore_cached_files: If True, the file will be preprocessed and saved in the cache directory even if it is already cached. @@ -56,6 +58,7 @@ def generate_description_and_write_to_cache(self, path: str, name: str, extensio object_description: 'ObjectDescription') -> None: """ Generates the description from the file at the given path and writes it to the cache directory. + :param path: The path of the file to preprocess. :param name: The name of the object. :param extension: The file extension of the file to preprocess. @@ -69,6 +72,7 @@ def generate_description_and_write_to_cache(self, path: str, name: str, extensio def write_to_cache(description_string: str, cache_path: str) -> None: """ Writes the description string to the cache directory. + :param description_string: The description string to write to the cache directory. :param cache_path: The path of the file in the cache directory. """ @@ -79,6 +83,7 @@ def look_for_file_in_data_dir(self, path_object: pathlib.Path) -> str: """ Looks for a file in the data directory of the World. If the file is not found in the data directory, this method raises a FileNotFoundError. + :param path_object: The pathlib object of the file to look for. """ @@ -113,6 +118,7 @@ def is_cached(self, path: str, object_description: 'ObjectDescription') -> bool: def check_with_extension(self, path: str) -> bool: """ Checks if the file in the given ath exists in the cache directory including file extension. + :param path: The path of the file to check. """ file_name = pathlib.Path(path).name @@ -123,6 +129,7 @@ def check_without_extension(self, path: str, object_description: 'ObjectDescript """ Checks if the file in the given path exists in the cache directory without file extension, the extension is added after the file name manually in this case. + :param path: The path of the file to check. :param object_description: The object description of the file. """ diff --git a/src/pycram/datastructures/dataclasses.py b/src/pycram/datastructures/dataclasses.py index b67833fbc..a97abda86 100644 --- a/src/pycram/datastructures/dataclasses.py +++ b/src/pycram/datastructures/dataclasses.py @@ -2,14 +2,14 @@ from dataclasses import dataclass from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING -from pycram.datastructures.enums import JointType, Shape -from pycram.datastructures.pose import Pose, Point +from .datastructures.enums import JointType, Shape +from .datastructures.pose import Pose, Point from abc import ABC, abstractmethod if TYPE_CHECKING: - from pycram.description import Link - from pycram.world_concepts.world_object import Object - from pycram.world_concepts.constraints import Attachment + from ..description import Link + from ..world_concepts.world_object import Object + from ..world_concepts.constraints import Attachment def get_point_as_list(point: Point) -> List[float]: diff --git a/src/pycram/datastructures/local_transformer.py b/src/pycram/datastructures/local_transformer.py index 11408a956..e045d0148 100644 --- a/src/pycram/datastructures/local_transformer.py +++ b/src/pycram/datastructures/local_transformer.py @@ -9,7 +9,7 @@ from rospy import Duration from geometry_msgs.msg import TransformStamped -from pycram.datastructures.pose import Pose, Transform +from .datastructures.pose import Pose, Transform from typing_extensions import List, Optional, Union, Iterable @@ -39,14 +39,6 @@ def __new__(cls, *args, **kwargs): def __init__(self): if self._initialized: return super().__init__(interpolate=True, cache_time=Duration(10)) - - # TF tf_stampeds and static_tf_stampeds of the Robot in the World: - # These are initialized with the function init_transforms_from_urdf and are - # used to update the local transformer with the function update_local_transformer_from_btr - # TODO: Ask Jonas if this is still needed - self.tf_stampeds: List[TransformStamped] = [] - self.static_tf_stampeds: List[TransformStamped] = [] - # Since this file can't import world.py this holds the reference to the current_world self.world = None # TODO: Ask Jonas if this is still needed @@ -100,6 +92,7 @@ def lookup_transform_from_source_to_target_frame(self, source_frame: str, target """ Update the transforms for all world objects then Look up for the latest known transform that transforms a point from source frame to target frame. If no time is given the last common time between the two frames is used. + :param time: Time at which the transform should be looked up """ self.world.update_transforms_for_objects_in_current_world() diff --git a/src/pycram/datastructures/pose.py b/src/pycram/datastructures/pose.py index 6a86e5772..960a4ca19 100644 --- a/src/pycram/datastructures/pose.py +++ b/src/pycram/datastructures/pose.py @@ -11,7 +11,7 @@ from geometry_msgs.msg import PoseStamped, TransformStamped, Vector3, Point from geometry_msgs.msg import (Pose as GeoPose, Quaternion as GeoQuaternion) from tf import transformations -from pycram.orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData +from ..orm.base import Pose as ORMPose, Position, Quaternion, ProcessMetaData def get_normalized_quaternion(quaternion: np.ndarray) -> GeoQuaternion: diff --git a/src/pycram/description.py b/src/pycram/description.py index 1bbf7fc52..826a08af0 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -8,14 +8,14 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING -from pycram.datastructures.enums import JointType -from pycram.datastructures.local_transformer import LocalTransformer -from pycram.datastructures.pose import Pose, Transform -from pycram.world import WorldEntity -from pycram.datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape +from .datastructures.enums import JointType +from .datastructures.local_transformer import LocalTransformer +from .datastructures.pose import Pose, Transform +from .world import WorldEntity +from .datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape if TYPE_CHECKING: - from pycram.world_concepts.world_object import Object + from .world_concepts.world_object import Object class EntityDescription(ABC): @@ -87,6 +87,7 @@ def axis(self) -> Point: def has_limits(self) -> bool: """ Checks if this joint has limits. + :return: True if the joint has limits, False otherwise. """ pass @@ -216,6 +217,7 @@ def current_state(self, link_state: LinkState) -> None: def add_fixed_constraint_with_link(self, child_link: 'Link') -> int: """ Adds a fixed constraint between this link and the given link, used to create attachments for example. + :param child_link: The child link to which a fixed constraint should be added. :return: The unique id of the constraint. """ @@ -229,6 +231,7 @@ def add_fixed_constraint_with_link(self, child_link: 'Link') -> int: def remove_constraint_with_link(self, child_link: 'Link') -> None: """ Removes the constraint between this link and the given link. + :param child_link: The child link of the constraint that should be removed. """ self.world.remove_constraint(self.constraint_ids[child_link]) @@ -239,6 +242,7 @@ def remove_constraint_with_link(self, child_link: 'Link') -> None: def is_root(self) -> bool: """ Returns whether this link is the root link of the object. + :return: True if this link is the root link, False otherwise. """ return self.object.get_root_link_id() == self.id @@ -246,6 +250,7 @@ def is_root(self) -> bool: def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: """ Updates the transformation of this link at the given time. + :param transform_time: The time at which the transformation should be updated. """ self.local_transformer.update_transforms([self.transform], transform_time) @@ -253,6 +258,7 @@ def update_transform(self, transform_time: Optional[rospy.Time] = None) -> None: def get_transform_to_link(self, link: 'Link') -> Transform: """ Returns the transformation from this link to the given link. + :param link: The link to which the transformation should be returned. :return: A Transform object with the transformation from this link to the given link. """ @@ -261,6 +267,7 @@ def get_transform_to_link(self, link: 'Link') -> Transform: def get_transform_from_link(self, link: 'Link') -> Transform: """ Returns the transformation from the given link to this link. + :param link: The link from which the transformation should be returned. :return: A Transform object with the transformation from the given link to this link. """ @@ -269,6 +276,7 @@ def get_transform_from_link(self, link: 'Link') -> Transform: def get_pose_wrt_link(self, link: 'Link') -> Pose: """ Returns the pose of this link with respect to the given link. + :param link: The link with respect to which the pose should be returned. :return: A Pose object with the pose of this link with respect to the given link. """ @@ -277,6 +285,7 @@ def get_pose_wrt_link(self, link: 'Link') -> Pose: def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of this link. + :return: An AxisAlignedBoundingBox object with the axis aligned bounding box of this link. """ return self.world.get_link_axis_aligned_bounding_box(self) @@ -285,6 +294,7 @@ def get_axis_aligned_bounding_box(self) -> AxisAlignedBoundingBox: def position(self) -> Point: """ The getter for the position of the link relative to the world frame. + :return: A Point object containing the position of the link relative to the world frame. """ return self.pose.position @@ -293,6 +303,7 @@ def position(self) -> Point: def position_as_list(self) -> List[float]: """ The getter for the position of the link relative to the world frame as a list. + :return: A list containing the position of the link relative to the world frame. """ return self.pose.position_as_list() @@ -301,6 +312,7 @@ def position_as_list(self) -> List[float]: def orientation(self) -> Quaternion: """ The getter for the orientation of the link relative to the world frame. + :return: A Quaternion object containing the orientation of the link relative to the world frame. """ return self.pose.orientation @@ -309,6 +321,7 @@ def orientation(self) -> Quaternion: def orientation_as_list(self) -> List[float]: """ The getter for the orientation of the link relative to the world frame as a list. + :return: A list containing the orientation of the link relative to the world frame. """ return self.pose.orientation_as_list() @@ -323,6 +336,7 @@ def _update_pose(self) -> None: def pose(self) -> Pose: """ The pose of the link relative to the world frame. + :return: A Pose object containing the pose of the link relative to the world frame. """ return self._current_pose @@ -331,6 +345,7 @@ def pose(self) -> Pose: def pose_as_list(self) -> List[List[float]]: """ The pose of the link relative to the world frame as a list. + :return: A list containing the position and orientation of the link relative to the world frame. """ return self.pose.to_list() @@ -345,6 +360,7 @@ def get_origin_transform(self) -> Transform: def color(self) -> Color: """ The getter for the rgba_color of this link. + :return: A Color object containing the rgba_color of this link. """ return self.world.get_link_color(self) @@ -353,6 +369,7 @@ def color(self) -> Color: def color(self, color: Color) -> None: """ The setter for the color of this link, could be rgb or rgba. + :param color: The color as a list of floats, either rgb or rgba. """ self.world.set_link_color(self, color) @@ -442,6 +459,7 @@ def _update_position(self) -> None: def parent_link(self) -> Link: """ Returns the parent link of this joint. + :return: The parent link as a AbstractLink object. """ return self.object.get_link(self.parent_link_name) @@ -450,6 +468,7 @@ def parent_link(self) -> Link: def child_link(self) -> Link: """ Returns the child link of this joint. + :return: The child link as a AbstractLink object. """ return self.object.get_link(self.child_link_name) @@ -465,6 +484,7 @@ def reset_position(self, position: float) -> None: def get_object_id(self) -> int: """ Returns the id of the object to which this joint belongs. + :return: The integer id of the object to which this joint belongs. """ return self.object.id @@ -509,6 +529,7 @@ def current_state(self) -> JointState: def current_state(self, joint_state: JointState) -> None: """ Updates the current state of this joint from the given joint state if the position is different. + :param joint_state: The joint state to update from. """ if self._current_position != joint_state.position: @@ -556,6 +577,7 @@ def __init__(self, path: Optional[str] = None): def update_description_from_file(self, path: str) -> None: """ Updates the description of this object from the file at the given path. + :param path: The path of the file to update from. """ self._parsed_description = self.load_description(path) @@ -578,6 +600,7 @@ def parsed_description(self, parsed_description: Any): def load_description(self, path: str) -> Any: """ Loads the description from the file at the given path. + :param path: The path to the source file, if only a filename is provided then the resources directories will be searched. """ @@ -587,6 +610,7 @@ def generate_description_from_file(self, path: str, name: str, extension: str) - """ Generates and preprocesses the description from the file at the given path and returns the preprocessed description as a string. + :param path: The path of the file to preprocess. :param name: The name of the object. :param extension: The file extension of the file to preprocess. @@ -614,6 +638,7 @@ def generate_description_from_file(self, path: str, name: str, extension: str) - def get_file_name(self, path_object: pathlib.Path, extension: str, object_name: str) -> str: """ Returns the file name of the description file. + :param path_object: The path object of the description file or the mesh file. :param extension: The file extension of the description file or the mesh file. :param object_name: The name of the object. @@ -634,6 +659,7 @@ def generate_from_mesh_file(cls, path: str, name: str) -> str: """ Generates a description file from one of the mesh types defined in the mesh_extensions and returns the path of the generated file. + :param path: The path to the .obj file. :param name: The name of the object. :return: The path of the generated description file. @@ -645,6 +671,7 @@ def generate_from_mesh_file(cls, path: str, name: str) -> str: def generate_from_description_file(cls, path: str) -> str: """ Preprocesses the given file and returns the preprocessed description string. + :param path: The path of the file to preprocess. :return: The preprocessed description string. """ @@ -655,6 +682,7 @@ def generate_from_description_file(cls, path: str) -> str: def generate_from_parameter_server(cls, name: str) -> str: """ Preprocesses the description from the ROS parameter server and returns the preprocessed description string. + :param name: The name of the description on the parameter server. :return: The preprocessed description string. """ diff --git a/src/pycram/designator.py b/src/pycram/designator.py index 6ce66f970..b023cbe24 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -558,9 +558,9 @@ def insert(self, session: Session) -> ORMObjectDesignator: def frozen_copy(self) -> 'ObjectDesignatorDescription.Object': """ - :return: A copy containing only the fields of this class. The WorldObject attached to this pycram - object is not copied. The _pose gets set to a method that statically returns the pose of the object when - this method was called. + Returns a copy of this designator containing only the fields. + + :return: A copy containing only the fields of this class. The WorldObject attached to this pycram object is not copied. The _pose gets set to a method that statically returns the pose of the object when this method was called. """ result = ObjectDesignatorDescription.Object(self.name, self.obj_type, None) # get current object pose and set resulting pose to always be that diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index 1d98a30a1..f448d50f3 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -60,8 +60,7 @@ def call_ik(root_link: str, tip_link: str, target_pose: Pose, robot_object: Obje :param root_link: The first link of the chain of joints to be altered :param tip_link: The last link in the chain of joints to be altered - :param target_pose: The target pose in frame of root link - second is the orientation as quaternion in world coordinate frame + :param target_pose: The target pose in frame of root link second is the orientation as quaternion in world coordinate frame :param robot_object: The robot object for which the ik solution should be generated :param joints: A list of joint name that should be altered :return: The solution that was generated as a list of joint values corresponding to the order of joints given @@ -130,7 +129,6 @@ def apply_grasp_orientation_to_pose(grasp: str, pose: Pose) -> Pose: def try_to_reach(pose_or_object: Union[Pose, Object], prospection_robot: Object, gripper_name: str) -> Union[Pose, None]: - input_pose = pose_or_object.get_pose() if isinstance(pose_or_object, Object) else pose_or_object arm = "left" if gripper_name == robot_description.get_tool_frame("left") else "right" @@ -172,4 +170,3 @@ def request_ik(target_pose: Pose, robot: Object, joints: List[str], gripper: str inv = call_ik(base_link, end_effector, target_diff, robot, joints) return inv - diff --git a/src/pycram/failure_handling.py b/src/pycram/failure_handling.py index 5aab138c8..8fb266282 100644 --- a/src/pycram/failure_handling.py +++ b/src/pycram/failure_handling.py @@ -1,6 +1,7 @@ from .designator import DesignatorDescription from .plan_failures import PlanFailure + class FailureHandling: """ Base class for failure handling mechanisms in automated systems or workflows. @@ -8,21 +9,13 @@ class FailureHandling: This class provides a structure for implementing different strategies to handle failures that may occur during the execution of a plan or process. It is designed to be extended by subclasses that implement specific failure handling behaviors. - - Attributes: - designator_description (DesignatorDescription): An instance of DesignatorDescription. - - Methods: - perform(): Abstract method """ - def __init__(self, designator_description:DesignatorDescription): + def __init__(self, designator_description: DesignatorDescription): """ Initializes a new instance of the FailureHandling class. - Args: - designator_description (DesignatorDescription): The description or context - of the task or process for which the failure handling is being set up. + :param designator_description: The description or context of the task or process for which the failure handling is being set up. """ self.designator_description = designator_description @@ -33,11 +26,11 @@ def perform(self): This method should be overridden in subclasses to implement the specific behavior for handling failures. - Raises: - NotImplementedError: If the method is not implemented in a subclass. + :raises NotImplementedError: If the method is not implemented in a subclass. """ raise NotImplementedError() + class Retry(FailureHandling): """ A subclass of FailureHandling that implements a retry mechanism. @@ -55,14 +48,12 @@ class Retry(FailureHandling): perform(): Implements the retry logic. """ - def __init__(self, designator_description:DesignatorDescription, max_tries:int=3): + def __init__(self, designator_description: DesignatorDescription, max_tries: int = 3): """ Initializes a new instance of the Retry class. - Args: - designator_description (DesignatorDescription): The description or context - of the task or process for which the retry mechanism is being set up. - max_tries (int, optional): The maximum number of attempts to retry. Defaults to 3. + :param designator_description: The description or context of the task or process for which the retry mechanism is being set up. + :param max_tries: The maximum number of attempts to retry. Defaults to 3. """ super().__init__(designator_description) self.max_tries = max_tries @@ -75,8 +66,7 @@ def perform(self): If the action fails, it is retried up to max_tries times. If all attempts fail, the last exception is raised. - Raises: - PlanFailure: If all retry attempts fail. + :raises PlanFailure: If all retry attempts fail. """ tries = 0 for action in iter(self.designator_description): diff --git a/src/pycram/fluent.py b/src/pycram/fluent.py index 89706e3c8..9566e2906 100644 --- a/src/pycram/fluent.py +++ b/src/pycram/fluent.py @@ -1,13 +1,3 @@ -"""Implementation of fluents and the whenever macro. - -Macros: -whenever -- macro to repeat a body as long as the value of a fluent is not None or whenever a pulsed fluent changes its value or gets pulsed. - -Classes: -Behavior -- enumeration to describe how to handle missed pulses in the whenever macro. -Fluent -- implementation of fluents. -""" - # used for delayed evaluation of typing until python 3.11 becomes mainstream from __future__ import annotations @@ -115,7 +105,7 @@ def pulse(self) -> None: def whenever(self, callback: Callable) -> None: """ Registers a callback which is called everytime this Fluent is pulsed. The callback should be a Callable. When - the callback is called it gets the current value of this Fluent as an argument. `1 + the callback is called it gets the current value of this Fluent as an argument. :param callback: The callback which should be called when pulsed as a Callable. """ @@ -138,7 +128,6 @@ def get_value(self) -> Any: def set_value(self, value: Any) -> None: """Change the value of the fluent. - Changing the value will also pulse the fluent. :param value: the new value of the fluent. diff --git a/src/pycram/language.py b/src/pycram/language.py index 8786f9309..81612a78b 100644 --- a/src/pycram/language.py +++ b/src/pycram/language.py @@ -157,7 +157,7 @@ def simplify(self) -> Language: """ Simplifies the language tree by merging which have a parent-child relation and are of the same type. - .. code-block:: python + .. code-block:: ├── @@ -165,7 +165,6 @@ def simplify(self) -> Language: │ └── └── - would be simplified to: diff --git a/src/pycram/object_descriptors/urdf.py b/src/pycram/object_descriptors/urdf.py index 47b76931a..d21490d31 100644 --- a/src/pycram/object_descriptors/urdf.py +++ b/src/pycram/object_descriptors/urdf.py @@ -273,7 +273,7 @@ def get_chain(self, start_link_name: str, end_link_name: str) -> List[str]: def correct_urdf_string(self, urdf_string: str) -> str: """ Changes paths for files in the URDF from ROS paths to paths in the file system. Since World (PyBullet legacy) - can't deal with ROS package paths. + can't deal with ROS package paths. :param urdf_string: The name of the URDf on the parameter server :return: The URDF string with paths in the filesystem instead of ROS packages diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index 95bb205af..f870ef77e 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -33,9 +33,9 @@ class PoseGenerator: def __init__(self, costmap: Costmap, number_of_samples=100, orientation_generator=None): """ - :param costmap: The costmap from which poses should be sampled. - :param number_of_samples: The number of samples from the costmap that should be returned at max - :param orientation_generator: function that generates an orientation given a position and the origin of the costmap + :param costmap: The costmap from which poses should be sampled. + :param number_of_samples: The number of samples from the costmap that should be returned at max + :param orientation_generator: function that generates an orientation given a position and the origin of the costmap """ if not PoseGenerator.current_orientation_generator: @@ -92,10 +92,8 @@ def generate_orientation(position: List[float], origin: Pose) -> List[float]: This generation is done by simply calculating the arctan between the position, in the costmap, and the origin of the costmap. - :param position: The position in the costmap. This position is already converted - to the world coordinate frame. - :param origin: The origin of the costmap. This is also the point which the - robot should face. + :param position: The position in the costmap. This position is already converted to the world coordinate frame. + :param origin: The origin of the costmap. This is also the point which the robot should face. :return: A quaternion of the calculated orientation """ angle = np.arctan2(position[1] - origin.position.y, position[0] - origin.position.x) + np.pi @@ -116,8 +114,7 @@ def visibility_validator(pose: Pose, :param pose: The pose candidate that should be validated :param robot: The robot object for which this should be validated - :param object_or_pose: The target position or object for which the pose - candidate should be validated. + :param object_or_pose: The target position or object for which the pose candidate should be validated. :param world: The World instance in which this should be validated. :return: True if the target is visible for the robot, None in any other case. """ @@ -173,14 +170,10 @@ def reachability_validator(pose: Pose, the validator returns True and False in any other case. :param pose: The pose candidate for which the reachability should be validated - :param robot: The robot object in the World for which the reachability - should be validated. - :param target: The target position or object instance which should be the - target for reachability. - :param allowed_collision: dict of objects with which the robot is allowed to collide each - object correlates to a list of links of which this object consists - :return: True if the target is reachable for the robot and False in any other - case. + :param robot: The robot object in the World for which the reachability should be validated. + :param target: The target position or object instance which should be the target for reachability. + :param allowed_collision: dict of objects with which the robot is allowed to collide each object correlates to a list of links of which this object consists + :return: True if the target is reachable for the robot and False in any other case. """ if type(target) == Object: target = target.get_pose() @@ -230,18 +223,15 @@ def reachability_validator(pose: Pose, def collision_check(robot: Object, allowed_collision: list): """ This method checks if a given robot collides with any object within the world - which it is not allowed to collide with. + which it is not allowed to collide with. This is done checking iterating over every object within the world and checking if the robot collides with it. Careful the floor will be ignored. If there is a collision with an object that was not within the allowed collision list the function returns True else it will return False - :param robot: The robot object in the (Bullet)World where it should be checked if it collides - with something - :param allowed_collision: dict of objects with which the robot is allowed to collide each - object correlates to a list of links of which this object consists - :return: True if the target is reachable for the robot and False in any other - case. + :param robot: The robot object in the (Bullet)World where it should be checked if it collides with something + :param allowed_collision: dict of objects with which the robot is allowed to collide each object correlates to a list of links of which this object consists + :return: True if the target is reachable for the robot and False in any other case. """ in_contact = False allowed_robot_links = [] diff --git a/src/pycram/process_modules/stretch_process_modules.py b/src/pycram/process_modules/stretch_process_modules.py index 2ca0bdec5..e5aea17d3 100644 --- a/src/pycram/process_modules/stretch_process_modules.py +++ b/src/pycram/process_modules/stretch_process_modules.py @@ -7,6 +7,8 @@ from ..helper import _apply_ik from ..external_interfaces import giskard from .default_process_modules import * +from ..world import World +from ..designators.motion_designator import * class StretchNavigate(DefaultNavigation): @@ -20,16 +22,18 @@ class StretchMoveHead(ProcessModule): """ Process module for the simulated Stretch that moves the head such that it looks at the given position """ - def _execute(self, designator) -> Any: + + def _execute(self, designator: MoveMotion) -> Any: target = designator.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("link_head_pan")) pose_in_tilt = local_transformer.transform_pose(target, robot.get_link_tf_frame("link_head_tilt")) new_pan = np.arctan2(pose_in_pan.position.y, pose_in_pan.position.x) - new_tilt = np.arctan2(-pose_in_tilt.position.y, pose_in_tilt.position.z ** 2 + pose_in_tilt.position.x ** 2) * -1 + new_tilt = np.arctan2(-pose_in_tilt.position.y, + pose_in_tilt.position.z ** 2 + pose_in_tilt.position.x ** 2) * -1 current_pan = robot.get_joint_state("joint_head_pan") current_tilt = robot.get_joint_state("joint_head_tilt") @@ -84,15 +88,16 @@ class StretchOpen(ProcessModule): """ Process module for the simulated Stretch that opens an already grasped container """ + def _execute(self, desig: OpeningMotion): part_of_object = desig.object_part.bullet_world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - goal_pose = btr.link_pose_for_joint_config(part_of_object, { + goal_pose = link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[1] - 0.05}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) desig.object_part.bullet_world_object.set_joint_state(container_joint, part_of_object.get_joint_limits( @@ -103,19 +108,20 @@ class StretchClose(ProcessModule): """ Process module for the simulated Stretch that closes an already grasped container """ + def _execute(self, desig: ClosingMotion): - part_of_object = desig.object_part.bullet_world_object + part_of_object = desig.object_part.world_object container_joint = part_of_object.find_joint_above(desig.object_part.name, JointType.PRISMATIC) - goal_pose = btr.link_pose_for_joint_config(part_of_object, { + goal_pose = link_pose_for_joint_config(part_of_object, { container_joint: part_of_object.get_joint_limits(container_joint)[0]}, desig.object_part.name) - _move_arm_tcp(goal_pose, BulletWorld.robot, desig.arm) + _move_arm_tcp(goal_pose, World.robot, desig.arm) - desig.object_part.bullet_world_object.set_joint_state(container_joint, - part_of_object.get_joint_limits( - container_joint)[0]) + desig.object_part.world_object.set_joint_state(container_joint, + part_of_object.get_joint_limits( + container_joint)[0]) def _move_arm_tcp(target: Pose, robot: Object, arm: str) -> None: @@ -150,7 +156,7 @@ class StretchMoveHeadReal(ProcessModule): def _execute(self, desig: LookingMotion): target = desig.target - robot = BulletWorld.robot + robot = World.robot local_transformer = LocalTransformer() pose_in_pan = local_transformer.transform_pose(target, robot.get_link_tf_frame("head_pan_link")) @@ -179,11 +185,11 @@ def _execute(self, designator: DetectingMotion) -> Any: obj_pose = query_result["ClusterPoseBBAnnotator"] lt = LocalTransformer() - obj_pose = lt.transform_pose(obj_pose, BulletWorld.robot.get_link_tf_frame("torso_lift_link")) + obj_pose = lt.transform_pose(obj_pose, World.robot.get_link_tf_frame("torso_lift_link")) obj_pose.orientation = [0, 0, 0, 1] obj_pose.position.x += 0.05 - bullet_obj = BulletWorld.current_bullet_world.get_objects_by_type(designator.object_type) + bullet_obj = World.current_world.get_objects_by_type(designator.object_type) if bullet_obj: bullet_obj[0].set_pose(obj_pose) return bullet_obj[0] @@ -339,4 +345,3 @@ def close(self): return StretchClose(self._close_lock) elif ProcessModuleManager.execution_type == "real": return StretchCloseReal(self._close_lock) - diff --git a/src/pycram/ros/joint_state_publisher.py b/src/pycram/ros/joint_state_publisher.py index 45f89bf54..f420eec4e 100644 --- a/src/pycram/ros/joint_state_publisher.py +++ b/src/pycram/ros/joint_state_publisher.py @@ -34,8 +34,7 @@ def __init__(self, joint_state_topic="/pycram/joint_state", interval=0.1): def _publish(self) -> None: """ Publishes the current joint states of the :py:attr:`~pycram.world.World.robot` in an infinite loop. - The joint states are published as long as the kill_event is not set - by :py:meth:`~JointStatePublisher._stop_publishing` + The joint states are published as long as the kill_event is not set by :py:meth:`~JointStatePublisher._stop_publishing` """ robot = World.robot joint_names = [joint_name for joint_name in robot.joint_name_to_id.keys()] diff --git a/src/pycram/ros/robot_state_updater.py b/src/pycram/ros/robot_state_updater.py index 8c8a8e43b..72b602e31 100644 --- a/src/pycram/ros/robot_state_updater.py +++ b/src/pycram/ros/robot_state_updater.py @@ -14,6 +14,7 @@ class RobotStateUpdater: """ Updates the robot in the World with information of the real robot published to ROS topics. Infos used to update the robot are: + * The current pose of the robot * The current joint state of the robot """ @@ -47,8 +48,8 @@ def _subscribe_tf(self, msg: TransformStamped) -> None: def _subscribe_joint_state(self, msg: JointState) -> None: """ Sets the current joint configuration of the robot in the world to the configuration published on the - topic. Since this uses rospy.wait_for_message which can have errors when used with threads there might be an - attribute error in the rospy implementation. + topic. Since this uses rospy.wait_for_message which can have errors when used with threads there might be an + attribute error in the rospy implementation. :param msg: JointState message published to the topic. """ diff --git a/src/pycram/world.py b/src/pycram/world.py index 97e4361f7..7a77c7061 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -14,20 +14,20 @@ from typing_extensions import List, Optional, Dict, Tuple, Callable, TYPE_CHECKING from typing_extensions import Union -from pycram.cache_manager import CacheManager -from pycram.datastructures.enums import JointType, ObjectType, WorldMode -from pycram.world_concepts.event import Event -from pycram.datastructures.local_transformer import LocalTransformer -from pycram.datastructures.pose import Pose, Transform -from pycram.world_concepts.constraints import Constraint -from pycram.datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, +from .cache_manager import CacheManager +from .datastructures.enums import JointType, ObjectType, WorldMode +from .world_concepts.event import Event +from .datastructures.local_transformer import LocalTransformer +from .datastructures.pose import Pose, Transform +from .world_concepts.constraints import Constraint +from .datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, MultiBody, VisualShape, BoxVisualShape, CylinderVisualShape, SphereVisualShape, CapsuleVisualShape, PlaneVisualShape, MeshVisualShape, ObjectState, State, WorldState) if TYPE_CHECKING: - from pycram.world_concepts.world_object import Object - from pycram.description import Link, Joint + from .world_concepts.world_object import Object + from .description import Link, Joint class StateEntity: @@ -105,7 +105,7 @@ class World(StateEntity, ABC): """ The World Class represents the physics Simulation and belief state, it is the main interface for reasoning about the World. This is implemented as a singleton, the current World can be accessed via the static variable - current_world which is managed by the World class itself. + current_world which is managed by the World class itself. """ simulation_frequency: float @@ -282,6 +282,7 @@ def get_object_by_id(self, obj_id: int) -> Object: def remove_object_from_simulator(self, obj: Object) -> None: """ Removes an object from the physics simulator. + :param obj: The object to be removed. """ pass @@ -385,6 +386,7 @@ def get_link_pose(self, link: Link) -> Pose: def get_object_link_names(self, obj: Object) -> List[str]: """ Returns the names of all links of this object. + :param obj: The object. :return: A list of link names. """ @@ -394,7 +396,7 @@ def simulate(self, seconds: float, real_time: Optional[bool] = False) -> None: """ Simulates Physics in the World for a given amount of seconds. Usually this simulation is faster than real time. By setting the 'real_time' parameter this simulation is slowed down such that the simulated time is equal - to real time. + to real time. :param seconds: The amount of seconds that should be simulated. :param real_time: If the simulation should happen in real time or faster. @@ -499,6 +501,7 @@ def set_link_color(self, link: Link, rgba_color: Color): def get_link_color(self, link: Link) -> Color: """ This method returns the rgba_color of this link. + :param link: The link for which the rgba_color should be returned. :return: The rgba_color as Color object with RGBA values between 0 and 1. """ @@ -659,6 +662,7 @@ def current_state(self, state: WorldState) -> None: def object_states(self) -> Dict[str, ObjectState]: """ Returns the states of all objects in the World. + :return: A dictionary with the object id as key and the object state as value. """ return {obj.name: obj.current_state for obj in self.objects} @@ -674,6 +678,7 @@ def object_states(self, states: Dict[str, ObjectState]) -> None: def save_objects_state(self, state_id: int) -> None: """ Saves the state of all objects in the World according to the given state using the unique state id. + :param state_id: The unique id representing the state. """ for obj in self.objects: @@ -683,6 +688,7 @@ def save_objects_state(self, state_id: int) -> None: def save_physics_simulator_state(self) -> int: """ Saves the state of the physics simulator and returns the unique id of the state. + :return: The unique id representing the state. """ pass @@ -691,6 +697,7 @@ def save_physics_simulator_state(self) -> int: def remove_physics_simulator_state(self, state_id: int) -> None: """ Removes the state of the physics simulator with the given id. + :param state_id: The unique id representing the state. """ pass @@ -700,6 +707,7 @@ def restore_physics_simulator_state(self, state_id: int) -> None: """ Restores the objects and environment state in the physics simulator according to the given state using the unique state id. + :param state_id: The unique id representing the state. """ pass @@ -790,6 +798,7 @@ def reset_world(self, remove_saved_states=True) -> None: All attached objects will be detached, all joints will be set to the default position of 0 and all objects will be set to the position and orientation in which they were spawned. + :param remove_saved_states: If the saved states should be removed. """ @@ -842,6 +851,7 @@ def ray_test_batch(self, from_positions: List[List[float]], to_positions: List[L def create_visual_shape(self, visual_shape: VisualShape) -> int: """ Creates a visual shape in the physics simulator and returns the unique id of the created shape. + :param visual_shape: The visual shape to be created, uses the VisualShape dataclass defined in world_dataclasses :return: The unique id of the created shape. """ @@ -851,6 +861,7 @@ def create_multi_body_from_visual_shapes(self, visual_shape_ids: List[int], pose """ Creates a multi body from visual shapes in the physics simulator and returns the unique id of the created multi body. + :param visual_shape_ids: The ids of the visual shapes that should be used to create the multi body. :param pose: The pose of the origin of the multi body relative to the world frame. :return: The unique id of the created multi body. @@ -877,6 +888,7 @@ def create_multi_body(self, multi_body: MultiBody) -> int: """ Creates a multi body in the physics simulator and returns the unique id of the created multi body. The multibody is created by joining multiple links/shapes together with joints. + :param multi_body: The multi body to be created, uses the MultiBody dataclass defined in world_dataclasses. :return: The unique id of the created multi body. """ @@ -885,8 +897,8 @@ def create_multi_body(self, multi_body: MultiBody) -> int: def create_box_visual_shape(self, shape_data: BoxVisualShape) -> int: """ Creates a box visual shape in the physics simulator and returns the unique id of the created shape. - :param shape_data: The parameters that define the box visual shape to be created, - uses the BoxVisualShape dataclass defined in world_dataclasses. + + :param shape_data: The parameters that define the box visual shape to be created, uses the BoxVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -894,8 +906,8 @@ def create_box_visual_shape(self, shape_data: BoxVisualShape) -> int: def create_cylinder_visual_shape(self, shape_data: CylinderVisualShape) -> int: """ Creates a cylinder visual shape in the physics simulator and returns the unique id of the created shape. - :param shape_data: The parameters that define the cylinder visual shape to be created, - uses the CylinderVisualShape dataclass defined in world_dataclasses. + + :param shape_data: The parameters that define the cylinder visual shape to be created, uses the CylinderVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -903,8 +915,8 @@ def create_cylinder_visual_shape(self, shape_data: CylinderVisualShape) -> int: def create_sphere_visual_shape(self, shape_data: SphereVisualShape) -> int: """ Creates a sphere visual shape in the physics simulator and returns the unique id of the created shape. - :param shape_data: The parameters that define the sphere visual shape to be created, - uses the SphereVisualShape dataclass defined in world_dataclasses. + + :param shape_data: The parameters that define the sphere visual shape to be created, uses the SphereVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -912,8 +924,8 @@ def create_sphere_visual_shape(self, shape_data: SphereVisualShape) -> int: def create_capsule_visual_shape(self, shape_data: CapsuleVisualShape) -> int: """ Creates a capsule visual shape in the physics simulator and returns the unique id of the created shape. - :param shape_data: The parameters that define the capsule visual shape to be created, - uses the CapsuleVisualShape dataclass defined in world_dataclasses. + + :param shape_data: The parameters that define the capsule visual shape to be created, uses the CapsuleVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -921,8 +933,8 @@ def create_capsule_visual_shape(self, shape_data: CapsuleVisualShape) -> int: def create_plane_visual_shape(self, shape_data: PlaneVisualShape) -> int: """ Creates a plane visual shape in the physics simulator and returns the unique id of the created shape. - :param shape_data: The parameters that define the plane visual shape to be created, - uses the PlaneVisualShape dataclass defined in world_dataclasses. + + :param shape_data: The parameters that define the plane visual shape to be created, uses the PlaneVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -930,8 +942,9 @@ def create_plane_visual_shape(self, shape_data: PlaneVisualShape) -> int: def create_mesh_visual_shape(self, shape_data: MeshVisualShape) -> int: """ Creates a mesh visual shape in the physics simulator and returns the unique id of the created shape. + :param shape_data: The parameters that define the mesh visual shape to be created, - uses the MeshVisualShape dataclass defined in world_dataclasses. + uses the MeshVisualShape dataclass defined in world_dataclasses. :return: The unique id of the created shape. """ raise NotImplementedError @@ -941,15 +954,13 @@ def add_text(self, text: str, position: List[float], orientation: Optional[List[ parent_object_id: Optional[int] = None, parent_link_id: Optional[int] = None) -> int: """ Adds text to the world. + :param text: The text to be added. :param position: The position of the text in the world. - :param orientation: By default, debug text will always face the camera, - automatically rotation. By specifying a text orientation (quaternion), the orientation will be fixed in - world space or local space (when parent is specified). + :param orientation: By default, debug text will always face the camera, automatically rotation. By specifying a text orientation (quaternion), the orientation will be fixed in world space or local space (when parent is specified). :param size: The size of the text. :param color: The color of the text. - :param life_time: The lifetime in seconds of the text to remain in the world, if 0 the text will remain - in the world until it is removed manually. + :param life_time: The lifetime in seconds of the text to remain in the world, if 0 the text will remain in the world until it is removed manually. :param parent_object_id: The id of the object to which the text should be attached. :param parent_link_id: The id of the link to which the text should be attached. :return: The id of the added text. @@ -959,6 +970,7 @@ def add_text(self, text: str, position: List[float], orientation: Optional[List[ def remove_text(self, text_id: Optional[int] = None) -> None: """ Removes text from the world using the given id. if no id is given all text will be removed. + :param text_id: The id of the text to be removed. """ raise NotImplementedError @@ -970,6 +982,7 @@ def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> N the fixed degrees of freedom: a fixed joint will measure all 6DOF joint forces/torques. A revolute/hinge joint force/torque sensor will measure 5DOF reaction forces along all axis except the hinge axis. The applied force by a joint motor is available through get_applied_joint_motor_torque. + :param obj: The object in which the joint is located. :param fts_joint_idx: The index of the joint for which the force torque sensor should be enabled. """ @@ -978,6 +991,7 @@ def enable_joint_force_torque_sensor(self, obj: Object, fts_joint_idx: int) -> N def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: """ Disables the force torque sensor of a joint. + :param obj: The object in which the joint is located. :param joint_id: The id of the joint for which the force torque sensor should be disabled. """ @@ -986,6 +1000,7 @@ def disable_joint_force_torque_sensor(self, obj: Object, joint_id: int) -> None: def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[float]: """ Returns the joint reaction forces and torques of the specified joint. + :param obj: The object in which the joint is located. :param joint_id: The id of the joint for which the force torque should be returned. :return: The joint reaction forces and torques of the specified joint. @@ -995,6 +1010,7 @@ def get_joint_reaction_force_torque(self, obj: Object, joint_id: int) -> List[fl def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: """ Returns the applied torque by a joint motor. + :param obj: The object in which the joint is located. :param joint_id: The id of the joint for which the applied motor torque should be returned. :return: The applied torque by a joint motor. @@ -1078,9 +1094,9 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): While this loop runs it continuously checks the cartesian and joint position of every object in the World and updates the corresponding object in the prospection world. When there are entries in the adding or removing queue the corresponding objects will - be added or removed in the same iteration. - :param wait_time_as_n_simulation_steps: The time in simulation steps to wait between each iteration of the - syncing loop. + be added or removed in the same iteration. + + :param wait_time_as_n_simulation_steps: The time in simulation steps to wait between each iteration of the syncing loop. """ while not self.terminate: self.check_for_pause() @@ -1119,6 +1135,7 @@ def check_for_equal(self) -> bool: """ Checks if both Worlds have the same state, meaning all objects are in the same position. This is currently not used, but might be used in the future if synchronization issues worsen. + :return: True if both Worlds have the same state, False otherwise. """ eql = True diff --git a/src/pycram/world_concepts/constraints.py b/src/pycram/world_concepts/constraints.py index 540155ff5..b05c34469 100644 --- a/src/pycram/world_concepts/constraints.py +++ b/src/pycram/world_concepts/constraints.py @@ -3,11 +3,11 @@ from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional, TYPE_CHECKING -from pycram.datastructures.enums import JointType -from pycram.datastructures.pose import Transform, Pose +from ..datastructures.enums import JointType +from ..datastructures.pose import Transform, Pose if TYPE_CHECKING: - from pycram.description import Link + from ..description import Link class AbstractConstraint: @@ -167,6 +167,7 @@ def __init__(self, """ Creates an attachment between the parent object link and the child object link. This could be a bidirectional attachment, meaning that both objects will move when one moves. + :param parent_link: The parent object link. :param child_link: The child object link. :param bidirectional: If true, both objects will move when one moves. @@ -244,6 +245,7 @@ def loose(self) -> bool: def loose(self, loose: bool) -> None: """ Sets the loose property of this attachment. + :param loose: If true, then the child object will not move when parent moves. """ self._loose = loose and not self.bidirectional diff --git a/src/pycram/world_concepts/costmaps.py b/src/pycram/world_concepts/costmaps.py index 2b2d03000..3314bf4a4 100644 --- a/src/pycram/world_concepts/costmaps.py +++ b/src/pycram/world_concepts/costmaps.py @@ -12,13 +12,13 @@ from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData -from pycram.world import UseProspectionWorld -from pycram.world_concepts.world_object import Object -from pycram.description import Link -from pycram.datastructures.local_transformer import LocalTransformer -from pycram.datastructures.pose import Pose, Transform -from pycram.world import World -from pycram.datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color +from ..world import UseProspectionWorld +from ..world_concepts.world_object import Object +from ..description import Link +from ..datastructures.local_transformer import LocalTransformer +from ..datastructures.pose import Pose, Transform +from ..world import World +from ..datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color @dataclass diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index 2d8cda257..703bdcfab 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -8,16 +8,16 @@ from geometry_msgs.msg import Point, Quaternion from typing_extensions import Type, Optional, Dict, Tuple, List, Union -from pycram.description import ObjectDescription, LinkDescription -from pycram.object_descriptors.urdf import ObjectDescription as URDFObject -from pycram.robot_descriptions import robot_description -from pycram.world import WorldEntity, World -from pycram.world_concepts.constraints import Attachment -from pycram.datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, +from ..description import ObjectDescription, LinkDescription +from ..object_descriptors.urdf import ObjectDescription as URDFObject +from ..robot_descriptions import robot_description +from ..world import WorldEntity, World +from ..world_concepts.constraints import Attachment +from ..datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape) -from pycram.datastructures.enums import ObjectType, JointType -from pycram.datastructures.local_transformer import LocalTransformer -from pycram.datastructures.pose import Pose, Transform +from ..datastructures.enums import ObjectType, JointType +from ..datastructures.local_transformer import LocalTransformer +from ..datastructures.pose import Pose, Transform Link = ObjectDescription.Link @@ -43,16 +43,14 @@ def __init__(self, name: str, obj_type: ObjectType, path: str, The constructor loads the description file into the given World, if no World is specified the :py:attr:`~World.current_world` will be used. It is also possible to load .obj and .stl file into the World. The rgba_color parameter is only used when loading .stl or .obj files, - for URDFs :func:`~Object.set_color` can be used. + for URDFs :func:`~Object.set_color` can be used. :param name: The name of the object :param obj_type: The type of the object as an ObjectType enum. - :param path: The path to the source file, if only a filename is provided then the resources directories will be - searched. + :param path: The path to the source file, if only a filename is provided then the resources directories will be searched. :param description: The ObjectDescription of the object, this contains the joints and links of the object. :param pose: The pose at which the Object should be spawned - :param world: The World in which the object should be spawned, - if no world is specified the :py:attr:`~World.current_world` will be used. + :param world: The World in which the object should be spawned, if no world is specified the :py:attr:`~World.current_world` will be used. :param color: The rgba_color with which the object should be spawned. :param ignore_cached_files: If true the file will be spawned while ignoring cached files. """ @@ -115,8 +113,7 @@ def _load_object_and_get_id(self, path: Optional[str] = None, This new file will have resolved mesh file paths, meaning there will be no references to ROS packges instead there will be absolute file paths. - :param path: The path to the description file, if None then no file will be loaded, this is useful when the - PyCRAM is not responsible for loading the file but another system is. + :param path: The path to the description file, if None then no file will be loaded, this is useful when the PyCRAM is not responsible for loading the file but another system is. :param ignore_cached_files: Whether to ignore files in the cache directory. :return: The unique id of the object and the path of the file that was loaded. """ @@ -206,9 +203,10 @@ def joint_names(self) -> List[str]: """ return self.world.get_object_joint_names(self) - def get_link(self, link_name: str) -> Link: + def get_link(self, link_name: str) -> ObjectDescription.Link: """ Returns the link object with the given name. + :param link_name: The name of the link. :return: The link object. """ @@ -217,6 +215,7 @@ def get_link(self, link_name: str) -> Link: def get_link_pose(self, link_name: str) -> Pose: """ Returns the pose of the link with the given name. + :param link_name: The name of the link. :return: The pose of the link. """ @@ -225,6 +224,7 @@ def get_link_pose(self, link_name: str) -> Pose: def get_link_position(self, link_name: str) -> Point: """ Returns the position of the link with the given name. + :param link_name: The name of the link. :return: The position of the link. """ @@ -233,6 +233,7 @@ def get_link_position(self, link_name: str) -> Point: def get_link_position_as_list(self, link_name: str) -> List[float]: """ Returns the position of the link with the given name. + :param link_name: The name of the link. :return: The position of the link. """ @@ -241,6 +242,7 @@ def get_link_position_as_list(self, link_name: str) -> List[float]: def get_link_orientation(self, link_name: str) -> Quaternion: """ Returns the orientation of the link with the given name. + :param link_name: The name of the link. :return: The orientation of the link. """ @@ -249,6 +251,7 @@ def get_link_orientation(self, link_name: str) -> Quaternion: def get_link_orientation_as_list(self, link_name: str) -> List[float]: """ Returns the orientation of the link with the given name. + :param link_name: The name of the link. :return: The orientation of the link. """ @@ -257,6 +260,7 @@ def get_link_orientation_as_list(self, link_name: str) -> List[float]: def get_link_tf_frame(self, link_name: str) -> str: """ Returns the tf frame of the link with the given name. + :param link_name: The name of the link. :return: The tf frame of the link. """ @@ -265,6 +269,7 @@ def get_link_tf_frame(self, link_name: str) -> str: def get_link_axis_aligned_bounding_box(self, link_name: str) -> AxisAlignedBoundingBox: """ Returns the axis aligned bounding box of the link with the given name. + :param link_name: The name of the link. :return: The axis aligned bounding box of the link. """ @@ -273,6 +278,7 @@ def get_link_axis_aligned_bounding_box(self, link_name: str) -> AxisAlignedBound def get_transform_between_links(self, from_link: str, to_link: str) -> Transform: """ Returns the transform between two links. + :param from_link: The name of the link from which the transform should be calculated. :param to_link: The name of the link to which the transform should be calculated. """ @@ -281,6 +287,7 @@ def get_transform_between_links(self, from_link: str, to_link: str) -> Transform def get_link_color(self, link_name: str) -> Color: """ Returns the color of the link with the given name. + :param link_name: The name of the link. :return: The color of the link. """ @@ -289,6 +296,7 @@ def get_link_color(self, link_name: str) -> Color: def set_link_color(self, link_name: str, color: List[float]) -> None: """ Sets the color of the link with the given name. + :param link_name: The name of the link. :param color: The new color of the link. """ @@ -297,6 +305,7 @@ def set_link_color(self, link_name: str, color: List[float]) -> None: def get_link_geometry(self, link_name: str) -> Union[VisualShape, None]: """ Returns the geometry of the link with the given name. + :param link_name: The name of the link. :return: The geometry of the link. """ @@ -305,6 +314,7 @@ def get_link_geometry(self, link_name: str) -> Union[VisualShape, None]: def get_link_transform(self, link_name: str) -> Transform: """ Returns the transform of the link with the given name. + :param link_name: The name of the link. :return: The transform of the link. """ @@ -313,6 +323,7 @@ def get_link_transform(self, link_name: str) -> Transform: def get_link_origin(self, link_name: str) -> Pose: """ Returns the origin of the link with the given name. + :param link_name: The name of the link. :return: The origin of the link as a 'Pose'. """ @@ -321,6 +332,7 @@ def get_link_origin(self, link_name: str) -> Pose: def get_link_origin_transform(self, link_name: str) -> Transform: """ Returns the origin transform of the link with the given name. + :param link_name: The name of the link. :return: The origin transform of the link. """ @@ -330,6 +342,7 @@ def get_link_origin_transform(self, link_name: str) -> Transform: def base_origin_shift(self) -> np.ndarray: """ The shift between the base of the object and the origin of the object. + :return: A numpy array with the shift between the base of the object and the origin of the object. """ return np.array(self.get_position_as_list()) - np.array(self.get_base_position_as_list()) @@ -354,6 +367,7 @@ def reset(self, remove_saved_states=True) -> None: All attached objects will be detached, all joints will be set to the default position of 0 and the object will be set to the position and orientation in which it was spawned. + :param remove_saved_states: If True the saved states will be removed. """ self.detach_all() @@ -511,6 +525,7 @@ def move_base_to_origin_pose(self) -> None: def save_state(self, state_id) -> None: """ Saves the state of this object by saving the state of all links and attachments. + :param state_id: The unique id of the state. """ self.save_links_states(state_id) @@ -520,6 +535,7 @@ def save_state(self, state_id) -> None: def save_links_states(self, state_id: int) -> None: """ Saves the state of all links of this object. + :param state_id: The unique id of the state. """ for link in self.links.values(): @@ -528,6 +544,7 @@ def save_links_states(self, state_id: int) -> None: def save_joints_states(self, state_id: int) -> None: """ Saves the state of all joints of this object. + :param state_id: The unique id of the state. """ for joint in self.joints.values(): @@ -549,6 +566,7 @@ def current_state(self, state: ObjectState) -> None: def link_states(self) -> Dict[int, LinkState]: """ Returns the current state of all links of this object. + :return: A dictionary with the link id as key and the current state of the link as value. """ return {link.id: link.current_state for link in self.links.values()} @@ -557,6 +575,7 @@ def link_states(self) -> Dict[int, LinkState]: def link_states(self, link_states: Dict[int, LinkState]) -> None: """ Sets the current state of all links of this object. + :param link_states: A dictionary with the link id as key and the current state of the link as value. """ for link in self.links.values(): @@ -566,6 +585,7 @@ def link_states(self, link_states: Dict[int, LinkState]) -> None: def joint_states(self) -> Dict[int, JointState]: """ Returns the current state of all joints of this object. + :return: A dictionary with the joint id as key and the current state of the joint as value. """ return {joint.id: joint.current_state for joint in self.joints.values()} @@ -574,6 +594,7 @@ def joint_states(self) -> Dict[int, JointState]: def joint_states(self, joint_states: Dict[int, JointState]) -> None: """ Sets the current state of all joints of this object. + :param joint_states: A dictionary with the joint id as key and the current state of the joint as value. """ for joint in self.joints.values(): @@ -609,8 +630,7 @@ def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Objec After this the _set_attached_objects method of all attached objects will be called. - :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent - loops in the update. + :param already_moved_objects: A list of Objects that were already moved, these will be excluded to prevent loops in the update. """ if already_moved_objects is None: @@ -635,7 +655,7 @@ def set_position(self, position: Union[Pose, Point], base=False) -> None: """ Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position instead of the origin in the center of the Object. The given position can either be a Pose, - in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. + in this case only the position is used or a geometry_msgs.msg/Point which is the position part of a Pose. :param position: Target position as xyz. :param base: If the bottom of the Object should be placed or the origin in the center. @@ -690,6 +710,7 @@ def get_joint_id(self, name: str) -> int: def get_root_link_description(self) -> LinkDescription: """ Returns the root link of the URDF of this object. + :return: The root link as defined in the URDF of this object. """ for link_description in self.description.links: @@ -697,9 +718,10 @@ def get_root_link_description(self) -> LinkDescription: return link_description @property - def root_link(self) -> Link: + def root_link(self) -> ObjectDescription.Link: """ Returns the root link of this object. + :return: The root link of this object. """ return self.links[self.description.get_root()] @@ -708,6 +730,7 @@ def root_link(self) -> Link: def root_link_name(self) -> str: """ Returns the name of the root link of this object. + :return: The name of the root link of this object. """ return self.description.get_root() @@ -715,6 +738,7 @@ def root_link_name(self) -> str: def get_root_link_id(self) -> int: """ Returns the unique id of the root link of this object. + :return: The unique id of the root link of this object. """ return self.get_link_id(self.description.get_root()) @@ -722,14 +746,16 @@ def get_root_link_id(self) -> int: def get_link_id(self, link_name: str) -> int: """ Returns a unique id for a link name. + :param link_name: The name of the link. :return: The unique id of the link. """ return self.link_name_to_id[link_name] - def get_link_by_id(self, link_id: int) -> Link: + def get_link_by_id(self, link_id: int) -> ObjectDescription.Link: """ Returns the link for a given unique link id + :param link_id: The unique id of the link. :return: The link object. """ @@ -746,7 +772,7 @@ def reset_all_joints_positions(self) -> None: def set_joint_positions(self, joint_poses: dict) -> None: """ Sets the current position of multiple joints at once, this method should be preferred when setting - multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. + multiple joints at once instead of running :func:`~Object.set_joint_position` in a loop. :param joint_poses: """ @@ -818,14 +844,14 @@ def get_joint_limits(self, joint_name: str) -> Tuple[float, float]: """ return self.joints[joint_name].limits - def get_joint_child_link(self, joint_name: str) -> Link: + def get_joint_child_link(self, joint_name: str) -> ObjectDescription.Link: """ :param joint_name: The name of the joint :return: The child link of the given joint """ return self.joints[joint_name].child_link - def get_joint_parent_link(self, joint_name: str) -> Link: + def get_joint_parent_link(self, joint_name: str) -> ObjectDescription.Link: """ :param joint_name: The name of the joint :return: The parent link of the given joint @@ -911,8 +937,7 @@ def get_color(self) -> Union[Color, Dict[str, Color]]: Please keep in mind that not every link may have a rgba_color. This is dependent on the URDF from which the object is spawned. - :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and - the rgba_color as value. + :return: The rgba_color as Color object with RGBA values between 0 and 1 or a dict with the link name as key and the rgba_color as value. """ link_to_color_dict = self.links_colors @@ -947,6 +972,7 @@ def get_base_origin(self) -> Pose: def __copy__(self) -> Object: """ Returns a copy of this object. The copy will have the same name, type, path, description, pose, world and color. + :return: A copy of this object. """ obj = Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(), diff --git a/src/pycram/world_reasoning.py b/src/pycram/world_reasoning.py index 7e7d89712..7d91fc3dd 100644 --- a/src/pycram/world_reasoning.py +++ b/src/pycram/world_reasoning.py @@ -3,11 +3,11 @@ import numpy as np -from pycram.external_interfaces.ik import try_to_reach, try_to_reach_with_grasp -from pycram.datastructures.pose import Pose, Transform -from pycram.robot_descriptions import robot_description -from pycram.world_concepts.world_object import Object -from pycram.world import World, UseProspectionWorld +from .external_interfaces.ik import try_to_reach, try_to_reach_with_grasp +from .datastructures.pose import Pose, Transform +from .robot_descriptions import robot_description +from .world_concepts.world_object import Object +from .world import World, UseProspectionWorld def stable(obj: Object) -> bool: @@ -70,10 +70,10 @@ def get_visible_objects( front_facing_axis: Optional[List[float]] = None) -> Tuple[np.ndarray, Pose]: """ Returns a segmentation mask of the objects that are visible from the given camera pose and the front facing axis. + :param camera_pose: The pose of the camera in world coordinate frame. :param front_facing_axis: The axis, of the camera frame, which faces to the front of the robot. Given as list of xyz - :return: A segmentation mask of the objects that are visible and the pose of the point at exactly 2 meters in front - of the camera in the direction of the front facing axis with respect to the world coordinate frame. + :return: A segmentation mask of the objects that are visible and the pose of the point at exactly 2 meters in front of the camera in the direction of the front facing axis with respect to the world coordinate frame. """ front_facing_axis = robot_description.front_facing_axis if not front_facing_axis else front_facing_axis @@ -223,8 +223,7 @@ def blocking( :param robot: The robot Object who reaches for the object :param gripper_name: The name of the end effector of the robot :param grasp: The grasp type with which the object should be grasped - :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose - or object is not reachable. + :return: A list of objects the robot is in collision with when reaching for the specified object or None if the pose or object is not reachable. """ prospection_robot = World.current_world.get_prospection_object_for_object(robot) diff --git a/src/pycram/worlds/bullet_world.py b/src/pycram/worlds/bullet_world.py index 0013a52d5..f702967b1 100755 --- a/src/pycram/worlds/bullet_world.py +++ b/src/pycram/worlds/bullet_world.py @@ -11,13 +11,13 @@ from geometry_msgs.msg import Point from typing_extensions import List, Optional, Dict -from pycram.datastructures.enums import ObjectType, WorldMode, JointType -from pycram.datastructures.pose import Pose -from pycram.object_descriptors.urdf import ObjectDescription -from pycram.world import World -from pycram.world_concepts.constraints import Constraint -from pycram.datastructures.dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape -from pycram.world_concepts.world_object import Object +from ..datastructures.enums import ObjectType, WorldMode, JointType +from ..datastructures.pose import Pose +from ..object_descriptors.urdf import ObjectDescription +from ..world import World +from ..world_concepts.constraints import Constraint +from ..datastructures.dataclasses import Color, AxisAlignedBoundingBox, MultiBody, VisualShape, BoxVisualShape +from ..world_concepts.world_object import Object Link = ObjectDescription.Link RootLink = ObjectDescription.RootLink @@ -99,14 +99,14 @@ def add_constraint(self, constraint: Constraint) -> int: def remove_constraint(self, constraint_id): p.removeConstraint(constraint_id, physicsClientId=self.id) - def get_joint_position(self, joint: Joint) -> float: + def get_joint_position(self, joint: ObjectDescription.Joint) -> float: return p.getJointState(joint.object_id, joint.id, physicsClientId=self.id)[0] def get_object_joint_names(self, obj: Object) -> List[str]: return [p.getJointInfo(obj.id, i, physicsClientId=self.id)[1].decode('utf-8') for i in range(self.get_object_number_of_joints(obj))] - def get_link_pose(self, link: Link) -> Pose: + def get_link_pose(self, link: ObjectDescription.Link) -> Pose: bullet_link_state = p.getLinkState(link.object_id, link.id, physicsClientId=self.id) return Pose(*bullet_link_state[4:6]) @@ -136,7 +136,7 @@ def get_contact_points_between_two_objects(self, obj1: Object, obj2: Object) -> self.perform_collision_detection() return p.getContactPoints(obj1.id, obj2.id, physicsClientId=self.id) - def reset_joint_position(self, joint: Joint, joint_position: str) -> None: + def reset_joint_position(self, joint: ObjectDescription.Joint, joint_position: str) -> None: p.resetJointState(joint.object_id, joint.id, joint_position, physicsClientId=self.id) def reset_object_base_pose(self, obj: Object, pose: Pose) -> None: @@ -149,10 +149,10 @@ def step(self): def get_object_pose(self, obj: Object) -> Pose: return Pose(*p.getBasePositionAndOrientation(obj.id, physicsClientId=self.id)) - def set_link_color(self, link: Link, rgba_color: Color): + def set_link_color(self, link: ObjectDescription.Link, rgba_color: Color): p.changeVisualShape(link.object_id, link.id, rgbaColor=rgba_color.get_rgba(), physicsClientId=self.id) - def get_link_color(self, link: Link) -> Color: + def get_link_color(self, link: ObjectDescription.Link) -> Color: return self.get_colors_of_object_links(link.object)[link.name] def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: @@ -166,7 +166,7 @@ def get_colors_of_object_links(self, obj: Object) -> Dict[str, Color]: def get_object_axis_aligned_bounding_box(self, obj: Object) -> AxisAlignedBoundingBox: return AxisAlignedBoundingBox.from_min_max(*p.getAABB(obj.id, physicsClientId=self.id)) - def get_link_axis_aligned_bounding_box(self, link: Link) -> AxisAlignedBoundingBox: + def get_link_axis_aligned_bounding_box(self, link: ObjectDescription.Link) -> AxisAlignedBoundingBox: return AxisAlignedBoundingBox.from_min_max(*p.getAABB(link.object_id, link.id, physicsClientId=self.id)) def set_realtime(self, real_time: bool) -> None: @@ -322,7 +322,7 @@ def get_applied_joint_motor_torque(self, obj: Object, joint_id: int) -> float: class Gui(threading.Thread): """ For internal use only. Creates a new thread for the physics simulation that is active until closed by - :func:`~World.exit` + :func:`~World.exit` Also contains the code for controlling the camera. """ From 85eddde1cb76bf9fa1652f7a7ca493754e666742 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Mon, 8 Apr 2024 12:22:48 +0200 Subject: [PATCH 170/195] [tests] Fixed tests with independend paths --- requirements-resolver.txt | 1 - src/pycram/datastructures/dataclasses.py | 4 ++-- src/pycram/datastructures/local_transformer.py | 2 +- test/test_cache_manager.py | 4 +++- test/test_description.py | 8 ++++++-- test/test_object.py | 5 +++-- 6 files changed, 15 insertions(+), 9 deletions(-) diff --git a/requirements-resolver.txt b/requirements-resolver.txt index 0425b4650..4eb2a63a3 100644 --- a/requirements-resolver.txt +++ b/requirements-resolver.txt @@ -1,4 +1,3 @@ -r requirements.txt probabilistic_model>=4.0.8 random_events>=2.0.9 -tqdm diff --git a/src/pycram/datastructures/dataclasses.py b/src/pycram/datastructures/dataclasses.py index a97abda86..d83bcd00f 100644 --- a/src/pycram/datastructures/dataclasses.py +++ b/src/pycram/datastructures/dataclasses.py @@ -2,8 +2,8 @@ from dataclasses import dataclass from typing_extensions import List, Optional, Tuple, Callable, Dict, Any, Union, TYPE_CHECKING -from .datastructures.enums import JointType, Shape -from .datastructures.pose import Pose, Point +from .enums import JointType, Shape +from .pose import Pose, Point from abc import ABC, abstractmethod if TYPE_CHECKING: diff --git a/src/pycram/datastructures/local_transformer.py b/src/pycram/datastructures/local_transformer.py index e045d0148..87a87003f 100644 --- a/src/pycram/datastructures/local_transformer.py +++ b/src/pycram/datastructures/local_transformer.py @@ -9,7 +9,7 @@ from rospy import Duration from geometry_msgs.msg import TransformStamped -from .datastructures.pose import Pose, Transform +from .pose import Pose, Transform from typing_extensions import List, Optional, Union, Iterable diff --git a/test/test_cache_manager.py b/test/test_cache_manager.py index 0a4ac8524..bad803f22 100644 --- a/test/test_cache_manager.py +++ b/test/test_cache_manager.py @@ -3,13 +3,15 @@ from bullet_world_testcase import BulletWorldTestCase from pycram.datastructures.enums import ObjectType from pycram.world_concepts.world_object import Object +import pathlib class TestCacheManager(BulletWorldTestCase): def test_generate_description_and_write_to_cache(self): cache_manager = self.world.cache_manager - path = "../resources/apartment.urdf" + file_path = pathlib.Path(__file__).parent.resolve() + path = str(file_path) + "/../resources/apartment.urdf" extension = Path(path).suffix cache_path = self.world.cache_dir + "apartment.urdf" apartment = Object("apartment", ObjectType.ENVIRONMENT, path) diff --git a/test/test_description.py b/test/test_description.py index e1c62ccbf..a0d12b3b2 100644 --- a/test/test_description.py +++ b/test/test_description.py @@ -1,3 +1,5 @@ +import pathlib + from bullet_world_testcase import BulletWorldTestCase @@ -19,9 +21,11 @@ def test_joint_child_link(self): self.assertEqual(self.robot.get_joint_parent_link("base_footprint_joint"), self.robot.root_link) def test_generate_description_from_mesh(self): - self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.stl", + file_path = pathlib.Path(__file__).parent.resolve() + self.assertTrue(self.milk.description.generate_description_from_file(str(file_path) + "/../resources/cached/milk.stl", "milk", ".stl")) def test_generate_description_from_description_file(self): - self.assertTrue(self.milk.description.generate_description_from_file("../resources/cached/milk.urdf", + file_path = pathlib.Path(__file__).parent.resolve() + self.assertTrue(self.milk.description.generate_description_from_file(str(file_path) + "/../resources/cached/milk.urdf", "milk", ".urdf")) diff --git a/test/test_object.py b/test/test_object.py index 5c71fc347..b024526c1 100644 --- a/test/test_object.py +++ b/test/test_object.py @@ -8,7 +8,7 @@ from pycram.world_concepts.world_object import Object from geometry_msgs.msg import Point, Quaternion - +import pathlib class TestObject(BulletWorldTestCase): @@ -17,7 +17,8 @@ def test_wrong_object_description_path(self): milk = Object("milk2", ObjectType.MILK, "wrong_path.sk") def test_malformed_object_description(self): - malformed_file = "../resources/cached/malformed_description.urdf" + file_path = pathlib.Path(__file__).parent.resolve() + malformed_file = str(file_path) + "/../resources/cached/malformed_description.urdf" with open(malformed_file, "w") as file: file.write("malformed") with self.assertRaises(Exception): From 2c47f2cf3bdeab6220798b5d266fbaa8ff641cc2 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 9 Apr 2024 10:58:06 +0200 Subject: [PATCH 171/195] [world] reset_current_world now has the correct behaviour --- src/pycram/world.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 7a77c7061..ac1c58002 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -589,9 +589,10 @@ def exit(self) -> None: """ self.exit_prospection_world_if_exists() self.disconnect_from_physics_server() - self.reset_current_world() self.reset_robot() self.join_threads() + if World.current_world == self: + World.current_world = None def exit_prospection_world_if_exists(self) -> None: """ @@ -610,10 +611,11 @@ def disconnect_from_physics_server(self) -> None: def reset_current_world(self) -> None: """ - Resets the current world to None if this is the current world. + Resets the pose of every object in the World to the pose it was spawned in and sets every joint to 0. """ - if World.current_world == self: - World.current_world = None + for obj in self.objects: + obj.set_pose(obj.original_pose) + obj.set_joint_positions(dict(zip(list(obj.joint_names), [0] * len(obj.joint_names)))) def reset_robot(self) -> None: """ From e414c19cddd9caae1f4b147b2caca49b56079584 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 9 Apr 2024 11:24:20 +0200 Subject: [PATCH 172/195] [refactor] moved local_transformer and costmaps to top-level --- src/pycram/{world_concepts => }/costmaps.py | 14 +++++++------- src/pycram/description.py | 2 +- src/pycram/designator.py | 9 ++++----- src/pycram/designators/actions/actions.py | 11 +++++------ src/pycram/designators/location_designator.py | 10 +++++----- src/pycram/external_interfaces/ik.py | 2 +- src/pycram/external_interfaces/robokudo.py | 2 +- .../{datastructures => }/local_transformer.py | 2 +- src/pycram/pose_generator_and_validator.py | 4 ++-- src/pycram/process_modules/boxy_process_modules.py | 3 +-- .../process_modules/default_process_modules.py | 9 ++------- .../process_modules/donbot_process_modules.py | 3 +-- src/pycram/process_modules/hsr_process_modules.py | 11 +++-------- src/pycram/process_modules/pr2_process_modules.py | 13 ++++++------- src/pycram/resolver/location/database_location.py | 3 +-- .../resolver/probabilistic/probabilistic_action.py | 7 +++---- src/pycram/world.py | 2 +- src/pycram/world_concepts/world_object.py | 2 +- test/test_action_designator.py | 2 +- test/test_costmaps.py | 2 +- test/test_local_transformer.py | 2 +- 21 files changed, 49 insertions(+), 66 deletions(-) rename src/pycram/{world_concepts => }/costmaps.py (99%) rename src/pycram/{datastructures => }/local_transformer.py (99%) diff --git a/src/pycram/world_concepts/costmaps.py b/src/pycram/costmaps.py similarity index 99% rename from src/pycram/world_concepts/costmaps.py rename to src/pycram/costmaps.py index 3314bf4a4..07a061146 100644 --- a/src/pycram/world_concepts/costmaps.py +++ b/src/pycram/costmaps.py @@ -12,13 +12,13 @@ from matplotlib import colors from nav_msgs.msg import OccupancyGrid, MapMetaData -from ..world import UseProspectionWorld -from ..world_concepts.world_object import Object -from ..description import Link -from ..datastructures.local_transformer import LocalTransformer -from ..datastructures.pose import Pose, Transform -from ..world import World -from ..datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color +from .world import UseProspectionWorld +from .world_concepts.world_object import Object +from .description import Link +from .local_transformer import LocalTransformer +from .datastructures.pose import Pose, Transform +from .world import World +from .datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color @dataclass diff --git a/src/pycram/description.py b/src/pycram/description.py index 826a08af0..a4accfc15 100644 --- a/src/pycram/description.py +++ b/src/pycram/description.py @@ -9,7 +9,7 @@ from typing_extensions import Tuple, Union, Any, List, Optional, Dict, TYPE_CHECKING from .datastructures.enums import JointType -from .datastructures.local_transformer import LocalTransformer +from .local_transformer import LocalTransformer from .datastructures.pose import Pose, Transform from .world import WorldEntity from .datastructures.dataclasses import JointState, AxisAlignedBoundingBox, Color, LinkState, VisualShape diff --git a/src/pycram/designator.py b/src/pycram/designator.py index b023cbe24..385ac8a7a 100644 --- a/src/pycram/designator.py +++ b/src/pycram/designator.py @@ -10,17 +10,16 @@ from .world import World from .world_concepts.world_object import Object as WorldObject -from .datastructures.enums import ObjectType from .helper import GeneratorList, bcolors from threading import Lock from time import time -from typing_extensions import List, Dict, Any, Optional, Union, get_type_hints, Callable, Iterable +from typing_extensions import List, Dict, Any, Optional, Union, Callable, Iterable -from pycram.datastructures.local_transformer import LocalTransformer +from .local_transformer import LocalTransformer from .language import Language -from pycram.datastructures.pose import Pose +from .datastructures.pose import Pose from .robot_descriptions import robot_description -from pycram.datastructures.enums import ObjectType +from .datastructures.enums import ObjectType import logging diff --git a/src/pycram/designators/actions/actions.py b/src/pycram/designators/actions/actions.py index 6ad3262bf..73fbc1451 100644 --- a/src/pycram/designators/actions/actions.py +++ b/src/pycram/designators/actions/actions.py @@ -1,23 +1,22 @@ import abc import inspect -import time import numpy as np from tf import transformations from typing_extensions import Union, Type -from pycram.designator import ActionDesignatorDescription -from pycram.designators.motion_designator import * +from ...designator import ActionDesignatorDescription +from ..motion_designator import * from ...datastructures.pose import Pose from ...datastructures.enums import Arms, Grasp -from pycram.task import with_tree +from ...task import with_tree from dataclasses import dataclass, field from ..location_designator import CostmapLocation from ..object_designator import BelieveObject # from ...bullet_world import BulletWorld from ...helper import multiply_quaternions -from ...datastructures.local_transformer import LocalTransformer +from ...local_transformer import LocalTransformer from ...orm.base import Pose as ORMPose -from ...orm.object_designator import Object as ORMObject, ObjectPart as ORMObjectPart +from ...orm.object_designator import Object as ORMObject from ...orm.action_designator import Action as ORMAction from ...plan_failures import ObjectUnfetchable, ReachabilityFailure from ...robot_descriptions import robot_description diff --git a/src/pycram/designators/location_designator.py b/src/pycram/designators/location_designator.py index ccb1bb716..13f5e8e2c 100644 --- a/src/pycram/designators/location_designator.py +++ b/src/pycram/designators/location_designator.py @@ -2,16 +2,16 @@ from typing_extensions import List, Union, Iterable, Optional, Callable from .object_designator import ObjectDesignatorDescription, ObjectPart -from pycram.world import World, UseProspectionWorld -from pycram.world_reasoning import link_pose_for_joint_config +from ..world import World, UseProspectionWorld +from ..world_reasoning import link_pose_for_joint_config from ..designator import DesignatorError, LocationDesignatorDescription -from pycram.world_concepts.costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap +from ..costmaps import OccupancyCostmap, VisibilityCostmap, SemanticCostmap, GaussianCostmap from ..robot_descriptions import robot_description -from pycram.datastructures.enums import JointType +from ..datastructures.enums import JointType from ..helper import transform from ..pose_generator_and_validator import PoseGenerator, visibility_validator, reachability_validator from ..robot_description import ManipulatorDescription -from pycram.datastructures.pose import Pose +from ..datastructures.pose import Pose class Location(LocationDesignatorDescription): diff --git a/src/pycram/external_interfaces/ik.py b/src/pycram/external_interfaces/ik.py index f448d50f3..a6c73f328 100644 --- a/src/pycram/external_interfaces/ik.py +++ b/src/pycram/external_interfaces/ik.py @@ -8,7 +8,7 @@ from pycram.world_concepts.world_object import Object from ..helper import calculate_wrist_tool_offset, _apply_ik -from pycram.datastructures.local_transformer import LocalTransformer +from pycram.local_transformer import LocalTransformer from pycram.datastructures.pose import Pose from ..robot_descriptions import robot_description from ..plan_failures import IKError diff --git a/src/pycram/external_interfaces/robokudo.py b/src/pycram/external_interfaces/robokudo.py index a502cac99..5f41af46b 100644 --- a/src/pycram/external_interfaces/robokudo.py +++ b/src/pycram/external_interfaces/robokudo.py @@ -7,7 +7,7 @@ from ..designator import ObjectDesignatorDescription from pycram.datastructures.pose import Pose -from pycram.datastructures.local_transformer import LocalTransformer +from pycram.local_transformer import LocalTransformer from pycram.world import World from pycram.datastructures.enums import ObjectType diff --git a/src/pycram/datastructures/local_transformer.py b/src/pycram/local_transformer.py similarity index 99% rename from src/pycram/datastructures/local_transformer.py rename to src/pycram/local_transformer.py index 87a87003f..e045d0148 100644 --- a/src/pycram/datastructures/local_transformer.py +++ b/src/pycram/local_transformer.py @@ -9,7 +9,7 @@ from rospy import Duration from geometry_msgs.msg import TransformStamped -from .pose import Pose, Transform +from .datastructures.pose import Pose, Transform from typing_extensions import List, Optional, Union, Iterable diff --git a/src/pycram/pose_generator_and_validator.py b/src/pycram/pose_generator_and_validator.py index f870ef77e..4582699cc 100644 --- a/src/pycram/pose_generator_and_validator.py +++ b/src/pycram/pose_generator_and_validator.py @@ -4,8 +4,8 @@ from .world import World from .world_concepts.world_object import Object from .world_reasoning import contact -from .world_concepts.costmaps import Costmap -from .datastructures.local_transformer import LocalTransformer +from .costmaps import Costmap +from .local_transformer import LocalTransformer from .datastructures.pose import Pose, Transform from .robot_description import ManipulatorDescription from .robot_descriptions import robot_description diff --git a/src/pycram/process_modules/boxy_process_modules.py b/src/pycram/process_modules/boxy_process_modules.py index 0f133e773..e33570e52 100644 --- a/src/pycram/process_modules/boxy_process_modules.py +++ b/src/pycram/process_modules/boxy_process_modules.py @@ -5,10 +5,9 @@ from ..designators.motion_designator import * from ..datastructures.enums import JointType from ..external_interfaces.ik import request_ik -from ..datastructures.local_transformer import LocalTransformer from ..world import World -from ..datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description diff --git a/src/pycram/process_modules/default_process_modules.py b/src/pycram/process_modules/default_process_modules.py index 588b5661d..fcd10ed05 100644 --- a/src/pycram/process_modules/default_process_modules.py +++ b/src/pycram/process_modules/default_process_modules.py @@ -5,14 +5,9 @@ from ..datastructures.enums import JointType from ..external_interfaces.ik import request_ik from ..helper import _apply_ik -from ..process_module import ProcessModule, ProcessModuleManager -# from ..process_modules.pr2_process_modules import Pr2Navigation as DefaultNavigation, Pr2PickUp as DefaultPickUp, \ -# Pr2Place as DefaultPlace, Pr2WorldStateDetecting as DefaultWorldStateDetecting, Pr2Open as DefaultOpen, \ -# Pr2Close as DefaultClose, Pr2MoveGripper as DefaultMoveGripper, Pr2Detecting as DefaultDetecting, \ -# Pr2MoveTCP as DefaultMoveTCP +from ..process_module import ProcessModule from ..robot_descriptions import robot_description -from ..world import World -from ..datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..designators.motion_designator import * from ..world_reasoning import visible, link_pose_for_joint_config diff --git a/src/pycram/process_modules/donbot_process_modules.py b/src/pycram/process_modules/donbot_process_modules.py index 337318a2a..f612f89d1 100644 --- a/src/pycram/process_modules/donbot_process_modules.py +++ b/src/pycram/process_modules/donbot_process_modules.py @@ -1,11 +1,10 @@ from threading import Lock import numpy as np -from typing_extensions import Optional from ..worlds.bullet_world import World from ..designators.motion_designator import MoveArmJointsMotion, WorldStateDetectingMotion -from ..datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..process_module import ProcessModule, ProcessModuleManager from ..robot_descriptions import robot_description from ..process_modules.pr2_process_modules import Pr2Detecting as DonbotDetecting, _move_arm_tcp diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsr_process_modules.py index 52846d20a..3f02d466c 100644 --- a/src/pycram/process_modules/hsr_process_modules.py +++ b/src/pycram/process_modules/hsr_process_modules.py @@ -3,19 +3,14 @@ from threading import Lock from typing import Any -from typing_extensions import Optional - from ..datastructures.enums import JointType from ..robot_descriptions import robot_description -from ..process_module import ProcessModule, ProcessModuleManager -from ..world import World -from ..datastructures.pose import Pose, Point +from ..process_module import ProcessModule +from ..datastructures.pose import Point from ..helper import _apply_ik from ..external_interfaces.ik import request_ik from .. import world_reasoning as btr -import logging -import time -from ..datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..designators.motion_designator import * from ..external_interfaces import giskard diff --git a/src/pycram/process_modules/pr2_process_modules.py b/src/pycram/process_modules/pr2_process_modules.py index 29dcd41fe..0b0d0bede 100644 --- a/src/pycram/process_modules/pr2_process_modules.py +++ b/src/pycram/process_modules/pr2_process_modules.py @@ -1,6 +1,5 @@ from threading import Lock -from typing_extensions import Any, Optional, Tuple -from abc import abstractmethod +from typing_extensions import Any import actionlib @@ -12,16 +11,16 @@ from ..process_module import ProcessModule, ProcessModuleManager from ..external_interfaces.ik import request_ik from ..helper import _apply_ik -from pycram.datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..designators.object_designator import ObjectDesignatorDescription from ..designators.motion_designator import MoveMotion, LookingMotion, \ DetectingMotion, MoveTCPMotion, MoveArmJointsMotion, WorldStateDetectingMotion, MoveJointsMotion, \ MoveGripperMotion, OpeningMotion, ClosingMotion from ..robot_descriptions import robot_description -from pycram.world import World -from pycram.world_concepts.world_object import Object -from pycram.datastructures.pose import Pose -from pycram.datastructures.enums import JointType, ObjectType +from ..world import World +from ..world_concepts.world_object import Object +from ..datastructures.pose import Pose +from ..datastructures.enums import JointType, ObjectType from ..external_interfaces import giskard from ..external_interfaces.robokudo import query diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index d84625e9d..74f59bcc7 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -1,12 +1,11 @@ from dataclasses import dataclass -import numpy as np import sqlalchemy.orm import sqlalchemy.sql from sqlalchemy import select, Select from typing_extensions import List -from ...world_concepts.costmaps import Rectangle, OccupancyCostmap +from ...costmaps import Rectangle, OccupancyCostmap from ...designator import LocationDesignatorDescription from ...designators.location_designator import CostmapLocation from ...orm.action_designator import PickUpAction diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index 428232bbe..2a75da2c2 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -4,23 +4,22 @@ import portion from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution from probabilistic_model.probabilistic_circuit.probabilistic_circuit import ProbabilisticCircuit, \ - DecomposableProductUnit, DeterministicSumUnit + DecomposableProductUnit from random_events.events import Event, ComplexEvent from random_events.variables import Symbolic, Continuous import tqdm from typing_extensions import Optional, List, Iterator from ...world import World -from ...world_concepts.costmaps import OccupancyCostmap, VisibilityCostmap +from ...costmaps import OccupancyCostmap, VisibilityCostmap from ...designator import ActionDesignatorDescription, ObjectDesignatorDescription from ...designators.actions.actions import MoveAndPickUpPerformable, ActionAbstract from ...datastructures.enums import Arms, Grasp, TaskStatus -from ...datastructures.local_transformer import LocalTransformer +from ...local_transformer import LocalTransformer from ...orm.queries.queries import PickUpWithContext from ...orm.task import TaskTreeNode from ...orm.action_designator import PickUpAction as ORMPickUpAction from ...plan_failures import ObjectUnreachable, PlanFailure from ...datastructures.pose import Pose -import plotly.graph_objects as go class ProbabilisticAction: diff --git a/src/pycram/world.py b/src/pycram/world.py index ac1c58002..ffab6bd15 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -17,7 +17,7 @@ from .cache_manager import CacheManager from .datastructures.enums import JointType, ObjectType, WorldMode from .world_concepts.event import Event -from .datastructures.local_transformer import LocalTransformer +from .local_transformer import LocalTransformer from .datastructures.pose import Pose, Transform from .world_concepts.constraints import Constraint from .datastructures.dataclasses import (Color, AxisAlignedBoundingBox, CollisionCallbacks, diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index 703bdcfab..a7b43a28f 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -16,7 +16,7 @@ from ..datastructures.dataclasses import (Color, ObjectState, LinkState, JointState, AxisAlignedBoundingBox, VisualShape) from ..datastructures.enums import ObjectType, JointType -from ..datastructures.local_transformer import LocalTransformer +from ..local_transformer import LocalTransformer from ..datastructures.pose import Pose, Transform Link = ObjectDescription.Link diff --git a/test/test_action_designator.py b/test/test_action_designator.py index af915b4cf..af5708b09 100644 --- a/test/test_action_designator.py +++ b/test/test_action_designator.py @@ -2,7 +2,7 @@ from pycram.designators import action_designator, object_designator from pycram.designators.actions.actions import MoveTorsoActionPerformable, PickUpActionPerformable, \ NavigateActionPerformable, FaceAtPerformable -from pycram.datastructures.local_transformer import LocalTransformer +from pycram.local_transformer import LocalTransformer from pycram.robot_descriptions import robot_description from pycram.process_module import simulated_robot from pycram.datastructures.pose import Pose diff --git a/test/test_costmaps.py b/test/test_costmaps.py index b46f1fede..0623645cc 100644 --- a/test/test_costmaps.py +++ b/test/test_costmaps.py @@ -5,7 +5,7 @@ from random_events.events import Event, ComplexEvent from bullet_world_testcase import BulletWorldTestCase -from pycram.world_concepts.costmaps import OccupancyCostmap +from pycram.costmaps import OccupancyCostmap from pycram.datastructures.pose import Pose diff --git a/test/test_local_transformer.py b/test/test_local_transformer.py index e64682d0d..283c8f31c 100644 --- a/test/test_local_transformer.py +++ b/test/test_local_transformer.py @@ -1,7 +1,7 @@ import rospy -from pycram.datastructures.local_transformer import LocalTransformer +from pycram.local_transformer import LocalTransformer from pycram.datastructures.pose import Pose, Transform from bullet_world_testcase import BulletWorldTestCase From 5bc624787ef401bcaeae681f52d0cf7840932c08 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Tue, 9 Apr 2024 13:38:49 +0200 Subject: [PATCH 173/195] [orm] created database views --- src/pycram/orm/queries/__init__.py | 0 src/pycram/orm/queries/queries.py | 51 ------ src/pycram/orm/views.py | 149 ++++++++++++++++++ .../resolver/location/database_location.py | 31 ++-- .../probabilistic/probabilistic_action.py | 12 +- test/test_orm.py | 63 +++++++- 6 files changed, 225 insertions(+), 81 deletions(-) delete mode 100644 src/pycram/orm/queries/__init__.py delete mode 100644 src/pycram/orm/queries/queries.py create mode 100644 src/pycram/orm/views.py diff --git a/src/pycram/orm/queries/__init__.py b/src/pycram/orm/queries/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/src/pycram/orm/queries/queries.py b/src/pycram/orm/queries/queries.py deleted file mode 100644 index 7854b8c54..000000000 --- a/src/pycram/orm/queries/queries.py +++ /dev/null @@ -1,51 +0,0 @@ -import sqlalchemy.orm -from sqlalchemy import Select, alias -from ..task import TaskTreeNode -from ..action_designator import PickUpAction -from ..base import Position, RobotState, Pose -from ..object_designator import Object - - -class Query: - """ - Abstract class for queries - """ - - -class PickUpWithContext(Query): - """ - Query for pickup actions with context. - """ - - robot_position = sqlalchemy.orm.aliased(Position) - """ - 3D Vector of robot position - """ - - robot_pose = sqlalchemy.orm.aliased(Pose) - """ - Complete robot pose - """ - - object_position = sqlalchemy.orm.aliased(Position) - """ - 3D Vector for object position - """ - - relative_x = (robot_position.x - object_position.x).label("relative_x") - """ - Distance on x axis between robot and object - """ - - relative_y = (robot_position.y - object_position.y).label("relative_y") - """ - Distance on y axis between robot and object - """ - - def join_statement(self, query: Select): - return (query.join(TaskTreeNode).join(TaskTreeNode.action.of_type(PickUpAction)) - .join(PickUpAction.robot_state).join(self.robot_pose, RobotState.pose) - .join(self.robot_position, self.robot_pose.position) - .join(Pose.orientation) - .join(PickUpAction.object) - .join(Object.pose).join(self.object_position, Pose.position)) diff --git a/src/pycram/orm/views.py b/src/pycram/orm/views.py new file mode 100644 index 000000000..352b3c304 --- /dev/null +++ b/src/pycram/orm/views.py @@ -0,0 +1,149 @@ +from sqlalchemy.orm import declarative_base, column_property, query_expression, deferred, contains_eager +from typing_extensions import Union +import sqlalchemy.orm +from sqlalchemy import table, inspect, event, select, engine, MetaData, Select, TableClause, ExecutableDDLElement +from sqlalchemy.ext.compiler import compiles +from pycram.orm.action_designator import PickUpAction, Action +from pycram.orm.base import Position, RobotState, Pose, Base, Quaternion, _Base +from pycram.orm.object_designator import Object +from pycram.orm.task import TaskTreeNode + + +class CreateView(ExecutableDDLElement): + """ + Class that is used to create a view. Every instance will be compiled into a SQL CREATE VIEW statement. + """ + + def __init__(self, name: str, selectable: Select): + self.name = name + self.selectable = selectable + + +class DropView(ExecutableDDLElement): + """ + Class that is used to drop a view. Every instance will be compiled into a SQL DROP VIEW statement. + """ + + def __init__(self, name: str): + self.name = name + + +@compiles(CreateView) +def _create_view(element: CreateView, compiler, **kw) -> str: + """ + Compiles a CreateView instance into a SQL CREATE VIEW statement. + :param element: CreateView instance + :param compiler: compiler + :param kw: keyword arguments + :return: SQL CREATE VIEW statement + """ + + return "CREATE VIEW %s AS %s" % ( + element.name, + compiler.sql_compiler.process(element.selectable, literal_binds=True), + ) + + +@compiles(DropView) +def _drop_view(element: DropView, compiler, **kw) -> str: + """ + Compiles a DropView instance into a SQL DROP VIEW statement. + :param element: DropView instance + :param compiler: compiler + :param kw: keyword arguments + :return: SQL DROP VIEW statement + """ + return "DROP VIEW %s" % element.name + + +def view_exists(ddl: Union[CreateView, DropView], target, connection: engine, **kw) -> bool: + """ + Check if a view exists. + :param ddl: ddl instance + :param target: target object + :param connection: connection + :param kw: keyword arguments + :return: True if the view exists, False otherwise + """ + + return ddl.name in inspect(connection).get_view_names() + + +def view_doesnt_exist(ddl: Union[CreateView, DropView], target, connection: engine, **kw) -> bool: + """ + Check if a view does not exist. + :param ddl: ddl instance + :param target: target object + :param connection: connection + :param kw: keyword arguments + :return: True if the view does not exist, False otherwise + """ + + return not view_exists(ddl, target, connection, **kw) + + +def view(name: str, metadata: MetaData, selectable: Select) -> TableClause: + """ + Function used to control view creation and deletion. It will listen to the after_create and before_drop events + of the metadata object in order to either create or drop the view. The view needs to have a column id. + """ + view = table(name) + + view._columns._populate_separate_keys( + col._make_proxy(view) for col in selectable.selected_columns + ) + + event.listen(metadata, "after_create", CreateView(name, selectable).execute_if(callable_=view_doesnt_exist)) + event.listen(metadata, "before_drop", DropView(name).execute_if(callable_=view_exists)) + + return view + + +base = declarative_base(metadata=Base.metadata) + + +class PickUpWithContextView(base): + """ + View for pickup actions with context. + """ + + __robot_position: Position = sqlalchemy.orm.aliased(Position, flat=True) + """ + 3D Vector of robot position + """ + + __robot_pose: Pose = sqlalchemy.orm.aliased(Pose, flat=True) + """ + Complete robot pose + """ + + __object_position: Position = sqlalchemy.orm.aliased(Position, flat=True) + """ + 3D Vector for object position + """ + + __relative_x = (__robot_position.x - __object_position.x) + """ + Distance on x axis between robot and object + """ + + __relative_y = (__robot_position.y - __object_position.y) + """ + Distance on y axis between robot and object + """ + + __table__ = view("PickUpWithContextView", Base.metadata, + (select(PickUpAction.id.label("id"), PickUpAction.arm.label("arm"), + PickUpAction.grasp.label("grasp"), RobotState.torso_height.label("torso_height"), + __relative_x.label("relative_x"), __relative_y.label("relative_y"), + Quaternion.x.label("quaternion_x"), Quaternion.y.label("quaternion_y"), + Quaternion.z.label("quaternion_z"), Quaternion.w.label("quaternion_w"), + Object.type.label("type"), TaskTreeNode.status.label("status")) + .join(TaskTreeNode.action.of_type(PickUpAction)) + .join(PickUpAction.robot_state) + .join(__robot_pose, RobotState.pose) + .join(__robot_position, __robot_pose.position) + .join(Pose.orientation) + .join(PickUpAction.object) + .join(Object.pose) + .join(__object_position, Pose.position))) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 38115476c..20949df77 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -1,20 +1,14 @@ from dataclasses import dataclass -import numpy as np import sqlalchemy.orm import sqlalchemy.sql from sqlalchemy import select, Select -from typing_extensions import List - +from typing_extensions import List, Type from ...costmaps import Rectangle, OccupancyCostmap from ...designator import LocationDesignatorDescription from ...designators.location_designator import CostmapLocation -from ...orm.action_designator import PickUpAction -from ...orm.base import RobotState, Quaternion -from ...orm.object_designator import Object -from ...orm.task import TaskTreeNode +from ...orm.views import PickUpWithContextView from ...pose import Pose -from ...orm.queries.queries import PickUpWithContext @dataclass @@ -72,10 +66,9 @@ def __init__(self, target, session: sqlalchemy.orm.Session = None, reachable_for self.session = session @staticmethod - def select_statement(query_context: PickUpWithContext) -> Select: - return query_context.join_statement(select(PickUpAction.arm, PickUpAction.grasp, RobotState.torso_height, - query_context.relative_x, query_context.relative_y, Quaternion.x, - Quaternion.y, Quaternion.z, Quaternion.w).distinct()) + def select_statement(view: Type[PickUpWithContextView]) -> Select: + return (select(view.arm, view.grasp, view.torso_height, view.relative_x, view.relative_y, view.quaternion_x, + view.quaternion_y, view.quaternion_z, view.quaternion_w).distinct()) def create_query_from_occupancy_costmap(self) -> Select: """ @@ -83,23 +76,23 @@ def create_query_from_occupancy_costmap(self) -> Select: OccupancyCostmap. """ - query_context = PickUpWithContext() + view = PickUpWithContextView # get query - query = self.select_statement(query_context) + query = self.select_statement(view) # constraint query to correct object type and successful task status - query = query.where(Object.type == self.target.type).where(TaskTreeNode.status == "SUCCEEDED") + query = query.where(view.type == self.target.type).where(view.status == "SUCCEEDED") filters = [] # for every rectangle for rectangle in self.create_occupancy_rectangles(): # add sql filter - filters.append(sqlalchemy.and_(query_context.relative_x >= rectangle.x_lower, - query_context.relative_x < rectangle.x_upper, - query_context.relative_y >= rectangle.y_lower, - query_context.relative_y < rectangle.y_upper)) + filters.append(sqlalchemy.and_(view.relative_x >= rectangle.x_lower, + view.relative_x < rectangle.x_upper, + view.relative_y >= rectangle.y_lower, + view.relative_y < rectangle.y_upper)) return query.where(sqlalchemy.or_(*filters)) diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index f5feaaa32..7af6932c3 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -4,7 +4,7 @@ import portion from probabilistic_model.probabilistic_circuit.distributions import GaussianDistribution, SymbolicDistribution from probabilistic_model.probabilistic_circuit.probabilistic_circuit import ProbabilisticCircuit, \ - DecomposableProductUnit, DeterministicSumUnit + DecomposableProductUnit from random_events.events import Event, ComplexEvent from random_events.variables import Symbolic, Continuous import tqdm @@ -15,9 +15,8 @@ from ...designators.actions.actions import MoveAndPickUpPerformable, ActionAbstract from ...enums import Arms, Grasp, TaskStatus from ...local_transformer import LocalTransformer -from ...orm.queries.queries import PickUpWithContext from ...orm.task import TaskTreeNode -from ...orm.action_designator import PickUpAction as ORMPickUpAction +from ...orm.views import PickUpWithContextView from ...plan_failures import ObjectUnreachable, PlanFailure from ...pose import Pose import plotly.graph_objects as go @@ -274,10 +273,9 @@ def iterate_without_occupancy_costmap(self) -> Iterator[MoveAndPickUpPerformable @staticmethod def query_for_database(): - query_context = PickUpWithContext() - query = select(ORMPickUpAction.arm, ORMPickUpAction.grasp, - query_context.relative_x, query_context.relative_y) - query = query_context.join_statement(query).where(TaskTreeNode.status == TaskStatus.SUCCEEDED) + view = PickUpWithContextView + query = (select(view.arm, view.grasp, view.relative_x, view.relative_y) + .where(TaskTreeNode.status == TaskStatus.SUCCEEDED)) return query def batch_rollout(self): diff --git a/test/test_orm.py b/test/test_orm.py index ce5775a84..f27b24c51 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -17,6 +17,7 @@ OpenActionPerformable, CloseActionPerformable, DetectActionPerformable, LookAtActionPerformable from pycram.designators.object_designator import BelieveObject from pycram.enums import ObjectType +from pycram.orm.views import PickUpWithContextView from pycram.pose import Pose from pycram.process_module import simulated_robot from pycram.task import with_tree @@ -46,8 +47,6 @@ def tearDown(self): class ORMTestSchemaTestCase(DatabaseTestCaseMixin, unittest.TestCase): def test_schema_creation(self): - pycram.orm.base.Base.metadata.create_all(self.engine) - self.session.commit() tables = list(pycram.orm.base.Base.metadata.tables.keys()) self.assertTrue("Position" in tables) self.assertTrue("Quaternion" in tables) @@ -211,9 +210,9 @@ def test_parkArmsAction(self): pycram.orm.base.ProcessMetaData().description = "parkArmsAction_test" pycram.task.task_tree.root.insert(self.session) result = self.session.scalars(select(pycram.orm.action_designator.ParkArmsAction)).all() - self.assertTrue(all([result[i+1].dtype is not pycram.orm.action_designator.Action.dtype + self.assertTrue(all([result[i + 1].dtype is not pycram.orm.action_designator.Action.dtype if result[i].dtype is pycram.orm.action_designator.ParkArmsAction.dtype else None - for i in range(len(result)-1)])) + for i in range(len(result) - 1)])) def test_transportAction(self): object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) @@ -275,5 +274,61 @@ def test_open_and_closeAction(self): apartment.remove() +class ViewsSchemaTest(DatabaseTestCaseMixin): + def test_view_creation(self): + pycram.orm.base.ProcessMetaData().description = "view_creation_test" + pycram.task.task_tree.root.insert(self.session) + view = PickUpWithContextView + self.assertEqual(len(view.__table__.columns), 12) + self.assertEqual(view.__table__.name, "PickUpWithContextView") + self.assertEqual(view.__table__.columns[0].name, "id") + self.assertEqual(view.__table__.columns[1].name, "arm") + self.assertEqual(view.__table__.columns[2].name, "grasp") + self.assertEqual(view.__table__.columns[3].name, "torso_height") + self.assertEqual(view.__table__.columns[4].name, "relative_x") + self.assertEqual(view.__table__.columns[5].name, "relative_y") + self.assertEqual(view.__table__.columns[6].name, "quaternion_x") + self.assertEqual(view.__table__.columns[7].name, "quaternion_y") + self.assertEqual(view.__table__.columns[8].name, "quaternion_z") + self.assertEqual(view.__table__.columns[9].name, "quaternion_w") + self.assertEqual(view.__table__.columns[10].name, "type") + self.assertEqual(view.__table__.columns[11].name, "status") + + def test_pickUpWithContextView(self): + object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) + self.assertEqual(description.ground().object_designator.name, "milk") + with simulated_robot: + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + description.resolve().perform() + pycram.orm.base.ProcessMetaData().description = "pickUpWithContextView_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.scalars(select(PickUpWithContextView)).first() + self.assertEqual(result.arm, "left") + self.assertEqual(result.grasp, "front") + self.assertEqual(result.torso_height, 0.3) + self.assertAlmostEqual(result.relative_x, -0.7, 6) + self.assertAlmostEqual(result.relative_y, -0.6, 6) + self.assertEqual(result.quaternion_x, 0) + self.assertEqual(result.quaternion_w, 1) + + def test_pickUpWithContextView_conditions(self): + object_description = object_designator.ObjectDesignatorDescription(names=["milk"]) + description = action_designator.PlaceAction(object_description, [Pose([1.3, 1, 0.9], [0, 0, 0, 1])], ["left"]) + self.assertEqual(description.ground().object_designator.name, "milk") + with simulated_robot: + NavigateActionPerformable(Pose([0.6, 0.4, 0], [0, 0, 0, 1])).perform() + MoveTorsoActionPerformable(0.3).perform() + PickUpActionPerformable(object_description.resolve(), "left", "front").perform() + description.resolve().perform() + pycram.orm.base.ProcessMetaData().description = "pickUpWithContextView_conditions_test" + pycram.task.task_tree.root.insert(self.session) + result = self.session.scalars(select(PickUpWithContextView) + .where(PickUpWithContextView.arm == "right")).all() + self.assertEqual(result, []) + + if __name__ == '__main__': unittest.main() From 5e1a3f145e0ab7495d2804b33505c01cc59c9297 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Tue, 9 Apr 2024 14:59:57 +0200 Subject: [PATCH 174/195] [world] Fixed camera control for the BulletWorld --- src/pycram/world.py | 15 +++++++++-- src/pycram/worlds/bullet_world.py | 41 ++++++++++++++++++++----------- 2 files changed, 40 insertions(+), 16 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index ffab6bd15..3034d05d1 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -156,6 +156,11 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.cache_manager = CacheManager(self.cache_dir, self.data_directory) + self.id: Optional[int] = -1 + # This is used to connect to the physics server (allows multiple clients) + + self._init_world(mode) + self.is_prospection_world: bool = is_prospection_world self._init_and_sync_prospection_world() @@ -165,8 +170,7 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self.objects: List[Object] = [] # List of all Objects in the World - self.id: Optional[int] = -1 - # This is used to connect to the physics server (allows multiple clients) + self.mode: WorldMode = mode # The mode of the simulation, can be "GUI" or "DIRECT" @@ -177,6 +181,13 @@ def __init__(self, mode: WorldMode, is_prospection_world: bool, simulation_frequ self._current_state: Optional[WorldState] = None + @abstractmethod + def _init_world(self, mode: WorldMode): + """ + Initializes the physics simulation. + """ + raise NotImplementedError + def _init_events(self): """ Initializes dynamic events that can be used to react to changes in the World. diff --git a/src/pycram/worlds/bullet_world.py b/src/pycram/worlds/bullet_world.py index f702967b1..f1bbc00bb 100755 --- a/src/pycram/worlds/bullet_world.py +++ b/src/pycram/worlds/bullet_world.py @@ -48,9 +48,6 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo """ super().__init__(mode=mode, is_prospection_world=is_prospection_world, simulation_frequency=sim_frequency) - self._gui_thread: Gui = Gui(self, mode) - self._gui_thread.start() - # This disables file caching from PyBullet, since this would also cache # files that can not be loaded p.setPhysicsEngineParameter(enableFileCaching=0) @@ -66,6 +63,11 @@ def __init__(self, mode: WorldMode = WorldMode.DIRECT, is_prospection_world: boo _ = Object("floor", ObjectType.ENVIRONMENT, "plane" + self.extension, world=self) + def _init_world(self, mode: WorldMode): + self._gui_thread: Gui = Gui(self, mode) + self._gui_thread.start() + time.sleep(0.1) + def load_object_and_get_id(self, path: Optional[str] = None, pose: Optional[Pose] = None) -> int: if pose is None: pose = Pose() @@ -342,6 +344,11 @@ def run(self): else: self.world.id = p.connect(p.GUI) + # DISCLAIMER + # This camera control only works if the WorldMooe.GUI BulletWorld is the first one to be created. This is + # due to a bug in the function pybullet.getDebugVisualizerCamera() which only returns the information of + # the first created simulation. + # Disable the side windows of the GUI p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0, physicsClientId=self.world.id) # Change the init camera pose @@ -378,18 +385,19 @@ def run(self): # Loop to update the camera position based on keyboard events while p.isConnected(self.world.id): # Monitor user input - keys = p.getKeyboardEvents() - mouse = p.getMouseEvents() + keys = p.getKeyboardEvents(self.world.id) + mouse = p.getMouseEvents(self.world.id) # Get infos about the camera width, height, dist = (p.getDebugVisualizerCamera()[0], p.getDebugVisualizerCamera()[1], p.getDebugVisualizerCamera()[10]) - camera_target_position = p.getDebugVisualizerCamera()[11] + #print("width: ", width, "height: ", height, "dist: ", dist) + camera_target_position = p.getDebugVisualizerCamera(self.world.id)[11] # Get vectors used for movement on x,y,z Vector - x_vec = [p.getDebugVisualizerCamera()[2][i] for i in [0, 4, 8]] - y_vec = [p.getDebugVisualizerCamera()[2][i] for i in [2, 6, 10]] + x_vec = [p.getDebugVisualizerCamera(self.world.id)[2][i] for i in [0, 4, 8]] + y_vec = [p.getDebugVisualizerCamera(self.world.id)[2][i] for i in [2, 6, 10]] z_vec = (0, 0, 1) # [p.getDebugVisualizerCamera()[2][i] for i in [1, 5, 9]] # Check the mouse state @@ -411,10 +419,10 @@ def run(self): mouse_state[2] = m[4] # change visibility by clicking the mousewheel - if m[4] == 6 and m[3] == 1 and visible == 1: - visible = 0 - elif m[4] == 6 and visible == 0: - visible = 1 + # if m[4] == 6 and m[3] == 1 and visible == 1: + # visible = 0 + # elif m[4] == 6 and visible == 0: + # visible = 1 # camera movement when the left mouse button is pressed if mouse_state[0] == 3: @@ -436,6 +444,7 @@ def run(self): elif mouse_y > old_mouse_y: camera_yaw -= (speed_y / 4) + 1 + # Camera movement when the middle mouse button is pressed if mouse_state[1] == 3: speed_x = abs(old_mouse_x - mouse_x) factor = 0.05 @@ -529,10 +538,14 @@ def run(self): dist -= dist * 0.02 * speed_mult elif ord("-") in keys: dist += dist * 0.02 * speed_mult + # print("dist: ", dist) + # print("camera_yaw: ", camera_yaw) + # print("camera_pitch: ", camera_pitch) + # print("camera_target_position: ", camera_target_position) p.resetDebugVisualizerCamera(cameraDistance=dist, cameraYaw=camera_yaw, cameraPitch=camera_pitch, - cameraTargetPosition=camera_target_position) + cameraTargetPosition=camera_target_position, physicsClientId=self.world.id) if visible == 0: camera_target_position = (0.0, -50, 50) - p.resetBasePositionAndOrientation(sphere_uid, camera_target_position, [0, 0, 0, 1]) + p.resetBasePositionAndOrientation(sphere_uid, camera_target_position, [0, 0, 0, 1], physicsClientId=self.world.id) time.sleep(1. / 80.) From 23ab36a0096cb1ffb77a3caedd7a54d326db5da4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?David=20Pr=C3=BCser?= Date: Tue, 9 Apr 2024 19:13:22 +0200 Subject: [PATCH 175/195] [resolver][orm] fixed issues after merge --- src/pycram/orm/views.py | 8 ++--- .../resolver/location/database_location.py | 2 +- .../probabilistic/probabilistic_action.py | 2 +- test/test_database_resolver.py | 36 ++++++++++--------- test/test_orm.py | 2 +- 5 files changed, 26 insertions(+), 24 deletions(-) diff --git a/src/pycram/orm/views.py b/src/pycram/orm/views.py index 352b3c304..f49b349f5 100644 --- a/src/pycram/orm/views.py +++ b/src/pycram/orm/views.py @@ -1,10 +1,10 @@ -from sqlalchemy.orm import declarative_base, column_property, query_expression, deferred, contains_eager +from sqlalchemy.orm import declarative_base from typing_extensions import Union import sqlalchemy.orm from sqlalchemy import table, inspect, event, select, engine, MetaData, Select, TableClause, ExecutableDDLElement from sqlalchemy.ext.compiler import compiles -from pycram.orm.action_designator import PickUpAction, Action -from pycram.orm.base import Position, RobotState, Pose, Base, Quaternion, _Base +from pycram.orm.action_designator import PickUpAction +from pycram.orm.base import Position, RobotState, Pose, Base, Quaternion from pycram.orm.object_designator import Object from pycram.orm.task import TaskTreeNode @@ -138,7 +138,7 @@ class PickUpWithContextView(base): __relative_x.label("relative_x"), __relative_y.label("relative_y"), Quaternion.x.label("quaternion_x"), Quaternion.y.label("quaternion_y"), Quaternion.z.label("quaternion_z"), Quaternion.w.label("quaternion_w"), - Object.type.label("type"), TaskTreeNode.status.label("status")) + Object.obj_type.label("obj_type"), TaskTreeNode.status.label("status")) .join(TaskTreeNode.action.of_type(PickUpAction)) .join(PickUpAction.robot_state) .join(__robot_pose, RobotState.pose) diff --git a/src/pycram/resolver/location/database_location.py b/src/pycram/resolver/location/database_location.py index 412ba4ffc..35daae321 100644 --- a/src/pycram/resolver/location/database_location.py +++ b/src/pycram/resolver/location/database_location.py @@ -82,7 +82,7 @@ def create_query_from_occupancy_costmap(self) -> Select: query = self.select_statement(view) # constraint query to correct object type and successful task status - query = query.where(view.type == self.target.type).where(view.status == "SUCCEEDED") + query = query.where(view.obj_type == self.target.obj_type).where(view.status == "SUCCEEDED") filters = [] diff --git a/src/pycram/resolver/probabilistic/probabilistic_action.py b/src/pycram/resolver/probabilistic/probabilistic_action.py index 53867488c..348f0627e 100644 --- a/src/pycram/resolver/probabilistic/probabilistic_action.py +++ b/src/pycram/resolver/probabilistic/probabilistic_action.py @@ -274,7 +274,7 @@ def iterate_without_occupancy_costmap(self) -> Iterator[MoveAndPickUpPerformable def query_for_database(): view = PickUpWithContextView query = (select(view.arm, view.grasp, view.relative_x, view.relative_y) - .where(TaskTreeNode.status == TaskStatus.SUCCEEDED)) + .where(view.status == TaskStatus.SUCCEEDED)) return query def batch_rollout(self): diff --git a/test/test_database_resolver.py b/test/test_database_resolver.py index 6dfd121de..e6021ef60 100644 --- a/test/test_database_resolver.py +++ b/test/test_database_resolver.py @@ -19,6 +19,7 @@ from pycram.task import with_tree from pycram.datastructures.enums import ObjectType, WorldMode from pycram.resolver.location.database_location import DatabaseCostmapLocation +from pycram.worlds.bullet_world import BulletWorld pycrorm_uri = os.getenv('PYCRORM_URI') if pycrorm_uri: @@ -36,8 +37,8 @@ class DatabaseResolverTestCase(unittest.TestCase,): @classmethod def setUpClass(cls) -> None: global pycrorm_uri - cls.world = World(WorldMode.DIRECT) - cls.milk = Object("milk", "milk", "milk.stl", pose=Pose([1.3, 1, 0.9])) + cls.world = BulletWorld(WorldMode.DIRECT) + cls.milk = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) cls.robot = Object(robot_description.name, ObjectType.ROBOT, robot_description.name + ".urdf") ProcessModule.execution_delay = False cls.engine = sqlalchemy.create_engine(pycrorm_uri) @@ -81,15 +82,15 @@ def test_costmap_no_obstacles(self): with simulated_robot: MoveTorsoActionPerformable(sample.torso_height).perform() - PickUpActionPerformable(ObjectDesignatorDescription(types=["milk"]).resolve(), arm=sample.reachable_arm, + PickUpActionPerformable(ObjectDesignatorDescription(types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() def test_costmap_with_obstacles(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") + kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "costmap_with_obstacles_test" pycram.task.task_tree.root.insert(self.session) - self.world.reset_bullet_world() + self.world.reset_current_world() cml = DatabaseCostmapLocation(self.milk, self.session, reachable_for=self.robot) sample = next(iter(cml)) @@ -99,7 +100,7 @@ def test_costmap_with_obstacles(self): MoveTorsoActionPerformable(sample.torso_height).perform() try: PickUpActionPerformable( - ObjectDesignatorDescription(types=["milk"]).resolve(), + ObjectDesignatorDescription(types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure as p: kitchen.remove() @@ -107,14 +108,14 @@ def test_costmap_with_obstacles(self): kitchen.remove() def test_object_at_different_location(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") + kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") self.plan() pycram.orm.base.ProcessMetaData().description = "object_at_different_location_test" pycram.task.task_tree.root.insert(self.session) - self.world.reset_bullet_world() + self.world.reset_current_world() - new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) + new_milk = Object("new_milk", ObjectType.MILK, "milk.stl", pose=Pose([-1.45, 2.5, 0.95])) cml = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) sample = next(iter(cml)) @@ -123,21 +124,21 @@ def test_object_at_different_location(self): MoveTorsoActionPerformable(sample.torso_height).perform() try: PickUpActionPerformable( - ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + ObjectDesignatorDescription(names=["new_milk"], types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure as p: new_milk.remove() kitchen.remove() raise p - PlaceActionPerformable(ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + PlaceActionPerformable(ObjectDesignatorDescription(names=["new_milk"], types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, target_location=Pose([-1.45, 2.5, 0.95])).perform() new_milk.remove() kitchen.remove() @unittest.skip def test_multiple_objects(self): - kitchen = Object("kitchen", "environment", "kitchen.urdf") - new_milk = Object("new_milk", "milk", "milk.stl", pose=Pose([-1.45, 2.5, 0.9])) + kitchen = Object("kitchen", ObjectType.ENVIRONMENT, "kitchen.urdf") + new_milk = Object("new_milk", ObjectType.MILK, "milk.stl", pose=Pose([-1.45, 2.5, 0.9])) object_description = ObjectDesignatorDescription(names=["milk"]) object_description_new_milk = ObjectDesignatorDescription(names=["new_milk"]) @@ -153,7 +154,7 @@ def test_multiple_objects(self): pycram.orm.base.ProcessMetaData().description = "multiple_objects_test" pycram.task.task_tree.root.insert(self.session) - self.world.reset_bullet_world() + self.world.reset_current_world() cml = DatabaseCostmapLocation(self.milk, self.session, reachable_for=self.robot) cml_new_milk = DatabaseCostmapLocation(new_milk, self.session, reachable_for=self.robot) @@ -167,17 +168,18 @@ def test_multiple_objects(self): try: if dcl.target.name == "milk": PickUpActionPerformable( - ObjectDesignatorDescription(names=["milk"], types=["milk"]).resolve(), + ObjectDesignatorDescription(names=["milk"], types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() else: PickUpActionPerformable( - ObjectDesignatorDescription(names=["new_milk"], types=["milk"]).resolve(), + ObjectDesignatorDescription(names=["new_milk"], types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, grasp=sample.grasp).perform() except pycram.plan_failures.PlanFailure as p: new_milk.remove() kitchen.remove() raise p - PlaceActionPerformable(ObjectDesignatorDescription(names=[dcl.target.name], types=["milk"]).resolve(), + PlaceActionPerformable(ObjectDesignatorDescription(names=[dcl.target.name], + types=[ObjectType.MILK]).resolve(), arm=sample.reachable_arm, target_location=Pose([dcl.target.pose.position.x, dcl.target.pose.position.y, dcl.target.pose.position.z]) diff --git a/test/test_orm.py b/test/test_orm.py index f9fbbd737..f9c96c126 100644 --- a/test/test_orm.py +++ b/test/test_orm.py @@ -291,7 +291,7 @@ def test_view_creation(self): self.assertEqual(view.__table__.columns[7].name, "quaternion_y") self.assertEqual(view.__table__.columns[8].name, "quaternion_z") self.assertEqual(view.__table__.columns[9].name, "quaternion_w") - self.assertEqual(view.__table__.columns[10].name, "type") + self.assertEqual(view.__table__.columns[10].name, "obj_type") self.assertEqual(view.__table__.columns[11].name, "status") def test_pickUpWithContextView(self): From ebed1a346ab9a0f556c60b57065e76b9beddca41 Mon Sep 17 00:00:00 2001 From: Vanessa Hassouna <33067562+sunava@users.noreply.github.com> Date: Tue, 16 Apr 2024 18:18:49 +0200 Subject: [PATCH 176/195] [giskard_interface] Update giskard fail import msg --- src/pycram/external_interfaces/giskard.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/external_interfaces/giskard.py b/src/pycram/external_interfaces/giskard.py index bd88af990..a5fc75a52 100644 --- a/src/pycram/external_interfaces/giskard.py +++ b/src/pycram/external_interfaces/giskard.py @@ -21,7 +21,7 @@ from giskard_msgs.msg import WorldBody, MoveResult, CollisionEntry from giskard_msgs.srv import UpdateWorldRequest, UpdateWorld, UpdateWorldResponse, RegisterGroupResponse except ModuleNotFoundError as e: - rospy.logwarn("Failed to import Giskard messages") + rospy.logwarn("Unable to import Giskard messages. Real robot not available") giskard_wrapper = None giskard_update_service = None From 43c1ca5452ae9052e3223f54744789e168214bae Mon Sep 17 00:00:00 2001 From: Leo <114857318+leonyi4@users.noreply.github.com> Date: Sat, 20 Apr 2024 09:12:07 +0000 Subject: [PATCH 177/195] Added devcontainer --- .devcontainer/devcontainer.json | 22 ++++++++++++++++++++++ .devcontainer/script.sh | 7 +++++++ 2 files changed, 29 insertions(+) create mode 100644 .devcontainer/devcontainer.json create mode 100644 .devcontainer/script.sh diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 000000000..7d9e8666f --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,22 @@ +{ + "image": "pycram/pycram:dev", + "features": { + "ghcr.io/devcontainers/features/git:1": {}, + "ghcr.io/devcontainers/features/sshd:1": {} + }, + "postStartCommand": { + "pip": "pip3 install ipykernel pyjpt", + "git": "git config --global --add safe.directory '*'", + "source setup": "./.devcontainer/script.sh" + }, + "customizations": { + "vscode": { + "extensions": [ + "ms-python.python", + "ms-python.vscode-pylance", + "ms-toolsai.jupyter", + "esbenp.prettier-vscode" + ] + } + } +} diff --git a/.devcontainer/script.sh b/.devcontainer/script.sh new file mode 100644 index 000000000..d45f309ac --- /dev/null +++ b/.devcontainer/script.sh @@ -0,0 +1,7 @@ +#!/bin/bash + +set -e + +source /opt/ros/overlay_ws/devel/setup.bash + +exec "$@" \ No newline at end of file From 7c861c8663e93171eef1a34a1256b1e3dce169c0 Mon Sep 17 00:00:00 2001 From: Leo <114857318+leonyi4@users.noreply.github.com> Date: Sat, 20 Apr 2024 16:24:51 +0700 Subject: [PATCH 178/195] added README.md --- .devcontainer/README.md | 15 +++++++++++++++ .devcontainer/devcontainer.json | 1 + 2 files changed, 16 insertions(+) create mode 100644 .devcontainer/README.md diff --git a/.devcontainer/README.md b/.devcontainer/README.md new file mode 100644 index 000000000..8945893df --- /dev/null +++ b/.devcontainer/README.md @@ -0,0 +1,15 @@ +# How to use Dev container + +- Install Docker and the 'Devcontainer' extension in VSCode + +- Clone the repository and open the folder in VSCode + +- Use `Ctrl/Cmd + Shift + P` to open the command palette + +- Select 'Dev containers: Rebuild and Reopen in Container' Option + +- Wait for the container to finish setting up + +- Type this command into the terminal `roslaunch pycram ik_and_description.launch` to start roscore + + - Note: Bullet world needs a display to be connected; the render mode needs to be set to direct when running on GitHub codespaces or on WindowOS; Otherwise, the kernel will crash diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index 7d9e8666f..b5c5b59a6 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -1,4 +1,5 @@ { + "name": "PyCRAM vscode devcontainer", "image": "pycram/pycram:dev", "features": { "ghcr.io/devcontainers/features/git:1": {}, From 4c6d2afc4a5f568236cd6152ac8e12746591ae72 Mon Sep 17 00:00:00 2001 From: kecks Date: Sun, 21 Apr 2024 17:05:33 +0200 Subject: [PATCH 179/195] added binder config --- binder/Dockerfile | 54 +++ binder/README.md | 462 +++++++++++++++++++++++++ binder/Readme/Binder_default.png | Bin 0 -> 57733 bytes binder/Readme/Binder_specific_file.png | Bin 0 -> 87048 bytes binder/Readme/JointStatePublisher.png | Bin 0 -> 39457 bytes binder/Readme/TFBroadcaster.png | Bin 0 -> 28874 bytes binder/Readme/VisualizationMarker.png | Bin 0 -> 33327 bytes binder/Readme/rvizweb_config.png | Bin 0 -> 85395 bytes binder/Readme/rvizweb_load_options.png | Bin 0 -> 21285 bytes binder/docker-compose.yml | 30 ++ binder/entrypoint.sh | 8 + binder/jupyter-config.json | 6 + binder/me/CMakeLists.txt | 22 ++ binder/me/package.xml | 9 + binder/pycram-http.rosinstall | 25 ++ binder/rviz_configs/pr2_config.json | 72 ++++ binder/webapps.json | 37 ++ 17 files changed, 725 insertions(+) create mode 100644 binder/Dockerfile create mode 100644 binder/README.md create mode 100644 binder/Readme/Binder_default.png create mode 100644 binder/Readme/Binder_specific_file.png create mode 100644 binder/Readme/JointStatePublisher.png create mode 100644 binder/Readme/TFBroadcaster.png create mode 100644 binder/Readme/VisualizationMarker.png create mode 100644 binder/Readme/rvizweb_config.png create mode 100644 binder/Readme/rvizweb_load_options.png create mode 100644 binder/docker-compose.yml create mode 100755 binder/entrypoint.sh create mode 100644 binder/jupyter-config.json create mode 100644 binder/me/CMakeLists.txt create mode 100644 binder/me/package.xml create mode 100644 binder/pycram-http.rosinstall create mode 100644 binder/rviz_configs/pr2_config.json create mode 100644 binder/webapps.json diff --git a/binder/Dockerfile b/binder/Dockerfile new file mode 100644 index 000000000..c36eb0594 --- /dev/null +++ b/binder/Dockerfile @@ -0,0 +1,54 @@ +FROM intel4coro/base-notebook:20.04-noetic-full-xpra + +# Set environment +ENV PATH=$PATH:/home/user/.local/bin +ENV PYCRAM_WS=/home/${NB_USER}/workspace/ros +WORKDIR ${PYCRAM_WS}/src/ +COPY --chown=${NB_USER}:users . pycram/ +RUN vcs import --input pycram/binder/pycram-http.rosinstall --recursive + +# === Following step should be replace to === +USER ${NB_USER} +RUN cd pycram \ + && git submodule update --init \ + && git clone https://github.com/Tigul/neem_interface_python.git src/neem_interface_python \ + && cd src/neem_interface_python \ + && git clone https://github.com/benjaminalt/neem-interface.git src/neem-interface +# === To === +# RUN cd pycram + # && git submodule update --init --recursive +# === When all .gitmodules use https urls === + +RUN pip install --requirement ${PYCRAM_WS}/src/pycram/requirements.txt --user +RUN pip install --requirement ${PYCRAM_WS}/src/pycram/src/neem_interface_python/requirements.txt --user \ + && pip cache purge + +# Remove double numpy version +RUN pip uninstall numpy -y +RUN pip install --upgrade pip + +COPY --chown=${NB_USER}:users binder/me ${PYCRAM_WS}/src/me + +USER root +RUN apt-get update + +# Build pycram workspace +WORKDIR ${PYCRAM_WS} +USER root +RUN rosdep update \ + && rosdep install -y --ignore-src --from-paths ./ -r \ + && rosdep fix-permissions +USER ${NB_USER} +RUN catkin build + +RUN pip install service_identity + +# Jupyter Config +COPY --chown=${NB_USER}:users binder/jupyter-config.json /opt/conda/share/jupyter/lab/settings/overrides.json + +WORKDIR ${PYCRAM_WS}/src/pycram +RUN git config --global --add safe.directory ${PWD} +COPY --chown=${NB_USER}:users binder/entrypoint.sh / +ENTRYPOINT ["/entrypoint.sh"] +CMD ["jupyter", "lab", "--allow-root", "--NotebookApp.token=''", "--no-browser", "--ip=0.0.0.0"] +RUN pip install https://raw.githubusercontent.com/yxzhan/jupyterlab-rviz/master/dist/jupyterlab_rviz-0.3.1.tar.gz diff --git a/binder/README.md b/binder/README.md new file mode 100644 index 000000000..b10281a0b --- /dev/null +++ b/binder/README.md @@ -0,0 +1,462 @@ + +

Table of Contents

+ +

+ +1. [Binder](#binder) +2. [Project Integration](#ProjectIntegration) + 1. [Docker Foundation](#dockerbasics) + + 1. [Dockerfile](#dockerfile) + 2. [docker-compose.yml](#compose) + 3. [entrypoint.sh](#entry) + 2. [webapp.json](#webapps) + 1. [Custom RvizWeb configuration](#rvizweb) + 2. [XPRA](#xpra) + +3. [Tutorial](#tutorial) + 1. [Pick up object with Visualization](#pickup) + +

+ + + +

+ Binder +

+ + +> BinderHub is a kubernetes-based cloud service that allows users to share reproducible interactive computing environments from code repositories. It is the primary technology behind [mybinder.org](mybinder.org). + +On binder it is possible to build configured projects and run those in a virtual environment. One simple way to configure projects is with Docker. +However building projects might need a lot of resources depending on the projects size. This might lead to problems with the binder instance at [mybinder.org](mybinder.org) as the resources are limited to about 1 - 2 GB. The project [intel4coro](https://www.uni-bremen.de/zmml/projekte/intel4coro) runs a server at [binder.intel4coro](https://binder.intel4coro.de/) to launch projects that require more resources. Already built projects are saved and can be launched anytime without the need to build again. However when the project slightly changed (e.g. git commits) it will need to build again. + + + +When a project is built, a link can be used to share this Hub in its default configuration: + +

+ +

+ + +It is also possible to open a specific file by default when clicking on the link, which can be useful when sharing specific demos. To do this, right click the file that should open at startup and click Copy Shareable Link : + +

+ +

+ + +
+

+ Project Integration +

+ +
+

+ Docker Fundamentals +

+
+ + +
+

Dockerfile

+ +

+ +1. Setup base system + +The Dockerfile describes how the system will be set it up. A base system is defined at first to set the desired distribution as well as other predefined requirements. This is done with the following statement: + +`FROM intel4coro/base-notebook:20.04-noetic-full-xpra` + +After that you can prepare the required dependencies for the specific Docker/Binder in this file. The following steps contain the Dockerfile of this repository as an example. If you want to build a Binderhub using pycram, you can just paste the code blocks for the wanted steps into your Dockerfile: + +

+ + +2. Setup for pycram +
+To setup a pycram workspace with docker it is neccessary to clone the respective repositories for that. For this simply create a rosinstall file to clone all at once. A reference for this can be this
rosinstall file. This differs from the standard rosinstall for pycram since the intitialization of submoudles needs to be done seperately. +
+ +``` +ENV PATH=$PATH:/home/user/.local/bin +ENV PYCRAM_WS=/home/${NB_USER}/workspace/ros +WORKDIR ${PYCRAM_WS}/src/ +COPY --chown=${NB_USER}:users . pycram/ +RUN vcs import --input pycram/binder/pycram-http.rosinstall --recursive +``` + +
+ +3. Clone pycram into workspace + +``` +RUN cd pycram \ + && git submodule update --init \ + && git clone https://github.com/Tigul/neem_interface_python.git src/neem_interface_python \ + && cd src/neem_interface_python \ + && git clone https://github.com/benjaminalt/neem-interface.git src/neem-interface + +RUN pip install --requirement ${PYCRAM_WS}/src/pycram/requirements.txt --user +RUN pip install --requirement ${PYCRAM_WS}/src/pycram/src/neem_interface_python/requirements.txt --user \ + && pip cache purge +``` + +
+ +4. Build pycram workspace + +``` +WORKDIR ${PYCRAM_WS} +USER root +RUN rosdep update \ + && rosdep install -y --ignore-src --from-paths ./ -r \ + && rosdep fix-permissions +USER ${NB_USER} +RUN catkin build +``` + + +
+ + +5. Start entrypoint.sh + +``` +WORKDIR ${PYCRAM_WS}/src/pycram +RUN git config --global --add safe.directory ${PWD} +COPY --chown=${NB_USER}:users binder/entrypoint.sh / +ENTRYPOINT ["/entrypoint.sh"] +CMD ["start-notebook.sh"] +RUN pip install https://raw.githubusercontent.com/yxzhan/jupyterlab-rviz/master/dist/jupyterlab_rviz-0.3.1.tar.gz +``` + + + +

+ + +
  • docker-compose.yml

    +

    +To specify the the Docker image a compose file should be defined as a yml file. This will configure required capabilites such as the location of the Dockerfile and the entrypoint, permissions and the necessary drivers. This project used the following compose file, saved as docker-compose.yml: +

    + +``` +version: '3' +services: + pycram: + image: pycram:binder-xpra + build: + context: ../ + dockerfile: ./binder/Dockerfile + stdin_open: true + tty: true + ports: + - 8888:8888 + privileged: true + # user: root + command: jupyter lab --allow-root --NotebookApp.token='' --no-browser --ip=0.0.0.0 + entrypoint: ["/home/jovyan/work/binder/entrypoint.sh"] + volumes: + - ../:/home/jovyan/work + - /tmp/.X11-unix:/tmp/.X11-unix:rw + environment: + - DISPLAY + - QT_X11_NO_MITSHM=1 + - NVIDIA_DRIVER_CAPABILITIES=all + deploy: + resources: + reservations: + devices: + - driver: nvidia + count: all + capabilities: [gpu] +``` +

  • +

    + + +
    +
  • entrypoint.sh

    +
    + +The entrypoint is usually executed when the built system should start. This will set some defaults as sourced workspaces or files launched by ros. An example for this would be the following code as a file called entrypoint.sh: + +``` +#!/bin/bash + +source ${PYCRAM_WS}/devel/setup.bash +roscore & +roslaunch --wait rvizweb rvizweb.launch config_file:=${PYCRAM_WS}/src/pycram/binder/rvizweb_config.json & +roslaunch --wait pycram ik_and_description.launch & + +cp ${PYCRAM_WS}/src/pycram/binder/webapps.json ${PYCRAM_WS}/src/rvizweb/webapps/app.json + +exec "$@" +``` + +In short this does the following instructions: +- source pycram workspace +- start ros-specifics such as + - roscore + - launch rvizweb with a custom config file + - launch the ik solver for pycram +- copy webapps file and execute previous commands +
  • + +
    + + +

    + Adding Webapps +

    +
    +This file defines the available apps for this Binderhub as a json file. The main parameters for the respective entries are: +

    + +- ```name```: Name of the App +- ```title```: Title of the App +- ```icon```: Link to a picture as svg +- ```url```: url to the index of the build folder +- ```start```: Defines if the app should run at start. It's optional and states ```true``` if it should. +- ```mode```: Describe where the application window should be. Examples: ```split-left``` or ```split-right``` + +The webapps contained for this project are the following: + +- RvizWeb +- XPRA +- rosgraph +- rosboard +- webviz + +RvizWeb and XPRA are also started by default to simplify the process of running a jupyter notebook. The following is an example of the existent json file `webapps.json` which configures the described environment: + +``` +[ + { + "name": "rvizweb", + "title": "Rvizweb", + "icon": "proxy/8001/rvizweb/webapps/r.svg", + "url": "proxy/8001/rvizweb/webapps/rvizweb/build/www/index.html", + "start": true, + "mode": "split-left" + }, + { + "name": "XPRA", + "title": "Xpra Desktop", + "icon": "proxy/8001/rvizweb/webapps/xpra-logo.svg", + "url": "xprahtml5/index.html", + "start": true, + "mode": "split-right" + }, + + { + "name": "rosgraph", + "title": "Ros Graph", + "icon": "proxy/8001/rvizweb/webapps/o.svg", + "url": "proxy/8001/rvizweb/webapps/ros-node-graph/build/index.html" + }, + { + "name": "rosboard", + "title": "ROSBoard", + "icon": "proxy/8001/rvizweb/webapps/s.svg", + "url": "proxy/18888/index.html" + }, + { + "name": "webviz", + "title": "Webviz", + "icon": "proxy/8001/rvizweb/webapps/webviz/icon.svg", + "url": "proxy/8001/rvizweb/webapps/webviz/index.html" + } +] +``` + + + +

  • Custom RvizWeb configuration

    + +Adding an RvizWeb is relative similar to adding a local rviz configuration. Although the config file structure differ (RvizWeb uses json and not the rviz format) which is why the config file needs to be created using RvizWeb. When first setting up a config, this can then be copied by clicking on Load Config: + + +

    + +

    + +After that a window similar to the following image should open: + +

    + +

    + +This can then be copied into a local file. Delete lines containing the parameters url, colladaServer, and videoServer as they change with every startup and will be assigned automatically. + + Note: When using a custom RvizWeb configuration, ensure that the name of the file match with the config file specified in the [entrypoint](#entry). + +
  • + + +
  • XPRA

    +XPRA is a remote display server which can be used to demonstrate the execution when using the Bulletworld. In the shown webapps file, it is a starting window on the left by default + + +
  • + + +
    + + + + +
    +

    + Tutorials +

    + + +
    +

    + Pick up Example +

    + +A short example is shown here with Initializing a world with a robot, spawning and then picking up an object. This is written in an jupyter notebook in the file
    pick-test.ipynb. There is also one cell which can create an TFBroadcaster, a JointPublisher and a VisualizationMarkerPublisher + +
  • + Initialize World, Robot and object +

  • +When executing the initialization, the Bulletworld should open on XPRA and every action can be seen there as well. +This is seperated into 3 different cells for clarification on what each action does. Alternatively the Bulletworld can also be initialized with a Parameter 'DIRECT' if working with XPRA is not desired. This will not open any windows and execute everything without direct visualization. Although it is possible to use the TFBroadcaster, JointPublisher or VisualizationMarker to visualize the current execution in RvizWeb + +The code for this is seen below: +``` +from rospy import get_param +from pycram.bullet_world import BulletWorld, Object +from pycram.pose import Pose + +from pycram.process_module import simulated_robot, with_simulated_robot +from pycram.language import macros, par +from pycram.designators.location_designator import * +from pycram.designators.action_designator import * +from pycram.enums import Arms +from pycram.designators.object_designator import * +from pycram.designators.object_designator import BelieveObject +from pycram.plan_failures import IKError +import math + +try: + robot = get_param('/nbparam_robot') + environment = get_param('/nbparam_environment') +except Exception as e: + robot = 'pr2' + environment = 'kitchen' + +print(f"Robot: {robot}") +print(f"Environment: {environment}") + +world = BulletWorld() + +# Initialize Robot +robot = Object("pr2", "robot", robot + ".urdf") +robot_desig = ObjectDesignatorDescription(names=["pr2"]).resolve() + +# Create Object +milk = Object("milk", "milk", "milk.stl", pose=Pose([2, 0, 1])) +milk_BO = BelieveObject(names=["milk"]) +``` + +
  • + Creating Several Publisher +

  • + +In case any Publisher is wanted, it is neccessary to prepare a display for that depending on the type of Visualization is desired to use: + +

    + TFBroadcaster +

    + +To set up the TFBroadcaster simply add the display called TF . If you want to visualize all tf-frames, then you do not need to add a prefix. The following picture shows the location of the TF display: + +

    + +

    + +Then the following line of code adds the TFBroadcaster. As soon as this is called, it publishes all available tf-frames: +
    +`broadcaster = TFBroadcaster()` + + + +

    + Joint State Publisher +

    +To set up the Joint State Publisher for a robot add the display called Robot Model . The robot description should be called robot_description. The tf-prefix might variate, the starting prefix so far is simulated/pr2_2. The following picture shows the setup of this display: + +

    + +

    + +Then the following line of code adds the JointStatePublisher. As soon as this is called, it publishes the joint states under the given name (here: joint_states) +
    +`joint_publisher = JointStatePublisher("joint_states", 0.1)` + + + +

    + VisualizationMarker +

    +To set up the Visualization add the disply called Marker Array . It is required to set a topic name which is currently /viz_marker. The following picture shows the setup of this display: + +

    + +

    + +Then the following line of code adds the VisualizationMarker. Here all markers should be published under the given name (here: /viz_marker) +
    +`v = VizMarkerPublisher(topic_name='viz_marker')` + + NOTE: This is currently bugged in RvizWeb and needs further investigation. Visualizationmarker does work locally, but only shows a bugged model in RvizWeb. + +
  • + Navigate to Object +

  • + +The navigation to objects does not require any setup specifically for binder so there is no difference in execution: + +``` +with simulated_robot: + ParkArmsAction([Arms.BOTH]).resolve().perform() + + MoveTorsoAction([0.33]).resolve().perform() + + pickup_pose_knife = CostmapLocation(target=milk_BO.resolve(), reachable_for=robot_desig).resolve() + pickup_arm = pickup_pose_knife.reachable_arms[0] + + NavigateAction(target_locations=[pickup_pose_knife.pose]).resolve().perform() + +``` + + +
  • + Pick up object +

  • +Next pick up the object with the left arm. This also does not differ from normal pycram usage: + +``` +with simulated_robot: + PickUpAction(object_designator_description=milk_BO, + arms=["left"], + grasps=["left", "right"]).resolve().perform() +``` + + + + + + + + + + + + diff --git a/binder/Readme/Binder_default.png b/binder/Readme/Binder_default.png new file mode 100644 index 0000000000000000000000000000000000000000..0da2d6d5baf9ca60ae62dededb746728476f258c GIT binary patch literal 57733 zcmeEtWmKHavMz)Kf`kMK1Se?F0S4DV(BSSexDPP6CP;7(?jGFTgA?3gaCdjTkWcnL zvd&%mtb70MW&!nfS3liVUEOb2O^v^dl*lV2TqGD6m{($=f^sl0aCtB=us>eHKh{Xo zyyJfS*XFFCVk-x7Ahxmr8=9CK5ZgLg84w#dni#^sIL=tesH3+Lzr5YRJOJS8=WE!+(bv(i%jV<$U>q46Ii0ef14S#KXcG($j|7$r!p**hQO%&&Mb3O~p`*_mVCx4}v&0~B z9gnhkn|%5tBlhXjU*bFpk?0oABii;6ze8JIDEBQtjUT)I4=JpG0Cv;20WxW0NQIoS z8rLr*aU(FXMOrHt7rS)FTRT*h5tRAg+`?GfS&4xN$5IP*dq-h!E zO{2X~=x35UijD0l3eYUxY$blSDWag8%^M>@vB=T1zqGQW>22hcasxS~=7@yl4R?&* z`X97Hrwv|tdK$Vk zn(tf14A=K7Wj~z)%hig?)_Jawy*Mlk;&zxt-gJ>fhk3umQT#6R&F5tyE)|7b1<}dj zYp#2;T78?SmhRFoND87MM7OWq9n97#DQ7cvP&Qpl_d;b;&9IHf%x`X{s_-bkJmA!f zsNH`ih`l0foEZ5j@^OLH%6e{Om1ofg;hpmc`6nAPKFRkf2=jxR31uxUbZ=B3E@t~H zr?8^(%KmtZi*Mf1$eh=8)z?E^ZZ0Isn~6LkYzlhyR(?F1oukR4d8tTBaO#0A=t25m zT?2YY3#&)FgMs1ZbF>2KnHks;>lzrDSn`k@)Hjn5o9Oe9D6>d1NLqa|Fg6i&wlR=* zmQv7jHq+zKC*k8o;&$YG1h6o$1ra-1m|H?P9eGH8<8nUIPt^bt;@>Q`W;`S+k}|}f zz%~ZN%=FCk40J+{CiYAuyhy~{Hu{E~a)QEtLOee4kQm$AT5$pZ4h|0V4nTUajS+y6 zgM$OWzyx4oqI=|^gE(2*f*k2AA*4?be_#k2K=f=(tZYrdmc&n(AYHJXEe{FFV>|I* z^Ruv$l>8gs67r`O9`ylm1X%$X=@|eP7Jz^50kIXbe+2n+LjP?Kh{EG81;`mdz;-rz z2151*mbRq-456?0cYiB88}r}d=<5Lt%nd9aSs{<3GX94lMZ_d!{_gRl0wWU(tKYpI zmHi($ZA}dSp{)Nfx2Klh;{5YO9=rdI`yaUflKnUHBbTHkryy9*?rC~rf;=Qo<8$hR z^-T0Rf0G~}yFMcmI}05fs~!s-Gf>Zv4#dJ_K&Q*Wq6cJSWo2V#*ZU_ZF-wRo$WqVX z3F;A?-sBMn#Ad+2ruW#Jftitmj+w(yj}FAatV_pgsK>y_$i~LbXrTX35Yjd#k5&mX z|L0jfLFqq2u>u)5SoB%g=-5F926W5@EbMgbOuFoJ2J8kPMvy+cJ`>2`H&-Di1Cmx(KGy`M#dauYxvlKheX1}($4W84GJa}2J*I` zCv7saF)*;OJ{l)0D+?0~3;REqlniVjkCym^$;dztWd7aqv@D#D!aOP#^kk=x0Ke-W zW#Rl}V*s)R+bDp+<~$@%QzCxq`FFGA<95;q*@6T?wg!)&3`{^yMn+C1Muo?}j2xUS zEHn&^oDBcO57sv^bo#$>KW!dj?mw1X)CBT4zSHljKX#P7f%P9xe>|F-{N75$#J@KM zCrIxP5g;J@KNsr}>yIWqW00kh!Q<)ir@8)BZ}Q)m0vofwF0-xyGaZM4{-Y`AGwRc^ zv+AtYcbwP%IDDQ7{2-wip0c2yqZ}h0gM_oOd=WksRfB3ynRKIohH@Aba z!P6={DvXYik?tP~WBpTMfIkHWJe?VTNz4uSFFN7=&G1i$%wxYl>K+fT$FmUd_hI;_ z&K_s*|FitL7XLqoASV9zApeqn|E;cntLtCVz`w-&Z|nNEy8a~%{7cOLwyytY>O%U5 zJ7r+`cnflPbe3rF3Z6YWTJXB!B7!gvPd}-RIgyVwh*qMi5EvL_jHh2%nE1qZkCh0v zVv<4#8^~{wFxVq6&2C{}h+)J8`4t>zcIS*7F%{c7j~@07M~S^{1r8d;z*vH^vb%ns zQ?da`By!I&kyArcKM=Dz1JX%;d&X!N5UTf#Js$;sm&_oBe8fLUL4L*mL|`fi{ZaEb@xNjD8~1ONzlr}1+~1x5 zEAjsZ?!TZ2@>fqos92PYy`*M)wM zrMo#w94CkbKk6p;30`(RtHQe4uGIK!~I6?phV|X{US6;)m7o$A1Xpco!rtwSddQ!u! zz6&)BySaW&dkJ{uq9FblHMfoOSRZ&HXFl$ouWh$Iah56P6nWlsD-w59Bo|tT6P26F zP5mS#Ql2sz)!bdKY!2c527M;pXu2eedE5MZeIv}fcou5Kr8&IWuKZ%Nu3sKECB^f1 zLRtq!(Qlpxe=*KCh%QL(f#G!JKr`Eo+l2Nmgfo5AM z!{BMk#~cbeXg_Yr`Lwm{v=s`;{8nx_uj@V!31V(bFr~9x|C+3&tfE4>h2X9`ou~bh z$2Hy-uf|0=TWSZobvG0|cFLUOGPea@(9t&*p$OUkydSMdt6uK!Mpok%jeB-~*t zx#g-n3 zaK7q7d91sFq4O8RrKU@hxcWkOy=5JIC3iBkaj37KZC9nM7mL&srd`AVvaq)ydi!KU z-v_{vDI4W;tT2YnLow4|#Jxn~xYwng4bIY*QTm>=r5oIqZG7nAz~Y889W8^xoi-IR zzNOQcO3?;)~o~xKTy~7vab&8AQaJ$m!ex)$v zjqr!zc%VSVbeAO*EacaUJ&+XkVWXSa;$B&@4c~N7=B~xH9%(k0882Jv61>fIt&Med zrjw^A?sPr*#0|~og(XBC(X&6gy9LB0Y9{-`L1oBX*1F0}I^Vem6#bN}=96Mep|vlL z@45v{jI8#%b@uYtLds9W z1;SI@+Ygnu8l_o+r50=4ylx9p9S%fUU(KkX!`(|$bq}SdU1YekGm$x9fXK)MIqj_t zs~zs^oc!Xe*;l?8X7d|KQMDEOXDG!ii0$#tey_x_nXGN-^@JD1Uzw#@++V)`Cz$c0)Q)Gu5B2tcmQb z>_iClg@9x4dR$gf++w;CFzdD!xqluz@U~a4&2gWaf?fA=rjGib@p=H>##C#kW`thN zZX{iAc}S=v3jab#))gH6T(i-Rem+Xlx^DHrsr;{9-+F>KrZEw3Ig*_cg>8Wb=frg8=oL292rpm>5oc#J1`t<5A z2pU|y9<=cllE`kWyi-P?OghUL6+DnNjdCeu&I@roENl7Cm)zHX za@E+_<#C1{^3vxkG@O@pVmAbG@-$-w37)H@{hMM>UxL6b1Yw5u&%F zQr9CCA;?n$@H=>e8ZiATQD zQYkL~7?NGbq?~zz%f8`|cg%oAWL>Q{_^zy*^`Wc|cN(92xAP=Jc&M}3s&yCt&iVy{ z>4m{^Thb9L?DIv34G6cj^UIWi1<7Ix0(QQz1F01e;bYsIFF*ucI@5{c_cv!3mxgzY zGdwED$RE$?n^e(+3V9EXXQ!*usK>Vz+pY&*Mi^a2+`l_Zh~@&)<-DHUzspjs ztMkj|Lr%csn^H8+?R&sV3%-`qt}Nls#fMP7D_TJC{g*6+hE2y4yXSTH9WiAC3g^4r z0$1m35Y5shg8brzw;`7`%i3qIqI5bx8|4^ys}$tQ1L#TgitGS`d``TX&s3g0I|3R+ zB%36@MoCL+SE~J*fQOlcYHoAUTCHIM?eG?{N?WwAl6dQhcrHrGawlETw>=UxUwq0- z^Z_Xr}j;M%3zb?EKRM{4MA*VYbba$AcGhpCnD6=%o;5$aietu1}tlX__;kXnJE zJ{0?$RDr)W?Y@1W*>Ei((g2HsP?czl92+;YWeke)-1d(#Va6*h4ez<@OD>aQT+OxkSGDXzb)wbI|zhL zi>b|;*tl-X_RQJxbM(GISV?k=s6p{E_#O9&FU1Dj(7K|~j*nJAgSV?NS@s&O$1y!~mjDCtDgMPUKW|}A7 zC?`ce-I%?Z?#8tF^2Q4^H*=eZQccV_ne$twhJUFv-oV3GUFCn%F6$X!Sy@`rx;F7U zk1R;JriZ+a%5dsBXRa-JZ{g;8G%)?MZ;MfR1_}H5LZSu&;rwLXe6656(Eqhk;?HJD zqZwvnaiE7bwR6YGC_;JZ136dCrpF27q@|z0VYCvuzMwtndTdV5>|*;&nz{LKh>4c) zQlk}ZV|zPbI$FfNw91+$&7FeHL8FJ1t$4B1H&=k`I@BXcTgjvA8^=Kz`>&)tNiN8a z+r@CDmXDlNS~n?R&@&;wGV|HuI=oY@lX3$~=z5az+A*TKgV9hE#3{nTd?`#@#Cg)1 z|H);@lt35{#Hz8;!@VvdSysUhVPzQzJ$yHLEMK5fC}nfJ_oWi^fUSGB$-4s~?{E{^ zRzrU13gim$U6I?ysVh>^lvrJZ7MUb)uCSFDE8)z=Ue)0HND`(k8%tncw;{royRK2~9dPQCx93CUit2B%BN~rFV zHT?!7c=KL`P)yck>iC2@S|ax2&u&C+jl3M)+GRt#Ftw2*oz=*g*OpDnrJB_gwx%ls zWBv7_2Sa`Y>LiH!r_aafo^I=YFb0=gdDuo>(XZ*TVt{bQ*`5b$9OjrQl_pcWS$OY( zH)x9pN2R6gpRs-YcNdd9 z2F8*q$FIMUVQjszz0_nciGyO1{$c?hgBci=AVThVr$oCsvjAp zxp_BWdtR*7dS0OmrQHy6av|}j+TdG=!|92q(k|mDKW$5+w^JXPLT~Nd6C&#UbZ=et zfGf3J8SmlBVn-*`Y%*0sQp)9kt_N_2klWvcn)4-T)3Q+7EDI`y_rM5G5VD#}XRX`y zv)6M5i#J9yTTgdoTZjokJ8=f1`w^@yW+Lj0_I=;gQX=xj$}r2sYm}%-zUwsD-dOTS znASJMc1fB}S?{O8sJ?q0f|)O{|Fz#cQz1>LJl_SqT0Ci>;$m*lp?m^Ez8HD$?ydaO zX^?4kOqCzb%oW`YcO%B|b*Y<@lILseC$6bO_2=hUceVNcXBrddU>TwX^5*j0g!oz6 zK>>|R_z6piG?VHOg=^MIg?_n>iF%Xkn@NeA_Q)m&)~-pyUrl@yhkAn7Z-YkS5iMsh zo5Aj&t&7Twu9Ea@y=57ULzI4rYQKgHteMv%1sYz zFF8vkn)W^YLtPgC{N!@ll=G@{m%yHGHKm<~1Ky$-`!N zWOFS^&En*!>*_fnui%q7);2GZePgk=gWOWz3Jm9u?-bnA$t^tLkYCi1xu>vxi{z{Jf!ML_PWKX8$U@8mnQD7W!#+rUKovHfO5b9_?4?c=qI! zl2LSnbp&o%taOuK+VGv*=5QYFTF>ff@_`DDR=84|nfCD)wwtkZ`wk!P+peg_UN!}%eT#Uj^ZE9q9EW>(CzPi zt~L+d*Z6?_Y5)es$c*#o<`2zbj;5L6OYptz#v|Jqn2@tgn8AO)z&8x?vb<7c}4SAiZ0Pdy3D5ax(kE^`XZR>)pHp*d6X7 zxF)bBZe>a~K5TP3fOl}=*9Ii|s1@(ZQNdC$hY$d)lE(_vo{>9sN!Xtp-kFBRaTvWI z@?}3Nnhvm(4$TpXly_|e5jc6I(9Fln-NrT<#DDY*l$d3|YH)0aydr-P?blfkKS*?+kB z_%1?`Hsu)3e_Cqx&UEwyxrMWG441rXhD)$MYBrlL7kO zHaX0XxISdYc?_n`koeE9Kn1AZ)j6aO2Qzj6OY z`J4Ek;O^amPW8O^c%;6iRsD|Zpk0L`C~|G(prSPyy}n70=%&HKwD1q#4eiNX>~d<~ ze@)KRBfI%lN-lI?_rSlrn1hrr1TGE1zgiPSm97MII<6MvxKDGLisSFQ7mXO0m`v_o z8oFy=%RSLHtE%zxCiEk1?v{SV6mkG^P}q)hR~Z60>`(EFioQ&%CuK)Z5DMRqa*20K z^A#=0mHZv5_j zWuTKR$N8bs!X$!iQ2(|sm<-!Q4MBE6YI$!Bp)_SDX5}3agidsS05|X9LI&U&PB5C+ z67P%C*_N1U2|Cg)1&X&_{$UPk!gAZzN=-L}JB1EF&^}v%T5WvP3FRmhj4+yA@O}bO zCrd0eXKOScIZ9Hs-P;$!^h=gO?k##}=_yTfi$gY{f%2tT*2EM4}5$%9Ws!FL@U7KQ4OQ*B610uPh43fv1i;cQ$u1zM^3GSyvx5>o0W=okMbJ zSK=cBYI}eUJooOV_0birjkNd=0wx>eG`zGKBxbG0 z3T?b$eLYr+)nGK+m6*3BHrwMmD`}GHq&1k2p}n%M1L1e8mNYtTXCeE3(#1jptKRSH zw9@a+Ob32;gE-M}hCAxOb$C`5o`})MlQF-xrSz78BV)Se6v5P?HjpA2V zTMjTUpU9B-VUv0u|Bl>uj(RByL)^5bvEgVxk{JM|exIRLcYpq4T*CQ+*`io{HFOWh zk@cVpL63UHqz;Q`-rJ~u$3$6=zBx&>UCb^i>gkrc%2yl|`~x>rn2?0AhMbP(EnWO{ z4xwbeiw!?($=LeW>iN}sHA`j>8zi8i)Ot94Gz3~sPGF$z$c|?8K)@?`t~lV#a%}#5 zjw|je5Ub=cAFYC$(HAg5X+7LOC0%|aYM1ORo5%=rBYw!82H_4~f~<|OkkiEj+0=e``s163IuSWh-Q+8aBO zc(t70ap^2vyb45R25s*8^d(ovN~f5JDrp?QAPrh?*>7OI5{s`JUvI58VmcY!Ft&Jc zlhz@jxxcudiyV7##*O8A&g|ao);>El8#vihkH%(4KbRcM)x(TrNl0csEvlcCP}5}7 zGuJCR-zP1SaI%d}qsjqh-;0<$*=h1j(=)Qis)}!nO`>7aE2(*(+8AI&veO*sOl;|&4-rwpY=>#FeuO$x=@amUKs5o=@yqY|CwG~cOFD6a;-DaWk4L9LZ9IA4$& zyC>D;|JrCMHRG$|s*};Ju*z+n1MrHOH3Pp+$4RJcT2r$XdadX)4}Vb)R;#%~>p|?I zV}>nJNc%OHl&k;ZN3R7BlnE^SL1d4>*wK+It*Q#8sgha=CX{p5P8}oKwcIPVYe#;Z z!3x*@*g~r1b0wG7B6(3mu&%v#*w88Ae%=b~m&(r$`{rD}($z%m^VvfDlvG-j1!K)k z$ZtDu2L}4^YI8O46Fm3??utlXHi-HGuk1J0*se!rURh0~+kZqA8QJ~vwp<#S(7oyf z`-xa+AUSUr0g)LKVvp2I>Zzp()IrAWaIEibVpiiY8VL>?XI;=`BPOd{B}7z%h&AtH zr<+Do+ZMWrp*NW*y`_P`g3?6LAps9hbbR71)#A@ylj;F4XC)*X}f+1{Sp zOHXUZed8xRLnVjOE&Z9eEe8vB<2)KMv;~G+4qep#V}GZ^iRg-~>#07GQpIlf*_^Y@ zWUyVXl~9H|Y6N=3AqomDbJX~Yhn9d$5lRr>q*%Z>qE)T~ToO%){>p%arE!V>LI&P& zW8{O7@0KLJWsTZ^$G34Lsg=I4vT)(ch+NkOb3DqVw}_~=;g~MIB8x>x`11U{R-K#}`UrT`iezUAEb(U81+E zO$!7RgJ%bpy!qINGZ6?}#VY7w0T;DMD^3SJcpuDFqdjFCO!K%8>%PlQRw zycbGL4|ZpOs?fPPjrWwkv%35&Y;3QUUtb7}P7Ka}G!f`51~VSYbHP?VE7^7>`+YOD z3f7wNG_B31`;k-{rEULK{o#~pyd<{O640TWqok~1?zEb6#b9)7tveFPcT|1oVdKwh zgL{ytNac_f*N6Yn3Z}gi^EyP|9ZR(;&@Cu(j8sIlNFyl^%PLnRs%2FVe~|maM`<}k zI8r&6x;5IH{p!PoLhuq<$! zPBqN6gPTMU!iXCQD6(k$Fz1-(f6UMC*uJ|O>ej_x2O-Dsb!(p(DVor=_`G3{%G#&d z9r9x|arS{!UfU_)!d;4fY2Eiqdc3*2i?uFUYOR{lr5BxbkEeSHu3qI~O+hL7$KV-( z=V#ujzSi0MU9U@vxQ@i3f|E6fAqJ6~H>n88;4PPcgqRuD@B7{@a#ZcX58dPRvlg+S zvzv$)`PqjMS9sKmkESd;E%Kx;!wv0M;cLbY51$HL4&2}is^xB$94@t+)s(S<@-G%k z38Aq}S1hawCT%=kzOs4~zL{_7<$RpSSXqyI{BSaBCfBcFGd7{!XLmYvT{eyW$l zAE88TGG5EWSMIllh4;8}pIB&JlHgURX3sL|GdG%Q^Gg7gv&2>c6n;!cO{|GGYXzRw zi8xlBB=o&w^vjBZS`A_hj+|w5WbJ-h+dAA8C5*kMB5J7clQ1I=u0P+nN^liN8Cg%| zlYRI(tA0E-wP7ux-7At|7`arkEZ_K|x|ugNS&`mdx?AlA7Jjxi84ZXvWTEDP`;7gZ z(c|*tdP+0-$36EHrox4BAEPHfINXCoUO+d30{`Bl{BFP-0b9;xoAUH3hexKXDrFF% zLG1cVv14Un{dv~YA?kN)LT~zv>J=%^w;#3`am{W6q0#D2`B?&gxV;~K^gd`ykn3G& zXr){tge+EZbKauiZiZJr9ZMuO!N%Lgzft_YQyH>+{e%45k^P(aFCOh}WK_?Z$?@^A zn7HJ7N=kK?-+@lSRos)~RE%L#E1h=y`lZhE1G7Mh<_YZ&$DSTn zK~qCxU=5(n=ka3vS5HsRgy?q4bQ(Q&??_MrC-O3(SOPJx4?fBf3^IxyMN1qGID;`JAqM!>|qcJf&$Po zaZR&mOnbaF3tk7eU4?$IKow!NBxCBjytvSNT2fh=yB!X{_y=zAePS!$Iy$r}D)-Zd z^^`1D@xjV;g$-BS8okCo8(`p0IQJ!)b|{y z$7d~FacG8sn&f%jIHMdNT|N&Mv6;GIlbnY zb)i>O#eFmCKlbi%2jtaXS|5mVr7V9X_briRWZst}+F6Uls5e4gJzMKS7RE@*xiZ{U zFOa-`y(bL?u?i`q$%{+35Z}dIysKIiO>^HT-k*H!c-B8IxB(}O+QsVH1N{U)((K`J z{n|OWN8CRAv>K%gH`8)KKxt<{;VvdIiGDuxDIBr7K%kH$W*&PCFJ5k`J5?b>tJV-y zJn!_pnJzN+v~A1ti*9az(kBs!2VAh}Es&kP$qAb`No~b|nlSm(H2y-+Kqakm2>~|l zJlA(vHs$+4DWYz^68}$?T%%)!t2(i7OTSR@DWool^W<(J3ExsEnOE6B52;*P&9HzJ zykci1gR#}5H{kAEe{<-5re@biiHBo%+NaGEQy1{SwmP=LS3;6U3YRk{@oLgDrB>N= zP_G!lrVmr)jZC76`Hd;OlNSY~t5o_OuN$zG1B8MK5GlOrWW23PrMaesM*E}8yCI~Y znrjU?hJ13p8__jw0Gf0hh-3YabBvvUx5caOYZYSZOs($E=8p z02iE)6*JrorOn~bkNX|14o5YJc5R9zo04lI4s9uGo{yvrek5!fK#)II%5Ex4{9N29 zaxmlLnRE9c;T(Q6*Qi$aYX>opKJr%KH5RTlS&C2gz0g6v$cz7`i0EaRq1Jg z{+o*%Y+6M8jv;!=EB6u1Ccb#@t-`chg`!u|!5-ceF~(k>4NLYeW0zdO>vuWvIierapHsEAINy~KI$7*(2|qQI8j(Ewlg z)3n0o7gleYEqKeL_eiD@9mmpcBBe(gLl7vQHqbY6-a)Ijtt;B=751wr@J2@(TX>^0 z{E2%Y$>;_=eDJPFAc_Bnn8t*V;SwkYc?d65y4YwYhH>_ETc+rQ-Z6!06H5!n>7E6v z*tx=TwdZz~7KNJ;wsx5BWDT3oiX93Q^V!zP9Oi;8*Q&MY^Yl65!M#QT_P2}FcyUfN z8bhXyi^x?_y6YX+)Rz$gyM5&-sTI2IVp+fZe zrRk#=ycMfVjxKDxPEF%+!Zk|r`~>(jI6@bbyqO*b$YSce`l}-OChSM8Ok7dJadmM{ z;+l?!(-)3R#Qx)8_ili!=BE4xh1NTSNXqu3A!uW+39NA!G@ARHuhwAZeg8m35}cKl ztu#t?(=A2li+HhlRnt+p4B*~()kCsyOC;MG z(Q^>jG}3yfcP}CirtINbFL&&sQk#=~HQK}CT1M+zFXHxbCxF5xU5RmP)JGxia4c?E z1|fWbzWrgz$njtpY4_fd9k{?DkfBbb_w)24st0c(3)g>sxBa9a;`rSrz+~A!Y-?Y87@1d~SvpG*Glg*fz9<)aupNALfD@Kgn0hjUC$nI%-cn;{s)S5Ti z6+};7aCbA`k8JX+m6ZdBSK0QQ9F5Loq4&o0$K|uL*C;j17AnRgCyaFp^rHRld;1&L zLcpmwTRug&fM~1x+uFVaww(4t?(0px(>>?`*n~fF!|v4S2u-a9?zwDrU6OW0l9kZ= zJy&H@E2vimBJE3pCX4;_(Y)GSsU|O|E2O8_zKt(cN1=y2m8X%2^M)6^U16zYuI}Uw z4#=JlzWcz7YS9ih@Xg}!x*Zf^M7KBZn!i$2yHSBbcJHqrZZc)R@=(XC89F@oHP+5e zt>7(m9JNpI2=)u$lq=&p*$Od3?|u%(N64W3|7s(=*q6E%Ak= zhUV@D8!D}eMw^HukYOY;blxXg7#=0m5#I6_C0?gVg@Izor8GDN3PzIZ)HRrBUm(+vTydl~FT(az(=;<{rx3lNiquJ}xjJz~{cm;cQC z4IQD;u6)%7Gtdsm-;jffzx%PGuf@d)?1cyA{wUj0TP=j=edk0x1@ z_LC-0t@S`Ou#0$?65tW|vl&88JoH)D6$^e17K1Q3d4scIeEjWe zE(o&<+>_NG+0mS07IyiIq>34pLhnR4#NNfvnLOyysfwt(YcGX#!}cX|j+B1LB$Rt@ z7S2WB*?G$Zw#RZAFkBLt1F6^(?HuRjE1t{(v019!F@hy##dA>i9ut}nqqqma?e?3m z&y{!D?+9ZowI*ALHCQPk%syV(&~3`-aX?Y0j3>yF_v&Z24%7K4@MDa3fFkwz>ZQD! z#3l!7O;?QH^|tJZ18WMLZK-V|YV*#Ujrp*iJcnPDR z%Dsk@iPk}hl`AA>skr*ymK3E1l%|+OFKqGkMhW>itBZ2kXyB?hN%kC!mMZL78+J}{j(c(yU_3lkZLyow#KVET&;cz_PIPF&Y_ zg=zhY4c;yXRnmS_i0tw1v0A1*2L}B@VdIp7Ftvt$_7M)J(;7E%I)US6yB1O-x{6EM zBCkjY7w(Rxow3bx=HI9gvDDRGld3qRo$+zIYY>%|YAzEsVghy6zLNle`?l06=~hn!OCN= z(3Shl1vMMfThvJFnJ;Qm-R1?R|3OMu8*7NPen&RzAN}gTHm0O&A#aEKib1fRmu2vkoD0gAW^cOkOw6^Z6dXvLt`(kpHq zxe`&|9-;+aZ0Nv*Y#zjNy3zTLBF_v(<9BYKSu-~lv0}Bz)$`D;xUb%H?|M#BS{R*E zEY+fSb99h51)E#hWDj-b0>;d?2R7utm2wYygYrI(-XIKh!gYt}oSm*c z4~-Q);H1!f+*C97POgF43mf0cw^ZCL-DlN)^49tqaY}5IF9CERXX&34iYf|lKDA=U z1ipAB&!J}59Fk&$YVac;u$O`(R6G+iy}?pv<1nN@k6(fsnrBg4y^vuWcO)O~rq%cr zP;V5pyfeDRe#>>Zxma|W07DuVMh=`Bxwhy$fB946ObULE$9Hhv)n{4?&Zzd=?1@H_ z=b`4>V>MfhD#ka4F2tJ2<%zF@Lk*bHL3a3af{rqj&RVTwijmST$v9TtN25licDu;7 z1rz=WGyt7}Sg>fHgQq$J-GOUdm)cueNw3QHjqnRC*eRjwQTT9eKf3K25oE`o34NQ_ z%!6zI*%+5R%BQuA81`t`vevHwI2Sh5Qjr*w)NDuXEvB)-wgRk1LwV9Y8KH(L&I;06 zJual_Vtuw*?t@>s)%91$gN5mKP57IK)5v!WDUnzk1< z9%P-BHfFIKCt@FT{f@QI(jJZW!s&p_6 z?rD)lX*`lHz~16+4X9RdTLOt%%7A544H3rZ$(9VD}CHd9X zNf)N_AzxbE&W!)zi0=Nq4-49u9$DLG4C_dbwT$X!@)`V=SAz|LZe}=tDtJxVKmPjW z;OK$v&!E@681tW$;Q#csvNOQ?(vq04aQu1D@33IEb~^(~L}cXA@iBGe8V%&vsH5`f z`}0#Vn1+Uiaj(zQTfakUg7neY%PT7!PRC@w19}FukDM^8Yip6w@d8p(RnFmmps}p4 zt@$_z5z%4={uN{EUfTqHelm(bQhoj-ft2_A`ROZEe-KaEK>sq!-<|$K`PbmCiPrlh zm&W|%GgsLGN9hXb4nF8{#&E}C?C*Nho~z^J2_lIIkoxsAR(yI83$hLI^|2wQ*S0uH z;lA3ep<7BNzEOByACkRD`)SWooU7kI5>bB|!2K=MXKzWR?kHzF5wAXUsF6|sUcAmT z+%3Q@Ej*LmE*ax7B&;D*8R@?LX36Ee1VHWIpzD$NpOb{F_r%c}JtuF@3|a!=HZLyq zS&d>eCN`tMjK@1K@z)9#C5(2kS1wI&rjMgwLmo3N_=2^UKdYxV7X?533OLvE>WgjM z4f)Ko0G3Er2?6NMcB}3V$f;04mFMFUr|<;2LkMa16FXZ`r z>4jGvGKdAOxrq`nUOWQqQF*B1J;c1->3WPCuEWi%x`&;_RM0DI9ifLJfOW1TK241o z8$4ztnavaR*EmoznvB#poXrpudSvn)6!UdN31X6ReV<;*DQE1tTHus=*xJA{LWfT5 zx8xkyMi*)H!~m{K49DJ36a>@>^K*tCz5u?o;QrFe2CtF8H$z@o>&6$@iE1#L4mb61 zEwY>UnH=_fr?$M&tQ1}WQDQkOQr&m1l|OJuRVR~()cnAj>G6YU-rlA|QFNQY$#F3$SF$D0k|6ndl;hGyU&xA;_#JS+9`CSn&_ zukFR&?lSbM_`!o8^s6n|F*b?IzU*KuE>QF_Jjw0M)frE2E;VW4$<%+C`fKQlR;%p$ zT0R!zk);FcKS zI!v!zZx4tIx1Rs}$?nRzb9>|w#{?bGog%{OyvN8T|AtKp2>;>Nh#%BXy_9GZKG?9l zfNdGVobGU-zp#~^KEV8DhSSdO&_FnszeNF*BQmI(L1V2Cn9;(GbIX%gKhzaU}T7 z7b8i-9H6;;FzusE$~oxoCo21Y$>2i1@232pQ@C_vUJlq+xidyrHq9L&-S~VEC%42o zN4skron~FJqj>lp0{(*BV=bkI65rkpz2&$*Q7%9oB!jB7VVBzvUHSBkozhR}pMSb- zqDrv$g31&bOZr`bXr%`@eU`S!9`6WH?UeRZRNh#C64u~{|B?!I|Cr|$Qj~5C$9@Zi z%84HEoJws91^8Lq`Jnt*s2sj_yMc>_v62rOcX5dSu@ObK3uCEjmWd+(f z$ zDP8A6`0+OsM6@Aoi(4;MO)zgH7aIqOQUeR+2zPzmy1s`_hM7Q7wB!QI^&Xxv?s z;O^3BaCdi?#@*e$ahH#C-sc(bH^#kpjQgusbye?Ld#~M9tLB`ww%g;g$G&C0GTm58 zI1k^iBr7o{o~x~MsBTxc?GL%81kb`T=H0(UOCkFzybz|8@tUTTL~C*2YJG}$ZGpO{ z_1>k;X@2X=FuP>F57d#vM)L2lVdqgFWI3B|=LkEWx;t#j33|T5+FGep6t~r>+hg?@ zzY};t&0KDLQ*v^*c1CG)H=p(Hp{~1e_W5Vs@hIr*BLY@oGlTEq40v=7mE2b2W2G5R z86tJbx%YvxZP3nTJqBoy>LgNwu=b!gTdy_`Bz(G*e5!;%pSK+@?Xg8Ggq&(OyB$@C zy18+?wwb4@IwK-_@3cI(r}EorRtipJ)F%bqThM>C6+ia?t|1cK6)1Pr{j-#2B&zDb zLHCuCusRSquZGRCJgo~fcGI7mwaG;Mng+S;iO#C;OahXh-MHNEuYO6UaUxVwiX0mw z2n)Nv^wQPY>2#QC%J6`KV?XLNB%L{88mIUeOy;8M{Z|Vx+jh!#*Xt@;>IQ7*zsgEVAmR(ZE%_w5M{?@zKT}TZ>wPZtC!)>9(W>NXnw9t2QUvsJY zP@JF2@6%=~^Kf1~VSMWTmXWJVcFJ6%#1vP3ro*ojf7HY}ihA!ef%=+?ulv6bp18J< zPtDb)xaz=3UWkr94h-!hkH5wKT;XNEtoN6u^Km!`u!2U7Z!A{0m~UNf67l!%=Q&$g zx=;guk6o^Wz1r!4bl91f4YKT)Fs5Jr><3|Zai(Wn^CIKC^j$4kF5GpK5HioE;z%iw z_U*cy_5NAAGrswNBi)YOohOJWTTIxmTJ2mxN*RRfqdPcxUp`J{fvJ@>=riqV`FX8m z+;(UV8O#ZK?;t=NjN#@N$BNmX=UQhy0=n}+zPC7F(9 z*RC=GA{AO5dSM*v-ZxX zRIuRr(J^+M@ic_41^KwY^tU!!^e^s&(CrLV!oR+5v4^8XTNzaU%~kAlw`AoODc~ zj}v|{Gf$}>Y;8Lg-cysY?lJ|Ek#Q5^OH5bh_%v)~MvTT%I%tUnhG24Hw)+S!(DP!- zd(NH`#N%pHLYLQ@ORx04@9Hk-clQ*c94 zWoz{JEGb!8agp_TDnrj=R>PWCN%;S|KnK^$u6_Cj9Su1j!&>nn=>sTaXm+|Wzx`e&!Yk#8aekz@4y5F!k>AN0l?b%Nl8J~aLJW?0& zHkh$sivj61M$b9}lJ6fjEqQ$ZnSL}*%iKH1U^<^Sz$Wuh1OEr69v9?e+1nasr6 zXeY)+=oaP0tIFcgr#Y#4MWaWg*#E5PPw+CneZHo%cm}mp3!{;RkLLhjx4Sx zNTx%+*}Yg}%gc}1TmCQ>+M;U=KG^21?|8PPQK>k$?Wg2Tqhn<&-=E*Fl`JLdUcAWl z?jHx{3dY*FJGv9Or|nwyOBSnBGpn_V!jC>RX3YV|_a`#$y-MNfap+J-o#A+SJ=lKw zV->D{wb)Fi%#HKCT-^?m^&Rbldu7;iea_S}D=U2TE?f|7wxQ<+8zryoZ!6pr0668A zAz#UcJ}@l8uguM)JJVk)nz&Qe5fiI87td_$ZiwhwQsw~wq(Eo*Mt_96ozj7C8N8Fk z!0Ryw^W}3#r2)uj=N~Vk{t{3!U17=dp~uBD@ov5aKY^KYeWsP{Xa8Q+`6YtU!l^^a z_PS(dGfp{9X=V+q0)3UpUrpX~r3qCUkvGzZ+@yY=5*7Xyt#6(N#3YLp;kR7rE?*sB zSbqq6%yWQ(!UcPZOl#-$9$6f8_k-J#Wq+pC0N6kujx^tNKu+`f=GJcEpD*t{6&SMD zGRFL5NB6@$z}{nX*8;fVs-eA>_qPmcKd1%0+TM42=~dY}(h}D6TDsk$C8R^Nej=M( z{$$*kG%vbuTkz8W&is`HTHQ~o_up|A;II~nk}(Qe4=QWHx1S>@JrDpq+qGFV=>fw@ zW8iOW2134~-4t^9qQ$+I0xp?V3#K1R%lfKHRM_@Ctv9<#NOHn&y1pECd2$-E{MOZb zkv7%oFHuXT^H+azpW2+x7+!LsXS{YXj{{L!*f=m)Vq))f{VolKD8)iPx)VJ}xvl`R z`D5K>Ka%z=)D;xM6^-z?pZB-o zr8C_SDqg*OJP6HL+Exu{kznpgxL=3rOkGxggL`{@`~DUvjsUv)r5PvHR`{~Fd2%FS z=Sc`w8Kq!cn>YQr^TbzY)bm+yHu+_)uImS~`o%zT6^GW|LAZr1l9|dXvKdFpk(Z8> zfVZnr8fDpE`@oIqBz4Kwr?XiO**3OOW`$+yU%A05!-beMTyU_;!%?#{CbO4#?13q`3+WR7Bvn}u z_@ck(fZi1{C(DOT)Ha>EG#CZ3Ae6O%7^gs*qQb;1yPg>p;mv4a^1Pl;DVmzlsoR64 zj9);hq-xR-zc}?S+?Jti#;2|c_dXZR_V1n!a`qQbE)x2bn~?`}^X@^h{Vq(e%@jG# z1hRTmxqV-HN2f4T{8}v|d1QuHb3Jb^=8nG=z2;u+3x?fP`dn;H!lcRu?{&n;xn2~K zH0b+8ne)2aStg$o(MI6R@J3?e%JJ1wEfCp0DE}hxCKoO z&H7>C)=p@Xuo^_7XIm)>}{>a9Z(U(8P;pFST9 z)e37SAn?uPXv~?sdnW9@2g)){NJyljfFW@RYx)vG#{61M7HE1ejlKo3V)HCVVjM}2 ztSu={{1Fq2}l>qerCXC=3%%tUaVK;7z)4Et|P*ZYOj96DFueiF}Qv&@l( z^Fl2%wXti35GBqgxV}$qRJSb?-l*Ou{M^_5fh}iU%60gCEIW-G4YM&@52r5Y`@ghb zk}t^1N4b8jJx8)kXTHas@*rev=fJpJjC6g-q`EgM1%H;4%hB?>c}F9q|C%>bvJ6)5 zX6V4(tz0npcq=gfdp<*VeW4!r)7mx7DOAOny|IlfR<{)$D!g_!85?`=-26MewPieA z>^6j3~R(TCASbg=N+q6Uz7W z(Pk8>bUD8En8^Ua$?;?YsdQQ^5%gDc?|BkTK8YQNSJnNqSYa7M&D#@4 zy<5(VopJ+C@5chLcbvDKUC@U3&Znf20LCxYj*DuIy+uaSBQ4)YH`Ak{{Fb=$X ziI$^wwWMUctuI&OH{-iQMfWb;*jbSKoYSl=tNiahZ!hK<2|$X>FDh*$vZ1(ZDba7= zm>zJ>#!IGyH@#GO{z0@hs?{N%#b${)hV`wkPF+B5=Fb}FWRd6nLN3>CJYF6SvHnKO zN1kOjhgQ&o|0lJN!XWF`Y&Z`eot}wF+FQ2Ve-dlb--o&SL_I5GD3lxdW+l>0y6Jm= zZ8~)_+J>CMAN2F!c-8m=_gW!ax68f4HVm1jXQ6yN4PTjB$@^O--EFx2Mv_LI+XGz< z8&Z}lgtYxfYWAGu?CLLhUT&uZF3Nh?&Etk(3=*WHh{C5LU z+5i7(ivRug&w>9Oz!oQ4_5EKfs5p`08PC|mrxS|=ZC4QzRs4GvDb2?Qg`ed6)@qpq zWu?UFg9S$lWCTJfD5!@N{V7ZK=H`ZrhdX=5Jogks=%d|2MP+601O%U!w%Z4ggG2A3 z_+h%3OTV^lgTPUjC`EfRc{%J&+)GI+fX2wk*wWgXd-jp^FfK7sOvsba`{n(sMuleW z>68-(NWtE>QDp}dt=eIU?z3CutZw4Aju&dkS3#ik4VO5V@yfqmtMYF_- zE9&JZJ69vrO^I8uyKA)d#!gf_+#d%y-uQiTaxzIxOB=y6SB7?Oec-hDe<4M^k5SfApILX zQopG0D*qG6|1T4^=s%Gr_4}_GM9bhgas7Z;ZlU>94;hc>dX9#uOR!PA^+-C<$K(S2 zv4On2P^DV^c7pdQ&9HGWBtUYv3Ej=Z4Fji9&aXk*dPyit^>rkZ@49FVNlKC0$2zpz zlg4|Q@C{Yy7B5!YG5tzr&Px085K1w`ff1jbeyK5>*Ly74Ino?^c(2D) z$GA9X#`+6fB5a}F$cY-eJhK@?OLi9<2*#$!l?lodb=k?tiiTlL-$AdRyW5|A2NuE+ zV#^$LL*m6P-Az)6#F3xaSYHbEe)c`9D!UxYIn@;Mdvq18X=*51CajNd-&|xe_-hke zPQaL7lTMIN`N{5M)3PV+NUd?)4x#=+m#6y*H(tAs`&Wwm1){?I$Lrto9HN?1k=52J z#I1d|T`Ee%OnnHioy5&Y_-oz%K2X$7O>Lgr{QIU)Us?LcS5!2uC(hO#=5Srk%o@-L ztm0#K1OhnoRw8ZAJop+LabG=r2u~GT-lBBf&ewahMRnQGDfUO1RAegq9N0mWZ3=uR zecyAcJ+#Y2WlezbOV@ty0`x6&dhoLt40XtR+C*m*VzaIn5>D}N++t)jW?u9H0aCb3 z?oI>{{j{leyqxq#Mnbc+kxO#Og98+g8*kz>+}h^+*$WpR4OY#qBEx=b z)66YmrjSC{mq$t9=n8nhcewSn|aD_7n%q6>;t7JW+4 zOKRl^z!+9fb!R>|%8Ye$vXsew{pL@ldO20zNuHuC z?aI8}*^fWhmk<+_;pPEGXKZB#FrpTi9o=mgqgZ=+U|0=BT-?fC&I8mw;9zP(-!DJ* zSUK7$4<^$1JYo0NFaJ4!-dpl0{F>?z1KU@#Yk{7-nzFg)9or-4((!(!D7G0r%v>{Q zgK!~v+4xxM+6OMTO45f1nli~2vgKcIqd$c!lPzJ+H?lu+=0*V#J9KEsz2!b`3k`WTUiC11pm{WHVjU}?FmWwhvsZ)h@TzRfoqUsRcG z9^uAN9{T;54R<#DXMSDPZV+#G*-@B7`~m^{9uolv;TP_;t_MM&-3i;DjZ#HK^gZ2H34q z#}(TM-6i7aiArO>UFJaLAK*EB|7=-m5Xjo6gHe6by4F`x>|kK1xjql-K2C(0Td1_J z32t-;bvQbo1XH%E`+C$zhaGQ*;4qmG8^5((nEMOP^4WtqM=uoM>zt;h<>>;YD$9Yh zD#>;K6yEP?PBX=MyK%Jls5-Sqvvu`gbAJlOj4LvsV|aF3_kY~qpleN|9IB&ui20c_ zvKRu%`itm^TAo=iU$d?zeT|40|NU5OMe3yvSK@&eq5Evj_Hq>k@NS>9D#J4% zlGyHt%tFtVoHuFCh*1ES%2eClvC+#{B241PID}D{{WJ5M{<6B0BbWGtxG;9&=q>rN<@ zsj60*Do*d_f`X&>3o!k1+E7{>lE3yUvv&*q`*RO5Z0(9P)ERvp+*a`zY1JU>>RYEO zk3kaHI5y?^@P`v#GWhvO*js%iG!kkajMEV_9N?e1d@qbsOUw>W}0ykXY@g8QcA|`0x{+o8wEXW@EIUX^R3Ua*?Rg zs@pdR>C$+#0_KN`sqbc!XsV|IqL-CAXQy5;!Xtb1&noZP6AOqwJMQzRE|t|%0_W_V z#r7~iZQIIz2bu~*odYm^dTTdktB1@~LS!vLV$Kd_DdRW@;o#-$l=)A9?uHHe#xJS` z6kazo(>~@3CS;vX+cjX=r}Ixm(hxpVz!i0=5u_p+S%|h=DbL;8ckoqy*IS60-DjrJ zToxq2dEN2zy`+*w+f5$%jUVL}t0!MKAzP9ITBY+5si*a^f6DGti!`Omo=kI*Qur?0 zjWze5>t6&7D?>=Nt; z#r9|8F%@YnDWv;s`bBar1$jyhrz-ZbLoUrUQar)4V=(@%XMkXtRYOHgjbx-XbfC0qBE+iRZh5-VlT91yMGtHyuiz}oF*v{$Vv|KEq)UknlvUh4@Xdy= zIHxGE=vdI;qm>g}mb5Q)Dktwvn1u43EaeT2yIuU*H=jF3SlQo(j#pHNEKo!aoz;R??Lgd#c# zzzO(9N?L~XT9>|aooN`ZCxw2Y$U@si3+MY*A>lbW^L-7P)xmM1u(rL%%AT1dCFMdI z1JTeD7TbvFYA%IwzO0h^&hm5>d6%!;7Jq}_h!tSt0hCG!$z(4b#Ppx7q!>Xp%fZn} z$~4zypooxFPNS|j>iGnk`~9W-;#)sy~tSs1I2%2qwVXam2 zk^ZTV0;l&Cb}PBD-bvHYWs6T89Y=Hnd{tUmX5zph0RN7i3Fil?EI@OPsKs) z#RC&iM37?2USRI#r5L5>m*z8LT%vh=Qj4{n_+dumcY+WS(nZi})1SL)V6br#Ka54l zdZkN6Zoyx?8N-rmJ{27Se^s=3HHl(F==bU_MksP#efL&y@;lGC7zG?R-;;~}WSQA^n^YEQ z<^A>jNKF#Zd+XXbJjF(m{XTCNtV`PSv#<#~d4H|2`&MTcd&;VZ`hj;}fez7+j{BOi z<^gy0b!Ij(k;}`RXv(x`Q+945`#@fYPz(5+H+{)xVZ%TD#HG0MK|z+7qE=Y21vT8E zt&SeS9_Ryopm$MZcxszm2c{=dIpsh%eS0ws>ukO*T78_0xb6_mjv;AG)-QZ7qI4u^ z_%jkA?_Bb=$>#9VR|Qe=HI@lGT<+5#{bzxbPjcX~b1rvAYlbNz4m{JQ~r*|R)qY+rla zl@{7PQC|S>u@y1|Qr`iN$2S*n`&s9@_zhK7Pgv0qWFz%Mm-HJbJ(oQ?!zK$Hse)=& zn+uj<_V-tr)TBjrYwTsatp7QIXU;G86DU_bseUoCu00{CdEr1)QOoF4A`I7CM)VwT z)oW{tt<{Z*$JqfT5p2(^t@Y3PD*atY$EbG@sW#_o8M?HT84Srsfrjh_tAt!4jV~?C zjO&6SBQ$*sf9;j{;A;Cu)w_M#&2K=lF&ok;oy74P)|G!}?G7ZRB$?GUAeKdUiKcdT z)l|IvxX7p10Hz{9l4R7w8VbESQuRcQrGEffl2!92(*?I>$yb_^yXDl3@X= z?_IW7uHYSaALz$al{n-#uQ1Tsv>+10Vs?1HFF)xasgC4Iv%JPM8>TDJM=WZ#1e#bqiX zJJ9t<(r#JRP{Py3V$gHo-qvH)!9CWz|M_CnK zUckmdn&nW%+TC%OsL!lLO@8A0mLXZ+RqoG!{+W4OjSnr_gYJ(=BF-HEklYpkR}?V< zv(ZC}5i-NtwmRQw8jh3Gv2xB%V zAS6=7OW)$;l#xH0f}?9jD3Gkvrr4)Aa3IXQpMs$8LTNZ@I+4}OZu+IP%K0;n+Qk@w z(e3w^>PS1fW>2pO3dZE|sO%Ym%VI7r!}t`LnSM2PYx=V>K_MeeH{t>c2qBNAkUnx^ zHGzCQ1rh0?bh^>c&(WJdq%uNGwL!k|%o$Gr;;rJxTZ`r%j(Nbvz$h~e<%O(&<+H6b z5i1sseN||MOU%knZ~Gkm&C!hSA9^2$mV%ayM4}hgsTUpv3qhO791n8wXGYQy<0{>QwO3csa!gJR;aaJ06fo{wLEwM-~fUF{CDJD$AHxuGp*$wpfHHZVX!(5KzIga zO||}w7@tv3I0p3f+1#7U$p1Lb zfOY(wrjlIQGP?keMG&w&5gES5xaFGYVan_N;Z(1!znb9K)`mR^5fdJ>^&n#>rRv_N zg_$f|`w9Q$4D*VQ)mXm#YEXu}hoboJb2EmcA*Pg%;ID9BTq1WTvM;RXmbRd^D$LO% z&NEOLasG`k{z9RFuLGdI&T-PlsCSbZocbT>O9lmtpZQQ>ZwN%J2RIT$@ZZBV|5`;k*ta$4$gv|e)z?zB znupNbX4c$MNy%P$UlB*io+VHaGQ$86G;fHsPtXQKN;!4&_{kF-^H#t>bN&N2D_$Yt z#Oea94gj=F_`u6~NFS~>g?F$roDLb1ukMuh++l&p7i+9(!&4Kge>5q$0NN3TGCvPy z^yjv<>m9-6>7bKvSZeot^x5@Q3Fic)2A{pnd! zi46PK5AK4TWDF4pXJgWcr=wJIS5Zjn+Ox_ky{2p!pFjW5zr;~=2`7N#^qJJ48kQPn+K;eiyyL zy>{GHNPpGT{Dpaeqi*d-J7dzjnM6Hq*SXc9j!JK8GxOY7x`q%&@BF}|MTv_aA4wV1 z>gdaM^4!aCrteVn|BUU}s%mOCha047>%N__2qORg6Z|*rs!@$WP=qI!FGct8@TjV) zl2=hd3jdU)tE@snON;#WU19SZMWC&Eap_Q5S@}E`QGN-f$KCjre||DUzV?1?+xgka z(f%Je{~bDdBqi8PC@2p*CoeZQIw>hA!{^tu&Rh5Vr%%+RqLO1{{S)hIi!d#LQXm1(Z+RD$PGnL$J8T0QD zzx{Gk4@FgmQc_Zq2@rmPH>C2$FkHFw&(6-uFo^q8He9Lw56XVdhyce!^rktD`J4rb z(((B(dGdcTCjXcDLFKLG|AF8C*G#OHsyixANh#hg`_DdY0~Qt*#(QQX(f?xkBC%ip z>zL5T|5u7e8^`f=xAP@D(E7hFutmI@$7+KW{+H(YUr(|mCfIvL-iqMcJ5)i&#u91C z|KnHq@aihD7!{~SvlO=I8dVW2u4r^=cq!AMu{{L_bc8G6V%gf6HBM|GD0}K1#=HA|Iu!aBGd(H@3EOTuqwID6= zU#{Z6RK(l%|C;3T|Mi{p|1$q~AV~k$L{#n-%-$8jtm94AzBcDaKt52&Jm%FI*olYx z=AVCCxg`#t0H0wGuaNl|#HhFf-%tcCXNf`g$A~tJ;}QMGi_Jr1Wtr`spH-ka*&AYs zyzz^*+@2Vxu(XZ0yZHfAa>OX`VhEYb+&Ye!hRXS5)Ah!U|E-IzJ%e}@;N;KgA#Zp4$vj%g01-T#rqBh14ZFwCB< zw|)!keU<5d>Yz(^v-&)dSk!GAqCa{$#=^U~JT5V^+O-$y)013t0h1D|cK$*ZdHGbV zlyq?@#m8-i@{F)LI!(kKpLS@acX8M36HA_^WhW7rSlLhPm5`V(Z7?__=kR)Galm_Q z=N-zCM%451{+Qv^{eaVuvDx0$dvPRHo6R5OBM@|MUk3blvXRR_=PQ__IHY@|_a4HU zSaN^w=@ceJ(dpTqeY`u%1&gQz?+n8s5~864$D*-DHNxGTgY$w@rw|a=JW{VF2P2$s z&eM+h(!EA4gSfAmGCd4wxNJgtQr(lryUp-IF}OZqNDpKh4US6LOB^cP1dveP|Dnh< zx!5F|C#p*Xno)$aK4w9OifM%xDuK8j=zeF<1JWiwb-!X?b9^lrzL2t{o)s7sY0a1q zM;Q31<2}lm%&cf|?${pc;~6~4DnlHoW%$JR7g}ibya}8)rGHtGZi!nB1<_;W5*mz+ zrX2@M=5%PU)T%0k#&8j~1p>`-anlWD=@6WuJFf0#{AI#42mQBIv~+*&o(@@O6_dn` z?sOw^Gt>anij#83z`0Q-wBFrRRtv4hxG53YVehV+{xo_Ua|uBIZNO(|>WG%)GGn_B z2z6>;0|fcYU_^9^ZzG;{p15zPmz%f#x^>A-Rm>7um2Hl%h8(m~9ShV*;F)p}uxb|5 z_*CUf#CvQ1#giGG2cC8776yB-IKQ7L)@^qq8rJm4C!Bg{y{B#ESP&dunY=X{Cw47S zulZ>xeVoily~q<}L+6j}qn6-VkmafRHX&y#(+GnY`;q_>;(t__7CgUHyOi) z{U~1e_!Eza$h-rEgi{n{z;B6E#Xlh;Cum!yP4~m7Bar9j`C7q%)S_SxV_VBt#42)i zoVRH#LN=xI+0J}BUtiG5t$wbR_tx_UGYyl^w44@Qdy>PaLzt2ND`XY( z=m~3Zk-zVjH6yp)SFugx^4ulZYAMW5iDLd6x6zVbKhvp z&CYK~nGFfZ{=mcXaOP=w{)^$~DV(43sinrJpow`Gk7RD0zKwSUdCGtCWjFoZ5NO8n zm>&f?7^U*Y`*A9As_%Ufl3LghTo{S)gK-{OStHA-V6&`hXip(g3aynIPBH4NHEls8 zs+TTj_jlMLpe22kq~CRW#ltV>?|IY{UH)t(%IvvtDM~^GLIdh1m4gP$dGPw;j5J?l66fk=^OP&~uAI(QZ{B}=B837^SOm@BK&q|;Z z<4<8&rOkaDmMC^RX;V{=wiaduB93_K45$REz?+L%jApy%Hd}J8@mD6jr+r=DcqguV z&T%W}v_2I@(g2wdnqE$HrP-6IgL6}s@OU>-+_pJaVHq+UdjGWLRMYfG&;~Zu5}3E& zMyHHS>s=HYv28~iVKBs9cD=RBm~a;2#$Ud2iB#;MW2eA6U{5>*au75KtA_{f<4Svy`&ByB zpTDrXn<@O01WcHg{lZs?4;%Ox^ZYO+xV~Hz;jwMpg)$XDG z23uvFH!WBT;jWSGs{|3gP}rAxdwL%q9<;d-vk}Lf+4g_|GuDsvX3K=M^mH9YK;K&XXl`Bep4+y2ztiQ>(eSB; z-EB3`Hon@Y#;Kw|u9=v*6Harj9g_kFKP8 z{KavLQb^duPWY5>*OI1yrO7TPeyF<9z~tlOtq^|!(cu&R^^mq%%a;X#Ca-HR>N8w_w0R+=3?`qj7x zUTjPSZB_R}R>tC}_yLeuq{|28NMyT0_b0p>s-23hIbe)61n`lj0yV##N(!<~x z$+#uPLhH(_Rd;H%wYReHI6+l1sLW_U1l%^=r-Aow_D}2dVa+WM*cWUErQOn&EL6r@ zHFKOTFrh+dcB*?G1mrGG>R-2_i7|5iRlaI>!k!3H!Q&l+`rJk->YZN*XOp%y$5TEc1Sz!qp>XB=BTVnM34ynXaad?ViRrH zZVGCvGbdN%O#E+v z+fhg7P|CvwM5Sr88~5em(vz?AZTWZ(mRSAQL#)&fGy1&vwI|H@P3LC8sbO?Xj-QD?aVMtaNKZ}*7s}gBujSPM%ZpxiBhtJf?HuW0f zzjB&<(`$>#Zo3CE)g9Bc`8kE9>&kfzlC7kTa-iXahM0fL9fmb+#b@2YBtFz-{%(Xh zz@Gh(FbDoO6A#}HQGY0&G4HUv{nv@f1UYYRdgQ_U(Z;! zkPl&k;ZX~SIOrCup0zt(z{x3J_+zlGc4euLATyz5kXwG-06;;)34Oyk#fSbnu1Tji zye1AZa@G9RtNrZzAtc28#lcBk{{7FwNiPo3iy;Se7CClBO>?RKr8UFZ;%-{r>sQ;7 z?x8W{sR_pmI{n0SN#|49HcwZ%_>NJ3>$uEx&Ra`}B*n#9HTU!Q8y<#)%ty8 zo#Tmo&oWuC2yS2}dpRpaAS7Q1J!XYJB&Tj}vQu6sc{s;1ZPbEf7^qf6EGNjwc0id* zry?0-*wI(S0)wLJK0SF6RY*q~;TXwrr!{v;dFaL|=j0PrFN$L1ytWb6=JqwV&#_BF z>$Xz98ZqOZ5<0vnU2+)E9?8z#YqF@^SQa81sH()iHYv_1^YyAVa9()_u!yd}{C*D< zTsDMP=HT(Gmeef_O>-<6xYD>o%gB}_E+x^wI*0IB-45&+>W@FhG>e<5{=+5c#lEW) zn6FW_Eum@ggI)>*E!lHB&W${%u;a-lDt_EZz8r}Ge>V(f%ziE=5h$RIyt3~wSUP~UAgaMP49%uxx+}d8L##Y6TK#a#M%LnPbOJz`peYj!hGFvBTru?OMvQ?F(>BtGi?> ztJCiwbwnd9X*_G@!~8gN0e9u+PS||o@uP_^iyTM3Hz)e47P6ZY_l4C%L}StQzvXma zkc; z9t)@CU_REAC6ND_I65av-=|f)Cs`sgRsdVmmvo($sK@6+Oj2jVVW-pOW)s?Ihz0k; zk*ugIH3-3NxX)p1+K4T4zb4VK(cjQEf36jC|Gr!8IFy662?R5gE&8J~Y{Apc&8P&l zvboxbT=ph~pmar7^%Bf-x@B|E8>1wjPnlQMIWYAqv@duf=DJ->Vgmdqp3zO_$qOj7 z3LjG!(Bl6k=4@%Sl1$<0^orpu_n0y!#*_W!pQl>8!mO5|^gqJo-i`yS!-G0-djawX zZ|gb?wFfi63+p4dOl5I{T}+AwrMoIIJJ9_EB;=FTO!k%wIU;;1RO)3zh*YOt78 zzu%a%bZ$wv`@!CSA0issXH?`<;R{dVV}m5uAMKRaU4Rp<){RzW>WO$(X}dX4=n$b` zzxmOw?&XeGZOXsquq(Sg>C;T|{^LdZK0wskfRM4c<-vv8)<8q^245zEh{dNRh|iNV&MA zQMEvGU)1yA*X8xzOcMm|J9M9gywj8VKJ+dmD>BxzZg|J`$(3hy1ZEIKR9eCmhohu; zzO;K4n>uKg%K2N<-eI5{UMnRakQaa}=vlhOZC4~|qN1TPamH6f+Gj%`@_1Z2tP?8? zeSb2saAov;oZ0);iIF3XXREZZO?HwRFr4R8VWhVu9QuwvKO&=qP@9(fP1VTz0VZwY ziNHxZzM^e-Q{?Cert9HWqbK(dsk7anfOaMI{{fSblz(iw(8{fpY?MRLFJJzI`<<+f zmDLKKU%R&==9R8Y=G@yzlPhZhCt#TY(%TW8t}bGGu4mvBl4wP?r zV?D#|@zK|@>D)azL#OLt;BVzKgx?b@aso)}{8~yXL#*3iOhn1|Ej_85ik3HEnot@R zg+L-j*deLONHBjhvifAHzwzb9jIe;gcEXkA>YJxpejrR8b z>G07oe6=>3h_WehQ7#)`U(F1m0Fl`AqFjT^w(qcjiVSFeJd~h+zRLPRS@mZRhKmvA zn&&yyn{wSyzBjDAO!(6Yi=o5`Q`G9sFDG<($02f#Ms^*Gq|wQS$IW8iu7nwc;E3e` z7rEu`>DFuXVW%`v=1KZEe5Kc2c}FbL_O?-4hinVageucLgfN1~ua{j}!I8Yfc~)Y~ z&lztO1wuB>-zo~E=(vCW1Pgl%?-AS=GmqiHnP6%Nt?VzTtXBsHwgGQjL)HK-FK0v^_G$>(i3q=K<}USU?$yxLyC#P|syv8#CE zSSh8S)&QV=So?Q##7SCfZzTM$R_ZEGym1?x*=i1~=J&1R0ALcX4>4Ex?I`!vgZ)=x zJ0DhgFU5X_wBEgSoIG^BK7UWA!pqJzbyBwbpn#07RXAiW*L!$eGzQSw9g$qSd<1(D^F;zSegCp4cyIeYXAFUQ8u6DhSzfeO8S<)i>$h7Xe(@F@ef!y!mWV?yj1P9 ziFX0(&%^ljzsN}8|AqEeb6mEV$$A4cF*z#c%{W5U!u6M)xs;DS#1#wrv9CF8!;t+l zywW{`nE?9as8!pMYhh<;KHd*orkoa&vN0&zqJy@^85O8)OnUW=9?5Po7tS~NNbVu> zQ-fm835DCx1gpMWczCC3Zs7|2R|~)yB$F9z>d>f=w@RH5R`T08&n-U1T^Qj~sv0c4 zqL8s;l{yuW%{e<&fB&%eVIzWo@2>4|C?$%$QA$a1rN4(^>SH~%Xf`u4-rdHQNV2m2 z`m%wDbdu>~E`#YKRWLlKJ3Z~@I0c%kt#DGzVR%t3z)BC2cEmy+#o zKfxdJMAV8eT(QTK2WJKiogrz8_>7>;c@D#~3Sm#yOIpq3My2vc*8rxVmH)%oTSmvR zBx}0@Tei>^*kZDnp~Yy+0*hG|Gq#wS$zo=-n3T#B_Py)e_1%9_ z)xEMZGqP$`69Tt$$-}gCnEpJVR<2y!>4ZOke|BH&5;LvA}h zvJTa#hOg}Eo+=3|k2+*gtfQQq!|^qPD-}Em^ixY(Yb9B7Gi))e`SgH{S9`0e;G0&_ ziPjf{GC`uDf=|~v*KpP4f|>odl&rQE8i}Gn8`|lBYRMq^{w?Ao0~Fl#FQJW(kqti! z0T*HS!nA1dWq<%0t?38B)n35Ksy#uzrMG~6EdF08jdV@-7xrhO-!GW&oNTJR4_|wF z$!eZkc^l!YYil2G?Y|f?LHBBe&UKup*7>IkRS=ig(nK{%t32&xkxcX9LSBC zD-1hNbZHDywYy2R)^h0VEcuWBp&izOh)VWC-WlND4#Q0bx?xY2g!?gq9m}Mx&W{Bc z+x0#b-*015UlkF?Adj~Vi~l41IA@A0@BG(ShtT`;OgD|j7hs<0-%LlSP5S?iPyS7f z{y~@ii;IN*Vg46fZDko>aZnDAjiDMC7+{ISVEmg9aY`vGD<~?4K)*`prm5)uBRKg- zFaBZv7vlUsc+UUd4sEsTU+HxE+}*iA);nc2HPhn@{_-po=#+>3d_m>l;DFW&*f=<# z_B~pbJAj3S<>Kbv+}oop{~s08`}4UbyIrJu;OxWC@lWXJ-5I>jzoMcFZ8m#e@7o?_ zt)JVyUj<}jWOl|gG}L|nZo1vb+FCXc>C>;sNJ=&~CAitw!lov!zbNhhT)G?;AFd7qf`YaV4*q0+^QYEo zxpGhXP?Pg-ZI-p~#Dv^HBw<)!;9KxgeQ!_Cmf6HZN6e>xQ^&g`3UYFryE8ou42;Yd z9bH`#L`1|g)oM6NNy$`BYnfm)Le+LRcIdd=9=M_Bfb-BCk@@-m?VPrbsVVik*CW{e z8_-P_Zi4Fd;qGo@d;4<5q`_jbXQkQR*1^Gp>hed!%insWzE0Em3N2Mt)hgR<(E_Oy zxUP5_#f4^jDqd%Z2c%Z^h3R>p!)oOhw9BndU^kP?gXi~3sEw-2?XZ~q3N?3faPJ0h zjmA(t2RdcWjhv!f)5V_!b;448PEXJrbX)^bDk*nq>D(Q38)V^VqqkUMg4#K42BWX_ z6x#}>^18_*^V?(ug3pe#5yDrngC8o5eno~!E-88+Fy?4q=T*uV07qdvtf&1xOXJD4 z&Zdt>{T8*gkT4f8e}Jb_d=0bQXCJu=d`Jc#_Q;-37eVt!$YljdFHJfRJ5}_RdRH>E zC1XW}upM+HY6KBzyG<~m068O{(Gh-}8%o4E(Q}o$dq9L4%MQe+A(Gtqm2e0-<5v3m zm2+&s2_Mn&7JzXC6M9hk-n2X=+rijCYY^w8_(xk^0x*Il*`Kb~-S*@4HJM@o`}?EI z&ur#$X>Qve;^?=fNdsJre0_bncz9mG<*kW{iBJmz2j^~lFUI286Yq3o&rO%LASFUx z$l8u>{44nNmWx3bFftyWdmFly+?Fok=ftq9yT(XgVHk3OG|0}loIt!^+JyJoi7XWO zQ=&Psr<|&qWRb{xcXs@W$Eajs#-OM2dO}N6YCmKsMO*SJ#Hg%YUzBldInnx6BK{G0 zJ^685M^I+VXIJ+#xGbWS(I>(nh{Z^YW$v2kS-~X1QNv~RBz)&=Sm*bw#nFPfivR}4 zM>kW-xEH&e*PgZbMg_Ut4*=&L#_$KwZexp;&8>6Ct1(g-vbDZPx%cfNI{Rc)z4@uU z`zY7Nb5_9@Wn~fh_*ZLBH>!um#yHyq>&3Q9d_Rus{C#Cy0jM4>t;X&8h#r1^v;k2v z`ys1P#M_w|@L<`0tIa0yB8rkZ5e0N*D>@HOp1Ky}>mk--Yx>k_{_S`nUR=^$e(Al! z^WL=M7V(?G-X;zroZq@C2ITlb%KdMC2=GPjEvFyIGoo~wZw3SiH`5{us z+#oPoqH|T3uKX_e3SQ|umcU5o_M-vkd+C~7yT(ZrYk4fdS8sbV|6uEFD?3)(7TM$` zb3S(I%>2VbZG-og3kYB{CP)B3$x0cmCly*wVlKjuO^A+ta?KG|bs}0*e6a|u)&mxW z-F8&}==zQr7gFf`J2oQb_?unJ>BI}iB-JS+3>yCexvLGSxl9yFMsDJapA7lmUrt09 z5PF=V@E(TZv01Y2X!$1WRCU}#jqxOCjA^}YmB9y}K1CQP^PnC|KEoAory#kuvySBm;6W^n zzJlPDv|9Ye1BtxVofCFf5ilo=`D@c~t6q!n{Yz&lvzig82MUQ>tIsVyiUSY#slKoR zk%Mg7l4SKZeIHH1=`^ctJjLd>n>^+etD(SYN}PDECvUv&c=-AEu7=Wq;|92^ON5u$ zQ<*Mq4CWB8fdiKNsS7@>MGCFwl#npLVooz6RIMqm(xa2&6;Ep7*|8|-73IQYL+MS{ zdreVPb4WwFIulvEpAq4z7Ww`|!t%{vhEsIjlGz*R@v$kmL-%;TfJYBdi9z&1$0tk@6m6cmE&Morm{Ns!VKel8wPuhX0^j+1=HXt z0YcgE`idY4f6B%Ct)1MxI6Q*x**`$`9{tcNUQYNv`nZ;+jGFztYi{%IeBfjb$k1P1 zF*@l?2=@!(Q|5tcpgfV1g)V06JpeZt5&NL*=2C=McvXNY+x{`gNagqmr&vB+jWaIL zy%Mt$kUgXrGENpWkrz#KP+40tuPH>kL;B~KHc`6eVlra&L?CO}1oQJ$X<6d5pjSVE zr}+`ZqrCuqdUP@$+mjPL;fTgQ$*4+5YgI&ZnAg5Sn;!zcMB{yswIEYapdU021w~a| zU7S{q*SCGGS&_mNuHd?^PEsYxJ>~; zXpv2iOGr2GXg{x%j}Kp44wbThJZz5bUxS^YQ-4{6QJd7)GZ3?)+m=Frqm>s^sbG_I+uIcxW1LZM zLz`bF>Xq;Q1V~x-{`c(DbseLrRNbiuf{gmtj{5DQ1W8y+FQjH@irq~i{iSeSa8Zsb z4FU=`(p&Z&GmZ%Gn9>(#)J?i5?6`_=X(wUM3w*}oxB*5}G{(*u1JLInuG%d5GV2%z zcrkKT|4h9hbBC!wfe9qjkoT&*g18s;_~~Ix&pe}zT5s^qb^^Ja0^|Qb!FrIANNGW$zWW0+I{cU$V2SWSZ8k{uGfAN#i zH$T=>!)2#2Xz`uJVXHoxBN&sb)q|RB3ya4z!QmV%UeWZ@HC1kvcQ=*`YN{uwNbBnKpk*q4VntY7A9!Bk&zZd*VdyNv$$}#CO-!2AA}f87^p@5kpXh{>>KS)*#}sZ z?pC!HrVkmPf4br=(BUztKXZE+xYg*Y*p3ou8LMS&((`JD&|HU2=9vjRK(0x)Y74li zzYdF_5x5GE{hqB-sgZ3RD2BPeOUN?j%h7u^dQzD~EANiJ(G4LD_e9>eEgmJ{pr;Kv z_a{U-Wl0)So}ccl^NWcYPT26U(Bz6X(vjNx(H{X#x%P?B>tbgOJCG*ZRrZmy_xsIg zavyplB7KSiV(Sd=6VC&FfdxZP&A13N!&=Ow4(fiZ+A@t`DUI#1Nj0eW1G2{6;QJr^ zjlQ^@G!7c=5kY9;=_%`Jlae3Khr$OIXw<`-x(U-Z>2d0VE519OZ4L*9FE7W54^~W; zTZq@Gzvo8xIUXiHID*-H9GLPPH>NE=ls-Rsh;A|%O{*e&VA$Ai8K)+Fm%_8*uJTE} zH~XRh`WEk^_FE`0na8ojuun4g`8Fs~A!1o!Tm^oB(L;4SO z#g2N4#5gCH_pZD;rG~mb#z`-+7zh)~gv7bN5_kUa9+omy$fI7DHx1z@W$&t)xQXiH zGz0L)OuQQf0f}b5vF1dH#?6sFa52oRwpeJIhcP)@SGhodJ-xyfB4HPKSuWKcgvI<8 z3qRCr>&&VKPwBONE8S&xYA;5`>aT4C3C#u)&MRW`!@ zyWx_e?P+^@DpR=w*YAwSHY+wFO}>wyD?KLyf5YpPybxmY+O=h#WTtX0UtMUtP1{GX z2I|N1A@{g-(=A$zm(^ZrEJyA(7+2*uT)wbO^8@Yc1zCOrt=eP%pjV8OC1A@|RlK=$ zYwC=?#|u8HE6Mtx2)(e%27J%^5GfrplsBhpP-!ii!{c4xEE#)HF7o~+IxcAS_*Q&4 z`%AuybiUbYfkVokWVd#&sr*;ugQhLp^gD^H>AY-iBs`1ZTm8wo<~oKm4>(20(|F!t zVKJ96t7Vvg`4IQf_ZjNQvK7(ceI3R1^FZYJz3pvvh?$Yzp3LmUXH9NzctX6DBhJE; z`gQ^&nNs4YaiWc6TdmYY&JndGc9or)U)?zm^A6PJ!IRq|U*3L=3oe*$sIAiwAB80= zyok4t+|es~F?-!Qfkb9hGdOXeVbPn0g;-jZVd#ed+B%=p@U{o5!z$P;w9t7`b=7?a z#sqh|5t$&kQ+vsmjRfK#P2OYO<%xBRy%k{6Z?OtgJ^7zY-XmZLvn4#q{{Bt6C-q2Yb?_sploLTvxjUv=^r9dAE) z#!@a)Dx1NA5S|X4%xNL2-2OQ^lnl)#(FZM^)$pROnkt|HI|;1ORQEP&wwSV%X6s!c zz`%%=tL|zWCNaKU?nxBfW42MDHip!jE*BCrNUHCjndM_uSgQ>TVYI8N4V>)i;6rLn zhKLuORQsrK%Wh~I&=&Y{b!g^xhToo_hZH66Z#;=6r}CFlhKjnTTDRP}C@@^+qjtey zNtTsmqTX%i|7*aOh_k?5^eZ*Yq-wnrdso7x z2DF^&Ry!<+?NKDoxxnH|uc43%a2)s<&kPdRkQ4v$qi=Nh;ZQh=(wXQ)C!M0IPNI>g zG+Q1euMz_|Bd=oVDI9i)YCF}&=NnVHC!9Ff*>^_@P*XDFCM#JK_=zngfZIzP+(|*d z@qVQ6gYg&1tIYMxLVeI zhW=IuvH%^J9e=A809g@(C{KEc+KJutWr$Ygq*Ejf;(EU79m^N7ziAb(vbR{M1sg#j zvZ4h@zL(m38Imqr^9pT^V#6_4KErY-_e#;+~DFnsEC z)w+AprKioVw(i-P^`tR*1Jp#RE^b_S0wtvhNcLZ{lhW*R{)LE$Xwj=ezdux|TwNJX zImTYXgI;zUhCOqEtE#5v2R=2;XRM0pj7i6qT*_eEm&O#St~t_e+=f8SO0wP zg(*Efc5R}B?yE$zYdg*4(QnZ@murUT_U3~-M(x%{j~CWpy% zdHKhdzyZJO$y$)C(pF~K&#yTJcZenA0M?-E zAh9e@;WdR%xU0_u&-r+82l0AP)OOsvTQ;;A{Mu+yY%zfT1Bb-R-6s*LOi?7YThe0Ag_e~x4E~>T zb9}k_AykY+f8stH_776(nwecU38=|ci)dZN-P-e)XF!EZ2hsir{ z!Y%EM8Ez|HuyZi+h`!vE|9bUg?3_&&NqZ9YiL^JTs=a{h)2rW6h|pujqDAEHKKxAG zC1YWPsA+^oP!Q3T)p(Libg#@IASZp68tdlJgDy4@v^oKF3op<@aDQ*_W^E_LBkE}S zv6QA@U~=VyOc%^Sto|?A+XC7CQLOENcPn92@CdQ`TQ2cd6ayb!L;VYLm|;R-#mX8*dd3oR<*m!4G!t2Blhe1Iij1@K*0G}M}fR3 zd}3d1nT}`1k*9_td0h7V$Gv{vX_lyICmhhkmJ;>#0|*JXIVoSYjx%_CK<}$q@_v>J z|0(e=)eeDApl-T{hr1{FS^{84iz6zE_A3dcV1s zU;e2T+M4WJl)i`4JsTHSpwgf2G#U2$ySyO$q+9T&3Pv_1detLS1$M=^*{f@+xQCl1 zqf|>zwgTZ?1g?zLkt6?k>e;-PZC(EI3gRq4jMmL_GXKdg3HxzFHifsib2w9G7v~a8 zkm~p;Pv6*2)gJNo>I9>;{)5S4f;}~_sbnEb(TTz{v(HaWQST6#Syy(uw%(QreiB8> z4&wpoP(e18nqUfW7bPYi5r zy3tbvF4D=4@QIm$Msr=Zste`xc*B`L9^PV8^Q2q)gS;J!m!!kDu2^T17UoM`LdJ7IKBdoIz64Xvcw<4G_I<*q<3 za0}gw7d;eBE)G)T{9?$FDGA*G7TyESmh{&cjnq7wLA8GFaa1)q4-O}4iF-Pq42DNJ z*dDsyNCsaxr0|4%j#?itVpxi163pxhm5ET(Hw@B>;Rw%~4#9}Bmy7Gx zv)zk71*B3&y_k(%@PVu1i3fgR<5&?4}(-J9BrG2k$8VJ9c$5^j$=*l(AYp&*`+AoZep;K3T$~NvohoaUmyhzMl$~wjhZV4+p;mzd#?KZ*xh2xvFyM2|uXaqVw&W-Jyd6h&(Dl}x2 z^b*^bo{y2HF4`lO^L}z>8;y%|rC<i zijq2M!S_c9Uj?46E^zSOav4%ygRh6#9v_nDRE{Pm9O04S%vp<7AcejOc;KOmTvB1P z{i*W%6_cMkOVH$FEitD;DweSH0*B*Wad9d0yOJtA*x3rl>Pl?f(Y4m_EPNZF{MPCx zJ5qLg1;P3XHo|k%7afq%UL@-%@c9#FXP80vmbQlgDef#ACxrbS%Wr>P^{*NoRB>*M zdfk5_%Vb%yRk41L7gg7dA3Pd_BVY9Y$xMfEW>D-VvDQgc&_8};f54&R9Go@;8n9}3 z^cHdL(!c0l%>!INCJIA<>#R4^4s=&|KaV)+dRh)S&6pdJ4zb5awJE?%iS_3EJZwAz zTiyKJd-}3#C4>jh{jQXiL<7KmZjbounQr%qP9rxvJTzjlgOz@dXCt`Koc^VDj#Y%u zJva%bm4TxdwEdhTz*vpkuhXXo;N>VYx{+$buWxDV4#OYg)vgY<{p^XH@fwdsu7|?z z_0+!=L@;LNa$B@syhT)J`vvhO6{dkW;H*XFs58H@G&tCZSef$OlqVQ^Sgf;TAr2pz zbl$yXt9uOa#q>|vtQmjts{g4Cpr(EXJ@}G zULoV)ufy>){?*mC4ePzm4_9Uq@zm$upuWF$_ceb0GAeD6`!QD(=)y}*r0Xz382@O7 z4%S>>4=N6VmNrBayLXr-P+u@vE2PXy5o^qEkW!mV=&3Qf+ZHWaJWl#mC22q+F^pXYfXu zf}K498JkfqTlY67(R@2&^Sk!uO_CBrzmKni;sT?`wMa%?1PIDCBv;ArlE9J|`MIM+ z{E!^hSLL2h4Hee~a%m#C9m<-2A+gu8ktC*CyWL?6!TAE|v_jvbRv9SI>uc?9`=aA; zV?3}@Q8#JMTthFKwwXa~K(7|Z4X@`dlMT9n(LD0%y+i5DRr^;vbr09aicnxBUKUn?^po7+<$X4q5mSzf0!8mNwN3wKW3jhv?viAK0ZF8(rZ>( zd3i{9c>EIe-`KSaN)l~sZSO%kgWeCvW>A^u`}gl*NSq-n3Uq&S!c%BX_xF&MX8-bX z2I!cf(k($XH8uG%RTe1Ad~NKc{##{8`a%PJaef_kwXm>&%JJN({AOM~vLDD*9i5$% zKL0E54C>v}_pT|i{{tZZKSYB6z_|Y~|8K)R)yf81T1p!ll9!Z79RB5hsFV5xzbY$# zAtS49Xz-$&Ho0n`_%kpU>Hf_b5e+SI3F_H@fy-BtMvwdTVTX1{x)Nw^!@mxe{%HT* z#LF>s%4|oHh|5(TRSG}{mQwL5r4)_r@XcVtJOpTx%70zQT~xc^-|EDFxZ?}p-*9xR zv!}aToAukj$hF<&U-BX7x*|kVGWy8ycQ?N9UWEUP_y2YLUncu&^bg>F;PjRt9Uq_2 z|GN!AyrN;4e=YdG2E0xR`p**h-?J?K7nBD4*Zc?R{)hR$LGNF;p_9wW)a}}`QVv+Q zwzdjF{~8MPkrkw-pY+iv ziiSz?Z;}tqM*5#=`-l188T`j&{$oM4(fsWjmw7?~kK|etP;7Mc*_u|XLN3VrOGYB4 zy1=OUKw%(#UQejA%Ea{#KLYSwpJ>eJpP;g$mtzGNo3%LP4~pw!BY*(=#Y>cLAxG|N z0>B_lE|rS)RLsF(0fSl4%j0$2S})(!E^^PTy(EVlqE-<*w@%yLm zSi#0OMsqQytYw)k9~s>q?3oS)qfc@3mG?)cIxrU;PsdPrQDR_S9@oA=BIkc;9>Jis3wxw7oX}%Z)`51zq#n zV@1sEVZ)m}xd}V1Z~HR639Co4Gqfe>mPNKgfLkwe`U(krmUUvVp4u~BQ8|NYJC=1E z^Uz2|ymrTe`sP_6(`!WLQr0=e1eBTZ^-S=}9`X%CsBL-^D8xs1BVLu7;jDjL`O-}+ zb;O?4rP<6Z-56@6X@u3f=Pd(yofvMx^Y&}@j-8=m&`hf=Oa2h^-(9&Jds32F?K!dFM2$>ASiFDF+44c}~;EEe1w`^P;G+OxS zNo}c>EEvyXtE&jawY=NL zqeh#y+{M~Y8E-GYp?n1uZ~?J+X0I47YNt9sKX-kw*YDonp^RxYk=ek;d9^^`x+cYz zP2Vyu3&rz<&r;<4H92U1n#0tQM0_?SL(iU4b!@_Q2=2XKo;)=6nzq)EptvXy?AZ7F zGhx#OYZ%=o$+w65MPdzX5xMBaoSiQI=tBgUc z-3{8u!uH?FESD>u)Vvi>Li^5@)IM%2cz<4r39%Wtlt61h7c32a$op84d9&;BaLG5~ zV3l#*Ju;Yuk50ohJK6Ux>74&?WH&fO_7cF_l~(&rJTFLd=dOA?y*cizj&PU$1J()9 z!T8U_xKg8h4b606L<$l(h^5Me|H6D4ZoY6C^}2e6e?RPXj0((r%qE1i$@z4C&Ml_v zuxHNk5H0D_(KMXq@ZlA6|Gmuki)zrXQkVNx$``Y}KKo@*n$M5k?HsQaP!Ug#_5JoX zG+x0(C!1j|En=|!?BZs-3?$kyb)vg8JbkznLV;>b*~N-A3mK=b;bP1w3{pZ zd-+7r<#M+r+qM9#AS-j9vFrDWuHsO$)pg)Y-x2+=0{({Yot)*>{Cssfd)8jIi0e0S z(2oyA7ZSW*HRr%`*wP!^#2(|CRP@}-8XgFaH-XcK22J)5rIrVwhJ6V%f#CgVx0JaC zj|xGxZ)_jE`Y!`{ZiKW#k+*W9u&F?AKE~!+w)5niruW`n)$dm>7LjLt!0GbY>t}JR zKbzn{XwTS^Wc?Wh;G|jGkL}b>DX8PQF8VK=8b> z9M9w#tFPKY0sRg`+bLUjh07&E&+4Arka{H2;(~pdA2LPfY5l|}!k%3sw@Q&BKYOi2 zQ`SGL38E5V4=<_MCM%q&QKd>rxG2se@*uwW8Ljqsi5jXPv16G^@qCGMf8df_j|OTxGI0&un}ODZAj~-QXMb*C%{Vg-@{wu_((eDQo=^ zBx#p|*vL8y1L>C7KSHN!tOiiaMn33TrW7oc>JenFMCkG63~gHoyHxp>Km&5KrD3JE zqgd)k#8Y2u5;`EFd7A1notYhViyWU)>b+Lw64tnzMcAC`(D3rvt(BL z{8a8IV*lJ5@gFvyAq}{Wioc&$1a2Uy+|cw#2=3LcQH2UWGmWO-V2kiD8tVB9<#h-V z9h?#wJtLqRwR(j*8XJ}HdGr4k&`@)oj?s=l&Se+2H8m!7`V9Wwtw?td_z{(AA$m>2 ztGYJFJ_n^_a_*(q^W8{FY zmMe({_WmGk8lqCUaT z443k?>mN|K)UxtBA6TkJ2XWx3=VmO_iC!a)&%s>2C3|jG7FuDllaw=2d{>;Of4T{V z@(7P05JTZx+mopJ!EgBDMGdUIKk4%%#V=9N;?*)3g8SpTj)zr(*wuzQbm4(D+_Qx* z0~bsy6JHbe6)G)s&!oguz=Sf~mIPwPPTQ@&thuX->8##V8)$kz@emlP`6gZR?`*tj zL0y&kRZhn-^r6|BdeHgUD@QCuYVLkk?j{2Gr$l2&6{!EKuA+D5+TJWh2RVpq9HQC% zGUHT7YZRjr927Ktbjj6F$@@J$Hgv5X-`opd+$b!4#k}UoeflA~vRz_Y!Z~2I+c^H9 zCjDB(awP;`i(D?3IWwmdVf)l9991`eOy|quO)Sv*9P=qNsVbrB=g|CrIi5EA| z^44?l%F!7^3&EPKZ#Xob`qMiq{>|M2dp9q5shUG?MShdXj(OYEvP<2m!2zbXB`Ii_ zN}t+ubS+aQ3TtR%h7jiNidMoncHw#XR|NtX^A(%13Zk>8`Lxv%{tCP-D;o|4M)Gdr zK+-RJL8s@S6!U<5I8&M_Gc3XgFTFhw=VajN_TVll8~$t>Yk}-%DaE0AOMvzo)tLZS zngpypR4jt>iJ81FMxl%opP!%G&$+<@_MpLL+ zYLAW!u9ug0I2sSMyf@mC8VN%ePoUb8NB-r`%I}Qx9HXnXQLBP^Z`q1XRG4>VIR_w@ z8^-?L z^(OfqFw&cx00}d^&v*JZ4P0Ki2?_-V0I$MdOfTgN@;=QoYKcYpKCV$Umk!uWU9$3A zz0v9jst{h3f)7vPX%TZ`(>m%N+SVq}m<>->o?gT%dZ!etANOb3iAJnF%4Va8(>s#h zXMb3yspK6-R5h^wJ6H#RbGqC=l( zCr_$2X}Foto#n6^@wC=tVGV?Mnh}i1Vi+rWwX$}_FNiQ}uv?8uz;fMF$iK!maCcB8k>T+V>&rjQdYB2{7TU^X(r>|XfJZmCR=w~ddx7-$v^seiBAm{r*W^$TGs{*nL|2Izh6+8oU4~etWdSWN17JB+liQi0yTpv{ zZ>PBg=X?W42;HM8b%Cw8$|X|AC$$fDFSnk_*Go@L9b8-O+svd0HT+59#WfyhXGlMD zm0fl~h@E0M6)twPqJcZ+n#~zmtodbt1(;MJ&9+b11*iLYgRp4sMEb_N$7O3Sw3p5l zI2iJhCz=x>9;fUaB?$quOK!?|Hj!MwIXLUd_e{Ut>T$UM5N2z;OsW_kp|O zQ+tSMZ6u~Pk;RE30hsPK>by@rC8o9QjL+pgXq(RLbFFW^7?F;A4RP4utDn(&M*7wD z_SNr2w(&GCr>V5Jn9kc=7M$AJgjwqz?Cq+jD6d;lK+vxFsT@)!&sQ@P0-z&A^{3jzKlydv<+eN>DQ8Z1_{4 zPJ)!@4xtf)-i8@*``bb7WSknfx{PQsTIe&<9x+y7HfiiH9Qf>gNX+*Y`gLDOf`!~f zY^x?25X-H8pW6{T((X(CXF~N)67DbKIppAF6_UFH7FGi95?TahF}qM$=KMcNm?=wh zgqS4PTZl3xM)wmm@yGKOwg5&!ip%x=sRSIQ?_5;;)(RWBu?KLKwqSK;V`8jcwhatU z?Oj`ROY{~{+V>=+8yqu2nmsEq2N&|7lku!v|KsM(LlKwrP^^&lp?dRqM0;A9m_9m9 zq&ffCFuZk?z1-T%6h2#4Nn#EYsY->)yOkXDe08V%pjsB)Z$p(G+4^_lG6+YTlV*I+ z_KLs5ac?WMwwJ(4NQn+R1N}ZIl&DuLS6la%Xka%ti5wp#lIZW8Yba zvV7`L8;+l&sGh`A%oEnDi`f)5Rxz8g;fvBPFfEl)s-A^WPd}z*E7Z2Qy8wWa0DK<@Me~qS@#@ zAVeZdWot2sov+7TuhPU*YhIiFT(U6)a6;{!!6f>;4}D1;xGHjuIoDQ(08p=ZOV{;_ZE` zW`{SRGZfBiV?~qNBBsT3$+$wcd_pUm`&6`5BPJQ%hCIh=U%Q4sGqjL{CZ0b(fZT(5`LiO}RI+rH}7i6a;D&^BQvLV6l_3eEEgnsBCd^ z9Uu@c{NaF+c*jOcy2Xj!_pR=hW!&BBq`NmOBR9 zV2I}{g#;AsJ{RFBDQy^(vy+vDUB)O|#m2?`$sOr;S>E!num~(E5vDMgV@IM)ErX}? z?>_ThBzly60{bi;i%+&MT^|rp{Fan)>t}=RtM$b_R)v+mz26CZ!?a?%_K9*f+2x9A z$*74hH@b9yq=RNXc~eY+RnOX=Ud5J;tCc&>jXhlT(`ZPKbH6HO8Q-Yotgi>7u`t!) zJ&6`^2@7EV&~vg6%b?$6P0rVhQ8Er*9X!v;g4uI}p*>SA)bzJ#Z zNz^-Myuv+{)Am4Pz_@}t?rf4k^>%*b2pQtF;Bs5taOh>{&q`?vgD@r>1T^-2zB zJxBq*6Ty0_tu4CGSGAN}tqYir{P9>=77_{Fmg7cn`h@3g3b9MuM+Q??$W+8i+nbK& z5{{#fx5jaGj7>b>T}-(U2qwrijW7FH=$|fWqb#&+t0lguzuKxdtIy=PpJp9SSAHg< zD3Py}$LH}-4$etAkz^M(&Ui=pD)-I`XmwNPMLj@?QyMgSoKG4a{Cndh(JH#scA%do z;qpT+i|)Bl2XJUT8@(SJyuIO%#>RV1)p3sp7}ZM4HP}5s3J;&y%Vu_LYy=bxGGb}5 zii-xCvKn%4ci6}zX-lS#-io`&$RogN-c5FLZObKtPP4jCf5R?+snA^Z_Tg<0lj92G zW^M0=Q3oSCs)lKdKxVW!;=60>lros(wgx`jZ|8T8(@JwEi$|i6DkUXFT?n*Fl*iGH z2V9Vh!bCEW^DXnFxq1%0XhP!YV*a$yb+7!m@Qo6i?tWl><_Do)ZyG^by(Nr!T@~S+ z0iL7uUe{3rw3YZy5AP1b4(wOFQ@L7oiS2p8xFaY>q52k~#pkuUD}BP9}_P~lK=4a+pzCO z-14Wq6>!2i&(Fv2rl}_Ac=WLn8D(~C7Ews%mS$rVPSMFz+ayP^Re2+7(jIsx?larz z?G2?X6To_?II70u-VQ2ns;a8eU2Ai_f~@kE<4>BZwmLCDaSVd)<=&XZS{p7WC#R;C z);+j!oy+rq4W>T~yU_FTCOJ7zYq!Pm_%A^ijC3m7Z>WkSIVGi9uQ#aB`*Q1zlc>6< zl8-_KhiY0{)wLmsm+vMFJ>FbkW~oec31?NY4g-h#`j@N>ZpP;F1=|O-LU=M5Q;qzO z%As5zakECp-o=1+uL~*Ci#3Mdiug8(@u(0YlJE(n%q1XgSr|mBBtI?bxWda#E@Gp10aSfITRP`T7)A;+W}#FRfH#< zc5U61ZMw*>xeS0Ze_Ur3v95yV-Q6=p%>#1g`8(C~r+-f;8?~{IG*Rm?@cw8Yp<3uX z{os{xLD9P!h-DLIBvs>utUr49-rfx*;&ba> z?Rl~~{5DD$bIisv>A{bUy;=7>wxNi_V{-M`m{?#yU^SdNDqe04%7YQ6)~YsN4*xff*(A(Tj}eWY>gXar-qWRL&xD7voTL|M^1By#@TXkY^Uf4;AW|_8 zGY1Rom8J&3j~GtCc+yvT#)f6k=3Fe*!S&2=M)tl#&^~Whjqm2UA7V*n`ux+n!SXp( zA2&lFjn9SGbQ0)Fdg_>0;HQ#in+aSwnr`ZYyCG}}2uvalObwTC->!O@jk;FPunYNi za#v0q=r=dnybByfZZXK3wooBEyBkRoyVbRb(vmgLmvQ#-cXprTon9qC5b`6=UgC|_ zxbzTFvGbI;ZK!yP1hoZptBJg0TX=Ex zCYWh5dlPOJ1oN}zVJ!BTrDM2n*0|QrBV?9YRQS0wq&Gu6u7FHmj#Ic|*}~V-7`N*f z=z6zy{4SXeie{Y3i<`mqFFfGw#rjd#9ez!!j{ZbamOH%tJ5x>fSVp!r-CE^N_FkVX zonx>3hQbyfT(c(3jm_S7fyEy3s={&49BpX>=P#(1T$Z;KUG?0B9?n&cw?vWHZn`}| z?JaBHMdY-qbYV@#(_wYbHoBqrXqxkyYjA9Atfau$lk4Kt)Rbz21uj&oNw3)yy|ZK3 z*4CEHW&35iK$?t!0o5luI(qnacV~y$coZimCnuTTonvTd$PuliP=>&uXZe+KVlX3# za&_p%ppaWbDX4uoPaftSn(@WbxaZxxz42xqIyv#^Z)HOmP6T&m;GDtfxKDS1uMh{!ovGc`2cY``rb zU;LpfcfSr239w-#%N@4YnG5CJm?fw%1|WQ78b^^W6cP!y%~0detG$9o&5m@ znJm#Tuwzb?(e)B}C33#v$&LpxaqGU_pAdbsN3dlx8Hfh#UJS*hA0rJ2PUVVC@cd0C zpDydAwmPDohSzv%gO6YwmM<|lAZ6lsQm6 zT$4%30LCJXz)uLaNHXpdA>PpuPdkT9_{!x9fO$ou)9d_Z&bajXnQ{k#l?q2S&ri`1 z2_*++1Qj$wE-Br@H3uZe!8cgDdv+B^xC-h)k~WfVtNaNf;&H#0J2S@wmtZiB<8Vv! zhl!fXc#1{@+Al<3_Ko@oBn-*?N9)3oGuF1?^Nigw&^Py+HUYttxwjD~&-+rbv6Z>9 zm7=?xen(Y|aiw&O6e3tZXMC@f5K?|}`DabK;6z1T?8fy4dbn3aQq6gG!oYmo7Z?7f z6#Nw;I(K3*nk9G_$?tv>|9Ya`JCinb=b`0v?WkRs#*Qz8VQY^JCzZ4Y3U6i#k$vS3 zX|U=XfV5okvCUgc<(Y7p;bP&{*e>4lSQDCd z6RWpu5-f+zxn`X|1o2t@3Ul)CpKwZsPhqT+IQVAB4^O@AVC7XF#kNrTMCa^HTiBCp z>aln$2<)8Gv|4_YToOADK|%XGI8|$n(t)5mMs|7aJ!@)80eXWnr;Q1V ziNz%*4iqaEp55M7YI?o!<8xZ|LI08E^?+z?Z9QsipAr1xm2yG$5>p+2&-R7l@_oz; z1Z|{#e-Q2oTI=vmbYmCdxA=zT8&TP6rk}N;{SzLi!77CQs!Q40p+$0JGJw+Hh?!y$;q`(9a)*)!C8^z?<+aR_fkS6%Ljxs6E@Z z7GJE543wp`&HFC61uwO+l&Y;&=JB*8>Cr5hR;G1&en-gfa-c&+=x{e0;B+cm8oo=; zxGv;&^UdkWo+IrQU<&mQO8zG*`Q2Vt7NZh_t)+KgaoM82B+FmYgQT;uL3 z-~Ebu_pi*XGJ;95HF_#(EY-k2W#{gCobUeD;}PzN?V0+#wbhM^}Dw? zuJoD%?nHv0@}+7UX+p1>``um2zS?oh*G?72S&ratem6|#yLYT<*S~+N_75osJEr*K zW4IjQt5mLbCwlV_wtvqwG0&Sx-boQ1}tSc()4lJjfge|vtK1Rh_H^w!Z zp$_?K-6_uEHjVyv2(cc1VL#?lP@DgJfd(eq4c4;IYW4d+tzCIA+j$#rw=GqwtJ;QA zDP6}~t+Vc86-A}(wvMzEMcqefiMrd;#JW=J3<Lv*4sv}fI6b*4kL&YOrE}BIzB`v}a$d+_-BTpf z!44sARTZ`R8LhS(5?V34wH1bujceZ-s`8t>7(2Z)IMNClPy<%gylclIou=#bWaEUD zBXbh~QxH{@4aaDx(%sk7`lgKr?4-oqj-@~^Gcz)-B}W2BLi2hyOFB>VW!)w?6E*ZJ z*o@(f`e(Ak4|%_g?G^VZQmIh-Fnq9#OJ*nk!ad%;O*FxdKw(o53LI+$iVHRru$1FVHoh~nT?5KGv zc0K;_&Cc@`5Bf*|`T(s%etfJ}r&f1OZ?;u&1)mEQ49YcO+_^f?^jf2f zO-+*sVlB3+Usa|;UiLok=>^?WLgbUBRZ84~p!iASWWGVsanb?&;a&2j*>!nZsXn{F zmi)Ek(tLY7AL?s~*L^SM4@1@Ayz4=`=dQl?OG8IB4DRpY!jiqZVkB^lErC-X-}J97 zL3Awi*{&VJ&UM|m&ZHpW;C1|g{BhzbS&Q%xkhuAm*&~fBfqIa}7~oUIgl5FGjBf}O9 zApNWXJ3c)R;Bks{ld26|?jfPI0>VQio#kO`+Wl9`M3?lKb6*-c8LDLrQ`nDyOdQTq zzz3UDwWB&|w=JO)>-BClBkiy^q9^0U1=I1#3|@z@6hbx)MIt4^mGN7LI!}n;or@<# zwRUfv&FOPorv^{8T0gohZn$i_t)yP~+Ey6&YXjK$8ACPEaS5n`HF@0mLj=Kbj7BuD z+n7&PcTP{~_iU@}0-YfPJ^%)J`!6^iUcEb=u{ZE&l(=GASZ^S2V-hleeGF%SDPx`t53n->GJeGbpCv(an0y9tdH>}3_p~=;e%*&_K=|502M%J z?O`|VtC^=@whu2=5{XIml0l&0=by_9lvg%*?DP_Fn)9R#hm_Xiv9-{#1R@qLLq05X%eQ;a4XW~RQA%Z$FhfzW@)fABe$=)K z_nTNUg02Hw9flhQ>&-V`F*3OS>NALx&{*~((|rp50reAbPbAT?Xk1whtBa-TY^_n% z!h#0uYjZuT{P8w;m>b4pNenLl_seHaeu&p~=x@FI2_UUCgEYly)*Y|imYfo{VRRUA zvnP?-fyb&wK)c)P^CMMmG|ZbfQkTx~H#awvm=K$4cYm|<0o8=2Q1;2wr;U?kZeDCJ zhQUlqb3PAAAMNZ)*}wT>()R&bF6K*KJ=c-s`7GYhzdk0`CcocuGr*LF@!7$cxdY7I z{k|tiOx6W&e}3=N5PRFQP@wu)(UZ$OmWGlwOErNP=>^3_YMLpjKj-9-BNfTM;V;YJ znTVD>zEO|-%k?&>op>0JuiKo7s(Wa+zo+y%Zcm^)<3sIfvYK2=yxOW24><|HqGm2K zRW5qmD8lv(wr`;`3SBj#S)5GO;#+X%<}fD$NX&;S{lwCPb_++S^qK34HPMO$@o5Hz zMF;)t9(9{8guK6V5@{M(mzgRLellzqbjQ-NBbrZ`8?_ZwRJ^8k!G*csz{yGKfU>f3 zytvjc+$YJ|*@P8JyQp@6+<{{2Qm3g8FH#v{)C3I?-H3Chw^BGJ=j z1mnW3qOjb_#$e)>Pa?G84R7(wdZYxj7i6WY&V8X?t8$asXL{MM-Ot|z$L-u>k4aJ~ zP6z@ncAir#DGnnusPC0#iRE&dp_w|qf@tH#z?m~CezR*HXSYLD=!3hba(dAgDJKj= zAstFt%2}Y2eaS31#C5PGcuONHvQD<3Gkha}EQk7z)nIAkja%@XiZ~sp${iFQ<1QXd zB&NPWe6;GjwbU6XzEAzhcR+LpSV(SLyplK)OHyG2k&9aC62}UqT3QP;`ts>HPQ!ui zqMx-7uYRq$wBPtV%_7sz-woY465<0H0-zo>6~=Gd$@*c>!#GTszkH=LOR!D){RQLT zf(n#gY+>elM^~5dsZ-I($->+QK=(>%hDCiRy4Klj-iM5#(y%RBx(M_|TpYidnOSO& zHe}J%^y4eVv?f}b?NL6yR&VuW1fqMcKTkQHC0V7Xr>Ci-1KyE+P`hes!N`PCY_FQUlwCYmcKbTBt<0x?^3PlZqIr z^b9xT_Frc?w@+RundGQIkngr?W)N-7PnKSSYj0vu^A96j*Yn@f1((C*oTK8U0DkR zhcMm^{rVOnywUdH$z6@9G1mjv>HhbQJy8l(`#>Cna~_kU-l(SBRt_r6&CUJ9+}z%F zs-PY<`EdiVO-0>YA89VK6G(kU*Xc9t`#5FKVr1 ze)5{|Z1vW(dyqzg2=4E$lEbg%Row3Zns07tUlog{jGT|hOkYDzELbV5dVg#`e_M z$L4GM8Sj~2Sp##6%w{yEC=>%nM@Lj!k+hdiS_zY=u%EN0zcG(4D285-jd@uV6BENB z)OZX+kBg~4XgIy1f5y^QgEeFzFLkU)N=k~gGgR)Nk3=F#7#IE{M~)P|E>0;Z7Dnam z&P9ZWTR~&yM6HB=lO!)9aXY@K+0~kRE>})jat;3^;|y3q*xv+atA5CfunkiQ>O2cR-}41N53BM4bJs+6+;P>CkMD_o2@oW>ySr;}cXxLOsD7LBO(8AvQkf0?G6u!o*XH zjZsV#235RvUE1*U!1x_YZ+NJ#g2M{(`qv-s3;( z7qZ)W1k+=?lGHpvaJqa;m?x8d%%4wj9M+Cn;=kTF5VXGQT~W)Uee6F6PA|YrKtNVZ zK;Un)0nQ=KGnQMlhYzbyM?t6vekl>^yj+z)Knl;z92k-*gD$EJH#TsCL*i%y4Wm7JKy3spMreXHZK182~2T}LH;}` zX{bC*t75MU@BN;LqJBP4q9n;Wd;7`8)}dB_iEHMg{S^g!+&i9FmxTQwq1G>4ZD#vv zx1j>1WaPcOy<6Z~F?X?t)gyp37&sU%M#Ef%%U*o_s>yyk%$n@)h%%poQIv8#@VBbF zUBheC%d3BJ-^2K`TNx!EGKnAz5G2F|K%y&slMM=lEW;otk*~$QJcH+aA!;(Ti|-t) z@_|+qjlz9`_j0!QMM}Dys|&m5QFRnpnV&h*t_f6Jm8@FSWX}lNv$Q-reG4>*}4Tf=Vdn`Z@v{ zrR+`fKugP#`{S)-O$V;`SG&?-gRMf~u5&R1?k-g+Ne%;m6^))DK;MYQ#mWY_?La`d zcwKDt3@nTs@bryL%&fTyPFp$%@XQRk2~?P+=%j1}j7-f$-Rz7M+@uu^+$;>(4GDO8 zpt)Q)fC8+H9Q5#9tSqhVIb662e#_+met#>bCBXaL#KD4_KvhZ>PXJ(NgvUg~L_V&GmSGN4ZzNXmY$uRotBP)mVtp9 z*n-;L)!ISNh1%Ml@J+-YG6aq64eZQp9LxaLcyBWG^Z||z+yn%`dc42sXJsQL^>^{s z_J5)P#DmsF&xV$shK|>Y%hfI|LM=wJ4*R|FnXT6rUTfTNv(k&u&-wFBW_ zMHm|Vy}ym4o#pT87#h$TSsGaZo7w|MrT?cPMZ~0J|K8&b0uwVUo8P^FVEXnVFi!K;PJq-iY2vkDdN6B4q5$fV)!9@~>LGi82I= zVqs$fDx+^qZ9vCrK+UAD&q~eCPR~ruXke^oXv|{7LdVMXTa=*zhcLj-N)Nc4W>$J8 zMzl88Cci7*0O$B3E5=R0KtuPB5?M<<2V-CdZURX&Ye$!VR4AHR87VmEy`f3ZN=L`c z!obANM9<31{HM;pht=|q09@igBE^1~E9N+bK(H|#D!N~THr#~Jo&3+#xJiOnBfXk15#e zIT;!L))Oe}k17LGJ!=yq;O+6}cKutq*}vEd22AvZ`iAU`)N~BS?9@!Gbj;N3Y(|FE zOlFKHe0T|PtfYJUrVcNGl<8L$OqWuq;aQ$xZmrDlN?~gLz5sjsLy7{tefE3xWSu4Uf+JQ+6v-;B~Uh^YW5%?Fi3Cz-+`p0p#cja9K@uAAa-F; zpt0bV7B`DQK=44s1ivV{EFP^mJ0L5)4xHZ}$+^t%y{^><@@7;SDzHg_8X=$LG$wNo! zEtgHVtzC<9nNp=s!63{7V)SwVID~XM$0sDD9^kkk zp`rLJED4^EH}sANiXa@02Si}Ry=&`h*L6N&ALrET3+lJD@U?;#PoiRgoHGvAlgF*de-rBL;sS_J z*hfs3Se6ufG7t zvA9_eU=dpMMZ#ki4o-V~%ec2#u~4aA5wH?@01{Yr^mq(O@~%Rz;S3}dPA4Z9u5ozS zAA@$jcWDj|Mt~)BH~Q1P3V}LdVX01*)3f>=+mdef!dDc`zVbpB=#xlK%T~l$M((GaDke${(XiE_DnU>*$L$^8JZI39xq1Q` zj{#w}8iCTbs^a3#xe_?{#rlJ>97sZ+Hjr00 zVR{sTa0ih!2Dv4f zAjeachm46SVQzjfcG%hwY*}YMXS!HR{&;g7=ZDDe*B~j6S~5&KRd-RQQay2GDB)mU zG*2@+LPVHzH(a7GaZQ1~gVe7ej20UO_132YCjz6UC_h9ZkAWslH{+NE*h#-dQGS-&%;Lm53iR zY2jmikVN?Lbq`Nq@*@lN=U3G%qmD%WEdh?v-_H&bMdW3txSlBag(6r>Ke-$ z&0E&)euwD75l!TpZMNDnGuh|n;femt;{3+v2!e16abLw)_`=5D0Z>uD8dSu@SOp++ zOY>0M*wqS(jrCON8(~eqZcZRoZDaUe8T@dq&rNGVF{!bO*`scAz5GS5*Zm=1GP(QZ z`B6+vtZQT>yxwZ*z0K90968bN`{2`Yyy#7)ScmIZmTeP#7t`fQ7QflhOL>G;-w9LdQ3!99Ha72F`^xA4}qX%OFR0WWyyCDNgRsVPRC)5 zOKN&yaQ^B-U#309HA;lS(SI4UI#FbDQ8%U}zjr%2rjl!E9URemwvG=G7mCUQgGOwP zUOWW83n<#$uCwiT$N8q}R)9C2&CW22a1_>1yXT{7vqKSb0`OeDV*0a$U)9z!G?5hQ z673kGiEKijLf&?BJ#PuR?x(`LCWijN6nHoW@Mp@DPlarlf6%DV=`XNTDh99pE-p`` z_elHI%Hys@&ieV?W<~C%Mj2Mrl$mPtkJv;ssUl(fNbm?UGUzO)9H%%`TPbeo*>)nk z$azK6NyvuBGIJ(fzAt&mfh=frXkX-z`QCv+Z$%?IaqUNKnUD>}TeL>w1FvY{Ld7>) zuC;qISuG;-b*n%^t#;((Sn?G>z|3T4s7(Fj36HQWG_>$#IehS}$VvD@`fR-C6Pq?l zb@dCQ6!xcPlMLd4eOx0#x}c>#_aaMKM8hw{0tTG4l&~^Nn)$%o0uzH?(UUm|qWg!9 zVLqX4M8J#_wC;AL`NdQqoCA&~qk}JH(L34?t+h#vXfI`Z zbKXrr8=1xrMrooU83~5GT%e?@x9gWGL8Hnh*KYjrh`}I4oND#*$%Ur>eyUR13iiPT zE|=RabGmShpkxwbqBvfZJyATP3yX4QpzX^r-$CGI?)_{pFW*2>IQcfZRAsgAA?jvq zladUL$Kib0NPi?I@LceRg-*4jI$fhnTd73HC!RFB=){clY*#%a+-wCZM>5sd}b=XO1he-XBbYdXAITE?m zr!Jng@Cyv}eJUlA*69$;)(?tw7xLg{QcXf5AC%rPH$+CYKNTl7;6Wc+ICrQJh`S)k z8X-Pj6uS}5BtHHXbtuZ^9jcjmP&nStqYbZ+**O$~cJQE7AeRM3krU-49o~spiE~3S_`A@+ihyzinds?arILch=(F>4*KGjl!D<^P zK0dx(ZN>+C07gTJc>l>UJa+NtiHd=HSe~QQ34Q^AJl()6m%dB>$oO<>k}$9nW=~tm zFcNuwAcG@v=|jpkEkr;Nb=1ICThM1ibB*^PN5KzpVewn&?tYJpi>s-nRn^b{fyd3A zo|{WVqthOtToNz;R6w6^Yj;?Y_U$VIe~1aG3pEwh+3hVU9v%n`OgN&qNXZ-`4vw^- zV8Dk;AZI*p>^eL-k#4YFvA(gvMINVCukDxsxBEq1{aP zR>xOYGqSSqmRDBt1c78VWE#98Fc1v*s%<%)yy$W3h;Au=6WZEnP{@vlw;t=(OnmJD z`u_coHh1UbQ`6g%l^s(k{D8aL52uksiq1!k_dLB^xonY}_Z7x*&Q}ss6Z@KXCoA6F z|CGf;5NU>CwKDtrwMd*PpkR$klJJ^Xed}%l0dK}JbA5! zg~5UQP{v4p?%AzDDwQSAY$l(WCY2R{BPS4|+m;?HU5r_0j99$qqUaru=QY{vwD5b@%!y%tm%;Z--I$l84 z(>x~NI`ztDvB_3Ua7MV4@o2Mv5eWkHUsS@`ljP;sQx!P*dO~&N=>~U!tDK=ZaOee7 zt4<9xz>HU0T}#z!g1Fsp5U{bO92}V3Z;tfFQkXq1$5@Y6+a8nQv_L2+OCH-j3qW+L z;jl?xS7-YQc1a~IzYY(>KTbWDkz2}l^w)-B+svdJ?ToHXwlb$Uoj84fMHjn%u2Dr! z4j1!(*LrKmW3hTHRzUN7=Mqfa7Ua}ja`(P^cnEjxs_Dw=78*1$Z_0dn;fhAHzmi4^ z?YShQ9^jaj-Mn|Yu=m6uJ_vEOPam?cF}ly;Nl?+e<~oR+Dje~0M4blj(Q}r;jn4c^ z#XR8Mud8D}3L11KH{hY%F%wS1Jy2DDhSGmqu60poIivo8?ODj>YcKE+b6w+{uDtX3 zHJa?bOU)m~{oL}B;@vd%VRo}0ECr3F;RnG_}Y(pG&VNGe8j-WIm z1$g%09I=DkF7Qdv#k0&i>k&1E2pi88Eae7G@k5gFC$GJFVWA#4CJC*Pv$`pw17A=H zwfX{V0}Vwzvs}MnMgQ;;(ERhnA9PI+9hCiu6-Ff`VC$bRNp0QkWr4?H4WsqdIIKU@ zEeNuGjJk;ND552tdTdqW%kxqX*%p@ZJhUOQ4T}T!?y3vw60riCTlKuI@Mmq~ngLn6=%?rYWLET)ntU*mcZo*nofgu_mPWssY`f*6JDJ9y!hH%)b z%}#{Xq?Dq4=t!q|r9MvB&M8>|t=(s6WG#DQGWqIUInKtC^}7UW)kXzXg!A=D2@}OY z-%1rjm*m^spQ(DJuT_B~zI|&L&y+kEBP1-0=yLYsWtACK#qw%Gqu$0@iYQWv&qAN8G z=MI#gDt^$zYBl2r^Ut5#RD zZ55B1HF!p$u6b{=twRxp$1U>FWrbutLiP15A9X9gcD!JZHos5-YK~h=-rf|pJoPbju z!fzh#3z**cF`K6+yvLSR^*Jf;$npA)ACCyPg5D22(YXT}`BYD54Lsu$3#ZPflK7;F z(!Z9z=b&-f6Yo%6hHzsI&(gl)&E?~tMwLxWu?vKbj{6eZL+PBs5vE{oji9U{o^P-v z1iu8Amc&}BqmR~8{Ui9dWK5fp5jy8PWF0u?^$%Wygt#r$2=EH z(_RJ-2KYj97cWsR%Q(BE82n^)DdAN1=>G!w%QRxdL<4^u@;VFwbUi$o9ir_Cc z>g6qA-npHfoe(teA3w(PBTjEUlm4jG1Er^@kFFihd1?RcDtb%n+$VkV_Aso|MIa zcI&wt#`=>*vB4kBg*&QYB3U=sT@xKL`Az#X_wFPg*9-)HNPFRIxXWlMEuaaXMbWXy zm=EWiMv+tJKlLA#(-h7+qP5te`q&aUwaVv9BJk7YBRHMYrPm@?rfNpA})owr9Y|n zq~qM>l1zPxT20vna$sKTIu}?O3YzR(8dFNxHL8y5uMPJNh+DLq-3*ggc)Mfi_F$;V zX^-J?L_r+buxG*{QZ!;2K(J=XJ^J8+$;!0*JO}F4oeX38&f=D5+!*5vecvciYOMn{ z$l?#kdR&QKykN1Aj`Sg3Gn4BD=}!jg>2LsNVh2OIP-kk^OY5=8D!^3#EtqAzC8GXK z^~F-tlM@SWX8T%=p)8p6OZz+j*OA%DZ9Bas{`RFqsaM;It&*XQr}99L^XtssgU;>( zY60P!Y*#7T(z+_am--NZH-})g1A0byv`|y0UIgxJ)FRF=DwHR8_$XG0y8P5 zvwP4zQ1wwO^Yu9Y0unkxdS)EGG0MH>6ZP)1^K&xHhmJ?~CHVEihJ9Mq3L9n=Q1OEK_Yj4ey9ni@A|=TcP|3{kfo)i zNpyPekw_$C&O8PCmjy=AIWq1aw}xowvPOmoP%)Y2p~-B53|9Pf&aNaES;c(7>B$G?mfQBF6flR|v38nkDJ&{C%+#z=!Uk-=4_hIKh*W2{v*RwJ6EJod?>8suQr6nbf6 zuaLl2r@QR1s`z{g~$(3I#W-&Z4ZVaYHkVM(p6OQvFw53l%JFP_- zwMWbSO%x#qF1rqmm+1U!55YCLS7c+Am^Q?Z!&>ZV_V?ANNTa0_jRz;YmVMC2tGeP9tG%(+Z>Lk?CtGcK95UG6xkh5 z&+A`{t;$#Zp=w~|c{ni4AE~b&7OE{_-Tp4ViSv5(NZKco{g*K`#lYu?WcFkp$CXM& z=qdASU8>wHwjN{{2`U^rvD&k39D+0*W66aJtR;8YV{8d~_SP)~xQceE=*4kWHFtzb zZ#-%k=c+A39(v9mQ2>XJp6||-D!Y8ih^%(W1>~vPf5!R*u-u(825!e<9SRS8;4plV7S87_bJJr5I$nC+##EaV0HRw5YnKB#f`A8WV=p?S<1=ffQ%1CrG}Wl`lwm)k$03g( z&eo=;rqNVZ8FR-XjW}9*@~b>fZHgb)^w_*QqqiSdw`O$a4J2Cx@0t<(;3JIAOnTTC z0Z=sw-%Lg!!uPBJ{7%cZ^W2qO*=63 zi!Pq?0zEIf*O!-sWMmy5f5P^a%0sfdD-$dLs$c zSiD}EZhusMIDPh;otwM<)ghC~qgCwq7Ii%LS@)FnQ7%!A1p2@90RS0!`LCLnZzS<0 zah+Pqrn#jhXUf!C`*NkxmT+on>i0OkIpBay9#3FW?#anX>%&2bpomBfP)km?j?bSz zI~@Ix6ITY3O&8fS9tuv*mef~i8JP})FF$$&fWPuFs^769y%AwV2 zD?8A2Q`>Z$Jg8olu;%r6?0d*_)bDmavA(rM7>E~u5RKWYUUu_+!+q;z1yjA&)OO-x znrqA)I72j8aB@%lmpnxZl;g#^I6s8VFI|t7XOX~IA{W=wuZ|L>k{i|UFuLaIS4yD5 zIdV}x2(JuwMPeZ$kgE`Z0D1Xo?ALZ~7u@TnF;le9vnP&_ zmE03uHEPRAu31jje3MDv9m-E5g~o-t7ie`)hRMp;v?dQIU^VZ^=W8ArNY!Zrfi$QU z=k(dF-P>8Fp}EcPJ(e^}!hs06_HJlesm|W;6#!zh1bh;y#*3uu6FQ>LD^nQt%k!#% zEaQR(E@V98@!DemT;QP#@1Em>^kRhBf(-iF;=ANzyZ{${?$xhu?I0b`H%n_Atyr;^ zhA&0({TfmzFElcHie~!ZsV&^b&_2Gs21{ZdwTwJr`hq0Ruby+jn6KQ2I)JDFFYBgP zYn#}CK&1G+phtWBwN4F%N$eKJ(Gh;#o%xuu>ozgZY8b@p%o{{)a=HnQrij~=6U|1B4wv8%S^ z7(BG#$K@qfJFmPye7jd%SQG`%{g9uUKzqKfCS;p*$5>;`2gM9(G_HKyGLI3xSl7@T zjn9|IGQna~sj{c(nfs}qM(6Sc_SbVrb`SKF$L`YNN$p&0z*GM>I{ToU!(Vlov#|Hw z;i4iShbLoj%}e(t8bWN|-}U|`0&6Y0^I*J?fu{1c0FcyljJxqRX#*a?#0$KvD zF~|fISED;JH|C7w@J?Z^qcdCB*;S$u7#=B=u_u}fR>?4Q+#;}rqWj}3Rg93l zpWr`x)P+0`xzSx_kA*r#bO6!^s#c zTH87o^MI!)>ynjZX608Ha_%SgPOD2AFJkV^DOR71pE2ZCTCM7r*CmY~P%qtY?M6efb@<%3Op9A%k<-+ktPj=0uVooDKv`Dp z4aZ3H6jtS~F3q6J?ZEOzz-KRL2|0Y$`7IL=mj)P~o1EEFfIN)kORstppLz zTXpl|s|WZmDe00YGs)v^B$dib33A*PS^cnUU77TofdU@vWFdNtIYq1c#A)BM`~6oW z43aUn2fLDc_U7ENV8#{owy(Not70zS?0uu3r$gMmY2UY!J9smW-h(!$QQ1{}F(}I_ z|Czv&()QGN1fs%N)A;!XiLrgTb05MXe=c4-JN{8GVPdW8zLrY<3~ z^v;a*MQXX}YvZ?FaxSbEeg&a^e$WyS&S_Q=xk6qOOBL+{`HJXU?XP&EN)KKPA0DaW z_7<8zwZJ`wSM3Osr)%CHAgYkzd0aEV5u;>H@C^9oh^bmwcIAF9Q%|b4pOU}P5hG>9 z|Ek1mNl+qZfuWj^EoW*Mf83?Po+uacQ}geFKYd{Y{Cb1d=1w`jowGNqOnOYKIx4F!NZHkLs)>23zlyg-BwO zZR0^D5)q7V5X;O{MAH$nOQmV$Kln_Ag&hY^H5e%|HNzrS{LzBZu7fk~^D{(nnmyLy1tX02 z;sA3x)(c`P``psxIJe)u!7XAcgyFGa*YJGl{>s;|5?Z^PlS)S8n6Gvg>#HtXv4zG_ zZ0ZFF={6-dc`F%Xw^OOQLE81s^zwAu2-+o`1 zZtF5kAo450)pXcD>Nd^Jx)x6 zA=V2JI#wXx-e2}hL9DF6k7?R2{oFx8KvPb=WSPr`J~u8wsn##M&>D`r=m@K-g*rM? z7&K@TG}m-^BLTZV4T|z!ysWE0kC()g$@g2Ffhv;s60VBM_uF247fY<3^}57C#^Un> z?nL%gzAxbWuF{R{lrgf3tm!Lh;j78`|FB_Z=@eTwPtqjZ+6O*vpkCCjxFH%8inao@%ss+HzH9?m+v3sLbd%-E=CPuBxsp zlXBGT0mHY2Vr1ILB>~k^-sj+k{Azz<<&ziK6rR*6sbe41y}PM})>k(vtg%SsZ4_O_ zD`aG#Ub-4p_`dH@tl=Cf>ru?m(D(v1Xl1M9@ZRl|Wu|JFU76fg($>&FgR}OG^dm~$ z^R1p}C0e-O*qzH6e?FA1^mN9jhG-M=31(IvuiK~JRyu;S-W4tXWM#|}MDgy9vqVnq zVX_m6RN}udwh@A`hWV8NQz%`eZ*OC7XplCNn2*vQSu|i5XB|642Dd zp5JU*ABb)?cj{=)p{l2n2kN=#iVB~(Yv(e6kEQLIic^GR)Ylx4nOAETOHo2Z?is|YsUZXL#V zR6os(Ct2Trn_%sKmASq9obeDFZIan((MdHQK(obLmwjg@aL#gF6(ITS=NZ+O)Xw#- zZY?rvx~d|%`2f-F8OqP3l(=I>QQ7iGFKvxq<3Mxnm*GX!Fz0_sPgHxMSJ39eCaLcr{*7JGdv{E5Y&)5w2f^Z! zy}y$X?gmv_pF=Q>Xbye**&@oyf8v{|YEzB4rDAD(n1Amewj{FcNrG@lTVXK&)#bpm zGGtQf@XlHhjKE~n@N%V${aGhq^d9uEofn~*Cn@>44N|Ac*CKLtXGX<}y;+xlmk9h~ z=t5}}cfV(YH(E|rmG7PKbdNE;s}ji=uj*)XOjAUut?zxDcjGA!6h4jtR~gW3l5xzP z8W;$!tgIZ+_8yWrNWDFmzEq*#D)b#iB;k+(er50OJllM9fjIe!iPu;2B*xS=Jp92b z>Sl>pK6-gcl89G=gfTq!Ipc^>}hpmi=V2=_rdsL4S>wZEIH7@ep=xh-hHNiF#TL^Kea`i>FKsv?>(@)lqVlXS`<@AJfq5Z zVa21tfh=K#CHH;i?nSm7ITHBNCSJ1n84|3t@BM0X!AtBC=pvqeSQ=OQ+)-5;pN#-a z-(upY9a2F6no)PVUrAMf(fB_-`+ua8{%4;3|5*ENocAO)_Oz`qJLNgY6Wd*~IkqBd zTaJTMU6bV*s2 zy<~Dk`whPHqxmhzhaVZc>p!WixqfOKFZ*QC3+!vIVTPxL2UO^EF2~DhcC~-;m+=c9afitZ0Avz84NJewl+@aYy*AQ z`LGN=U^w~a)RRBB+p!h*io=uCs=xNIAOdiVHy{Oh?s4t%j^JzLD6i6Rx!IeAGBI5w z-!5LY0JC1N_72QIM0KCXKnc20XrA4 zdE4WUrm_MvH_w#e)}d_V7n&_Vifs;zK|MN$o#;JuW{PAxWlv51EM0vf#Z(zHk&jk4 zMds5AuA)R`%({pilvi**qDX)%zUV|yIC^q1nC9|ZcyFW;2X}>gc*|*={7_rro$csdNA3*=r=>=g)nHFzb^(8$VHj&*{T`D~x z(uP?{@8oA1A1}6ddaK`t*T>?p^n25Dj+Z-o!mc$~{Lb%$n2V{uZXRBg!th+c{;B$s@#{%X()VC>r0*l_R0a( zt_qMN#_c_nDAakyz<`s+&8WHK4vNu7q}8Lo%AcPaZ=U^LYh6b-bmL)Yz3JkmE%gsN zajsru=**}|7>_^FzNmABRooic>z~{7Q}JHYt z`e;teYp#L4rCZD2)=9_OQGhxyXTJ|Xm$D7zO2td8Srx)m)Bde^B!z;EnfM8EO3+m5H7>=@$4gq zQ)=hu@N(GwZGViBV4O?{W#a#m^aFCr#4BDAa(@nO^Q7-DTfDcZvqGP%0XH8#!+t_1 z)Mo2V^!Gz!VN5wl*X|Z0H|P4%#*|R>B?>EzJwm%}plV$bMOYeF5*wz7nqTxRfnMMM zE`jQ&h@~5cErhq>OFk^d2bRu9Oi!zE%RpYxA2Yrj3KObe2Xr!7K23~aAv!gk#haUMg1uIM^u>ryvt zNU0tIu%juA4-TdnhK`}4a-^92gz^Me@e!WnCZorEeYiOkHW{OP|4<$JTD{s1x~i&9 zi2gj!N&?A=N<+%Qj)c5`U#)qcLFkyC@;`|OeEW`wKYVmWASAndD;Bk-zEOsxqG`z$ zmWf?oocmQe7@kM1`7ca+p$2KPVLrjRTV zY#eKR5T4@*Jq6X!Tpbj^hB!yNSty6%yoxABKS=L|d~jf8x{K5GROKEz23qY@t!rd4 ze`PJ!H;2mZ?)(FtQB-Vd^`YW>W9JwauA2vrYMsLnQNd@ck)-y>WCbkrNp~)L5jWjN zkAP!~&()TP#1|*lPwWdh6EQTiw{-Zd*BGHB`3Nvc>|6S&;@e};dU)jcPzF}O?9`l` zuwGB7hM*Zos9w?~*_kQWm<>eW8)@W1@Nm;N6-sjo_2Y-eM0jpOElEaYgvCuX!8 zvSQ_G$%H|N9BoCJV%KOCOmEUH-Y#!(X7(dm3|9(oXB%z4ckO0iPHB(Z77_<@fX?NZ z_#(o*)osEkid8n|i(3Yg^*A&U@|>dy>u$EQ@gUxD^E(w8Rz*V;EpWO2BcFD;3{V=k zLYwXQl)*CJICt1{Ce3p6d`ahO7@NE+obCgyS}bW(x{#}aOq2x#}6tUE<*^KfZeQnC=yWxZ$Vl<~4{g#?5R^y74p}msr<)s>nsBFV0X-#vnVfn?<$0VBSGb}h-C9R%sHQuht$qo< z-s2o6aTv)gy|3gVz14I(J0^Ni<2 zA0fS$%JLq+V+8I;*NLsU?XI||Ox`GrQ5b_%8&HxnPfC(ebabtEJgdGfFSnsW<}enc zj_ljwTRPwFNvA$gQXQwe&l^|W+1S)eWOavr{-eX&-8MdMB;ynO znH*w3{hZC+(hP&6I51KB(PBNDu2p&eWW;P;^U7t&B=+S9y#3zNf0q9o83nP<5W_;a zeau86SidNekir3D4R<&`8<=g}V2DYBd0t8Je2OdW<>apt(vfGM?)bItl{KMG9vHR8 z>;lH1eB0W%p`f59w&8-czxt{Gx$tZD`Y|wd7npEkxzZf}^Et(n3>q>zXR5;it< z-djTKaxfQz{2PDfbZ-TwRyxBnSEyF;i;KMlEabVh%ak8SwbyCyRH1Ync=#>L1k{;dYty_KQqEeF*ltcxdWA4U0|hz8C~eH?^~VW=Dn6 z>F{Zy%xUy;R+3lITkn>s%2-KcpR$t#hC|R=Cz=oXzGKP_)AF1-%UPEb3Wg$UJUzAz zWNi-xWRCH}XW8XHyJt?~Ti~2R9RF&zz+An5Qs^gb>-$z_Hn?C7i9bx`@(LAK@+WD= zv3w)VMo6tBBqVzdd5`n*@#=wJUQ4g4QIPvW{x{<61>#vKN1hon(O}1;1+kxc z_k4!euXM{_#~fL(TA`Gzo4q$F7OWoPt#kGgN1`HhOXs<6*TEc^xBL|&xEVm_A?a@|wtgI1yvNaH_8C6)$JtHj^DhY3v%B2B*=_YG042Vang;?3E7?rc+6U z%kz&;Nh=9fW8Sh?&KQiv!2}VW9>>*RI>_loUn@92{*z;80y%c%s!WiC{rhK!r@Fmi z&!}`iqrPzurh3{j9XjIcUho%A&rcg>!j+|ilszI-C1T9WvkUB~RT*IR3w8uZSe)Kt zVc?ki48#%d`E1=HlPNLImJZ{7nk}TO>9|+x74bKGXAVhX3mU@#bv3bZe_9?JYH|yR z`KeQN;4;rWpa7)b21jIWOyvP>6sdPx-j(YmLPs+5{>i9T!jigtC1FXVLe+W|u`18m zXy+$x@{{XJR>%S^A7p=i5z!y@@=E5+97DaxZHAOnJ~kzPFYE5OGb6JUdpQz(b;ulm zzHtKka7S%k6uw9@r*j(8*ZhibrH0lI4(f8c<1yd56eq3qaDEP_;r8)3AhEfTFa7CU zDpO+3se;Z%4Wo?2Q|h$a2=;I~aH`|L>`@tlq8PVb#`wAgF{w3#9&n|9=N-Mye)j58 z&=kb^a6%!&5rr+@x240lS10X&TNTszkh71e>s9k*<5nGSsK(E9tsFH|@Y`0|7c1L@ z9BoON;eF7fm6m9Qp=QpWk(lm!*YKu!eU6d_%iZWqUXt~v_rFe?C+KSaB~O<)XyZ=* zq%?lkbBE{lF|+T>0A7BSm2W;WDE)u!u?GlL|NkWK_!WtZ3j4hiR6lHeYmbnnOEZRc zDWkqBap7cfHpgZXA`Q;?Z)`L4N8F|G(i(lOpd@1Dgz%4~W?^N?57+NGFv#7%2<5el zXiV#Q!m#@)>4}31FA`^%*L2+iuPeILwb|z$A|*q5G8yf0tHBbv$kKTcr6X?ixGQkC zJ|Ozl4rUV7I5r&+RaW+M3`grBBfgX)BS<<^`s&4$!Rn|oR$?^|4W?LpO(saU!wB)2 z!#QijN9L!7HIagwa@Mw!!n=)fFko9Hx@{+#WI`&D&59xHBo-Ll~>Yt)}vDg@`2nI=h z+_-Y24s@edV-NiCV=+7FZn{1XiZh{%go8cqo5FXh6^G<(7&2uh)0L!%NElU=WIp45 zB{(WA{-mE0wZ&!xj{G6j9BrbXd~!-alh4n$m-mK|wKvv(QTjkx?}dc3IQkYMwerRyesQ06({^99a%U-(OL!}oOe50?Wc#4PZG zi$i|#Wok1m#3(8{+ea&UCZl-7LhgqhL7QJ$?0cs;0`~$m>_K7w>XjFc{eSezYy6W} zUZPP+#^G8J6XGdlkfS0PX&>kMnO>FL2{YIdcJ^rSOutL#Zxt&PW&&bmDgVOJuIxdF^3R4rquevH6#H^@PZFaZu}%^59n;Z3 zZZt`ZogJ*jCg5@FfZ{5H?L%~=0b1(~qN^~ocH1t)04CWW9`^(ks|grl*g--~s{Irv zqhXBGicd)aCPkQubBUI%^Efeg8((n%g3-1P{cM_&so}C0H+RFqAcen1R@5t`n4Ai4i0=% z=3~=Vn*GFM+U>3f53Z*dobwg*?9JTS{_+P@d&bcW+Xv!C+ zw39foV`k=OdEct;>YA#as`>hxf1>M=E}bKt zwfDOBdb*(smR2!#^hRD2ANZ)tWyvL^b9V0lG~jV02G|Y*1lcz;BOocyB znoLj49(h)mS|x2fG&1cYBlb#!EQ2g>3g&2Y^$Sa3p>;AeLakZP(9l1KHma;ju+_D; zpty~s9#w6!&7i6K#+mkV`A%;=A3x2MUDsq+v`zEX$;7epG;!3yFS1kZAhut4-xzl} z8YXoH<54>&TrRl)y8Y=o>Z9bkpIn8u;tv|4!DH|cZ;y@1_R3pXvcIwbq#0l%?WE-^ zpW}a&84QKqDO-eTmz1N%46ycJVS3P=9**@Eb1@wc%=$(+C)AQ;Tq>0A!80klPfhp= z?p(aSDb`p#Ho&+(b5kj$b+)}RHv<=;X!B^!Z&EwS0K@34A4nW-U72+BQ(SR7rtWZG z$U?If9+fUKFVcQ=4|sf2H}Tvn4cr<~X?+%iR{b9Po)~T-5Zqqkg%z53lqe?573XymX_z}$zgW3wnU&AExPlL%A%t+ z=ho>X$|U=RuZoC9uo5LD#Ps8xo!!??K*v^YvaiX^$%DxeQViM$l+nAHCsbEr@_Hsk zq;zEGk9Yw}%CcEH$S321F_GC2@~xY1JX%YBzgXBelkoa(Z*JVS?g|UZiySXSU5X+u z!TT|T>u4zM*X?rU1d&ph@b@Zg{x07xJMwi{Jz&_d7n@<{A5fPP5wEgwRIbzOI>vT2HkN8bRas#yCIp zJnP_n=EE`G{$#p<8o^)?Y~R|4XfFfj0+Rnu&O=>4Kve+$hd&}5y#9!7K>9NR;!o1P z^LMI)@SnW>9|ZoNFTIp?JuFve*`pzeJ4rudwJ%^6G<>C1YDJ1DuyIatncH7*Bz;~h zLstmLdw@HRkV>;j+*jY|Y^LY`0&ji2nV(x6_;&wIdF)nCGg}i%?(^k(@}*+ETxRCR z(@5WA0r|?lK!ni|956kI23J}b`}tl@S*~FKpw!a!h18-u zR|A14Wl<~*icqr*lg{egqqR@giEj;kB}Px@JUAx~>XY<}8Z)_qD9n=)J(E(g43*u1 z{?%>4ScmR0;Y0g99IPp4%uSDv!GR#^Jy-8o;9jaAL~_^*(s}@5+(>rl_=X>P*-Q}v zlG7V35?2zpwd0`u`6i6c;GczK##-?-F}kup;KShXCpc1VmNpM9Hro68m2MiNu|JF&CJlfuNd}YPOUJ$hZW!Rb ztnfyj*2B*q(z7-_F%_S?&e$;!?H_$poJbqGB3g`qIYVKcJ!E$KoQBn?SI{bO6*cBN z24f_Zj3+)a<@U?i#Z{@3n#Jq3CA7B4Iq+LXDG@GqF<*We6k+-#yK3+|d4pv{l$q#M z)Qrg-v3E6ajlYa+q|)6+v{2*R_lfIVFFa}MPrLR$J#(!b<`2ID7=^~vy#bT)s#&|hC zi|^26vIZ43*!o!~uZ<1YERC35o18DzaRX>A_ZS%_etZ6-L5gV57-_J!95l*8Nta6o z+|dMqcVm~#tN1<%glT2#)ElZXhovh>J$v|Ma_8z8SzL_4E)6Mxy}rB=I+t_5K~!YbjS_M z8(gKh7R5r#hJCadTV^$BooBocc9>(yt!OZZ>Yq^a<P;gZyK5qGK7osU`c{6c~Fi@dVl<|WtD@@OTO?JlcR=S>@C7x)K3lBYzh1xYj#7M zM{TzJS7Troi1U8J1l3QOYLMu_4MA#-Y#Zkbt42 z-N^bz01xks0@rMsCzHlreRgN9vERN9QXO0zm%_l^$Jef>jUX*KI=D)ZVTqE{1Os$s zaA&P%tR|P~g0v-o_tj&iwI3p!Gy&Q z3i&xbXJqs{yf`o8P@_p_Q7w~bH8k38VXBq&s6ft;Xa0JRF|&3fc5V&h(CBKPqsR0^ zS*4QVVuvKjviSHA!`jvkeDLE!+th&cOxOAg45JM$#c8Q`uD7=mXN&A`CLvLaRb;O8 znivlS0Jl;BO``xRg^_(d*kJ8I*s$2#%C!IjnJknPxInK+!gsM(9BhY;|MS>i=SIUe zYFQA~pv8~A0w*#fXwN|;6&E#9HuA>C&Vl;Dkgl=}>XPzVDmS^NPEhbf@Dr`r!{RW^Oj)Yb(Z^{-(NF$~<$YMps1>eAVYsH|TyEhe>4l+T)73Jm67=4ny ztI2lFeRN*~)c!mRufM>^{J;cli?V~%0pPm>JWUq)6U8f*&m8YYBsf4Uhx2q``tq8P zRV5rxnQ1evRW@`^<9DA4thYr+PdD7i{x_5|-=0#DopE>N#@FU~n|}T* z5;`e(L7K-1W}<&xDtGPhO)G*l@pCjs9>Wxe>Oeg)7#WKo??T~r?B1bw#j6{!*RA;5eLk;AYJU0R^7U}dUyAf*C#_|gDvygdhwN8Qx`a-S^p*caf%t(8 z`mxew?<`l4Zv@c0aq4wc1+g!p#;t0dBkWR4lFy*~mK9RR%QwAZcq4MQRD(WTP$fz{ zxdki?(dM3(yAtL?3-^U>l_Xo_QcC^y0}Vp>aQ+~-nS<%RRHfJ#^eh! zKp{|xCS&jP6yO$Rd9b%9Xl{O@wdScKH`{jYR4}W+cwFgK`ehs|Sy4$uJJrj}Z~yY? z{2}F0A?}l6{^QO{Ja?HBUdIoX_;}MRn=7aCd1bl(8y$=pN^{dN^f(|0q#R~GmYM(u zWmu8JsPqcC_3Vi;k~^7T+VAYO{Gpr9kQ$x>u_qV2 z=|U8rz)DchQ!(HNyhp^^S8j;=+(tq%Oe(j|r)-QjnH6Er2KGaq^r8}avkFbz8u*lg z1wraoK+SU~u*Bdp13%+V>vJnVcaMnW9mAX(M=A@b=PtZK6J8i%lRyZPy>u126{hty zH8E4aQyMgTLmTu4!sUzQgIZg;K?4cGpv;hHWY9C|1ECG-O*WusAm7>A+9tDE(&mwZ zbTN0uAM!ZRXg^Bc7R2yd+t@VUHzY0M(_tK(ocs#GnT?;v{-E*n+$rN-i%238c-{q@DCv#`RC#tA`0zpj}(q?gQKJR zAV?pF!{(!!ni>u+ZpiJI-^;YL$kiB1$jZqzftJ?GFf%e5=nFy5+wpsda0TAZXEXwL zhGIa|7;*ADpO~4kVENu&uG_91Ly(=$X&bL@Z+A;7+FdO0okrC}DHnNGVRfZULPuYK zmkG)8ZEHT~hFnY?$JASzgEXq*#*7rf;RDa~y7t3N9k8h)IYFg|cHTdu%o=Hx7O2-g z&+Gz@R5J9|lg!UF7u9wTyv{3MA7&^5oX0=Gl|mB{Um>vJ)5<9bymY{Ko0j8WBkjV; zfLsPw^I{G&*%8*kUN2 zeUEPgHpLx}G&iZL=;A-rNs-XsKB3IboHF?HhNYgp5yXbKvKc~^)tX@*FXMFtrO=z8 z_YNA~k>~dMB22jSLw_njTU=V=y@dwZ1lg0u>Bj-#VoXRbt%-ys#nH`q=_?9YmT7vH z=7_*5*`Udbjpsz2{S)7*+Q9u{3F)I+6w7wKji+-4bx%d>@9zbh-cM_pzM`tZcip!+ z8cRKSvL^sRy0pYBfvN;MSy$p#udhd09>{gTKFga~rtL9KKowQG3_u_IL&Td=Zo;p5EBDM+vCX6jB&Zu=EzI$vmcp zQTvBF79dRC!hDCI-HyhSRx-MPm#ciza%`t%@KVqugPgD&BcL<-m1?w~ zO_x}=>DEQ9su2AI+}}Eu`xG*IeWHcjJzo+LMe_csix3@i|E|V5u1-Qb z=LV$l;*``dH6i6etZ+jwp9%ALXYHTSwEPQex}mZLao#A-aEyy1W) z2y7l0De6GX*?S(-=ENx5TY{4Pas9`r=fg|ajQ)JiG=KOkIWWhQ*al(V>ZHn~%@dJn z9}|^icq|FabEw2T(n^nnC{`ADhJzUUT)pqNaNiHs>+viXjvGBp;i>rf7wul_nb8T; zXW5^+_{`1Cji+)&qQ2dWnCyf8R6qeaFZ@1dwluM_V~>R=6`@aspYY)V30e-do8>`X z!a~uD4e$#U-!0jW_BV2tie*U4u@C-tX#<kq4Wgs@`hCl%#eBHwTE>hZ>@50|ugo z?94BDJ+!oP`+uf0lea2WnbbMBWh(a_M6}RrTi{4~XkD1tLWsn?dZpjQxGvV2u?N%2e-Z?o0$JsZp%tP06S8B>ijJT}rWS=C`y8(l`c$ik+i zE?l+b^r1{Qd==JehDq(=h0w}}v-Fl=p!{xfE-|1=1__5T9L-GUA6_OUd+?RB_SRs_ z0oyI0uIDsrFE3j+LF%$@QBvCx->o^+P(l;h->%#nO0M`GnEI{abpP$?fsuecY8an2 zFE?BJLVMYcUCteM0iF9N?W!PxL-QA(g8N;7tqBc3cS7egJ17W}1Qcph(f$++8b|}) zi}hJ~7xpbTxv5F5&9>n*8V7~dWe=*rCAXD^bM}XE6G_6R$N*PF+ZU};Z%Sdt0ng!i z5E_@Js$OLNnm`3sj|Sfdvm|}>Py-Jq>U@c|A{(yov>*eghIS^=8Tnf`bcX>e;ts2J zhh3$33-<5znqo(5JgJIH+Ga8r9I$NlRaTo8v}Vl2r_Wx$!jhbvT(n65?TJm9Y?moW zKUd>}ZZ1p&me;b?9(_a4@rOpJOKfiliVxaN3p(z9T*CP79{vk*;12nQP zf|rw>pK1A`f7=qLP9O5i_jbm(YoEBQZEIsI>jksQC86n9meDGR8E8Uowq>Z7oQmj) z^n!$H!1XOY>pAm7sU#^awipvu@%Th!03Y$6>k zcC*G`EuGvv<{~}P?7n|PsJE@$9Er0^Gfo(g)$)# z-7=0I^U@d~pD%nbX*hdnuB|^`uV;MjKFVyd1~djIg7*-2S4Enyz31A>9T_4&F|Uee zY6uZfXyTyJ*ivrRMo*}*jB(Zhl|w=D#)kra*$;A1SBFFtd<{j{nQf2+4 ziYV39!dn!uAt{Ncngf->mV9X~<_JAce!CYbX$J?-@>5mG2=5*oUYLqt)qaSqRV zq`Xn&aTH>XVu|J!Ms_L6SSK6W_2L3*10ctin+!XNYYc<6l0fq%0z~2Ef|qK z+H#Y&(K8tZ!ESrAIsS;yaY7-{*}5xVIl6UoSMf+qokbvw#kA0H{IQ4oQAp4JznSQ0E5Xx3TYf2v`;w3DU!0-19GkV=%5Lej>I9oyc;sH#1Qn(%( z5LP_F`5*?Xx6%0N#^#qba0ibcY(Iv8h?OvX^<`{%`PuKT&%(k2G?e_h3q)sCSmlav zRMjA5NQihni6Z9A*C-r$aHmF)(~l;JLHx!2@jKFS*mkS8DUs%qWpH>F;Yl$?+l^w zE(fiJvkhZ5VEvs0`reWmIp?ef8zo0?f)WzcCBK0{p+75> zKivV}kAGxF|7j!;{~6ZvPmF{gm#uaQp*Yv^S4HP_uA+MSd*=}yGr85`O8oq*Ds!8* zcg7h#2YVbH?GMlLw3c!cPdLxxD;-8v!;@g^I>5^!Ik@XoXdGp9LE#-j3*MDjdDP1{ z-p?gX9;0HhYQm6&uX;>t|D}Ft#cA_Ibr}bGhwsWyF=`R}vDmwYW=RnhJoA0dBRUUD z;-@-Q?SHBtu-qaQU;4yQox}r0!9dts!o2+{@Xx}4O{}mu*PtW@g4?=l060sU$kS#QVG*{%$~giXQL-%-t}*MCm>a&J zJZ%Ugrw=-Bg~FdU1V4@M$2Ct`U9uQ5i;AYBiXD3ec9#c+QcJNlhnhWyDTaEw$K;Fk z=*g_^c10zB_?s+AOgW46)qy3;y{cC`T0zj~zrhlDo3kf3Dig9L@yY;Y%5Gb3(o zIA7O^RXLV*6YCI44uKrM%rS8%JO#R!eGXDPewNEQ$_(4SBYLjQ^)JDEWE-#Hvw_nR zNZSjSb8Sz4CUs@y{FPS#QQvGQX$iY~{RSXYsp!tLewXvqE+m1@WK)i(f4h=I&1b_` z_GHQ!ZEeA)ri4d2#2yb0Z^5X(bs&Pe+IF-Z+ZZq^8+KV*wEg2DZeRsn<^L~1AEFQe zm2zZ<#p^2xyHX{$_T_QVu-nkThD-uJ-@t^|n7OTuN;^Ke^GQQ+X@BYh^fRQv^yBiB8q{TJ|D^0kc+@~MY~GYB-hPSc%kwFp%P2NudfGsX zGs=JHI20Fk_U5qZt#$MiOL1Q7EaQo<8A>F);>*@Is^|d?6eH4x>E`LGujD-W;f~(1 z#4R`UyPXz1c;JQ1^@n(6%#b{`ytjL(#C10!-J0v5)ATE{Gbq|~lfP3Ebf58thxie> zYDcfJCYw_U82?puD*}Zp98ljbzGC5XUg^--c7+MxIV8KUHk-EyFF1U~XoWd62O7Sg zPZl@YjmKbpV^4C~@BX|RC3B-KAQNm@CR%e_Q(k*UpG>oN`uX7(EGpW}8C%*nR4FFU zTsjT#ah(hwI=KM0u6&FjjQ_Mb#HLz7|-q0X$$XD7SiXr ztWRLxEP1?EM9_hGBNx5s$ca)yfy38J1Tf9cd%1Uk9ZUf}>J(5hI=N`Au_m;C1NCbr zir7=JSaY75;@oOB*$-7PQ#o(K_W^Z6MEuZktgglAOmz^0c@@(x4=$YbiN!4Ke z^+GUNjafT1N4LTy#m>rbU`R?SF4_2^&Mv?`#DzEO@j{!Pljc2%vs|N_;w--=#7NMR zR8~=*bitAZsr%k0WN5zG8Hd1_^B;u zJ@(y6y?Abb6xGrloUT$*m-vx-diDU-BaU)YBCzQ3z%tF?d{e&Ey!4v}>^Ui^IlNYH zIu%y6ERr&>C(+_<%BIfcKK}Qtc2V&k%tlOg7{MA5;N_*bQk^risjW!?iWx!<;qgdw zbL2C#CYyPN%Uf~8`36xQ+`$6abTU?&yULb-WdRU+kRl9W2UigKuY6Ie87rzCC;4?H zQnoY{XaJy))me}y@sgF&Gu{=>HD4ZO&6Z(2N^s!MQCcj5g+2$+q(OyQgc+ zO^cXC82F99H@xYLIf+v=SX)aNv3@0$zZgW2$}LYw4&4{X-s~buwt_q{oU9&4>qpke zwzSGY!_uQY0lzqO_G>H9{6}^k$@_$NV`Gbtw3>Ko~l%zxj+b&5+6YzJ?sTzR6_Eayy41pjh$wV-Y zcg6FUckUrKg=2~Lu(>`@T>f{#q$K$Avk;d(3q}_~F#WDP)nWJA{jO`;OP~4RR%U!e z!1^ohTpy^omlBp^yB-y(uLXq|r$=Mz4#FNk7_p`lp&hGdwS#QP`_3nzhrh9i8hI<8D!yR&=PRY;-*p*?O^$7Ax44{Yn#epLl< zW48wZS0Si}WtXot)@nWN!^Qs_cY;));@@y5sNO_*cn3emEp?`)a@Pu?vRX24Z^xe{ zCMD@)i|Lz{BA(-&7MWTG0s0i}ELFVXRlhe8Ed;mWE_vK0w@noGFmT%
  • 3|C~&i~z?sDRM=eg)2(ffXjQOb}lRj9T=d?Hx-M@5SW#hcHhf?LX&tsu!l0OK>=f zJB=KOiMVGXMhh7m=r&rQ?LVtlg~x4fo20je2evubJ-ZRGWJt$6{np3yNlV+^K}(JC zmI1M3I*Rluvap%8yJ_jj54jSL-Tj%p?7#UY10@TJ2!Hq>XtDGXu=1N#V~LxV@sd5jbl-Va+|n*VGuf=%XWu1 zG1)AVX0!QEvFfowHoWokylw{l&r>@tfR@&= zV~{ZSvIYl7OCLDy_^yZ)TQOSiZ!5@q#ed+&p?`DF| zKfmE?`me@>-Bw2K?yqi>QmmDT3G~~6FLXiQWu_l2JpY)Abqc9}jYd=&+2Z5lJzWP; zHV+Bn&~zO$OrhRqWW(gg1^<@TX}a=8cn8u zY2}|Dg386;t$d|c+4w_I;XBeWrJOxU-Z(R%uYXJ=}lZkL35b4_QwA@pUe|} zc%GO3ljzC)WV0d8>hkVS8D4T?iE;dl&6bwTWGaY2BAZh}!~N21;D#f_dSmhVt(m zW<1GMkS{2VA%h{XiR{mMlX!|EXg7;n)$=MD7~FhgU_2 zlU4ql-uD%7eCgj7eq3-@`Gq)EV&78C7I8}@EGO?X9wov&s~hXCduU4j_Ie(~Hj(8o zZFPjz6@|j#dLr^d5)LZf9HE4FhPYN)6Fceha$Z3~mi?`s0SXy*dp-3$iLGPFv_QU{ zx>BtqUe4(2!w$wiOYmh&o?imRlv~)$;oxjv9!D#fUZ+`g+(2KoY72^DXmBzr8td+oBbr0};Na1dSF4&=vB2 zV8cMz=$H+}UoHP3jim|2bQSo9b!XHj=8{3raXw9dCv zk7-Q#OXh2#rzwLCoI8#OMtdh@^I!%v*(KNMsyPvFF#l@ev5+ji;}{gqNH~CdQsXN4 zy3VPU91o{c>B6p@8=xL}VHF~SHb*69-kUJ3B(ppA$eqvVm)Y}U2X8yfXUW{F011jB zat!VTR@`xUEr`2M@R?!_h`wp%gByqL&T7dKzjc$6H9L#B;H@pyqhXKrR1G70!zouh zo?TzbA$IH94bMu%tMEeowf>6e{=u-eAvKqHJr>LW8k6}ibC0&fKHRkU6*UeFQDwO; z5nHqSe5aP)8e%)_ea31LzDuU85<2Oe#TLJ=*+4@h;*kjb%xN>>l^9_~NHtONbZ)(h zlhYvJnV%cBZFp!Y3euPFDxM-_v(NJXtSg>FX%pZESE@exI^%ZJFkXFcMXAU-ms#%b zh>TnxK&Lx_3adf^NuALVb@DWJQTcEkktMA~Li#1SCP@_rN}3Y1<&#afVp3mFpo|+c zz4u5&ZU(Hn3Rn8iq7n{gCipVmh!Y$dlF~An!jkE3v9bC-DiQIKFF+@h5LV6XOnc?6 z$;;aTw){L z2c;&v*{}9R8@h4|{~8;V%=jl86#EQ@ z|F;_aHHtQ@7W-3$!9UUYS5{w?|2uJB*YtPde0|*Rudow=58H2N-}aBbcgdc28qyTZ zJ2du|rAT)UurS^bB-B)T2%C5E72BuJXooT>4CmOw5Vwvnr>GL5yoJT^TLD#`R~DFT zL$$OaHJ@-=6cCtCHPRSHxFzBdMLV^WdCUm5{r#g2)ETy^o8D0hrHYE$Y@0yn^tqmR zEHj|6P!3NJ5Y0zTjZ+F!2F{5ZDT!h->+7SRWJ;5t=cUKi!!7ViD+uPi|E@zMz3|U8 z{-YP0(*IGbv+nliUrCF?f0gPt{fnwZM0W>=IAug?&yMl0Si-BwJ=XVk}czh-340Ykym=`Y830g!ZrzneOg*(Nl1STmuuBCP8^hmZuk-vjfz^(~`~U zCP>;n!^G9o5($uCCl@N>Yw%f^X@0o9?j7q#YGLEk{z~Q;4p{zvq{X`|JW+I7WsG%a z_;dewL77v!4B*LI{O~nzSt&cp2r!(u>fY%k8pd7Z{`MY+lC8T&(PUI}65s!IRMNqS zB~xf!FqTHgYwS4v=2$VrjLXq_(?k*NI2`FZ1+9XYr)b~QFHaAa^HXh?gBA>gZP<>% zYPWP1o;|JtIn9dk;e7B_#G?Ww?*Du2z5~wA*?v5_m=B;$7CPD2}&`ab1f{ zY{;xXJS@WOdhxF86=sBVf_OX+qK3#*S0oaiRLwiFity1=V~5}M1%h;fM|5$`RvEP} zQK|%2_webtqR7s&hYZ=}YJ9aQZVESJ68S)8BERw*xpU9H9O+GA$Zbh8#*^fiO}!3+ z@>)Jy#UGd3)LJKwl6o)E(^5%RZ4&&-1X=qfjO_X>X6T_gGK$18duLzud{^4UAi4I& z2MtmJ*DyqvLsyBp4c}M2PO0uui|5}pT4l4A?=BPWiX@_r<_8FwJRz5+H(*kAJpL#P zA!t-mf%{RuuL_jh@pDUVXt;;w;hGs63tL!N=xBZG&M$V|zmzN~(Vx=+QxQmIVJ<6= z?qml8gPz#FT_+^_8vLJ%zIET#fWeOh6^pg&%$ymL!sTlp_Urm}p2lYlALR5y8FeYC z2{Ma_;NWN%^orbsCk#vN)GX!YXqz`NrF3bTd=*a@Rx5H&4V}R+yj$3;TG3wpVtxNU zeDC=m@cooipH|ktsOUS;K#D#kX6;0;^wEahESLN@l8+;UzPtAUq~tXDDo|8HczU~RGJQ9Px`hC*>H#!ZCh=?m3muR2Bcx#G`DueAlI zV;omKd}n)kN+K8F^;!K`rL6Q*{c#G^G<(su}? zt+m(=Uo5*ee_dBPvAH&KYDr#L=a9N-r5Ig}3bsFfBdUI_u=^a^b-)w$4=5P!W}9|5 zWcB1v8b;Q+L(GZ|k_K(fm}#c51bl~V?av*z%66C{_b#*;F%Ar#N9g9Qg<$`zp+D|0 zGI{y-w{Q=e5#>M7*|kb-=xl#m7kCP*{KI}cYA{|rMP=bekME`jv&Wb(w$S`_$KfW< zAicN1CteJ8U)poUZWa5O8tdcF&?-HX)K(WsV~i27wP`3~yqV;Wh+QMx4^8d_%K$D$ zBL|Z?I@w=Yo~T>>@Om*Ne1C5fL<0w5)OF;5m-ZH_@q0dk)5|R%42vL3*9~$d#=gTm z>Ej+QNVoMMJT;UJVBc|;XDsyuM@qA%b zF4|3lwoF*AhXIO6g`}4iW>V@}ELP&;36V}$^*ukhyGLPxxlCmSK7UGSSAZBn1)8j0 z>3K_a^c8LpvX{O2-T_>YJyw0zPR+8x#kpOW_JCZaPq|F^^`~7sfH}LvH$nr2zLzf` zQWTFXPODr?f4AV(7l&E4YNX&{$(*dR1)f(!u!gka(|1m#Z@0tq&HoB7<0PJ}^8cy- zj=@>aE0P6v_-ig9Xc=&UI|tVwL@9gg%gOfdw%>Vw4+BjkpCKG8y-NC@!3{xpl2MSQ zXDH$miFu|#Uk2r>E=gw>a!ki*sWflGEV|GXx!zl;n)sCUL*Ey9tJjuS{eyo|<3k%)uy93~W}5y1-VZhRrt*K(^eu?Y8C;HMuj_%|TvJ+Gl1y_p;Rh_= ze)X-2Z||)Fz=`|^xF?**B3`-y;6Cs5)&N&9j_YS0S5wBSf3NX9E$w#yzRg`N{}@yF zue8ynzU!nVb8cwIN$L&*^G^L^iOWksv|fIo^?6SYp$3)-8Y0NOcyCYOzSSKukN+|H$!45ND!?W75MTQ_0Zoj?I-<|)6{6`3V>dZ>UC`-uW z0?{jcv49WiKi-^Qc+fvit%fv$rak5nw$@^P|=#<C zo7HxGL-c5|B-)ulng3C5KZ-fj%=CNlc+zt0_06=-ka_-*XyyTED(i$dar}g&tn=dH za5fI3G+#6BAD~%fU}DPAHc95Fn7zy0Ou4(q@_96?yEK0wy>rB`Bo_lrI66b1KX`0S$>zMK*2*1$y*wr>{Ltw)*f8@z8 zjZGFSs;U%>cOJ@!vdUAAc*geR4|KaCOmHkk@ajFQ>hdv(zm zN%rPvFxyMVzE}%FGdLOdbWUS>db-pK9x5uyEv=>q-7UjfC;RuRdXnAOgmR|bZ1I}c z8}kimyXNjl0k>W@^LApeu!LY4A&YTn;eD*Sh1tVC3@M%*AIIq3qrTt3$J{YkEmrQ_@Ah-;|7H96FLR{9 z`*|(;JBbak^3|@*&)w-$7)g)MA?-7{kP@TuWJ~ymV}%)0ks)Si z8UKnjrB(i0c)VPiKk!X?qf8ycZadg{+ow4X<^In3wapRL#beedbt9;>y>x#Dl-9|d zg!Jz1^e=$8i5Cw0_1j6BqnpG&{=oYF+DY1At**RTgP?BAkIALH!ZsoEG6i2O8iDU2 z#ce`m;0nPAYQ7i(W#oiW6!(T?_iMHup2S~tNq_=s+~@Ph?Sq&T924vl`;Q(OalY@r z?h4mbX-#sQAZ|C~?PgsExV?_a3-;aUUwM7(t;hc0wNZw+CY0UsV9L8&nhgbC@B&>S zTE@@%qEW=$H{ORC2l-R{rtfPubpAWxXzwqkx1OaB31$qjyY%KsWL%xr9n-v1ht?z|saxfY;ZW-P{8^py{%_F-5 ziTUW%N7q^;-JVYMlUo+POsE9yhJH(ZdobeEz>eHCWu@yGX#ajFf6t>n1K)&N9YX@$ zV9OyRaXY~_rP1Q`d<#Ccq9HL1tT9i&hE1U@Xzi_L%qmpk6TG$HM^y^sZVJ;L83=Qo(_V@_lWNeKeCqrlLGIM?vcL=4jmgfH=&4w8KlXzI(;Ovf664?RH44 zS^(~(Fnhg!Qk*Kx z8h1#qOOAUK3ySs--@$)YW_0Bs(}UHP1yLCh`3+K-;(Gjx_Uc&%v)3@Mx@6Ye1#at- z$bA9?3AD|#Fs94#Ivp6sQ#Bk0Gf4Geg7jr2 zU2Pijs~zquE>zU`T{l` z;{m8bhAf+o3QTqGM9XIfgUC0M;Re$mh!iE47b{l)QqhpF1ilTGlNmS%e(lldxOP)MPo#$!{ne1I$p0c}tUdt9#CLn9b!cPxPJK%?1n7QY1; zb1>P=0dSStb*ds1KU03Cc5-0WFQA=$`@W~6a=e>IE6BfLOT(SD8rixqr zk#guGwvmy!LeNXortQ*$1;Gmiy#Ht$F7g2%0DB%UKZhwdCN{fgcnNE$kWr#FjJ?(c zIzbmXs0FLDn8$I5lEt&e4f>V8rPv%qEhD;r znI|`JM~SLZl((aI_A&us(grvQ*?4MQHu4`QkM6B2WwPEgTVHYj{h@4l!S#zO>lz5p zG>I`ez*pSQ))IzchwG4j>~rrQW8T}JSdK?@TX>2eEW#Pk<-D6aSey^ z`^`_cB$8-6t(htoC{(w$rtse=MjnTs3*uNUedyyC9!e`w#=gCfas6r;AxDF={@(5y z-dQ%H?7ji#jN3&yaAbG99*<=qnA^`sur!F#{T^8;wR9UYEXMW+Cn+U(o~XxggC+`$ z*VoVIe4(Wzn^~c@GU)R95grPlU6c}o1!Epxo*9vah3#_-L$JP7o0`XkU`v8hFLO^s z>o(}V^SAnc>06=SMJsw|DwGZQse7fJYS^nySH0oTA%E3{jMr1r4%taQ zz;Qj@saZvLQ`rv=sHW@68EISOd9MMZ&WGchuW1SH9M|37?Ij9;n95hbTMX3u=;!)t zq=DglAw_TV=-WExHKyVOYm1FTR&@e;TpB)yfZ8(*}sVpX4#V~uDA1;!A z$^d(masVFiNUnPrCq-5h=0G+KVj%ol=^GX;-KeYIO|SlrO}Z0%u}o6SbgiqcC?8py z0vs&n*||`IDQ%({=hQT8=E0!bFanDpfH)>9I$Tml?^;rilZ_^%sEDHfNel-@_Tq3d zJopZ6A>K@~A)ln?nj3#tjR4{EW?Q)o=xdqC`kZ8jTsq#DltBBZ?5Zp-QjM>4?li_v(e{ zg|DKxrP-h2nochJp1U5r)KEO{x^x*eX_u7Qw+65zF3E1E+rRX#{*67c8hxJ;aGgdi z)}PCmMk<*rw<|={BT=|w@&%boaTHN=x;QO~y$URDt)F)@RE!#*4HPBfo_KHj4tw9O z?{&eBw6sm;Yrt{HHSg^VXS_PaNa3w3N2L)109jH$F3*Ss{OnA7ZCJQCLQAqU9ruO3 zmO0DzWf41OV21T&sQ%M)qJ9Ke?$(SDrvNG0bpOP6{jZ+|( zk!MGsWP-@v$Z*3~0&*PB_iC=x}V)lIYl1!rr%Vi z5y$)6!@JE0zFY{kL!$V}OD7(%ci3>M1;A_^D}XUbMQpfr+Ic`pqKXiKP7rt2mNUvm zm7TYznyQMD3#gA3g9j4L-FGTP3$)Svpp{ebKb!^9Kz#h*_4VTEi()y_=ifI!S9}GX zULX0LK7sE1KG9JB_F<5$`d1!~d!okZ`km&k z?w*ML^l+!-^^p|3FTBf9Z^#%I$^E#={X!9jQeC@}oDKxYLMHh=njO z8}Efxw9OfXoBr8rd!T~JTf_n8CWAS{Sb4RWcckuKIiqx7};xL`TwaVPd*CZzRE$2mwMXPxrI19lF+7!Hk0Z=H|_jFWajq zLcwc?D!#2N8xGB^FahO_XXD?g)->5Bxh!*V!gU-1@f?UTJP)qrgs5GyOwP!Q30F3G zK@1U>o9;}s&%PJ0De6bsFWuJ)4M$g)(O3h?tC(vQ6!?v5F=*C)J!YQTkCTI?P>PIM z%G-1gMUHZ!*aOz5gW&C2tqIFTM`Y?_)c^%fSZrach-!9>FOWccitG7Q(z$nuP1E`t z!p*L2AsT`o6Fw+aY42jDy3pv`@la87qhI^neiSTiyYv=a_084fuMzP4CKy(*%6`uSFB!&x+a^<@m_l&UQ{vw2KT zwpgpPZnr}!lLKol{$I4cV{l|)+b%juCQc@{ZQHhO+qP{^?1^pLwrz7_C#UD#-`=%< ze7kC&I(7batySHs+Iak2UKrqO&rvOk<_=Uqqqve`GZ-mB)m?>f%TmQk@u=e~^;A*#9;6d{63Q zCQZ^ALD5v@nc1atMGX7zaQ}uyels!zR0R%A;tyq8n%BFEIQggPJh>8F=~ZO8>|3QX zMb&JVfI6}(A47G{LXg}T_2Db1f%GG--(=08svNg-FBXl4a0_qFc@t@{#LN#yZ)QdE zMgb?YYcRAPDIP(*1skg}#H=5QGnwlSCPVVaIpW86PCy2`7L+KasfB~>$a$@;34ItGoaO~gx&Y!r<&2DTx2TtNS_Fm`>Z{f))RQW-2pQ9 zKuYb)sMF?TB2r8y+R<)m?p*$-`BSEk;J4~^DMQJdKL!k~TToF!`}~+2ZV661qm8hT z^E?|U7#iI1Mz;>ep2P-3!;Jrh!QVU z;YAa0e{6SUPzpBNH{#>UbJsrl2E@gq37r=VUALBcK3+u;5h*9HbQ~HL#UVZ;fM`bQ z$#mJ9b8nzMQ?K+BuvH!lbY+ z>nlU%h7M!vc1QkxW+oO5srNX;O|)byE`FWR6Jl(a+YJTToIj5zk(VG{W#=-gkUX4$ z&0QFF1KE>nS~kAEO5^{w*l2yC$H^whE=0yrU0xO!O}5y#8T_-P)ry=czPa>6^{P!u zm7@Otfby9UO#}fH>|BHx2vCKQaJvfx8Rs1?NvV*aX^nH$5UdbON_buu#Bl$`V>n4^ zWCiTN0Tu@>TZ~6<{;K+R48_IqMvAH`%bp?Z#H%@7hK^K?O-MhHHSLBqw!9tM>Xl%8 zh;IGd=A~DBCzWGo+bY*PnXdlumLxGTqMz#+wfl*s(R}?A?t$<-cWsj5n?OcKNS%A1 zeb0h_-XO)=a&nn=J8A6>jqN@%JD-I18W8WB&~U##2n0UCPAkGAYtBI#X#V)lzRF#& zmDxg497n>+OGPc>1phtu>*1O)GDK)I{w9aW{(?~zuT@A_taiMPbL*|8C^QqH>=rJZ zl`+)5cMyT>!d>tHH+3kj6g`R3e;gGY9A%CyAGc%SQ9*cEQ(>;}CwzzqU@O!TH^;SP zs5*?yhB7qy;iSE3Ee^Gkw+lmw256-N42NlEait1Xa>RB>Zv&QC%$MPrmfI?EV(vgy z-bmf&(V}TVWgYG>HI4)(0clg8}8 z?4TCfz{0pPuyk|^P-tyC!WQh_apsX(NZP551tjp5qDZSCXk!tDO;}E`b+8+-(lilq z$Jxsnfc}!GC3;EXiqgYXTVc_jGIO4fmnKKN_XFt)&A2SKEtyM z<4^?(3mTlV2}eBB@ztGo$b!Lv_F!FQuuqwQi3Ul8F+SabU!cETnx>Om$|(60IMD^e z(!)dX?G^|So7~@!L}DjZQ@eM}AWOXbN37>9sg`l1I0+4;UHPD|?%+cuK4Iu>;wSFX z-c}1)j%|uMyXqgI@08V?Ux(V|f}VzqjvR8_*h{68TNdkG97VbJD&^RijGH@gwoBUd zsm_HZSp0JduSo=!(d*)*L?k%b`NPNA!_Kyvs7gvo(T}O@=!Lrr1vn^IG_^D~&dkHUqrLZ*ln3LC2LIiJIVm_ir>ohx;7yEyGt=0xL^8$G%G=C{;kD9pix%BRDunB#4W#>-8dkmyvl zl$!mWPQP4n0ea*4n-jSDS#`C+xHpyPL(a%Dq$Mu4-bA~O$gS_%JuD*DvGqw5!GikE z3Ydmh>V1#TK%fzYKc?DEpLC^PaNkM2Ho(!r1Cy(iiofCbYB%|zqQHyIov(jTzsh;s8gF8z<88HhJCv%YTRpE_V`usO%X&#A^{`rhN<`Fhki} z;z(ge8!f(dd7I>)EKh$17o&K%8tq>HIin{(sXiSu&IF= z3-;~W$wma=Oy1lKS;X$-#n+DIf4l;CFZuH2rK0G;mAx<02o9=modq7@g=ptzq#%WR z^8Yo@5O+s`_4-_IP)i~JL_BMg=@`6MB3PqI5CDk86daJ-ATIYm{^0I|K&1xxk8a=x ztNo)J|BF`y1BlB1b~pfD_dhJ;|8Q8>O1C4qVz|48ayG>;zR6|xGRkm>s_$N*!`HvW z1--Of(Py~jpVuGg9a6i3q9K>2OrC(~8{EnOFqGXI zUiE7t(yt9w=xn_b)up^0zK+xlxc&dg5pKFF8T-ZO3(&xt06*FD&Y>ds0a{K?yGp8^ zfJ^0C_TFd4T|ftm1%euT=M#7eUW{;!ZyeBsXuj4XmTi}(VUHI&U+Qbl_Pju%Wz$GQ zxZq`*i+6{p&_aUGUrGzX%~x1&9v3FR;;zd!(xeBB-dS5+WlGb?r#A&w8tuUvx5&AJ zuyo~hrf51hKK|yaiPj+yiR_DsKxkC=C(NNF=*rmUHKC7zG+A*7Nl}?$dWp&&G!Qy^62e$r{_S@8D6GdfHUo{;@a&pFP75qx z&{QCT=s#XXqUZaFFuslPaJCo(nYmxaNO2TocLf5^C5fzPq!mY#3 z-A*I3F0)^#rFSe_Dfl;uw(*oPld8z;uZGQiD(_06BVKWw`@bse*)}1+iF9 z%FEP+UJG$&4V*x^5>99NT2pz=HW*J)0i-;cN}@D(+|VEnE3ytBFOb#4=efvq9I-)B zs(TL<%d1gKP>A zq%Y2UExrYu&lwX**v1)*MfrH?k&6C<@WRX{gtIl3NFV_W$}EY`EBV2GQccOb;OV!Zx#$P}j&L>Ka^=FIo#L zef}Ig--SR#Dq!#N;CNTGT&S&QNM~c+?->c`-g#ll-*@;>)5S-LucfAo#%C_Xf76SNz4scf373n#O4M= zz}G^v!<7Lirx2$E1!rYtRYEl7!r(@@P(_P91#3cU1yJR>6B^GC)J1D;@T+SQ>t8X1 z3SPNN6{?8F^ANd_qWRJQn5fbfPW*!loQn~c8-FhWPCV3Spu@lSEFII#nhK3NOzJMcyF@3yRr zPfOAv^VuFYJQauFLiKAaY6XXz+bc;@42-z18vKiSalblLA5g{r{o!Kg3N){g=+~A=<%aXC;Ft zW$mr19(j!a^&97O%LExZtd(GgM{IZ5q>|S@tP_CPja=Fv?WADYh!hX-;BAay_WUD= zWS4J)hsQVwagb1g6hYa@?nV7=bP3{BX@Ws zlnMED!pRcRZ--}mewf=mAPsop;8P+kCWAMaW{nQ?i;bVuWx@EkVvI@S6D%d<(^`g) zDq8(dslO77SR(nrQ*n(`KT|3W<>+>oXRH{Vc1(a8y(?nP5^K}yQGb4LZcqnfdU;eE zPA#=yBKWKI3Rkx0%1vBpG3m5E9+V_NnkJ)>u$5gBKKTeR8q#4hGW~zE8?IIV%Wj~E z4Ca>???k9RCeH33{SC&6JNvtks#OBbi7~#yglqSGu47eWb@!UZ-CTWp)smatHLC|ok^CVQlDmAM!%mKSi@MIfQZVd`rj7?^v`zWH zQ}f&YzpD9LCuLbY$k9F%K+dK6;UPs>IbCnNRb2glsQTAY03glONvB};);~uGfpLWy z3h!plNk@tPHkrun{;?4Ry(N2m9S19YV=Fm+O=;EsUS)bqUK~<)w9v(25%ZO3!?oJX z6BE*^2Iv5&j`gl|_Hq;1p_=+Ck=%&fh0X^pb~w%h#EFq9;zD!0 z<4^3~VGf--KGtkVD?8-by$sP)L_XA=>e2X+jnz6s?nfjx29GZQaxcu$97&`y!D#ZO z1An3}w&{ly%w_UlwRZ!*R~1$C`EUe&y4)T4Qv{iPFteS;UEI7U*G#h-X7XJ0^K#SQ zuLdz|tuYF`sYl;Z%8Hgcy?5T6u3NJseMo4N~M|#NOK5G znSJJvuT<{4ETHzyPH9SMLikrnZ)zkcZ@RN%k?3np~-dz_sNUJf_Ky#m)sYjD}0pyL3PE zKTrFf9v)qPz4`h5N8S3g#;mqRF3<>1F0_Tud+77UkNC55K+Lr-IV37O#-G}_UX&Wa zfByKt_W)GKcZ?S^V(nR<^x$=02})F__LIns0>6wDb@XOQr!cn|HS#6aZ-NTy0-4^i_B(*$QSAT;UnP0jb14OVEyn2vG zX1A@X(cHEss`g84b0#ke(|l}VwJkwe>r^Lt+e1>g^~V<(rgiiE*zjypsNj!y$GQ4q zDHI#}la|_7IctnxJp*h2TD7`%N3<%S(0CWC@<%Ad$}IF&V^+Gc<%}f)MS>M2pof zwRgDTZNEMGHYyVz{Iby?wiiW<)Z5M#1h--Fr`q{qgM5eU%D~@@4raH-z3=kFHr!t( ze2Hf?T46Lpb{8?h{8RRWdZ=ad@$4Oj89^V5|83joW3{lJJ*Oog<{V64P z^9Qkn;5aHX#Z6P>9o;waB5e}`jTV*>mW%2pZgv60@phN|PMY9kXR$C%ra-8YU*%4d z4<|OV{JwYxc7#U9W9zRsRA`?c5~cNQftEf0Y;mKz zE)g|BW0zSu3GEx;qRNEtK&d(XF;s#fDj1;^cS*>%=fl--nC3O@jemeo?!w|Yvr-0b zC@1-Wfdds`1N8k3@M_^GY<8#zS4FJMq5H*o_@ zWvx3(5RzI;nxCUCBv{3XJ}qUa(vi*jd{Kx7MYNM#oqYyz%d9o22o1`;?=AQn^jl&2 zom?SId_i@jSP3UO8fZaO-3yzP^o711vx{E!C?*A#lIpiMs(rJR4qjZA2Ju9`FS6Q( zVd;?+`aDb=h-GQ09frzl<}RV&}pNhNVM+1U#% zW0R+HiipC5r@cHsUKqg^kP(&26BF?wtE|RMA`7~r$zt<#+>Y2$^g1PmPWdn70zp|@ zg6_Z-F?DFit%>nw_-*V9Cg84|N=Z}M(EkY)WXcb>d^lW3iX^vr&%v#YB z{Hf=mLnF|&s%C^E*rX08E9O_M2l93F2g!H@-fgG6YW66vL;df$@Om5@;!3zZHH3U$ zT4Ok=+#`-73JDEA*-i>!D7lCa*dH))R!!ZY&50Pqn@eTtK~)&Ie-V-3a-3jjlu_|` z>U#bJ`wh0*eB)0{_NS)$Q!(wZ%UlV{e>| zy48j^ryKj@pi(#`T86)Vu(6xY^tNJ7H^xhrwz%LFxz^6VZGa;Y4o^5WF*F~Rz+nWU zv8Az>N73&SSmsp4m`C3l7@Yv4A{Pckz7b8L!{Koaq$n4Q4wQp6t#QNewzMMQVWV(| zJ&5)*p@Ru>OHaUfu;@_E8HFQ`eavGs?nCSy*y*{#)Q^4Ig@FZ*^lVk);ml&xK}?+6 z3Fwi_C5J&p%HwTEtlH28kS@(a_<88b*hoP>mMX#fhUHi$nwH^jYzaAcGAh0-WXfLF z_dW~w)Tuae-cZ*K>BQ@yJaSQSOB5(lam8)s#ehmdMh4I^e{3Z2yQK~CH)naZ!4IB@ z2PGim;zGia57E1&zn860H-RV;L^!)76Qk{?>KHHZ^TS)T4}*fW(-Z$yQjm z8Ek$`9R*jrwO_L~F33+)#tjNGqmZXi_uIsk$-|oyYtmQ1TqsAXqcM9`Mqif56o+W+ zH!v4je2qZ^gYly!+%qN0l6;)PJgS5wc6gSU>{#htm4=o4X%WCQO8$)``#8a?=bX&l zKYkCYl5lST^nHL{-=rp*(6H509;x2)nRS@QGDw#jVyFo7JMy6RnHsu&Z;UOqp~`5@ zpHRx5;9ZD0ZOeDvUN1Hk~P{#%KBnk;Qbw6Q3*yIkiGkDPk*dBe((&Ihm9J8S-``cc4~B7y5(J4 zK9@BqbnoGQD~5e8GyFEnji_q#^JG|Etx|Xx#3Z2 zDE!Mi0a9?tePAODI$X}3a#6uA_)9PBDKs!hPDgqDpztF-+@ioOr}^+(&R7FAH-5M2 zKm?==ig4VcYG*U$#)_h|DY6_xVSyOnEcFJh}ANvBUpl3#|WoB8Mz%*p(#U8#x@>G0$YR5!Qv+RtE+KcKpd+^V03w z-|^X=W4Nr?{h83002WB3Ybe6b+P8iyQ>p)*>&|0FQcgy#!;zXy#iy_eU_rY!MK&AF zavD8tG-oTa?kzeC5!y7?cUD)FlGO;4<4E~bU5;pF{|FTCA&&B+xHpLeBEa5&(!b($ z;9cpZSc_*tQ~Bp|aP+@(1DMdA4ax~}q1dwR6Eh}cQEwC#fCu$u>X=ZLDwmhULhhj) zPE1uEW*1~y{ehs^*jItchyF*K?x3z3sPzas0|O(Rs=IY4R?3wV)u{ylXB$+0k;QzB-;D^T=5VT?;zUUNaM~`RXN|npzl}4(yU;R>L6c3cUh(6za1q;ea z>Xb_0J+7F&Rz3#TiJryL)=1zXzK8(DVjp@mErIiOMq-? zGz>`WX)vA1nM!9e%lYPAhDB#>#&zqy7*4}MFs3q6SYx-{-(^fO<3R-V(KUMn^5= zkk6FiN3y!Ef!qhYrtH%d=NRaJ6@5@O>0(Tn=ub?pGemPf!GTYUqP~!NGh*Acmyzh> z+p-LmGM3^kp0=g?cJ|JnEt6|+WMfd`u1lx9ra!MNQwJ2f)&4FN@y zWFQU$K0aE`Nj;0+2$Po^^Zxzgrn>fX{tHVrjWts=H6-Nlt&wM{%)1RUSn_UHki2+% zb6BgHkpd7}Y*-PktzTAG?MMT{x6h|+G}bDFnXG$Xo3RIU6pNwuL8uNdv{pjkR77?g=hB>^y%X! z&m|EGwdJh$o*f}Dn7QZhNpJ6)&klrAD|W-1^S}lTSW)Zkk$CMEGM?5@5mjmrbgU>| zvS~&`7s~+t_#IBg$parSQWoAmDp!sHzKh_S=M(aEGt^wRS^>q>f{Vr5#fY83)Ge-g zvp3zOxMKS55GqO)hV^I+(KTqMv->f!hm1#XldzZhMFqk7@~PSyuYLD(E^jVZW^mJf*$!>RfJZ=lr6N;#F~PGp`5(bu&a;}1^o>9C+aRE)M`tYvfgetG+I9q=OiLF zxtb!EMyN|yYPDT+_wHwJPnJbK963@3U$8EIxn5YFvCMk2uPl&yeQs z4{Ym8!s9(A;mA8;#2Nu-k&D`OKxiu5+!CQ+SGC| z*u7wW1M0AAYXcVh7Vd^KSx2rJ*7qfau{EpfjSU=-Cy%fYQO__a`WJr$lmf})2I%}b zO8;ip-^P$w!9sGn?IoO?@iJ1MY==z$Sen|?XT0#ps8+5`w8z(uVu!11L#j%6Ui|rq97r#%tEa6caL%qQ0!4AXf zxFYNJ5>pBX)G~lH88K{1?*f|ZiF%7lp&bQ**Tb64tE6@ff2k!lOs{pc>6dp2 z|Z6L1;SQff!E&-f8QVu8+Z@5w)6)dit#x z(w-jd&wfGYdmW7@pG+V5%<<5P$ytwrnFd?y4@XrRZSes2WDaF;%*5ZE8hyOHGWdFn z8l6tE;mvV8F9@2>00UfRtWZ*NrXk=bm!CsV1AM)k)B4TGZtm|RwXS8wX%rpNE-Mrq_R ze$!%H8*}`V_h)1GiVbQ`cdR05tYM#}KrX$s+Wwy0i0o_AUPFQkz2jFHj^iP!bMp>WQUJ{L#5;?KT z4s$;KDp~OzgA>3+78!V>Xkfsb3u?>k9%R1#h4w6Wl)05K8VYWm){spXDsAMWhh==F zGyVMp3msd8kM)b*%n~8=F}HV|AQs*&S!m)z-9rQX+|irenh@_}Ig9`+|1Qlq0{i<4 z^Tw|(8fZv)P-lB4I^v?$;s?F`_aJ2cn=8@nEP~;kMV+bc>Hy?PH}$42VnOQ#wiauw zNJ-*XQ=ec6P2tH*?#zk{3tx6`O4l55gn}XfA?gX=-QK>6RS^7N+6n_s1OM6HvTK;k zS5*nWr+DR>xODuo#Oji9(s4el!y3nnaPCu9O#NycE+hONHJBJb{AJkPLc^nNwqgkYV>4`UU*iG6GE9?U_`<2=5jhEj;6xfKB+7>vT5c& zfEwGG(yz53(chBD>9@jZN<;Tbc=%od$&M~{*HdNUNa%;VDlr&j))~H@jH;A6yK%-n zK?eQ@q5Yp7An5)L>AIz2-!S_9XlA5G+ZoCQuHkXQ2hTwgFl%F#bDxM{jkT6&lRx>d zga>}xFA?A@{Neq7a@9a)TdaTGQ!tT z|E!F_Z*>OOH+xDdH0R;lc}mj98~*p}f>#21q?)pd^qnH=?{vyM?N!9o3B26<(y3~z1C;~7W$gqh$ahP`j0dq7-uDGZfsQ6P02_@I8zD2 z&HrxcI|@e054sohm3<_sG8-RLyy}Ht1(RdP^h?V{Z$?2EO_25H68OKV-tF+m3 zQs^3LOklng!P~Kgug)tHmXKkC@IXGr&SjSPRc+A&W_`flO)RSPCDV^%4Q8p0;aXeh zHqAnud)AoUpc2RV-k2jF^v3I7p=_P-nI6mq0S0_V&%%ch75~40YR8-_6s9(8PtYa* z@+7A98PM^ATVF;3CD*)i#$-*D7)VYsrDjRc=$gtS$U=*-aZ(&Wp|+*YBDd08fiY){ih`(RwKd_L0ERtz zn_}i{OBF`>4@s!EApF$S<=4Aq>dv?YLE7gvF^s49#}ahz;G|zJ=@ndEFu3orx}|Pp zYE<_85tg{TN7rUH6rbVJ;Y4W<-utFrr`)7+d=gL+>2ioF!_ktnR6Y!Je_NWOX?Q;} zX0aKRidih4AeG9Gg>Vt1&XVhYmLlWiO5A{wyc8|}T94uIpFU!uw-fh@8;iDP3qxOd zn$+b@tnR@xbuHChj0WzbDpae{wO*?)ntg@~TWO7JX;nt`7bXG18UrGW+!t1`Cib$W zN(HjdHxKAvEFnuw16VV>(TDSNSdh`K`GT*69FRq)igTpA-Lw~}qSuzQg_1<)>Dh*B z^S{x#F%_6@ihqSlD}Ie^`;4qOe>-6NZEap+X$dkD|7i@iv}|DpX^QBIT319yuvA{O zHnh|1ctTx-AQY7lm#_E`hd`j!U^L$J@&&ZPhieSJaO1^2C_G1dU2{BpZSOc-b2vB* z4hLSdcBC;fzcdfw7)H@W*VoB$*JnNytPU8}rlGwcRCBW%3&63`)puQOLG2njU_a z6N*g#yp@xLDvA3P`Xh-_$4DX5mROg?>v8ppQqag$ncI?CA;Fngjk|xU;&gYIBE=N! zj>XNxQ`gdxy6dy)apdmV;$IH)RL*Fg46z?BYll-l`E{_4f{dJqcyqrmx5rdmxv+u` z{^s;@BZOUoD2tN&%wA+XjmJK@HAAI1{jg{Cjm<5vcdlpjxJ!hvbW4uzW zbGhCW_4tX?TEaHWeb514v}CGUi!3suBo@6ui}(?jGq0CaVmPFz&4D|~BSP>cjGrp0 zTs)6vLQ%ylG#avqb{gI$GPnhPQz%9^1A(w#HD}K34zTf`08_L&GKe5ZWFw}nfp+Ap zJKv`1m-FU`3x0qNd(_sfp`r~0P4c?JfwJTgx^+cdRz15H7^C96R}%@sp{EYLS{VVC zWaBf;`45b!z)Ti*ygIyTA#5t9j!@=iM0EVCP=vw%GmR{9Joo8hT5DmIM{P8?MT|KO3(mS5V;<|vM~LIqx!JR zr-QVt$VX-frII*%l(oXLdQeap970Dzx|v~aF}R#K9acM`6G-=-(_Rz+b&nWd@%e)6 z=IV?33=cx}nQ~!>pT?dpK#An13i@ zfK1`pEkEDm2T;U}wf66AjkmwT6`OE-vtzmT6&blSTKTUJ7nHR!7Jz`aB>@2tKowf? zO<3~6>J)Kbedy`ukW@-AKH}9RtR>@dkI_3{hAhL*-2{%SIzv*+50CoAm%#-;Auol@U3f&^dQ+WaRKY40mM0qL#U}`Mx5*kGPoB z?VuzA8R0($(s{vf(OXUYyd%~gO$bPr}CHrz7H50+j}i?LFR_$B@h66LS<2^WlVtyNrg6D2Kf--Q(%4(~YkJ z3lM4Qe_p9JP?qaDp!-|}!t!A%oab#Y1% zq8Zep_jRdoH6DagQhyeydhPHrs{sc0 znuMc7mp5^phv6%`!q+_acq_V67r~5mhc=#ig}(iaTd+CpAZEvJkje{Fc3HOfqy-lW$SOXG7xOn-=r1Jc{H<&o#O^&nL{#U5-6A|f2tN;kB z9avdmyXP)jxnP<}j?C}e={a~*T6WO&(-u?%1kQRLboB&;=GMnjy)_`V1Ex_DyYHC3 zSSCY2>HzX_Z#v=j!7#^&>m+)1dvwG}0HcA#qn?lY0q+cs-$nV)@XDHhLoNHL{+;?y z=#yaJf1M>PDXse`rx`G z7YL!f5XMLv=UbiFrFy_O4SB#;+Y}lbwC2Da93TJCvx_8v{bmK(!%P(ua?Zo~F-#lH zhnV%sf%^$h&iB#wdru{%5F(;wSl%_j9nJY{9@HO@h1;X}Iaj}IjvDh7 zC^d1+Xn2faTZ~$0yfo~L*A-lY`jEFXK2g}2ESEUk=5nBcjC3yvmrDQ92oj`qQ@Bx2 zwZ>iZJSBg9bCgen5|1NlZk@(=<@}*2-{Ga2hA6R{v-MtAfj5A zVG%u(l;9=5KhH`rARz)mh>gw6p2sK39hdTIPS}EFu6uW5*cgGSvMy5P5WQV~QjvP@ zAMa!~A=Df!RtOd;%ICb9Bk&~jaYc9=GJwD!e>%y2m1S*u_y_8M%^J)3v2J^7DI^Gb zTT|Cj{HPne)E>&YxlmkQ##RxBl1y1{Nk|a1w44@88y`h?v4pbFc+yd{wtlO5UAiT{ zARu9gU0r=wY#rnhYtI<+nrT$Tu{?Ecuzrsj(Tsqq^Q$plXre2AF zlRUXYUE{`DLoac7U+BnK%ANCCk_2lx8%gvL<8XcWp>_OtbO9_!a?EfbPT~1j zA@OzD?zyC@e8ZE@*YfH_yi1o7_nlL7hmkkFla>ztT^QBH*#(|=Ks_Tsf11;aSVXS(^Il2?}TyJn3r`*EqetZH#U&9yDb&x4vFvHzki4%Sx z_3$e**>Zd|MC+Chbu{5q>%~aj=Q0{kwRlph+3;h%3!9@c47LGGeqmS`Dh2TWAoQ|? z+E_DmJOcins8&;Ui}9l)F)-4C0qJdZw6fgE5orm9eferJT7Agrqfg~7g{d@W_C%ao z9js-2G~YC1aI=avyL%>)H*@~wvs91TLe_rk(gX(c+Ck3qwm5R|Y(S|o|>O4jIs|hk> zADH8=h6V-a{!f2!eJlxJic6%?t2ZFT$vR}F?e%#_d!qPT(?m0lVuW#6NDkXzq*4|A zT6u{gT~UY#fTiCm1f?bMctQF#(M+}s!KBwJNB(i*F2MM3TLRRh$BOinGtE|}}~_NH_nv^(JWtIS3$ zuq&;KYyGK4V%76qh8)r@qDp_9$+4Cz%+>#37i$@n%0JS#)8T?u6cxBN@$MmCmuSyUKm23} zz)yaT;MqNvN6FU*W30G^6o5Oo^hbz$v|c_|u*s{Di+A^j)G}7_e=l)4%+$YhWuno` z#gXMVu1_+E9JL)Z!I?%2Rrs(^m#RI`J*4+9%NVKzdB9lqL`9_M4n-2GwmE#6KzGz1 z3rzN;sh_raUZT&*P$?`wq5h&EOYhW@Yq~`tw{c6oBOOV1qkSw(4hl2sg!i(9c3N($ zYhGSaui*reWKKxHcot-%jKw#pDL=z zCSVJCu6NzGUe@zoKA9+G--;D}hZ36fm}vUrH-fpENrvR|iCK2c-PzHRI2iMnD}6*M zqGx>Rbn|e=><3`$gVenZaPK7H@_aD=AsU1EIDaAee@9n-fT?e&7sN#p(hjGkx%(Bj z!5ZleV*nbTf12EhI4OXm?3U4-n}O4j*VG%2d!)$T6-^%sFmq)oNI%vM4hrvcwR3Fu zVGvjvN{l6%Zg&3>bGxtu#t3&B;8M@g8YucMavX1^qlMikcQzy<`>ki%fzs>$5DU!n z2F}Go64?=fXvw5+M^9-5!Z2Z{9ml zCZ|Jte%xhte=43q_jX(9AE%jTko2535lq!&PpK`Ax8bmC#2n7LZEEANL(H@*%oT>c zTPaqn!CXD8&yz2rg)z@b9pH*X#JZlzsZcrN$fGT~%QVm}#Plhq?mgJ>=6GsL6!bN- z^oNx>UoVb>EXg*T*;YP(xCr^JgFETCrrc z!8ByPeCIU%>9ha;koJ~Qb%a~CC<(!X1b0Gkcemid-Q696J0!Rh+}+(FxVt+WcXxMg zC4Ktz>D%YNH|~4C7=s$MckQbB)|zv!`K_gwaDx&?UsKu9)%6}OlpB?DoI(#!+u)tSN75Y;C>mw$35rzlIVBx2l z2I()d3&z0L{m8p?Q&f`VI6=`Ui*I!Kme2kzMQqR@&H%k(x*Vdw@@hGK4rU9|cPw6c z;%@da(^ov_2W-%Hu5FU^GQ`LGoB~O5dVjZKo$v|Eh%ZZxouv#+`0stox!#(6=aY}9fA|#D2k_ig!KBw5t^=li=Ype|HZ=U6l)?L#ESkcX!QgV$=O_VlQ@K#n<7k76F zJa28aq-Z-uTjh~5_D)X5SG%JX*Sv2hkl1v63$D1$oEbS=h*ZC6TZ06G*m_1s;dOM@ zMy_(TE5^B1C_}!`XkS>n#QX&C>lrezgjeBUU|h2vDC;r%7Tc|DWuiPu{~+DXI1WzE zw(}Nyy5U!3foVzqxlVB)`1PX8?g{)?ym{|S&==C{X`HtXDynt>Umejh53-X=p= z*?>>tRRj{)cq*;dC~!uP2JyeZX#hI@KYSAbeB;jmmpxNv?3R`mpi7g%?J;Ov=c`tj zbST@oLSvwg2?)po_^^|I5$R5pyl)7os8tQMM(mpCd4ryG@eXFbZ?(Xi$C@5+zE*EgraYMm_R_Euf zzV8de?DTZ{eb*qvbB;jhl5b>EPNhf$#WVIJXU{|><&>P{ww)9|V`HSC#_>0l>iUp-ciRdqPUuL{wh{`8pKON3eoZsmipR@(B z?vnN=j2he560La|MH^^P0grmjuRI|E>mD*OQspb#!txV0zVxA6_cnY$l52A zCN3Y%+g~qUyuX@{{9e+a0}}T#Y}bZcQrfT za6^8gg^S2!W2Iou<>QAxQSVxhUP!*SeK-u`+*hHouyxPI(NVGJ_|+adl_TRx4d3zG zoKA$LX*^{0#@5biY<;D1f1w?#{xD3yP%Z9qGRE}L(NUcyD0^&y!$B-freB@qK`%W0 zk!R&z5uS9%odHzyanHn|K(4j^*{zViH6NjuB2v8VgTOO}hz`B(5sZL<0OP9<2lE(= z!Syoi^1$wv`ZXA&>-XcuNXTPj4cTfS0{WeT!@$5)OiZz4XZIVw=dNzaovyZVz<55R z#6&F@Gw8RcHm{DepM*7aX7rqNJ~mYVPcfnb^WXQBP(!y%P+b2b{OatGB*2~mO?c;} zFP0}reZ=sQPf0Qx1_aBY&SKnB;k_YI;$W+OcKVSKR~q-4=}&)tHKlJz-XTmF3ZlcA z>(^b^^-FIefrpAe(eGxK~fE zawfJ9dyy}2T2p@ikxFpA(n*rXj;!BHAT}=SA_S4nfvKA|ZiX4o&P;K?>jlsyDFIzF zPtl8MBvdhHJQl*mBjv2IL=LBTGLQH>pOnAcPdd}p&NvxKDSFqUshF?|(#gM~-wrIe{EZC?|Cq1>fP))sM^8|;-joHb` z$%fV8-E~9Igt_UCV(@ZcWaa-s4CFB&8GLS?2yFMp>*{MI3T{Rp$R`PXIJ)A0W~KZ^ z%B1rf{p<6F*vH3i-=BPRc^Y~|`m~Uh9={OZ**PN;uF6g`()EUF=&QMMYaE%-MBIT` z7J{?f73>Ua6wAxYZR%#078f_q&ggW4?)e?=vS&4Fms3 zLjEo>B9Zvvt*tyj=maVQV)w9r|EoZw1w^5Go3-?Z#gf2^WbQm1CeuaO`g^?1fle(; zb;fjjTBk&w#2g`K73d(NDbe5Ah3`tO?s$D16>!wx5i*h-o}zAjl@<_4^#u)~F13{!yJmB8ePM zPELTLg~RD`Qb)&Ez$+=Gs=6>7SkZ)f!lRz~RKw?4V7++`DiQL_Ak*#r2079w(pzpt zZUQ~jD)Hf%!(SP(P;$UTD`) zRI5K#rO3f95F`rxFf1r2DB#w4xqrX8Q~;k@#-*d98%yVr2t}t!$GjR%hgD!w_$Ee5 za+T-9oOU|i=?gXe_N+2hQyaDeOQ;o;cjTek*xwH_$fGR{k~QoH&OPwBuGQuQzFQlU#awZ>S7Chf^mJ^! z)AwMxkqJysPcICc<*?|g!0&h~XjACuagKYnoaLbfQmIU-`pO^a>?3gM95FGmAx;|* z)jvQ$d_qM9wtl?F4iBJIDh6IMMnN`0LSW{v(kY(d+{|Zjgyimf+Pd%5avvm)kQGgt zf0%Wb7$7~xqE`%|GBLpz0j=A|)&9Ia0Rg}dLZtGrS!OmHTOR!9N+wM)dE6X!T~6z*mcUFG zDmNqo%7LEgUfAKgapQc}*4ForkH+a_H*TK0jq-A+W)~sOIXg?0dV+seEtg}2n*#7= zaG|sTdTUVR&kq$YCS59k7<<7$AFK6w)&KnF{QMUlAh4qUU7h~{FJZI+Irbk4>wiGP z|5&^K_GpXQ;rMkDwawGaf*E@H`jBzT zNSF<&czyHj>NQn3*^^t^`s(~iSRqDb2MJNX?Cr+{M+TFyvIcN{!eFnwHwma<%T&9A zRBeSSBJHHI6VlcFTw^lcx3cmQb?#_u+X-|%1=X0KU}D~{4ejE2J7tWC=7~EMzEjc` zZ6j##8+AvtHyy{$zb%hYaw^lSLz{J%*&Vlf#f7;K-Pvm2EAfEDRC!D4^=$8I>7!?r zwizUYq#WV1=?i+mS+L)ycV`>x%!$AwwF3g?a5Tr(UgTUBY=kiw>B8)V?rw702iyyj zqpm1sx-wT2$`Rz2Fa5`B?Qc=%qu5PPcV};BHkrgownP!{{mW!=R3}ZZiIb~>^{fsj ze~;^*&f$)4pGk1D(&qkqHSZx(GIMxD7a1|4K<&*@$h3HiBaciOs(-4=%hM~-?WY}| zOz(?Cur}eU8xi{@WR$rC?2d|od>cj#&+vCI5ohdKi{Xku*lCMH+0@GxoJp!qs@0@( z&$6s1de3*VYO}e2gfgkcAr32CxdbNwb=e+kn(M}}xXzLkO-}^)+81m%bA+&;V6l#> zN+sq{#o6_e+~`yKa7gE{n@2#D(<*@hj&sv*BpGu6vv=TxavezE&B=f zsCGGoHBWY<1@%E6dFhB!Z8wN)qGvmeJOy|hqDCj$kl&r1$1P#r_Lgb(g~~1&aCPuS z)Ge7AE?y<=ar)YF!}dr16C3#?HDXCfN)or_q-^1(Cch>JlaNRx+dc*0=TN`H!N41S ziP12fHvxA>14DBS;n0n92v+2%6=)GAjV(Ixn+47K5w8|FSaK&M+~sc(BupA9cJVzd zqwgH@#J)fKO2Utj=z<~O{Py}H6ZX*NKr=P-9u5wU+HS8uUy}#&@ni0ClK-?T;>SLqb=zXm?nyG zO8Lf##i;s`$Ga|r(jTo~A>wz9RpZYF7S{SF_ECfp%8_iC8^ahHzR{hzQcIjWJ~4z@ zK;WQT?$z`9qi}%_EZKqKQK5BqG1FzR;19N#Sy4Ph5U1C=2uBoZHrmx2G$FpO0n5$L z&oAM3H7Mwi$l3NgF}XPQ;N(W?GEW?DjYne^IJD8ugxogvR44_GH=)fTyg+?~-ooYZ zes!$@q5r?rD1=K?=$nwbc6bFr+)JqueC0dygb$cLo4ujF@@FJ>oP-8~_CYDaoxxx|1nE7QeB7A#SMp70tY3EZ!G@t8kdP`ehZ3%q zD(oB`JxgZoH8eDyUtV@nuF_>uA>zbu1g2Bd(m*Y)S8!!2Ig{(_>*q7NWtxqQCgbTO zgoOMEK1iFbo4dOK6%{tSuJRT0Ch1gY!cpiIz+ecA(bxGkpfJ|cEbgPyatFlYbgsyp zoSb9wzwoQV*RL39)AP%p{Nso8{~FoztTs;ic8tjr{ zEzFwlOzx4mTLW!YrKyXNXCWzr(iod~*;BFEQT-0eCm+}MCw-3>uer2O+OyZ;^5srN znAn+X7+e*{T{F06u^LZol<#PL#p35jDP1ZL1~?z%#vAQ@fh<=7+(Q^RxbE(5a70AJ zuCA`{PEKB599mmiDjOQesHww%(9Bms9@FqB>-ARluGmxIp-4+X{RX@Hv9JP*VI{`q zsyMybqphjE+Webi*bWlR#V%%C=1T0tHO&K`a@etWsPP(;i!l-er*v<#Ak4>ij#YDj zE}wGwR>h|r%rhdHv9f(Y@8?9qsBFC1ftWrzQGwTgRuBzj<9WvU!TL-I%}D5->$Wv41{&xmbSVmx512dom5#h&H56eYA|iD5`GlmpkTD3T z`86hRA;sbMwXI}UAKB=gUd5vAzRL_?0yhhI|I8*b-vK}z4A3gF$YHU=A=h^VF=P|$ zdS?&W;a-~}Xpj7A;iyk1Q#Hk@Vf%hdF9@c@&>Yn5vbuHr-W9s7=MiqsyB#@rLfa+H zsIdh$w0>0Whi}EDBGk4y-OV>24G}symHxh&^A781Pq+lh0Qr*DaQRp|mRh&N24^&J z!TRF`xQCg$D>XkFO8C?Mu$AM2HS7MJ ze7{}$#LzI&m(OkgFw>2)&&ZV6#OO z0nKzf(M~vm$>D}~JP`D`mPh%CWru=WpWMHV(N15*XDNpx8?u>~%%2)hjWER?E#sGH zp(Ns@CT{(?x-X(#cb#z~00f=P5j8L}@&}Zl)zwu1rM7$rP@v)zKXs3LR4W$EazdPw z2e^cfb@WHf*6XQ0)M}bAAd5Q7XY`qW zEBB9CR2zo#4V%b5b`Ic%rI@MlMKkx zoB##mbUqDhZg$^IELScOE}7+>I(hD@+kkuGz|>00hquC~nFw&2u{;#->{%kFjBJQd z+8)fnsKZ4dT$P9C3dngasC+D^h@)1FRQz$JXz?|M5mIPv$SYNJ@YHBU82v>yP`wTq zKC{P2i=V-tvRGHBR6+~RmZ#JIQ_QUCqfO+Xu?;%@!q|-3+xmnvG(6mn<+a#(NCSQo zqF29#jm_JDzhaI^xSRgSoj-Ag;oyib>WeL>0Vlgcc_K-CFRtyAD{dMrp59GDQ5 z?oAHCYCrU063qJW9jZQ^-*=E6d5TFxr--;el8wlv>+Ak}plepfq|v5){pmv2`$(JL z4aT26cT>M$O{{SWev3sxahA-qE?235!SP&7*Gnrq&tME}KQsE!bjpe2iT+9Zh78i% zB+1}iA&`rdR(Ek0{~;7~{1FOdT3rtQNkx*5j)2mq(NOFl?r<8j88VQKj4n2Nldiab zuMdrlMNCY{0;;g~p?=98BXf5bx&J+J8m=y3kHy}?=h+n4s1Z$yepmgK@ z=w#D1pI64vTtRX?V;w*8oVKD8ZP*WYK}$a%@euF1KRe`4XG#4nylG7B4Q(X3+5gIR z+*>xCfAUPNr4}{xFk=1d(AAoB9))oC>S=AsPLQWIS`{1J`Q2mVh&tK`Uh9X7`ye1L ze7`+bJ3cun0(OHk?cLnn?cJU%jZbW~`xHGh?;=n32^TH9ff42JZF%+U zzy!$wmlBmTLcZpXz;q;1?GQi~GqwU*a>;zk6_k{7YT(V)s>xltSK|eoCtizG3Xo_l0Wa#ibnH@PWn~~a@YFb_ zYIh7x*mgJzjaiQu*3FC2m4DLASQpNU^PX5VLV#j3i`qx~vR4?&V)9i(734?`_cm%; zzWTfKdc*bm!bGy0(~_FQsGrB2KRx|WzMGZdGxE>8Y~7VMhnm%3la!C-bJe$rU zm3{pBNgmrszY-Ws9u7!6FvQ#qbJk105qGlm4ke)_c; z3{j;1SJ@dg=%E`{i3;m%9wh`FM{Ycj^9TmV9YK}`r4G}l3y^fWd$VE4MMF}v$!Nig zD{1RJrB{?akFJxHJ&7)!(x>o*tM+}uC*-;CTjrZF)2IE*0yrt}12QIi-I-ZxB@Wg~ zdCLN=gw2?vCZ$4iG2S~eU^6!ukB^rX&e!q{8(1*viJOG1!FRkxgVWAlX1%Ac=yF!d zIbXV|09Fy*>S}M_DN1ygz$EV{7m6Npn@=&A|6TC8-YxtuUj(j<`%qKK+?E8DQoJFR zKvg!RX0zSNpj|S0DW)5|>_gnLK%(_JxE};j}NJ51xy(v@79)?#4t4D%!il zoNM}KV88l6d}KAdGgkU_dlzZfQ2eZpg<6^t9j~%OKwF*$SY{=2g`Hb`C!P2Ov`xo^ zY0G$@L@?!Yp77h(;W!T8F!a-A&@09!PXe;7FIT+Ng1Ms1j9+L2?syCTT6FVQ{>#4Q z&tDGs`Dg6!+&&CGz(woCX&<%OzOW)vZizp$l#A?i7k?J|aJ+YzK&v>M7Ft|af>dRK zs2ANV(DH$YtzxZbWQ;c_JB7ucx`@jXzn!^ujP=)b15u3`iEq-8snh+##$JPO)Yu&J z1t>TpgP?gHKGUa@ri%zQ1g$~%<=$s^ZNjFU%}Sz}1fbqZW*E2j^i7OXIE&os10PQc zK{Iha!3|=+-2)T3g)3Rz?`OwVa_LDK@$C$b`bN@~5rGy|yp4BI&`&L&qQ%4;)kZzj_e<<># zkUoR`-1>|qU;iS*>`eZH^sHb8Z^5^i?QY#!465k}_q<(fmf%UA#DUG7=(>8`-vzYa zS{-1P61L9{3QTvzrH~tlmcc!ou*v2!qN6n#z1R-3WbPf2ydhYV8ZWbAQbX5@w4L_K zmdlG))j-dWRbcCL<3y?R;&|G!E5}hUH%GULYj5Y{=jX3*Epw}NZ`n^@jPufhVk)UX z+cjhGgE-r5(5?XinNw3YYR`0pr1M=#ET5d?Y)N_9RhtXhl1gr_~&R1DS>U*h*GS93JIC0RNrPm z-EL7DZ^r^;&yA)xP41UHUeAc{eEHWm218pYGY1=ZcjFmh=?&~p_99(8nopZVt@-*1M%_D#*v1GX6+}9qCtEEeFR?emDxEm!gAEo_dn8luRA3@JrV{6hNh-w zI_Ef$R5F^=|5MGszYc!Hd<9iSoa2CMjb?>S4`0YyVew4r0|_R9wev?xZ@av`^*T)} z0;J%lHGvypa=8y>n!jF{wb-fL*{kFc5|I9A`q0|Ms{Tluf?xQ^kO9U2->QZHxBL%J z=Rc3Gq660zPpdUFl_!zmia|x_caJmx&)lP-0;qt8^A#BnHURbnm>k$Xpae@xOD9b` z9WU_f>Si7@6Z-veGAIG!o~o)UP?+Qgh$o=XlZW_ZlLG_*prR=pE7Q|g4^)Z?nf-^K z0b)G$<|BjTvQDQg<6O`br|$F{=?p0@A2pmizsB4IOf(YTa6W(S!u$;lLWe%wjxD(} zD=B>NDpm9rJN{@qza3+$ZNPv^8DlRH&AX;nfx+(Z_%k2^_H6csskZ-vyPsUznS9dK;zQ86cZGO zKH6q-KJppXAvMG~5E=9Rp?+CXbtT)*n}N6GA_w2CaC~2H(F75{iS7&h+MlaWuZK55Ygl@kA)}tj^47D&(m4MhmPPb9Sgk^O zGg=)sXHttz?0R*^EK!fw^~PD)(y>j|1Qkb3xJ!T!^-Dh>nlqZu6c$K(uf~L?i%wFJ zo3ogsCB~Tp&5LMfs5LORdQwuCm@=wjoRH$*lagRFn3}SgbEsxVGzxWe*@i8pieF)& zn8~x#J#tu7VXg*<^A2Rcon z5Kt8TBhUJ^z+k||&8IMm>r4KrCe z)ZJtvSSi}tTy0&p-0NzHw@`DJKrDXmab;yDa2HO-y=SKaRKfzgCuY7FSh6E3XUt}w zA+pH6pp0;&!H)*q?oIz^edvfkMdC zd!<*t#u;x= zYP>bXuuurr8K&;tfDTHAMyq#xPKgQdIA zW>+~mxm~2*;3*ASKYBK?pvU&Cjl!u>>T8~W|2yM{vZ|pQI*j)PldB-GDOCK%O98ED zPIxPJ_8JVYgfnnC%jBx$01M5cRCgu~15}O=0xhxY|w zY^ez4Yx26?kn+Wx3bY=4)8&VD4tzj~4N-_PP;@^3Y&X#|q%OH-XK|w40RDJ1Cb-Ef zT+#m9`w15B1{+%-o?yDA9 z%JU~n%$0E0B2v`*QuG(nuuh_uPvFi*JZ3$Bxh42)f7b=7Aiv%CA8tBA1E5NgfZQ$j zrr_dWE}ln%!Jf>4S@K1u4w9L|;Kw)(kE(HvsgtmzbCfXOjNYeA+SyPezLg!aJ4aK3 z67VB|mj(AS@ba};!g>K>C@)08gy}uv2i73Ow4n|pmLg)(yiAo8gQJ%*Bex7QE(6H%S0Jqjt+k3&RT^Z`R6u+T%flQ^Gnx)u2=uq_(DBNC7 z+Sp0V`T$kw>4ib<^x8G^a*^5oCj&EQ)Wl^ep-GS5b?hCR{2sqDI=gjs7;O&C%JG~O z_f-kPi1A40d%V%p-Zybb`W;)wRbSb$g>zbl^(}*=;2Y$1!x$3sPEQXWN@2>8gR_)}x_Rb%MT?Ceb$f;8w~nJ~~N2qSs-_;_S@G$o^X?B-~m=}%O94Y+#; z6iR_=wG>bo-Tn$qxQg>XDsos`XdF3!Bn7ZKZhQQ25h5;e=!?#%bu^o_h6XlxY-Sg8 ziN~LSx3Z8Xz<>YAg%M}ZrW4~BIlJ}?npSXiP$$G<2n9%V{h#S}G;Xt0 zs4&_pt3I8%-{3`ajX+ZA`3o z58Z>mB}iqcp1$w87vnwKTBE6_@T&OL5le3WlOXTh9G%_QJk^q=QG&8~@k6HlcxpL7 z(b^W)IZ$C1(uOum3bn_cVUKX0l{^k%+157?+|ICU0v<^m*0k@U%p(1awHuP|=N9^$ zeVw8W)l(l|0w>Cx%q~|D$qe^ATJ|83iok2+r7ke1{F9B~3{qWU?A>>noTjWV9W;8N zP2i~8w8y%Z`6f^9s8GwM6ZrXNvOVM!^vBMO4st0hxidazQS*NOSAzW_{Qr$$@6|=e z{HcG|tD)hJ&Q(zn7Tg9P5m1u+48pNRCAai{e3-TUpR}3R^Uw#o?KW}nYjaN6*#uHU zn?!IKNAd!>x)uc($)z9)) zVp-3JxJx*|LJ*W$qki*@XC8ayNMb3lMk(QmJj>;St}YThDIlp(Gs2#eG#)P9!HoPtXKjJK8a#}0gtqS}wfH_DMQ?t~(>(SN`b&l4j&nc^Q zsa9EI@_$(OhR1($Zrxi)1>a@=O6E4PiBTvra2{uwGkr2J(rudgfLA;VU7K{tnH!7T z$#Y(+&@W43%|vm8ejaJu)lhg8ZlomF#GNoR0=WG5#1!% zFZ*z9+IKo)Jh&7Es*Ua(ab(5`@bqP%471EG;X9pG3vBIHcRZ0(+ zk$Xm*zyqsdW7nFW%seh~b&h4Cj)#oJ#oE;|tPdWag`P z!QtV1mzS#!&s%nnti>Y_+x8ln%J@jO^%Y>c{wCbIVXR&@yy?e zWEFg4^_NPp>g6z7BR@QosMw!-wZcQ2V>8g7=x#HewruG3V`NFIA(_- z7?4#2fsT%@x;+*t)#&!|8tYpl6Wqhq_8X}A>UUxBTjW-S-U2@>1cV&wG_$0z#H1$J zyrx}4TT)(Q+-^j!8lNB)9E(&A^C*vmru=tsO;uDhj1RrxNQxiy43%#6cJH8qs0z(; zZ(VuuuUtBoxtvq%&z{ol$I~>xOdF%p0u4%77qIqqb@zq}os)B%`#DUvI#CYJ6wy#Z z6ZTnMQGuxj$H6oOu2g5x%?OE;doj+Y=2m{Tqqkv~xMC<nnzvZ+YCv6Icu7={M-WT8t z?v5KdsF)loHRR_jsPuVr#rI*%Rd39tLBR@!g{8|AK;e0YNl8S&?atkpGP$toAo`59 zAK%ZrF-wH2C^oIH>qg-7JR(Y}Mb_(lK)MwkL^MS;)Z8#!f8Y1Kuj7Vj^NDPZ)^JS) z<(|idGk_TRH%aXFV}p4H$j>q~>mlqWtR&C(aNEgP@-@!hoZfxnxK{0hHxvHwVEV`+ zeSC4R3P+VAsm__KT<$}RKUK=r1KqoiG>W#yXXai{C(P6R<0h)x(6_=Oa-N%V&YNwss2PIf?f{`O|S*2-=2@@&uYiM+sC-7g|-hzUQVLZ5R-2*_$*{x9nMeBKC z8ru?@44L*xF>;(97cm5o3T`#~FeXI~E|Er^XL6U|*c`dq>;vfIk!rSI?sQgAVV#}t z#8mfp2@eH^^2#XEGL#s!qLZ#-+D?cyY05+1;_M ztn4i*src%5QM?tM-@P*c2=Eogag9abalJl3Od8sm?}?Oa&JHAe`Gaui zXl-oH0$&-GBqc}q+CMKkM3lb?w;}xz`CTrQ#4CYnHj|LG`XBG$Ked8?BAfqdSpQe= z(m2b*4&_C~Qmxsv)*B)w{rUxIrbklbn`(byf_O-catSHl3u6?2$-{=IH|_TG72^6- z(G4$^3Y)HQ!#E6uhugH$9M0fk?;Q313%uw~r`R7))WtFRX2*Q%12;L8!*x~hbTWSo zY0b6by#E3{`C92)vUB`EBXOJH9>{dsqGqh-(Xd}dE+j3@-~ z>HDZWJDZh5pqllljXJywJ9yT@ z6m@o+(!}V1zO%XA+ME11U48|f&KLG`?cSDtlYE2!=%MLNVwvDbyi`ks$+?W+3GqYC z)}64VLxX6AL!q2+o5w{7L8s^!=(YCnoeal<2(JSKv(?y6oeDko@9bHx?euv$c;XL~ z{(m+hh|QL1BmkS+)|@>t#LFMbwOf;$9FKTGlC>PfTBG^q@HnwebW9^lp-#oKlKUjy zLiGRX1(;83;JXrBI?`x)T$IDa8XKe>t1T@1uoA$|Wj4rW7E&WP_(qeAifnsMZQfD& zvh+LkIyYq)=lZ7YTMbN(sg1|Dv{DU0P1}+GoDHO}+qKE2Ioe4}3zoVL4Cn223hU2= zFD6&@8c2&SS z(W$AaPXRmI+vht8I>-bBZ>YP9Q&r*xUSv&+c*dYEF#YLjxwO?TpBr1|qs4Ud#(ro% z0~t6I2?q<7-h)0TkI1FX<(~H|i=$@d4ynF!5F~Z`!%J#y54fOS|6IQSJLP^{IFw$k zX2lzX6;n4oyeqa0fw(vk%ML{9$U?CMX}YYL!iAgOW=U12*w|%(8Gq3709((<2$;VS zS5uv&ard1CdvdIp`mr@SEh3RhNa!Dn#>E}pK~ypks~MDkdS@j{DL&5;{p zRW+TazB3WNixU|N`Fly=8&3`vO__yrKc%IZIMAcM$~`(Vj-FJqG-+MaoS5tWN|Mf3 z7QBq=&TV;we9@RAy4^O5mKL&GDPnn1pWE|r`2bqvGM`usu~;}bNWxqM>B-eQW9eC# zNIR)RE+DR7VU4o0?SVhudIn}~wfFI55v#Er6y;JJ7inENEmgNU-f-m;{oN@;5pWh0 zP+p!zk)NNRn5?Gvc9Gl<%GG^JH+d;hUwJ96iik^AI3x&(4z)2-g_~*P$?)3rNf=B| zC-(V=2!9`%G$gI=NaSnY-Fdo!e*s2cI?=^NhQHpNaKu?+A4UqwBv|42C;X`XX4--v z@wp$sIEWmy>oQNE+jQjoT#4B7$li2WBI{fVO}g>6PB7`fa7^6ZEGpHj;l|Le$EyUG zAe>Svs5yDfi)-}y;tC6$BTT7=FR$SC6x49Mx3p=UI_l1Ht=k#Bii%3T^~&S7>6^>TuED{gE?a$l{X`D?d=D6bpgr*n zUeEKpJ320DbLQk~gFNMuIP8jh=Th}LSObGC*#5!MxYrheAdE5idr0ZY97TTm9+pDT?s}1K&W<0zq%gP*8!e zff5RTJm_-4|C%cP=Li2i8swd@+)qUr7ZZa52*-(uiLqP}6%}-CZEe+6e`~{5wX2%_5jg7H1wuF_D`fueU{-V)zV-Bhc% zhUV9~Sxf;|YW)oYIYaZ;2P68Ux}Y?z+X;gf0=2~g7A4Q+y$=^-gFiiL3FDfT1>3=O zAl#x^irDOlW}Ur>ZbYhY3$UqAIZ_0L(WKf?R^6fOYS%<970ryuJ^?X-+lqsO1JHP7 z8?3doyX-J`IdS`GCNPVXVs7a{iGngBV@zi z3Q{vPGW$Wz2=1AvuG`(0)NR^+z;wInk}Q$+HESZ zlcr3mt8?_9w}*nq_KS&`7A(lIT#slTW$*$yQaMNzjaS(zdKa74OuToyJq^3T6-&sk zqaSG+xWMDvXnm%q#C`a_qlt@vo28s_%FIl)ZJx^)+WwjZ{!w=@!08zO97aP?y(1Ap z=YfIOh}#!EV`C$Zg9a1`&Qbc}qa5x4!pZ7fH2RQk;C`;I#bj3@giv4PH#x4K$@MEcI z({-E~bw?gc%|COa*ZYctt*B&wA_;A=OVe>y!TmK-J&lasQ_?xr0$VOKWM}=5!(+!i zp8I3v8FTyrfpb9;4ROG0A3sX3fp_~*Q@3hePkM&i*ly4)*KJY`$ zmAYT!?Qp~wW}d0zd}r>li2#<-T$7RW&d6T!~L!t&0~m`$pb z^rn}e_+07;T|xaVH@ir?y-gDZ;gc~0mc{LZKRCHCPj&?Y38@B8*^>xIZ%#3DV5LN9 z4W*aJjU!?vfIa5|+%>2nf%AQ_H(Zmmr}V?=6=dhU|5^E17OJ+X5-@-rZ%By#9t~r_RXw3CRw?OSslJNnX60b42`o5d;HX3cAqJi2OXAT z9>_yMCh?EUUR{jpQw;??L(T6i5b&Ow6lmDuQfrS4lb7@?9Gdqv7H2y?Go?ij#qm0^ zSPeNr`&Z%J#;fJ#SxgZ7BiZ$0vE4;DSiAaXW)4TLj)c9Rj!*kO$uSmHBb-}cqHk&v zC=5zB@heN?0GVN#*0Kdb^T~iGc-1;J^#$*veu?a#tlR-xWY0tLx_1iVt>rBoB<7J4 zgnz;RDF|a=$mZuB%r!b-hL8ey69;Tl0+;M!T=~`FMGFO*& z!1Q9lTZlhaOoKrlwjwc6Hy4IE4g`254%a1SsPF(xyR)b1Swgn9^_jp3;c+ra_DM>24V#m!#g)@0#4SOkRK zePAb~YcaMWzYb%yDf?ES%uc^8D`p9k82hIIXM%@HB4O~<|H5)gizTkuI+oHxzC@-q zFd%fnE36|d6$z->!IP21XR5s!uwG4A7{Y_C4MT|24Rzthl6gPdHo`FQ+FpM{vNS@& zQJ1#+)@%ILo>33pl@K$7R?w!I$ZMRbPYbu2Yg_Kd@B2eN1f4g(MH3lhjgP$-{p?9^ zgeQ@>n_UKVx8{S;$=#?pGNhx=zLT>djp!&{J`|zs$p!vj3B0~14KCw7P2}rruM@Oa zeX+zgzyLPowD-DrsX&ZJ##dX^N9Vo_tF{fM)9&nAJ3`W~j(2diN6mzXJrFOfG@w#(ut^Jt2 zXwq~jB2K+b*}P?Q&B)41>$J6LZfcgj^r>RVWmA|vNp6?WUlTd*AW&_ z{9J-gM|7^QomZOD<@Q;^$wNeF-~|7~*leCU-aO$_cD^A6h@HdRxa-;HB2l1FACIpU>V| zin)J=lDG^U`NCWiJtg58p(7Gz^pdA9i!IkW_%+{?1EpfS=A({#upL2BiRDOPhNzwW znBiPMh6MkoKXJ5xikJ8GXZv(&a&ia&tquAkJg?7Z-Tet;n!b;k&@*|WNOaQ#_i*UQ zd%oDMIz0tf@+m1wU!%u(6NQ$R>VFO`T_<_QU5F8;NzrdQMONFP@#_MUSUTL_7Xu+} z3X`Rk^f2uyE7SnbSq)4@2-Jb+oMK?P66fL^F7Fu;m-BeF(?(tUBfXUi1>=*d) zl}7jSB&{mdyFafVC~TfwM)~+7>GRjmI2e&Rp72@@<}KZHguK@^%FD$y(;Fo`miTwD zL!w%Q;pqPI7$j~phsT{V-lto#J%m2ar5i{5;q>xzM(5c!2U zRnJC?9Iyp;W$TsQgY@C`*>RMOm{QMe78i#?k?-immon zy+6d!nxXytt*T8Z*i27p%6LGbB6IF0pAE;U7r_L`mgV(n3+n)YPj7gI8jkr&=15eV zLyZU}OF@%IK3MRXv$76E!TT%P9&NjHGuUXWXTrZ6Z#Z2!129)dNHLg3q|m-^y^5jf z+?qVZUoDdd;OIed6dVUPM!mnxZHW7O%OQYuX1UhZdhAU`Rv-$y+Lc?P*--B58|=db zat??_?*CbHQQDevAX=;!C8Q$0B1A5Bu-z81iQ*o-B#uz ziozlEZ=uSU%0U=Dz`ff`|0lY5S((>zJesJg;F`5l7!+%k&Tqu47ikD>%hQ7Y$T&@L za9$dzC6!W*C!l8;*lL7sc7V++M(C$$+c(-ul%}CgNWRY)xpt=d(-i~J*l|qvpwR0Y z@A@6V_`NR^#E!Q>$?RvfzarRpx=&20I<82WjF;}Md-?w=?JJ||Shp>S;1Gfamq2ir z;1FClgrLDCxVuAe3GTjecXxMpcXxN~;@tOcpZEIS9A zYg3G5IXd(Re_C)K?4aB9L z^CtY&U864DPIh-MgZ}wMe=nqcgWeY&&b8MyR*DjOsYtw?RocfPu7~#PEwn%+%7uTY%KlikS+vQ{AqXye_$dbGaNQJw3!*|ABHH8=Yuo zE5G1X|KJi?-`I%fur->a5eP-8zj?0Ql+EeeoE#2Tt-JqSU-&PJmCh}XY~>!V+RK2K zAG(ItQ|^bt*b*R)F-mlY@}IJb1H-E(ZSrZrm@*_(-^T=>sMCGX@5jb#s$vQrfK30~ z>-CrB;!j2bK&$MUQVlH-AYigoFaOo|<2o-fH?e@x>#>~`lK&aJxNb>NW{K5(s8LhS z`Utc3P+j5H=1|XuEx*o4o_j9t&hudSj`P~j`nFa5S@rr0(6Wi!F>ejHG`5B24Zkd- z-aPE8`B|BVXa4vIBC7_xXY5LLkytIAbVU z#I1#p`yWw0fVext1BqdpQ+C*ZPkv3Kx!&N4bvb78HLGUrf`H4=T!tMfR#C}z?V?M^ zf~_jE~1gOS-(vm0WzLNXxEa0}mOHd}}ZxWOp7qP3W0mp?Svi4`WGihEW(UYm`+T5Gf zvPTF@AqaNC$7h;?<%qs1QH{(6FpgWrV&^V_st6)DLxByMVh9t5(B*qo8|$OC@rZ6ZjRL zCRP7rSZO5O#!wl)qwo*z${FhN08&PKIFjOU*IFyG(bb-mKm~uX@O{PY0hqlNBF4m^ z=lBh{R45BFXzw(dU_-W>$>1!$VLPX@TbuQMvSJr_TlEX261hm zlQn*x-DA$HnK)ZrgH#$@5;_NaH&eLGIFI$uI~4MNBYn6)`0!NK4{09taOdVE_Qy9- z-Pw5%xGz1->SQ6Bin#WRa4WAG#E2|s&ElEn& z;B^~bI>}oE#Ve`6fw_b~({&f8+ZHIlvAD*ozlLy>hOb#1z zpwmLYq)$CWM@1C?22pA!z?Snh81!V$486W7Tv79>?nnv^^~-SNT9b-wO+Vhy zAjj0+^g@ans?&J$0j3>h(-7Gcu1tF7S{NOs9=^YbhN7yo%izf!cN}A;<=k9Z_<*y` z&~3olOX2`SN40|+FLq*S3FdecCjl*6Pr<||`s(;Ma2Lap31bPJJ|`1d0%Xha=weG} zI=k9G=QoR2671``Bdp-=qA#I5%)|sh6L!(0Kmsi=(%tH-# zS6rKA6Xf{{ZOccTn<38pv#a^yVZp*sb(oOxU$h!SZ$PWzr`TT%%uLk~C2wvy%T>;( zo}}aITdOth^nMnT+yzr>e2=VY{@Im7%uzPC@z#J*3^YXd5T#(RB^2`ndUINFUtv>%`kds8w7kT;(x?~ij+6UFhPZvnE4!I@*~8b=u(h&>SLd^E zsZTigMAyZ~kI=~*lUi9i^pti5?B?2MHT89T4_-`(SBGtfxI#Vh-aeb18db>TnU%B% zJL^|e@z8Kg>vkN&Ut(YKCYU{>h~~X!BNC-Z0&{18+O!T01wTF9Q~+rbRz0>rJaJzi zERe_smy^d+11=3B*j<=NX}wZ3V|{Zlou;EBDJ!zz=Lml zZX98(r#KstgCzY8TDRS-iXJk!m@g8Izc(7m!urI&dJEmtt$y(7N)7UBGU+KOdF%3Q zR%p6Nl~R(FkpospMF#;5LYWz)8X1JA_mYZQT zEIC~0xzDtbQ;*4TKH@HM#;%?8gf6JTWvFnNk_Trh^z^`J)O_Snt>c7Eq%YH~Cvy-<5ciZqRWe=OU0==Qn(aOWJ=O8EYU`~}nKNwtbOQ1Q$C`mz zkZwjz99!+1u{UX%2I9kfI7lg??m78!N{xaweHj*FAGD=S7|_U2P?CZM$Tken33`_^ zp&_LicI@vh_pZ)duC$=B=YML+OvS`5AoW}{%_qUYY&i)zW{nCc=B2F)(;5|_TtF>h z&R^&vARypd*cE=E;tJEb;?*>IAyvY`(OR;B(V$5Ll_V&m)jRFxU-b6T3HP+d#1K4& ze$|7*+^6c761@+`@vNwV)%#HFaxSKS{?-mz&1PqA@TccB#+dD+h)u3eh)gtxP11Tt z#Mtm|?8LXUN!ISk$;<13PMD`2j&_6I0jh5*7QRy#j|^B`(H<{z3#HzZz;1*ZndpHW8?BAf_kel6GoIqYLz*1rOfoZH#OLEXkn)$h=@pBxsnQ7xmBsi zzWv#lW;9eK(&5D)Sw}L~O4AVC-ooTpl=^iB?lVBsLzi2SzF6SmZ9Z2WNr7c25jy(S zl@DSAJ>Z@+=ftU7j9?eo(H~6YOX9I6B1RSwU7>mW;lADb_2zEJ<+e?i)Y|?~Aki({ z%l)xCu+%U}jXq$bV`KD}_nLh+1^6MPTOo3=Pfdg2IVTb=m6v(U>OZ{z_KHVLPI=JQ zJ{-yx zr1#M&xUgs1-+=+8qR|T^V72x1^3omPC970Ea-Gqn>+V@$UABG-d;d2rsdTpuB*3z) zwMSrHsS;`emi37tzBr)9}YNPdYb$4}+ zvc#~1*PI+OV$cx30V8{rHL)W8q@k#xh{lPni`)|?559A6*y3ww6Wp2ie{Z^rNW2}y zGxPp+RwEa0CSbv(r0wnzaN(l*B@6W1z&{BvsszyLzs^28;rW3kv}aqXW|OGwhUZ%w zpr1*^()K~2@IU6T1EAlJhJ{6e!v}M=@^rx<_F7D~u ztNp10hxZv~gGkSTu{FUP$?Sf$c{HvXT0^a0RQ5^>pf{@Z(p~!xv}SGbiB{|cUzXqa zJj5*4GsD+a=!|7CCQ^B5Hl}+!iMu)5G}Lb@QQjV1Tv?)f3 z1{^X@=*`b|G#oqcTc{Dbv?c}Xl~+_MquH8wh7PYO6+pWpHP5nh`MAB0Kby+@;dXwZ z>nl$xc$x_$C0A}HGI!0TZN6ZD-~!kju07HU3ZLE>hX|oyIUb<5g}PFIkE#d?q%=Ky zbYuRirNNNtY|o==5u%twr)k3Ujslbawbyd*zP~!4GBIkN$(^s@h+5}NxAl>dG_bFy!*!CPJ8c_g0twTrjN0vpFPnx7cn)T&9*cfa^hpg##;7G zaUm&NxaW>#zwK%aT5W@-e}J}zIJOU`$x^;(=V^twP65H2Mt83{#btjvOo%KatXT1{ z2P3rhg1uQf8pu5J8Q86|Lm_@5v#O(ZFfFZM=(u{RMz+w$vDtP+kYr>-a|1KOZ1QmMMWJ!p8=Fn%Q_~+*$E~4~B;!V;#fm7ozqJpjYuoq&Xg{d`a({qNj~h;& zGbZSo%i|pnoK6dR9uDi|Wu|_G$2%grmpnUw$tfL2S`+TCf<>G1x3^ynDHl*rELZ;A zE(w|N;i~RAEKfH3);x=U4s)#NB76^nsL!R%HkKF?#U|d8)0Z51gVd>oelUCAN{1OY zrjG-UjQp*Wl~8AKVh_esO5>DL$tKO!zo`{escdT>MgDLyp?r2o;*f9ObeL0MYZv~bP5E~?-;XcIfB6Hsr|c{&2-(<_svoTZ z$tcE|`+8aHAH@GEZNkRV(y?$@-uQ73;yoL0I>6);WL2P{(o6@U_OrwPyaDw!>|^e zAF6mboSApVkwlCm4MW5N2r99%@@iag%z`?__o zW{84b7QlTv+>6Ruzq3qjZ7wsZVa_x@gND{2Wm@N0tmo8qVep?02^L8T08Hz-_*ugp zcRH$8__Xbspt7$y>4xFlpWqw(f0_gjJ@oSuD!;iYVT&xlW;hPrdN6g(>oQx<+?Tz4 zqvv$f=oGYfzKpWPYTQ+En#t{P=Dk}V6E9iZqFVSll#KPiUNohem!RN=*mFK&VhX9hkO1atBnkDgoF2_j26fM<$XWw}#V+nP9)hTI14i$5v1U?J>}fddNUD=*IVayN9{aCn1FXV#Ti^*&yN z81$<(V{?3I$QJ;=nT2v-Onq2z*)9Q4f8|`tRQK*8x8&bBAdYA6(3Ps<+tWw(%LjBA zjfc0zv`}8}rbwWAdAnODS%18AcXij}@OaTb5cR1sjN5YWSAo>UPCBosh24&A@`g9K zEXSwfOMO+sx{VHJbC0Q|nYM@7(Ka&+$8cNjc?pj3l;tCjIdLGLtmA@=qlgGCUcUXV z@C5upT+1C=ej&5=J2y>7K~TMo)84VNBjmu$c;T-=M`$OkA_-_K%@fT%(RF$0}7~jmS((W#rM1l$-|C~+g3!K zI+4bW>s{$GWyWiaPDRO`qAvlewD4bX4owCvo?1-bFV2NhTyQ~=V&THI^v+^{^3*30 z3NSUQpRQ1-)Q$NOlgj=qcLn&#y@i)5`L$e3>%v;c+Gc!`E2dCI!n;R_Rl}ifXe}l_ z*x6oB$+3vMjZOp3dpjDI;t-vrl9wyCb-wj>u!y=e{n2q(S-#`*1*MpyE&<6u-2|70 zV`a2Bb{eTOsV`$T3paw|K8irAbf!H(J4yd#lQe)eaBg%0m+6Vj*q`F>=pSvGK+VWh zvUV~>aDpoI-+EuBIpjzCrWF#G=5jcY)|W z5~gpiAl@dOX2#lW``EK_2qX2S&eQSVPY5V}b~iS@t%TH9;vON0Y?H;>O^x!Tcr|b% zn>L2^EG#h9S#4Y+mj3int~c$|-0&eYIT;Myp1FI@jB1h*z5Ic+-Q74i`{ns?smyx~ zzHKpM=->xGUMc zSK}PYrr!vR$_Gcs^7BS)=2&*DEP)sBW88Lnk;5JNcA*9#$H{%E^$6+qCG~1e0C)qO zp67tSZ(VqLxgK^T>hgF~+T{%4#F>58wJmt8RHy{$12B6pN0n#CRcHj?VDrWMQHiXYS&w>D6Uw?8X z7*x;j(#ufoK8-!WNsyUYs<%4s^*Gz}wu`qE-&bwNl7um$*I7ekdtxXzU3!0P*qF}P zm)+te(i~k5=afmynp1~RNXY+F#G^t*uACPXqV{Mi-%V4C`-_{4i%ZHb?s)MD8qXq6 zoX{9#bTv;`fIGe3F3NE3iAzn`BG+B9&#Si(EANQMKQZxj(+xhjd5qryURDL8gKl9rq*|?r;njzi%-ti zZWD=iIx(d~_Kd?$KNSAzN*MqNKQf+4fB7l}7$gw8DkNHaYGC-T(;IzOD>|W>7sp+> z(6e(!FCe|lPBaWpA=oyW=1()`roT}Ry-B-2^YcGKTen9g~XC*9P0Q)+F><#X<=#|TK+8ZPRG zE!#(CC)(#wmXtx3^<{V~8`ZBop~lWS0UK{ebJD8>=M&j;TbxvJZT+&7ZMU^P2FJf~ z(=9qmX`VWM$5?M-G)3}ndT7fh50lziFFX~IoeLNH^Bo8R!~kS!B3h`Pq4HVN6_y&&W5$LYvr zeZb4PE&Wx=bPq=^#nw5tE`?y^oE#~``n`vMY#an7VBoHR zO5LPMgN**TqRSdJJ`?HGFT~gsJM}WY(smyQN|u#00Y9EQ@AHg1+h$%0U2`;)rb(|l z20A9Y0A6Q%YOPu!h*zB`!D#B=)B)E0sDF*#oejphtVrigJwJ*YzecmX@hD8z9179( z_+^Z*74P$L07Ari`|*OLA2Kx46A+x)WL`XER{z831BfvLXr5`5$BZ z0E+Ve0n@;_>+!@bQ`G7(Z~{2k9IR>Twi1#EX{X(`#Yw;hMcQP3o80Gn6}FutvQ?XD z*O6%!m%ikhL)vqFgSSF(I=ISpXHG+jg2xD7XipgMmvvV~{hEu)6qns33WmwZsG@6o zGm@nGpz(0j5AHaGpzTni)!Qo3W0)N)@SH?ytRGLf-hJ2lZTm#pINzFLlzne-ZXOZi z5R$vgHV)4xlZBkzpoCJvl0-7mZDY;4wpmRa_3~bjc;Eg|>}r+_}6>dS;r< zXapI}#<#HL>5)lbzwWB7>-ZXK3S%cS8FwHcBS*AIoJrB)=&N_;0lMnm+$PoI9?kE@H(WinwX^=skV@USc*UQ0XOQS_ zjpSPh$aAbR?=UAb)r(X=KMD8`Knq1fRhsMe#=DM%UL&ZQk}`NWvn9G3BQa&^O?<6% z%D}>U_N&VuCgov-GaZh^Q$@s8-Y|0wXw?y0B=B-lVzumF7bp4_|%j{fo!BcDze~P zSEhf;8ot(A(EfFWpAWV{jPhqm2)sge zS5T7-4Lf)JKJlteg`ZC-eBwfWz(U@kaZO*M?e0chEb7}5`D86H(LG@AtpE5f$I!F6 zJciB@#T3xbgG#Nh7Fg#-gIJ(!hq);4a#YqYx>mn^wv!Ror17d?Pz7G}DJE(w&V+bR zh%J(jzg1?GKGM6u+lhs1GHM)8<3=pN;WLBN5An8EkoV@}W?jz58krX8s@%P#lt;9& z*c%J!EiIU}b%2B?Hdv62)oDPo%qzXrG`wJ>+f&;YPw|f{0d5r^+%-T9vx%hegN$TZ z5S_%Sob2c|%?+qot7?$CNm-0_;w{6y;_YXAs@N^P@5uPmFoI6lToT#Gx|X60T8K%E zfxUk#Nf?O6+JMxqAdX8Gn)0P;_4r-0*3iuEtrI$}udn6Trd_+;dA5lx9~!6n>Bha{ zk>{r!^1|h~nS|-CZdHOSMD$o`0^DyxYpTT*4yc$( z%Up3cE8KYO?{UnT84a*yV{qzb3elUR-?Re{4d>Gts!a1!6Tw18{AfK=Iojie(0DZ3qs#KjU?R-gAuW_64|O7ruH9SGV!82utm5mG5SKKlB{ zYDY&b(u{VuOD$u+fKFDvBrY+p3>QB1GrNYLvgyMZp)K?SZPcL3&jy+&?96hV6Q7-8 z+iw7o){o~1kQJdD&lcizVj(A#jpnzqVpJ?qCA!M4r>3UfpIQ?aC3N@osIt~q)vzUW zThXXN3K3FdEAR29TqV-C}KGaY$oi#Zj zqM@OJeJ!86Cx;X{X{}n9w>3-|*glIKYiHZXS&j69hBzI(a4yV(w{8~tTYy`(-Sdep zvpTh`fOAMaQ2%BxTHl3?Znc zh~2)w`9%5OGQcoP-(0_oLH6eRh7Ik^YkbCc6XclH64jQ`RB1WQXII*b}|#w?8J?`%pCy&`)XZ{bS=8 zs6IY{DuR3}-7hJQ;!9|cbq^2fXcY5J-~+45W6H0{9*woUFjuj`zsj1O{k}VarB-2c zezPnNXc>XB1t$IkS}nfM^y#0s@{|QLHDC)7_aBb%rectRYw|Q{5A;%tJvzNc;#5Jn z32;^N)0!IY{rXH)g3SJdp$sxlu%=T!T=*;f!i6KCRk+R@S97KrhcT5>)+V8sDtJL2 z0xjfkpIRB%N1P-D*kwVWkl3?@i`$KFHZfy)%FjPk0`^pp27K-M&uvWRk1*9*R;j5n zn59Kp)%lO}QOyzdA-ve36URp8$KRPf$-Y6CWVw9y8fpOiZ@~P4Pt_Y=ix3nl;xQDN3|UWtJ^{20kTPy0i4@bzc>-E1;~=(``~= zk)jQeH;!t1cl6<59hi_3rG10Z(dAL->IlK6?GguR@NQAv)V7q*AS(Bj8NT;g*t4c- z9IT-KjXo-4M+>I#1K($p9*%UMenASiD)5n`k1AVEBti4nE?55U|4xQK&5JHVePe38 zo#h!*QGj>nkOPAif`$LKu1RqaL$Zu;A$HOqN+6T^D>W>1$`tOtxJlsx{3+d1kB&*| zu$fLqAxz5-4+Bl_9axUbItbP2%Qe4ThbHv@y3jnNGa}AJzKg| zWEGpTF&UxwF;IGbP?)o)zn(k8PX>ZnDU?}uT4s<{@8?F(Q)k)lBPyR*j@_<_Q#S2> zubdVkPi<*W@=>ZRaghJ=)vvYI(HrPvQQP3YAlC?as3|dCmSApo*!cv@iWX6#BNA;+ zjoqPS&;ip4aj9SecmN)E8RUsq?JDM$zX^;Xgiim!s#g|sRpa5)w*fc%BL`DP%@2~B z6d_aAMOVt@v1LF04sT4FuAoo+zlyPV?nbL|d0p$D%txl1=MD$)&@D+8wUf&UoLg4nGEA`*Y7G~ri*;_s9dsSgy$r?Ry?SLX z&Wte54rPBptcV3~pDO&cKXApK75Z8|xGRGDOfbkE%P%aQ5#aKSFr>Km&zZI(sxH+` z(i>ZS=S+xdY7>f6pb(B78v{_krm||XiCzAX{}G5B=@!dmJ5=#wkzYg}pH%h(`Vo!X zZUvZ#+^HjlN#9f_VeBU!P3+2+3kVkSD|}rSi%ru+fa?>*gv5hr7Dn6Asm$!6kXksF zSKjaXVRhv|8zS?&>W8F=n1eR`ZBG&%cmb^P|S z)e)!9nY+PplG#PP68Pw*=0CD-Pm3S#d6-*JMRJp_hmGI{g$MQb_Y5htyVghx4F#L< zJ#~X8_Y{7@8Vb7btfL1{mU`<8y!#S*|NMrQWv&eK8z>VZT27p}xwh3xi^|n}whS9l zNnCmFWz}@wDik|_xOR!JpR+zMsKN4NUfJ%^j(NT8{T({`<}UgryL^&4tq>g%KW+)( z<94PC*W)(ly4sQIZEB)wBtK($Te)>qnuwG(S)7JZxO|LGQ6tkW?Ty)omRuvAc@}~dXrIqrGp@Is54CPXt)B!Yu;hmzEMtVt zt;xngB0bKPTX6_J?hp{~IK>3{b1{{1wZ&cN&|Xh&JlefHRVrKfHgqV^+B6SbsWbJZBK0(BkpGr`{ zlIu3cQX?>9PCU4DL8vqb=czXFceQgPZVg`a7MV`%^6~bDG@T})zfLzO_d9?n~~M&*=CT@ zSQS718^>JGGs}X1(%b)-08@+wzI~vd)LZZF%#F6GiQrt3N^nN?k(n{rMZScvQQP`Z z?WX`xN*x@ly;H4&IENYb;P@PZ!{jPX-Q&k#Jqa6+4{Lgqy%pK6SCQZIee67g^CX1v zgef5`R{Hp!Pdgp>1mj8Qzk%L42CVp>!nNazeyRA!A+HOka3xR?W*G1JdPBSzJu(cbkuTO$Vv{6?1}QI(6de1xu|43uV@>KYPxH)Ohn`n^fk&Grn+*bNyCKHn zU{8b4P3wrSO_~MnOd=LD3rHYm;wbJZtB;HJ!_5_c&IBHX18^kj;^4~c(vjQEgS(K7 zpo7oGpA&UjR#z7~R_fP3#t?PJBqcGpt~V$E_;F>>J7!w)@>f0`Ah1M^x}dklNZ&l) zuf!Ns?+MyvLlNqBs-)SgV_TkzIC0eyHsG=@EuE`NSiGLvW#6)%{{)pv*zT+phT=Ve z{V9~OTgbr&b>x(>O98joLWv&5ThUNeA45TxGY@SIU24;b2~zRB(#JJ)b?6GqBYY5;=Oh`(wm|xTLe*yg#+`#|< literal 0 HcmV?d00001 diff --git a/binder/Readme/JointStatePublisher.png b/binder/Readme/JointStatePublisher.png new file mode 100644 index 0000000000000000000000000000000000000000..d1f5fa6d202dd3fa7591b272c9e65ee1bb49fbf2 GIT binary patch literal 39457 zcmeFYby!zV*Dj7AAdN^j2omz4y9Md)25IR|DMdiKy97y*?(XiE66x;lGx&Y#jbA+1 zIp@DuFO^<%_qr!gURDeR5g!o>3JOI+{H-Ds)RS!RbN37moT)=IWCj1V zx+|+YD(btC+S=Qgm{}T=I=a~!lN!64nLt6g&RWT9p|+DE-)vy=21Vv7keSd{sYS}hrB5@$seh(KRg$TCUXd7)aq&G(~0G;yVc0*qU$pQJ@Yja z7M7O~7XEu@Ko?RxBl*PJ1qnO##)C4kV0pf98s*7izZD^@L=?$GH}_K|lBU1=^a@2H zDEQlNP1{4m((T{NKMH&cNS}H6)YNg()QJZ^NFhQDcscjG>pz6oyZFd6unZ!G!X#NI z=fBk+FjDIrQak-hB8W?tsL_=|LAk`!wEz6~j!uZ_Rr-y?>36Q+Cr=_>q;3}tQBB1}qL~f9xeU;5eoODC zP046a_Z1qYYzO|qcX2`UsuzKQh7g`xmvF=I>E=8vK3n${zjI0#0=frW(P><>BD@K| zL~&)s=JSzi6m9KlR%5i9`6qDc$TKlIG~!A<8y_!Nu5;)ZZIK*{-5S|0?5?4*@(Wf` zY;B)~U{ils*jUinYrOlAGqZ@c;An5*$Z!V(=A5e;m|N;H(%gnNR`mKtHU`G@u2!~S z(m_G-3b@+p8(J7Uk{TGBnpyLaAJjLKlbRXvk*l%EFv{2p8^1RbcegiIa+g&$bhj|% zG9nk?N91+o1_rE*9ra0Ftt_n_xLx_k|JdaQzdxR4ASeCP#LC zm7WnI;%es1OwNx;%4=_A!mapL^lv7>5g++`M@L(31_l=w7kU>KdK-IF1|}{pE(S(s z24-dmXaR9>vv$;Xg;+bhd^GWwjkm@QhW2K*j%GI2q>ncB4Q!ko`N+w^b<)4TpOvkQ z%sf16f(K9kwSuy@E`ZvI@w$P>5h>hgR!Nt6=>=Jp33we9w{avBma*(9*4lx%*yu9U0|^P zLrX_9lYb7@e|WdYD}TE4uP*{_|A*cG(E9Iv|I-+>l9AzlYh&p2_<9m=`N$ui&uwI5 zXlBIy=T~M%eJ&$bBW4IIE1N!qm644N!pX+Y3gH6h^i7PI*_k;x{>7ApwS%L+wW0B& zDPWx54A@~Z*5@$PXXSvfaItbhSPcz1AY8^qj1YEXE`0+=BX(A11D1a=A!ly}W~IL6 zzrNL@DI;Ktg@c9Jm_^?NVq{>z24OW}G6JU9^&uR<7ONp6D+ddc!5>pbhTNhy_E!4f zbDCM{n;J9NTATj4@HpVyZ{#KT$eHOG|9M8W>&^Zj{1+I z$;83P$jHUQ#>UCc#>K+Q_0LAC#`X?iCO+C^Vx(tb{d48MEZE=KQ7CFF(04XA`tzQ^)?b$l-|JhO8Uyd~x9R%#^Jf3eRA4sHXJKULFo76waT$Tx#K{F_ zlfFKLQ=iGegqfX<&Go`1%Ql={zyqWO>S;_}}3@hgA< zgD^2c{yAWre;Y7{zjc`5(P#X<$Gi;xWlVVgH24=M1Md6l9B^L17c%_A8UAg|9^KCW z#Xo=h7XKHY08IbSL;kJt{h#6bpW*tqM&RFS{6Dkne}?Pd8i9YS@&C-O|6{|2_)j=x zYz?v?7XX&nEEpyL(1J6N5_=2v@c8#@V{SA!gJ3JJ;Q$4N^y2a72~<)FE;tGAC?O*P zzk!4fh5RaQ6|x2eMG7VH_KmXZ?Cye#GNu|y*U>>4WUj=GHfa%qMk(;U(;Yb5b_aG- z>&s6DAobtr^_qT=e(u2%Q7F58&x$V@PY=O*`Ig<0n`o^+UMySj$>xJ69!x$vnLUa4 z@O{zv*2sHSMJAzDOh!03jb9wKv!dT+zD(QD@YNy>^z=kXJ|~YqNSuEf^EnFL=Fnt( z%Te*UP{ZI68|MqE&k^z%%c%%dWF2!K!o{f($lg$Vu88@JF7yn6lI$}&hNRFl zvd`e&za0w+N&NkoEQ10x`*RFzfM$P=A5A>k1jiJQX8s)iWv0W>|H1hQyVYz*sbM!R zyX8-<`2znJixs&C#{}<57!>eu4J^}0a>v&4roK`_V5Ic3hw27N`r(-zN8Nr9guOFg z3{ua(&+(l~F>O&k*~ml}x~+#~%OtZi>9;+7e8lKCv4^P*MMwOx zsD0a|5ff~$8DCl9cn9va#D_P^605rzEAt-`S~_96YqF!Gg`bh}C&;^Fh(opeqqNV> z-5hWU&UH!8*7*|6RhM|JX?Hmn_(zw<30#OVIeO5!q<;?Y^Vjqg8!Hz!g+nzHmN2XP z;w^vhtI^Kcxoc)7F^W=Z`QTs}N6(`*mB;12l=-v2|5%OPN_E}vmoLveJUs3rk8S3v zP)toti}af5sbW5lCBrJp%a1I&e-Z8K!c9(y9&U}@CTcRee&=n8>^Q$j(3vTWc4m=; zT`<(WAoPASO$~0YLtv=2_2bpa2Fr(Y%R1-1zWciyv#~4$9C~fno#9IRHOZ9JR0(P6 zm>`^k7;g{ht#p*E-MrG`$;4N$&r1()`JAn|1=A6qBt*9|yhvg;QX==qf-5&sG_)iR zr^#NN@9u-`pK(8=CgUrpKD>>h-Q|UM*4DD2_-v=%)z%A1>x0QG z??*_R9_~NnlafKQA9P9idb7zdU1u^ymqvRRxr%$;RQ5tqLN?FvPO6AkW?w2HVh+Gx zFxda@#zWpb!xC6fEBjF_HQ!nhDRp@!_hJ`mO(fRQ*D%?H+4ZnG#r3pIh;O;$lh^63 z0hv~qHkm>yPQ3>lg*Mkfmkr#g%XKjY?K^ea2q-Gy5lV;m2TZ5+6Su9!@XI5aT~+2# z`(4F)&PUcvY;2TtbRmY_VRp+M2zSSqm#%QgxIXdmIJ&yJ$VA*RF)^5TD_FG3@8)al zPPfM4Nk~ZgVqbTI88Twdl6!Y~dAUi2?dIk-+U)&6H(YNy!+d*pXXoNVMM3d-uG*%# zB1I~mKHFq4siwB}IVNTY7#6*{`@k1e?-!f+_V@Q=81&MX+5@6fQhs=Qw0?r+G0$O8)#8DIJ~;6c(~=` zNf}F?`EQDI)`Y*<3U5C-F5Yb}gstSe|45Ac5L*`PBI}2U1;y!l_|Bw&k1y4EZ`ST~ zQ=u!Ap!;yCeWuBiN7x_Pjg0!ca(-J7*6YoMdX8Xh2ste+qK`^}>T_&txRxX~i!#d( z=eruJMcNXsuAECtON88xU+h-8*3_FGmyr1c_4ah}@a|0c(aFg-xpe;BUyVF-XTzyH zVmniX3i-;?sob$(ft8z$zXEG5NH+dvMx^=foIqb+9}}V(BN6>dq2AeQeJJ%cRfywa zqZjED=>$fy{>9?saXEp;GiJPGTvPv#QE%M+p>t+LVFM8)Hldt!#RwrR_4U%hY*`1U zZk*@2s4L_qc~G9o!h1r6{?_XFM$TBX%9}#nv~!pCE{Ig#zlQJD2TKOm6P4rGaBFjz z@sSzXt2>lY-h~)W_QfPLrMJ&oXg7TK{p62{gxqmek97Oo+s8AP?J`cq?xe-5$Xrk- zkM_yFsGw+3Km9MAsi~=iq@?4GbZ_Vq=RM7#bb(+*lwcqRWl34tm_T}VHf1mlL)Yvq zzRzp5BJ>w8qVFKdqU{5TEL$TPFurgo&|lrpwzcaV1C9IRo};55wy`Va%2ImY-_mK< zpbNJT^vgw(i)@0nJTCiLs)d@h-{bT0sKGlV3V1hp39PTLhu|^^$>JkqUqlLNn$NDV zGPeB`k2O4VoyZHjJC~Wix+AD_;gk0976FSYK(14i)idYZzM)%5x!vuu)w0sq$R=@jDy=WF%=*E0+mi|E(k~9C`(@sX8rQBr z?SIFgyjNKHO(KrhKK;7hwR>1q6@bK^fgz5dQt#3%gp+)!2qCkzI-)nbwchx9TzAu$Z$LT=! zBDHOS$Av}f`PBJOytM>sb(Q_$iqWeC{tb9k-Jktv8yCmzLRg~g+4+-XAx(q*4a>q+ zw8shSZ(!e(@R4`xQ!aRV1#Ncr404R(&n#)?V?POVW0K|R9wI?Ax|@%g4cumvWO>+? zus*o)Ln=fpdkBFO*%Pc3obG1Wo};e6tX`;h37?oyzJukUrw?=37+TuizHX~SBj)X~ z6Sz8F8$UQO&N$^xRR_ZtJH)91_oZM&X$Azdpl?Fho$Q~tiB^o zpffNKzKORieo0359G0=iP%@2hYAj8!yTJ}2{w3&GqmMehriHLG#<36GrBU| zQRdfEmoIjj(QiDTgyquUa;s3abRJgr(~mDM>fBr$z>j!Obq@?60|r<$ocOM-&JPJ^ z$WFlJ;MX9#;IEEo>*jg?K+VFgwzf~8wW(HyWqhi~_zI|}mh z5nfZn(Khy%8)mh&S6T*OAzDejlcyYT&_09KG8rbd@3LgqlaFrx%uuOy_U4M zSCJ7_zlq|#R8DgEp;ek55JZML2~BN$31v@QYiJ>m9ukE+SC{t2W z4$sf09z0G*#WbL)XlQ8qo2slAf+{Q7zyuxO^+slvdnxHPH1f{S3O8I$~-#0 zJO`nRYR-yQ<$K3eq1GA8lk}%H+S-I(US1k?OV$f@XF_@WOIusL!vYT}#xvzCmmstJ zwS^t6`b|U%j>cPe_4m5SfJR;V)6^&IlkVt>t-INiFIEQU6FTn35bMxroc`N85axGRy(LbYn{v!CB+rU+7<(~hXEEu)>CoyXav8u&ch-8mkfo=i+k`j>}G z9=Au`AYWMVyF1&S3GY=v3-+0Jy}moE{~;zC;sXs;F;NpR(F0)8N=`2SSd z9;zAMe)mvTm08Cq<6dpj9kG^jW6YhJ3~3+z6%ycLW6L1o+t(Id1!-V{PP@w+-%EXg zFmul)YVH?;3_+xoma5Jc^A+M^mqFo69?KkHUnlf#x$m)Ny%j~#L<#Ei8Tf^a5>9L; zNb(Zyr%Iv3jD{Fz#P@fb%Awno6W;kCeY3s0cKYP&t57hBNv9s+;{$bly7kRwfp?2p ztI`|`xJXmbH2`#Yd3n_<-Ydk}rGT*RaD8gFK9J}e8TnkN&N1V|#r}2o-RXVEuG&JR6UG)qbNO2201{E!{T}ExII;vymxJFZB3_D6#_D%G2kqJ{P^(< z5s{piS9{U@wftA8$9O|d{%K@HUNVOI4KRbt**ePG1}(ShH{{9IMHE;7|`Go2vD6&ZfEX!scsk#%g?uPQ+;|Nc%>dI?y{T(huvE zXpTCUyCM%o%sv*Kv8DL4qx8e#a2kZ8CRe?#n9r{94f_dE9tnES$U1n0|2J^xA6)wX z25ovX3}bJ_u{pM1-sA?6rb^yS6) zxVSE=bdR=5i|NhLZ}6SLI2+5I!2{qn7C>m;B0(2v^Qs6( zs6R{eVZgi}2Cx_`4dA2nt*wjnR5OHN+uGaB=BgmslCjGm2E2XywxMLtABEuAvu7=x zoqix^vs)j)%YRP>p(N`lNag#$J{N~B`2PJSQvXzuj#RE}>N8Z-uF=sWzi#iFJ&v}v zwmi*BT96tpgXHtAsHmh!@PoJ%4PV?x-E6yqhNuscs5@D@Wb9=m5DVp&{sM9~O@AiC z8!W|g4VA!$$X{!cD^u?fsVX%{#t8|fzFN?LAS_~rqDZzsiC>rai-q>RZ)F%mCTo}HyZ}ufPnTo5f8r{lg=j3FLzAq^+|KMI_#+sFtwdp-JHdbaio~Q6q zGz9kz7=oT;jsv8dkf5Np(a}f%OvX#}h3i}nhD!9?v&uT*#}vmFR&PF%oXnhKrqE93 z8h>rOda%-8&kf+@vBQd#Axx7H@Vlw!IFSnav_8hpo{pRyvT@QWuk`hps^YAY{OVfY zU^*;gjn`R>wB99k)GLjr`(JpZ7Pp#CWh3v&h`esS2|Lf57EWmQFX1}ed`pE zyT)8n;8XZS`-7LxAZ*jlT;vgaOQrSeIvh0z;|=aOPwY0CDdvJ&-_u;Lmb4JGCqJ}n zqn^JM-FzrgEyM@-ZS29y#^zznlSsfT1t13f_m`)QXO^1?N9m~90RqD&+e5A?vxCNG zI4Zrl&}(ndziFPmn_Q(npSs8JE~h$Z;5@gSmD6m^#BB18{RyFZc5>=oL`rMeW z7$Z+%bHhGbco4_IHboqFHl%c{3E5D^7h zzH9CE(<|TCO9f|MuSW6aC!;`Kv;+p{IPJuFX{2&HQR~#P3dY&?6@maL@htFSOsj@TZe#O2bzY@*?7J_?m2!CTB7y=)P1}Q*VPvO z;K@-xWL}y-8l`zo>uJ%Se@<1AzZM`f>*+XK-m%{hvOM7vc80i#Ha~FpVm5|@;%K9A z*Lz*yxe6XmcPCe@o{5}kw{P`mbzG~>hx5pH@=2l)-gLME5lT(Ryl`(jwu@}E1K%}} z{bdLToEB2@@bL7-GspoXP+C&rx_37-GZUGRK#ld9zeRp*VdHoWo_d{BMoa=%78W?&8q;B8#qqF59N&)*>2TgJ2By;q(gH0;5L@4aI^GQ#>#Kl9ka)M z)-i7#V3aoQPNGkH#DYxw#n+pRer6+ zS1dWygQg590WOz)LXep;q%AUB3GVg_?E?@!R3?4D<9x*Lda}<$87h{K_?4FWK8LBAlU%!3?t28x4<@pJgusZ#KjdGJJ=OC=#`{f!8Ie!fP$*7e2G__o#+-L-{kg|3fS zRib0E)7?&~Z2D)|E2B}=ro2-FzU*w;cke$Pt!RBb&EmvRa!UMI$lNy1O=2?UdGW@4 zwt}X#wDfa8fW!6#&EqE$5`yM&-u(^23o;?+VdeQWNT2|F(gjYKjpv|D7wb`xlMB&m zdO&4lF~15AM5JVko!D?scQnh-qM?;O#{CBE=;B5to2^`eo zD<5?lA!&eC`ppQ^Zm} zV`b`mkWgYgvdWJ74MDnOopJ2BlYweDeOaMefO7k+@qt#c-V zh`5#c?+?kE49<$UcUpg*?B8V{*S+?Y(meFCU+sgT*9j6f-IXmBV%VQ6G5P>ksVm%5 zW;Q?*>)+-uZljWenJ*vj-c+0?8H*wkv@Yy)NbapYhOuh$*|f)TeOhi!`jqk2gPd#^ zTI$D-PsqpsegC<^u@U444JCBEyeWr=hjjh;?3Uty>Mo}P6FFJA!nJx4-lhr3(8C=5 zT>($$Y&N`v`@FJ36k7RlclqWnbl#Tn)4JpiYp$TKDma)NQ4GAqD;7^}9&KfpnbI{| z)D?EbBY{EVs{_ql3%0DNnP7{&VCC$j@+TM0Uc*H_p)`X4{e`f0Ku zeyeMW%r5ob)>1a}{$X;~icD89k)v3((rco;IT_A9<-+N7&0p87Ehp+anHQG24=vzT zoqQ97n5^h^sdmymKKc|-21Dq}v?a|}(L;yJ2?nG0`lr3w--fq$HzNY?(9#)pWRiD6 z^A!|3J9U_L8)Cv+j`;Eo;OZ>qW;~>YoBXXdM@SF1c3G?t=*5anuEPci@f8y#!+oju zf77nxtx|6F6J=m-ovnEg=n#EXajdQE=`Ifeb;e7Kvo%<**3Uqwb@5#~?F+lNTEouFj-9&EoT$-mptjc)y z_rd1d;Cv~j@T9JWgiw!ak{_veoBWjmd^&hb3{;U$Wli@lv^4BVVV#=7ZS$vmdmHOs7%}XDOfWzuHZ6^wBJavLUmQ6Z-` zreml-$L#vqnw+hAxQMGI!H0R`ew#XpgY!$sgQsXGbLbb|Z+G3VtCB3(-t_o$l1SmItKPixTB0wda?o6Yl%8D5oQQTdh zy<}&{_Iaf6-HwgmQ1C%0gWniRH3SH2buc;p_wRR5fJzWnR>lNGjdGE8qMp~4pWDg0 zzJ*1B_kKbG?)Ali9Ox)6wHHEEpj*z+#Tv>PqseQVgw}YcM zy-?~CsMXnj1wLnjEfqIh8ex}`&FD{wXNN&6Q)xH;af7M~&hs0qa~Qqf_2`dA8lFB` z5Ir&$WB5VLQA?Z_uD^Xr%}&@P6ctHCe{c1SU^ewT?1cTg7Zl(K6WA=U;ouSviXK^g zBBH?@nPl*Rp9mJJvb<}7+Mll#{s;}52XJLmQZ(`L34-$S=l}vieFf#H+xwdXPz#6vrBXM$j>Yvg z6v92&`UeUOD!%&DVvPp6`}AQhP3zuK&6vc@I|*=Dg_rVy=y48$7yZnE7`heJ75t8*}Zj;x=UAZ87P4K_j7uY$+uL|^XD(SE%teSMlZ%vG3DLjp}eK;TKr zhd@)QS%^mA^9dFS+VXvOK&J4Z%DK!Mzq1F-42fQ8ja z+nG@v1M8#KVFT4^dx8uC39YDL1tiAd(b3YyqIW!w=xs10d%`G+xrMyAljTipS9^tN zQIPqI0cqU^P768j?hu*qXSgJtn>pusKD4p@2F}G~hPlOA!jr_9@Pd9Sd(Q`m7N9J! zT8h}m;ilHQ-6ALYcE5%coMnFRWB{PG)Q>9%S>=BjEU5IAU*_AZVp=6p*uJuOmp zTgL-4C5Em@QT`*ge}k%2-;@-EQSx`8+xud}0r(e}6C_1R8$1etJ8JOjx$ z(a^Dgsc7$Xl#Gqe&dw(z#d^&+#DG5ZQLehY5Ry>9ly^0WP+l6I7CUzoV-Sm`6g!*=fL zXH@hS`D-RJ5(nhFnw)V%TBvsSQ!vD4%;GW%wvvN`yv-D0y8<7J2B6FZ#>*5m;73Ll zqag5TwkkWJSU!DE$9d%#&f%P6k6irnsfHtD6{Pj9v}<|xGoiloV$!I7p`uhw)G{aYVI#JF6Mev~kO?5O$Ny&y~b!vb}qeyv}F zn9n!Nn#(vzXxW#7v6|95?sY99%g*hp0x^1e#K}{0nAflABwo>IJfRG;Y8O}c?F#QU}$tuF(3m1**gju@O5@oInTYIb(L45-P0h%vF@ z&c?RPp^hvpXSvC?ekCui#NrLvc*Fhf^fWWoULZ_4mQod)Ya@f6?Bm;k(hB*Ejsugk zDfr9K>m;wxA1qoVNm>aT&Oa7gpp!lPH!+qaMm{Fqo3V9tQu<_1vJ_TqAYlwQy21)m zIUKLj!Z^6i2iCr>>lI_$ymLZv-yyc&xulQtW-k=yd90kZ|bbGv5XdXfahL?Jv}`c-^`V3=ZZ4%J=4c&k(?yYt@+2QYKKV4j~aB z2B8zMj-bpSoyhD5ru++HVtOpdeQF#AoL}B_8KOyU9J676>IOgIcj3{shB=|8CQJ!| zo~nh5a^(GkdHbh2y@)Z>!zuFO4R+CQ?d8JsHwCjMM(}b_>c(=XM#yP=i|j^5q;506Q&m*z7@3V2WlocG6dKRx&uE; z4Uf*xO!K=8#QFXN;$t8E+$maw6giLD?^h$Z(T=nVxKtNP?%< zKe69hq2Xj&nGFUeI!Kv5dnMTnCNX9zL~*ORe1C3@P(r1|J0U7qo4F-lgSt@7(bPVD zc=XKbQ}7Xr^I*DkNDjUsPrNrFr(oA}lk*#lZ@OpHMRkG$AzQa53ckezI75UtOeNWZ zUNtv6;U3L8!7hG5G4hS~c02Y8CLc%`EW2ck=6~O2Ip;~g*~6+D4y0_Ydc`kdBzfsQ z_~rS_)A8ab$dpCnqO_h$jwcwoEjNfiB{DQAtS& z0SU=)5v|+d~w&nix zjWOQzkm)a$Lm2-J{BbW1dr3nRn6H#u=5}HNs*f}ZnNLBQKJi0CN!RFTDi)%JU8xx= z8SAFwd3>N}LxVteuLPVJ9+y4EOR=z+KJ){^tK!!{bJxIiYi&kN(p5{TpVMo4XE;(X1Cdqqk1vq9ZeIqunn*z&Po2oSM+;uRzLCd}JGoP9G*kFSuDefs zdCBqhr00OsQSK%P!j_UUlM+w$wJZ0T#(PmT zZ$s7ibC3Hw9mz@rsz>-#cbPH67CH16d>U&nq0tGXja?|=h`~{5@a_u16P_tEesJh! z^S<}kp2+u=&ApK$90n2-Ao_bnNhu;bdqElF(YX7}Oe<<(=aa7CYe;-172`$7OC1vi z6QOYIiF}1%(NupHhVN8EYO3h9=iD>tQ;0zZf*G?*(s&Cg%NUZ&Fm`KwSU|QnQ)M;B zIDy3#baGLx()p=I*kpr*xp zlI7qwP9Z9D6Zx&$>8Ja|H;3#1>feY4s!IJ|NUufk6{+N$4QUcLmx#^4bdJ`3iuE-6Z zy$NGz%Im#p&JnvrEQ)`&9^AXKg%dHf-C6HOolo%#2F&*go5eK10w@$}vdu3n0B^l? zzBdPTy1$Uz(jo}ue!d%+o}TVC_n$R&tWqvYKqU4I4K3Gdt}2FBC1^ZXE;=fz4e*vg z(bWzpzpr0OfvzDbTRJ~KKLn4(A4tWPmzLgu2+8HNjS0oi&yP&Njts@XzyKg2n&8{F zPr)fDu%@vdb(-3>$ET@3#+P<>q~5;$d{52?ip_t+&cXqx+D#r;*=G}_hGM{vp3OaC z>w1@iGOs&#XlQ6^r5t34R@FrOnMBWjfzl>%hrLBL_ohL1jH3RJw2|*cX~Cp zPr!3?q!WdJ{E=F(sliJR37c*tz8YZaA9~HYnv%sBQ;o>MswpdP46f&pD10U;qF9vG zH8s8tQ^??>jk8|Ih4zg+Wr@!1tVF&3WW!$^YP{Y@IBc)=qPt4OqDGhXvjVi)e$ zS6GmJMbmlV+U3BDHXs}XqEVy6->n_p-6v<$dMwuSoF)SatsqdmU#MdPidK`=o=D{a zRTQ7oQ%ArHh-qr#uXKg30MV^<3TNc%s*%Z1O8(*nxb)~40q*AH=ElIs?*lr+N0<$Z zh)K%M9tXle5HjNocm(W*C4)bs!QT;IK9VI)@(` z<#6x;I0A4OxVT^Z{9v`Jt+N3^07b~>9#d1p`RNmL{f!tXqDf0510UQ4R2hKyMJFU2 z080tz1O}_p&i5CB6BF@3X1@#yp^t(-a4A!@U~9UV1Tay63<1fIn589M1lJVX{{x%w zn{WqcuyWOsKre-agcvzEsDRG!<;!o{(+?nx+?uOq01_d%cc9V%^nV`@4{d>vK)uH%k6?hPl}pPPwrYOL{xaO$ulrG*br2;0rkV7cJ|N#%BJtB8!1**c3xpH%Ed%)ti8l3G-Hr89kU)(GBr)eKXe8fC;#dQ(IaUx_eyuk+J5Z?Y z?sGTfCDs(1fT^7$>uA5p$mkhcKodw_qf~zWob6Fl{c;iK>+8!O0fmT7C$6nMFI7DQ zltiF5pKH6+mX)0y85bw|M-fQbuhZ1n=sEQZRZs7c7CBk}lcED}M@d5?Az-%D@)0Ia znbv$FFJtkQTpDjjN5@E(M6@=E65#5&+)t?ic!7OfIe_MZDzRDQhcch~kz69{ddBh3TK)T#?e{CU~#v7PPJ&?fU3;eLug^uj`ZPZLW z(O4Cx%nsI*uQ3k4I8Z5|LL^soXMJSEQ0-*2!VJtAD_+0h;t_NSj>azLdR9=@(g!`1 zn`I;$7O|6jDG1VWyZw1C&-l4=VqVvX6=ywxav;#rI>({Rh3=M%hUja*v)$*sjp0f`Kz|E>Ndi82>UjhU5fdc{LU^tnu ze*}Xbzi23aHd>+D3=lE|W!i3zkO7s^ubO)xEDZt6rauny60BWNn&fug6$hguP!ot= zJo&VjKH(Q<1Qar&La_*z3F<=_o>nq5P0xKI>FCici5(+dXnZ}w;=x1gT%(RHbI&e@ zM?%Uc*&?lF0RWr-p%gTf>taZYPfHsDt_F|KofV>4F~Z<|Zt&jNSj66*89x+GxV@R* zY=dd=dd2AUi3=7qW2=CC{E&E03wG+ zK^&UE?bn044~ou(s#2i-i3B$EXZ2_m)^F5rjg60UIjl<;RTrxj6SoJTb@%oLmXt8w z4b(R)K0pC?K}kz1Nzwv>6Ns418g;i>*)hS`2a`{>}HVPLKOlt@8arECQsC==;BbeEpEuF2+Nc-fQSDn@?NYUN4w9C! zu_z!bWVV`Ry|V{t3CKEyAMWoEP*6HSIs@{XN6H%r0Y!iya8Yvs_UY4-cdgJtI1FLH zu>-N@TALqI47CFJ^i5AR6&h%tt5I$uoyMC8YVu8G_YTW@dxO9wgWw1VEalCr4faDfW(L5caF9DeVv;C@g zS2#&H(3yf^GzJ~xbw3qv9s&~lL{2+$JIWIOIUT+MI(&JcP94zL(AIcp{Oi+}Mc;q76m}{Cx`?VP6~CkwM<}J!7JGmaX^X0(yF+d-F0_&o7Sff^WPvlI5+@7zZ4L) zg1`t03p=J{Uh;fUfK=kDsS*kgLT(xadIa-pJLZt;zMwm#eEvrdKu1Zf$f+{-oYWlPYYVdrW(Cr(hhRlt)g#4B7opdr`lq3Y~K= z4*Jdz@EVh%B_!jfH2d;nJ$|vHlMI(Bf1mb4&?<^J*KU{jaG{2cY$aA0q#IMH9(?{% z)t*^H)8!!gSL273-Q9r(w-cay1V|g`9>>AfCk`)ukZJ-S!GOi^>p&iHN7vs&wd+Be zl&@)XvBsI8a{!+}32XD-XlJAKGktBCMZ6tQ0;_X#>KW-TqK3@8co=}y>mGDkEE&xs zhM|%+csoa~t;_yJH&VB_o5XF}|Z@ zSBWGfq;J&447mVKg(BBqv+Le%fLkf(cVu(|uBtDu*g8vzj)OacWR`upoiy=c^f8)Y zA})WxBJqWAPHKuwc*N1|a2CIC&anRWSIrVnOft`S+axiPsLHN7EQ z>w|-oQe2mo(7A*rn$yJ60-8RmdeT(KC!(t}ca(hoHp_Co*%w2Pdzf^Js1Yrui((Nm z9^7j8o3vOP@kIp6dTu>Cxrixpn$HBmmPcYfX|hhJmHm za*kX@&v{Exj!H3D<^0`14egg*B1M^xbsX;ohJx9b2`t>tKpkf;og9r|+-%VP{ESvi z#@BNoxe_fpXOZ!B19u$l*D{i96)Q6)8*GBP!3>pB3|wqhurZZ-Q#)$;%HbZf>`mmk zbjlcx+)E$xpNl``y5CE2dp@u=N*Sx#QJx{3ew6a><hG7?7`u0ypnQ0b3OP!6QNRK_zvLQ1Y9?EgLvX6PKhDy>r>xf$) z?okNFrUZI@v&QYWS`qG*e6gqrsWCCA?64ocIqQCc+Wq>vz08p=29F&oVOeDXZD(~n zr6%)@!#))J!A56u+9Jyiu0q2bPi>a4vWJV)>4FXqcJ+dE)%-#oFXgVG82W406B)~6 z!y#csMa-VdR6SIIOxwY_nnd1(aJO1gb1n+|&1shR;%lp=0xfJ2__A_~yXFKREKiGP zUxw}SiHi0@edl>EAtm(^0!iiF{}r=J*FBuoi+4|abb6WvfCz)fo3&`{nB-&v00}kX za{1@PI-`8Bm=LVkW4T_aI@5u-L#6?sw7?|Vrek8ONw+K`@cvnot{Y5Gj$o6Dy{A-$%kYQz*@+n3B3Y3%0fi{C8) zomL<6Yb4>A&zQv9q;tY7jGb)*P%jU32Z-@~)*LPf9!w9KzGc?@5(sOK&*pgY1nV0) zHaZRYr+2VCKR<*@vYx*?FbI5(g~jA-S&DAhs%tQv@H4X%mTe0615Eyy^Th>x(AO_N zn<8)1rn$JN_J@8Y*7EF{rt`R%N(W&HzKJ4SyP}H$ncL4w3mhO-@BN_;Ab{Cy#g>JN zGS~`S0(Ov1O<_N>b%1f>a@<5;>x=Ezwg${pg~jxKr4uo~M?&OFvB&)%+>VXfYJr}IHM+hfD9cLpqlTmUq6;Kz;_Vr+C%h5CF)!BevkoM zXxC)0Ns1Nw@(r$QqVaVzR(j$+cQU+rQ+U-9EB>wpIQ$mqgYC!1OP%H(wGfc0rwX+l zu)BB$zdc5*+{b(H?bZFcj;@I;v#B>%m(t2HXY7b*eGGi;z_%->3keJswS=KTzMD&_ zIV?G~yO0QFYABTLa2@OSJPNg${N4wP-LZ56Et34z@xm9;(Pt;F=iOBcBs z>${X)C-w%ZOhs5kBXw?}H4NII`qy^ykOFp(L`A`_ksn@3n48lAZYl?esb|_u0Z9Tj z5~8uNluy%Ag2Wu)FFByPK0G}I(wA63uP!eymqARetnOy70ax?}a4Sb=XU1S-W@5Nr zqkAko8nJw_ZsUe<8x7z%miG6DfWV-vQr|fCF5nns>_$ME^C;;CU|T**{5b#ue)aYB z4Xw*7YLdmO(rQKBo=Jl4{7@#k^=PR?T8!T3=5?-4-9_4B&;*u7ht;0X!VW}qwAj?D zhmF^tE8!2DiskHXgU;rQF`+oMkN%gVe40SGGDa+cyr6U zI%UZJYVNJ0vi!bpQ7}Ld1d#?oM7l#tLIG)z?(XhR6#;3byBq12R1lC(k?s~yy1DE9 zo^!|f-E+>p}BvZN4KO{@C`Twj#O3L-L&Vwqx4_QF1et4Jop(cW~CM&|g-V&YG87 zKT#5A>@a`n6GEk@zZ_;ikoT%T4Ec?<)=BQ!SKqKbwh-~=qy^*iFsmR{R<|k&f3E(_ z#9Y#qGrAZggglFT-n$)0MUt|zt7C;qjCw7kZ>y{S2vL%A+mb@MXaL|_eSN*YzWyhT z+@^krDDw2N+D-1CJ32(e!a1nfn+Ywq=UZ>A%IK5}Afu_M9YZu2a(kkKM zeVc&2+=(hItuAZ*@k{+3r9O3@Bxx+u$~~h1oD97d?)&kC95$U&ohNA`Ns%lydb3>!Itf5tprW5<&>o0Tp98J;V{@|rH8u6j zSC`O;$1hBo$q5L8T3W72rlGJv4ET%jQb#agHAYrey`UvjZ**k>MI98L+C?PA#kc*- z_DixUPafhf>D1Uv$HBa2%F}`lStX(uC?Ie~mr++I1S%H@Nnrs>zIj6fc=O;kkdN>n z9vA~kSl`&FRBvwpeg`js^<`N@4BiH5{2s#Q=CmLTg#rs>m#b79V{lp;8Q}1SP()VO z)U0$^7K@RhN=r-I&kMoA%DtZL^@&NoM5CCKg#hi~;_?GfGL{zi1D1^SzQlH@_oIP; zXl5n_N+F1I9%wO-<+hVKEpVVthC#&sA(lZ62OIk>P#z$pEddLl4WJZ2N><&|=&EQZ zMhxMy2p|OX|DR!!f$j)}qb`to%_)DT2>~7R8C@v0N5-%@xT`?=K4$qG&IQk&JzF6r z7QXab-`WaMEbJpS9pIZuS&k>!L~vBo@Bjadqq-WfMVy@9XK-`-h-S(f(?OizU}uYV zWK{rH_~Q-6j&{1NKvz+4aj?{2H;c_}CF?)M3-k5FR2X>VepVy94##yt>S`{z9|zWl z1n5icQh&PoKR7HgI#|0i@yy|1MG{9^wS8FezU&_dUv+!T6T7M9{cl$}6uUiaS+tRA zL`rjYH7i1XhQI#dcwfbGKb4ZuEQi$RL1Rw_N)~c7g@PGWF)hd;ZC>YewsV z)H}>(53Yiv^Y6cQzTSBwhe=#byEPk?C$&8zEhUTNm(JfOvP{pTX_?9DkfU3SlR)Af z<|BV_xb-kX9(RyEk9NKaPv8Z)W+IUR^}A;ux+gMYB;VCqpwX)_c3vBuNDjqxYUA~% zH*)PCkl%dDsLqgyrRFTwz@bD^tamyT|9;&hQ>{ute_E4Um`o+b`E2$wwqNVP!9=z* zMyN`LuajSjk{^ZlnZa&O&Vk!+?=;ul*E=kgqVK5R6<_?ST&yGE=cvy0UcAG}Qmcz6 zGFFQDhsPuO*=&}w^%#mDjZ@5KBu}%6fKYm?bY(4-i4|x5>zXA(TFwrg$*w$`t_HH~ z&W?d(Y9=eC&cA%g`8F#*3B>s8i@r7PP2dWBjo1lH-P}&@{$-&R%%t-6ck)TFG{eiY zz#VgK!KBoxU-s;L50AcDJR94QB*w(^yLK5;1`t#9| zd9?evm#^+oTo}h3c3|A82d82)>i+CkrFx{%~wUUUAjsKf|INns!B^pjpNl zj&e9aCh>AVH(kR`DqXW#oTF0hF=Ny+`!D|_)F3~@-sX{N681QX9cd@CUVOQ(Vo9FH zXdA4ZO+N2i*<-3dm;%zi3}OiZ8b$l^FVc%}MY6?r1toV#N4^UZsl8dBmSr zn7wLW#iQRAnTvR05`D`!cAc5}8ao=CYtETL)ABmp-c}$6$u87d#M*9ZzOg85J^H#K zG|ldfSj1L@__@L{6ra3Xkq#YfIbxV~@zvd349s7sVFWLBe3f9~aN#x(Zu}WS)OO^5%`IzNmq7 z(S*F>?8^F3#htt12G)OZoi}xIMt@$Hbp3_=<36Jpb*ivEY80S!P&qK!j z#p5w$RGKf1>_tvLJ+oBS8ZFtfj~ahpHM6ve%2P@tMCITI-5Kfn?iv@J@Q;$#QhoX1 zppakZ8%enNQKJV={9C9gLKnCfTPk#>1>p(~EcAF+L9N$vucfu_m#pxR3Hb!p))4I6 zZj>Ka3|-mw+jlcyDT-%*RcIrnF`qY9$1Qv}qr4;Y{o_2(Df4E&v0T<{Q95a7d42gT z^jP$(c0Fz-r^mOvr?0nS_Op^o(7vL)rZuvXnHlAA+(wh_OHXM~N+GWKLzj^qZec-g z8Ry;BP(aA}_Io*@E7v*gP;PlXLG7DTN2XWN%`Dm1-+wowM66BGhKDLOJ5crzC`*G$ z)&94?sg-vy&rdRvG}s9y0xEjzL9&3Xa_isEJoO|ClLvc52}xNpA1Nh`&U=Cykg3H! zrNjsuYT{_-nG!aiwyEK^^{o(L;f%}w?aw@9WW!S;iJo|KXtnfFR$`?uGMeY+QZgJ} zDn`1!Et~E!&WXc9{@!GYWrT=|&}DJLr>IXK;wm1V55}tz#%CD5e(AFFSd0S`d{LuQ zVxqQ#JQTf|FD`oi7R1Hj6RYeFXGqFC``MOqE0N~Vnf3W74V&QN5$h;hhx!STP3rc-`XJAGRWZ)^`VM0BW6`F#yAiNpXlP5(6E%k2tRa>JH@~(yA%B# zoAUPkBJWA^)}{{p_e~j ze0VJSI=V=1ZEjfP(qbXRN`VSJ_kk2n@EZy7k^wTQAEZ5>?2l>H9&vsm>t8L#;-J4> z@|1_q(!uoRp)FO>P!9jfpWWFMzoNCDdsgbzi@1?WuO`~=-OeShAwHCTp|G^;;M@H9 zt!8T5e2}l<(PyuwBQ=#I^HQ-{3dvNlz5xFecja4NS~~I@8QH0FhTl1qEoE!BXzH%| zjW9AxN@S(H`RVANC-5#Qo}vUD>rn{my#5~EPTHbCII+KGj-1p%qTNImB!xG4BqDw~ zU4)SvjyHK;S)VO{mhZc$XwA1}=Ehs;d-tL&zelgVwE%#b-;jTth#n+s)|Mva023rJ~?8;1x)LAVl8LaQO6kt@-=@ttdxmhoD5qWv!apr#T646Yc zXDgWuNlNCfGT&E?szKM^o=j17mBI}{=d?S6LWzMlNm*OpKyn;Yk5NJW^)E|>i$z`h zJM#;LsuVLx)m{Cf$O#Jzsv+%KA{vKZxb+%MO04IaS{*zt=k#^vFt^Enu?l3--EMWx zcihJBcx_AZr_sGy#^#^(FiP2bO?xa{&+`tli+6<&BNY;3vvsxXzEpP~QyTer2~7#k zbmuihs~59px##9pA96<1Z*r6a)d$Mu+Y_x=7MutTJ8JL^|7%OjqLlf8`{U2K-b@Ee zz9hHAJLfMO$Z4sI=PgbfHkUX0W9)e%p8vm`Gynbo@3Ixoqip8o-VD}QU{1qr6UI_I8I7G3NPlE#&CNXE*w{OUR*FPZRPdL*C z_7uE_QKRw>urAJzcan`7?WS9}YnDM0j38x9ls<;+VioH64Yj$d#lYXC1{3e;^Dd|e z0!F#H>G-Ph5~znC2Suf%(4k;w2vS8*%o|_m&o?;H09r}?{P{&gD`0G{V8#R7B=uTr zB4BeP%Kt!!G1amK3J!uyMyHgwLg)_k8{p$0gYya!0G7gF$b^_dgf|)w&k&S8C#H0& zOfjLboDZBL-d!c#I+lD_K$htATKNB)#TVy9ZFP0EIT-ALYNh*^IDF55{KFhFDde~} z-7jL*dK5Vy5APjZ2P)(|cqg)2(zBO|i;v$4lL+sUH2o2kmL>;WY`x+vnD;=)V{2<` zkw7c+5Gt2YlBEUi%bFu_IdcFOEGszxZ?iB`-YDH>&*4lF)F(#u*5K{{t`U!LaqqkY z+71sWkP#dP$V(26z|bsldqDC(w+-d>l!oi3>hUic98hoV0O3twSs4plei4j%*fSCC z8UF-9Ws5MZ8ZTBuU_ptQ)wZ*Iz*PuJOq{feje_zu2z`tp{RF#}WXSh$aBx0`_6mlB zv)6ge(QLhgKY~&N^BMTS=geje-U(8Hw}35~6#oX|9>}A$Yq@|FoZ zsZ7r?I00(u+kaPnK0*Qp-_4X2Iv)L@+{Gcq^ogKNb3vRkJsy}ebqx;gWy`c72&%oB!f%CflQ3u5v zGAnyeea=2Sr4G){eaFO)Q=8^V7DVdye5Me>YJ{v9Od(SQeUczS|M`w8^Vx?}Y(73d zPOD#Gz%~Pt1dx-MG&RcxC8cC!L~|8Qk`28M)?|T9a8R8FS@k0Dq7dbCE^9)t{K$i= z{GOgRGBo@S>wg2%;I(~V@o#KzuX_jyI$zA?mppwPvaq=L4ekhZ6P>fOIuB?eE$s-h zguer8MI=*x2>1u2@oe1OU0_rR3<^$SOt5@{;&wEwPC%>ECSdps@DO){l+oVJ4MAeU zAY^?DI|QV`z=-7c*#7|5IZ!#+*Y@%Lvg0*Ti_nJyqPj8H+;~|_M}97<^!+*iIUSPO zI+?ZmIqxMGcdF928v7#daE_b(LA{JvnR8^)=J>G_o=y-Sc%$H%Lc3Js)k zm^}bh!yQ!AD&V{TuoVP!twG4}^N#=qMuVz*F=%en0W}5x&bK;oL5+O$Xk{Bu1k*rF2xPe_YoTMjn>4rPto9ea{8mHexDu}~eP5Lf(+)9@zemd? zpPTBk6#sY=0%mp*?9QQu6LFYjJ;6%bNI-6eOc6hu_|#a7k`&I{9fay2j(An z8PSivXjDQmQTWTsIxfs`_fQhq-18pBe< zKV+cP{p`f}*e-J3H^7-f&?%YA#t=5XYJjIezabfPNh5-W^xV%*r#-h)hme4s^d?J6 zF>7s<<4J{K$r3FJp+&Hd9Xmwotu<+W z9+1>Xf--8dA%@e`YA`jkdC2G&YVxjG0~@M{pAUuBhZ}FCc3&JlGycZkaxoIos)n(& zok$~zB0o>zXpdy%ny2X0=DgNV{7S@sK4JgpiSN1iRcA|YMPP_P+nXTtQIqpX>#zhF z4u8GGDKA_tvJH8kF_c=y4Phc15pOX&{obhEnBL5m@eXpz9IH2LX)L1C4poWdBP1sY z5-4s&oxd(Lo~}iIj)_1r1Ei@7bjJl z>!1Ej2WrM*cr0*#{wT|BKGpty_F(RpoPrdIP@9bSy9f=oo*3riV@x@|?>!$w6KXWO zQ!>ZdPzsd7g)5GT4%ZJ%6y?f|k6Fy0U#EFcS}DCmcAv&}%6wi-88O0C&o`VeXD_n& zBj$5zfz=)5;xJ7A1g`^fvLbqgl|FR*%Ocrm-YTL$$qvikEYnm)FOCdmkGHGO_<~w) zk2rc0@NWp@k{{i-K+Yv%6^IMPY@ssjWg_;`Ng9!i+hD*YoQ}z?F0p;EQ_#?Cz$G;6 zV7L%xafiQkRUFSvdWjgz_*W$dC*j$pFR`ZH5SufyKL=lmrI?>X`5<}9*UxgYG>Kt! zA5Q-;P%(v-FtK%i@f~nD9ODR?D2>dX>&*?LKUeCaj)?AJX(qijO8-H2F`nF6Q+2#> z@!rIM-qSOkDG$_5?m-8^U$}dkX+-btWUzi8*1tE^gICeUPa{} z4ld7Wj=y`@7FL%#mPnvQR6a3Bo{rF2l?-9F6pfYo|%z1J&^RF;vRjyua z4nw0Vw*1#?4qNmK%lYPDVXWH%uj71+gvTB2skT`5UALRvuX&DXw)T$-l5?Y!6DD#L zo78|FzLs#saS+sn_%^0DygyAO9@!3eKJOVK4)-!Y8F#jURHPBTY$V(g>f z;ydnNr>T~q)z1o`r%TIGo@-5=dDan~!P;KAkQ{WzSuxyEWHgDt@v~MfO$k4oQttLw zyz?r?rYBYH6KtE?tcFl_*qD!f=g+sOD=%Uw{FD%{O_avV4WHIf8u=|&VqppE_c8TX zo`(ECiHCfq_qRmTItz!`>%Q}AnbEV=vA+9lo@Uv0*e~!NrJ*Da`>9Z1R4JONnEinT zqouVjO2`^oWcG8y7bL9>mx^5vALWZ#*uKx4L#>V`d88yG@r*(ty4S3QPE5**Sngi7 z)8wDU+@YGRYW8faFU?=shl?5JsfCtC>^}D;@x+p09Zj~B<5A~Pf5LrZ$d_^Oc^>ab ziLA?fh}kmCS2wV;Cai)sBb-k#(ET}~iK{l>aO5)kxoF^Tz&_g={dTSXOD&IvD{63O zbx7dR3`4wEqVpE&Ov6c~vAocEtRBltx^>5mR*@Izcg;CHij%9Q>ldu?+xNOy%y{>r zq=bbnO_?%uik{-h7}dM#r90x$%P*e!m6}M&H#sYW;iCN^pN|pq=d#zsME7Cn8Q&e? zmbHhq|tM`W< zWS9ikQ1SECCWc=q*Lx`ERa-FYU0@asH5l)ViSJ$%Wh!VtJWY{A8(-uF8FwKd_N_fUcpRamV*$1)O%(EsBgc3fm8Es;qFouh3lyk-=%NX10 zsU0FQ+(2CA*a0lEvt|8)L`55?%=qiV`SUNIIi?G@rg|h4}c1s26 zK-q3%A$Pl9LeP&f4Mvh-f0_h^o^0Mx)x%5!g_3wZ+z;4G9LK@T9EY1ZH*5hYsc{Yr zLI2p8dbt?+cs^V5otfAPF0CeX7P z&vt*N%nka`z4XI4h~N(X6aa@D zE{<(B%ioAHchh&6fwRMCvzHt2|0RJbK?h!BaLzUYpVAZ_hxbt6&rqh%%@(Avva$jx zM+C@modZ8aVc)ct=rqPb9$n>q<_IsOow2JlN9S(M27C3;} zy!pv55%Gx;Aw)88**<&;B$XoNZ?m(hm?T`rUfz(7jFsw;h>MGZ3HoG%lUeP$-R#%b zz&!xw(vS9bf4C~nR9lXt!-e?;1c-pt0|;5aw;(I)CpcI>1ZF+t*!GT&Pa)BOv~k_S54`## zfC&ySO~%=Q7b#Tr2P;@q=<%TD40X@tl@(FI72toMz-q?)zakyrIDQXkwb0@rrC|n$ zL}0*xFpq^a(+PZddDVdzd%E`m4rE~A&MUaSw$=%{9gdr3Ft0)orPI^N57q~}0G&b5 zj{YvZLRwm0M))uS9p)(rJD}vff3ep(nk|ksX6cev2Wed}@U_@owv@s3JXo>t8H@y2 z1xN!ayzOdwJ^@fF28&vR8XBP;0mc%a)(db#G3-xzj&P}mY|{Y<;ncE8G5J>j5Vb?X z2*`v9v){?C4h%vD&?d*3U6}Stpq&F>tOLm8<>lr2utv(52#AOz0f7Ofa5g}WWdeR+ z35jsQ2eAr*i4M*bkaPBaI}iT(Hx>J)5(p>o4AKI{Az~037$ks21&of3l~o_^)_Hd( z5hNW*@>Qm?2rkNhljeb4SJK9YIWV-sVq;a-hLk~1(*OiEO-+v*Wa!jZUSC1hiMw=Qu(t1lxb3iR z_f3^)e*z?zkY|HadL@W%;Kv18b-Py6$sq0kVx0M}FGPTvAtAsZQ0#ziCfK?cEN~Js zGBUV#FAzd~&1zbJq{OteUO4GFdWE0*;Y%eQnmv1FF~rR#Do$aSc53JDAV5qw=;;Y*@$m8R*n>_RDFmNM z3Jg_lqhLItrw^fdllCboNeXl(P`BRL+(gzlGKwaWV43oO4>av0AL`zS1RF+^#BDbK zBy6De{OIo9sM%=-mk_AwkCo{OO)moju8heFC_ulqYQUT_@!cKcZKZ!KA4YzXzyEm2 za8=V)(^oufB>#MuF}3p-Nzs=<{ms$jcSo(K-OKMc`FV~XF}Ui{$f}{@xpMB!qtM)z zr2c%9n3M#D$_G;(aRi|Ld0Sh{1$>3Xbt_$E78Z4Nb>jhIFYpMqBL9va@Ln-j%I9w_ zKCS#)zy)vHgBLx>6JCQgVgjEFJ($-c1lOSQTWM%+`tyIHq7bDx&4=ECq0vKP;v^$4 zmVx9|T;aW~f6HAs!s%MHDqDP?rI0q`)nAy9{}S+8HagECYRyev+EbYbOg2N7)fgdJjrG#gfGEVpp@cdshyW5 zWZlnvPcgIk@83lcKwOc3*E>+c(E3t%IjUrVXXW-_rEUl7B`hdH&;tR?__|PeX?r_) z*^#9v{Yx~{TzqUS9;`D*`|C)brQip|OA*Ybj;C+F=(0wCTF^KB!qYuJ$oZ0ZowAd| z%Hz(wA9vbnKF&~q;m4_p4;J$gCf{QMtgkpwR6IE+26dNwL%1v=nGfEiBpse=X@4aO z{u5uTyZI8U;q1&wKfdk914Pio z8$YnFE!AxfL8uHt-BlJaU0iiAN6m6^8;D~9xafDmhdCGGz+@m^6+Ix4u-agOuh+2p zsKHtX64e3PXl#{H(0Qsy$A7 zg==S=az;NftMl`9^n7GWsV($p=ZnCVMX!h?f261FKRJF|RJSb5N1Vp{vX|Ygi{(-$ z>kiF>ABveaE+O4^7_S8}av#5N9Rk82H~_wf;0RuaW*{wbcXuCZ@$o`}2Y+L{m;lgV zfEkwoWrKhVdWYvgHolty5F}8$Qp#G+Lj--!GvsOS-Mwo& zDM~%Ey2q$(|6MO;(u)r;?`7vPTwTEP@CgqOAtfaxY-GHSEB8RG>AuaIqjm(UX^3VV zU~+-bgn@1bru4J_(Lrg<$eGoZ+nu|25$!{MFNA9kWJ(P)D~3dMY63Ar7*BkpOn3D& z@ylRY5AGJ$;nzQJ52X8q_#74Ca*TBr)Dy&pT(|4FF&4^?Ka{p%NU=PZpQGQVW?-!@ z6Mx)WCCWTE&_8m0I+nfSk@b7w zBZALLs*cpMs5|TVp`7%z!{*pJq%0NQov-OJ_QH~V#gaM7)J&Dd&79v>_mU*EEZNZ? z6TiG-S;<#h8U;cUxTOOUYgv;7dnBOpr%RzM*G?D2a9{xwEl}SLI>b%4X2Poc{rfko zNl%P+ytI^*u$mgT)~7m~X?#Gq;}|ubqVC`P4&A!^;UOL%{BI9y-Xu4|OX__K5em9Q zAAV#YA(6WLYVY+a-k{)h-cK7swa5L1dN<#@JKt6X-Q-BUAdoSB0B3F@peirL>-jDM zlmx-}sH8XO!w1l4y@n{v#>Hg{|3REB%5?CAFYSQo)#CD0x>mve=7(7Bd`sJp1n03q z+kexG(i^dK{zt`Dzv$m*XXBe4lP{`fq09D&4D8PJpXE2;IT9}o?k>E{LM{2q_3hs- z^Rc#XpjgChifh=v6TU$iArbZic*yK@d_lJk@{xmCxB21xH{@AaSqNMC+Fp#{n^Y)W zt!(;Sq^nA41_Gof5RQ4G#73_Ytt$9KKI(cZ54UVQ?feDTzvZxIex)SE@68lUGI*a3 z10|%+Lv-tui}@J2`h%AWj-Zfkz}ZE3 z4XfOV(J-eMG68Q(P))CZrXJb>8DIaBMOdD9w64MaPs;C(4aaVX6^`0#kFenIJWtW? zCfwA>EsN&ImO=m$IjCsmAhcuu_Ecqo;8%vZj;ODEI8_6U-A2tK|9`k@H=e8l-ly2W z&`Zo^f=p@NZSnhE=n?cR78-ti9L%>oUnu?{-f!`0_3OL?=h-8>l5_mtsTYel_0cPS znN^A>5Aw2aMP<@x=V;zZM);t3`TFIF1v7eHkw$Tn}Nz592_;uws?SKI5B=DOQ;@^4*0U$$!7^bLv$mw!gVDH%Oaa9aQ4IUX~ir zs$LH&f60G{+yuT+NH=e7tj~PzsCciwe=GdaTbItlaPZ&qhTK@;A7PL9p0Q1yD7<{5 zG`-*#sRtay3(7wHT_fy*geMq|?PtXv*6Ab?2V1s0YJb1)ZOcCp__+H0tAlgVa&WQJ z>!Lc+zK|-1!D&fjEj@x1zLJHs^B+knGxzMmm2wS8CHg(4qwM~eu5p(XtZu%KmNwaP zChgxUaOW)Wz#hJvzrS;~=t}Gs=a%7prusq8Pw+6#Gx@gD`Dmpnl{SO>@&r@D4!2^Z zPuop1WkTr@{qok*tDT5fUm6o)mdCqP{Py%Oe(ZDZvqa!Lxw23Nd{LC7 z@3dXYb2{2k)m+JZ6dtn%rRrURAGBX$d#Ylb|Fa636i4_?FA~yZ_||306sjCJng{c6c0;h1&eQFE6SSO7#^k+=-qgFKYh_OP_P1=5b($xxh#DOyLNhZlL{lREfmwjFgpg;mNMY5hpYbKH@ydKEmIt=vq-n}QN0cg4cc?+@4@gD`8 zLag|hIh}{&vvux$9u%Rw!s&YR!(jTWP;;`W_G+UPuaRPx_1bm6GHujBZ;h0*p_I9h zwlk8YzRxt!+Z8mmFo1A`f3GTG2>QE3WM zUo0vUq8Ww+(2U<3MR&_Iz)R&~1aa!`$Dz|Kayp%d8@8&viIX|ZA8N$s zO`;)98VmZl{+Ou3kw@je#8Ysbx}SN6HmqmJ{_hDVX^PyXQ2u1IG5a@v&reO>B-!+I zLQ{dXb8IZt`akupb$>kWP!*=9z6S9)G*URw5#Kg>r#*P1e7p&hlp1+kFz{D4F zKY_S?yhC(sh5ga9e}q~mh5s;1-#d`ia$jveTH+KVBx$z!=J%VG@e`GUZ=d!!s#><& z&QCLKb^f;oS{NHRg8s+3#+|9yPj9-9UbvsHnjD&sr6soJBTXgXo@A_+m;F_oqom(r z+ls6u`bwBgoaM3qktQ)b@879IAIZe$v>1tF1-|Ez+1Gsu&GD-a0k=4bUDkG|>KhcE z9ns(9#N-JFpeNq&#?ZScR*v z;#xZ5%@d}Bc{I{_x0DaJB6#q6SG}N^rk8(cx^%W5rpX$isk*26w6MO_2;*vPrrm7c z`&^CvwI#Gl@yk;jsXc0wBl*v9DgW)9Qa4+IWSxGO&_?%- zL;+LkET+3NebirayX;?O3Cj!^vqcIDc2A|nyn}4LxSdOPR)S(tgH^VpW4_#Se%Xs- zCGGBP%|UWfXn#;3V==+(z1$f7x!p74Le_07hU>}k(jcS8-}|{Vc8iTk_+vX$QFmw8 zIT**17W;RG&o9hOgRX@uJ9#uptl#5b)}1^38gMy`H)xcb?cXg>*%p=_ z$sGB%tr%uHRy}-p(N5CBA1_IyHu#2VydUsUIB5vf(qsltsmBz`1PwhrbQ*sb>6&`y zF8;Mqf};he(ywr{wn*yVo?Mw$L87MC?jpfz)tE}Ag8F~P(i7M`AKmRa2O5yWOky2i zMW_X|?-Yv(Wxf1N$XsWCBk?QG*%d2(F3#DpbX;Kyzla;96 zjxGFL#dRW?jrI3r89f!<4PBX!X@V7Uou1^NqUu@aI1dfSjj;z!R=GNk?9q%p} zD$*DAFW>u};)7=LndQu2kC1;ArwPtr2{RtYsf7)VMGWCj8LCWu^m>{+HJM-|9zP2a zxn`K;?b}(_3DkKcVmwG3#uqcn66{jIX-UA)h#SlB$5+^KU4vq7HhGu-!Z$XmyHKn> zZxsD{;}B$S`obl{LJx@&oN|qoJ2Y=e-ut{KNxPa|*V82G(U(gJM|%TyZyHfD1Uk33 zs}r`YW_p%Jcrej4aq0n{-oNNEe*)V~W5@L_?7YNf9 zAS%{-pY7A=O@Lzn;E>C3-nY|UgMJHnpwr{wIz1re`Gn~D1v&hUsGjX~Z8)&X z5M2PkkEg-&h#p+Y5D6i)4Cwtv4ICbK5=gay@DzWx2aXi-rP{n;OZF2)>=uwZrcD9( z@vWX#c{KzhW#Rl8U(rz`>DOxd-cU_h7J_ z^Q}VQqhSctI!?>6kHEge1{luj1qgATg4qdF9e@@^^7QFbg!TvsaF>?{gYfy^2RP05 z`fQzB)fmCv15En#>URStMT@(5F`EXODd~UmaU@DAMpixE5Z9DS>#@@B~9UM>; z%k^Ky0UORk@QY|L4g%x`*B$`HQu&X1{|9V5VBOW-{Sm-q{*#@_Dl-k3HqfLtlbS0?tptWQvEPm(cc)iMIZt9@!J2_|qK3Q|d&7Ev~d2>b^gMkwPX?xZNI0<~(=mt3(x zo&r=^QR_C1VBZ6nW0?v$eDs4DBWjO%9X~)t!YnxhVZjFmlVCh$o+h#hI6A0r?Qr zSA5oc7|V34b-<{`I#NqreMLRBP?;X2rn=L=2&PG(Tj;urkniPbsxWPFPR=vvd?W`B zA_?p!A*9Ct8Slu%L_VOxcHVQ~wX{%!z77abTknBf`uoB{x|eC~qJ_$a*48ORIc2tG z&~W$fvEE7Ry$TRmy3Lu!O1*~q42;(LcR8|;j}LG6K62v56H!3}JG)3QgaX*C`}h>1 z3y@_SP^Pqm?p0SimZX3U3L8875(I-uGAwlTEW7y@-j>eZUcdxgGZhQj$>Dv3VAu6+ zdisS{EZCzoPY5611%|Ef)zO4?{Ld2uZlbbK;| zH4LQ%MW}5c3Nv6=3@GCSs)`hd{J`EU8k_?cmX_X^l-Sg+AN}7$ko^_?$hT33Dovyj zu3atAEfhZB@1QvS_xEo%Klke5;ycjX!6T0-!hxaMdd;!t$*wGv5)#293Q)#X82E<| zA6C8!fpw4xsHqVWc7W{u0kqS%&dA6J;X3-Z6oNaN35Ho8;cB3QN7%X{a3<)V3r>fE z^|J_jeb^4zK?y%0jFthDMMy|kZukQo7Ge-o&mcHu!DGW)yScF;0fii;Jef?GGnfI0 zeS<&^W-sGXfaM7mf|3#v_ujpG7sITR1QoA+fOJf1|GNee7Au0aiU?07THFx)FFUU$ zt1TWOL3z(}rvZ$=elj)f8>uU{&4@_?h5@PSn2FD{r^m*2cXRV%d&2_oYvQu zAN?i}RA%26Cpc)<{P<%{z}V_|-~Ze&Q>IrV zPRWR(AKfKD=Tl;XDt)K2Z%lTjVV>=jehxE^>2sswmrQXscV$hg94l@G2O;;2Hn$3e zRblrjbK37sbdsOUIbj8{oTSvvJ7KBi=H`ZC?(X#F=Y)$UC!q-9VxTT7^dIB(D#kA)Z z?X?ft^qcliPU3;&UZm{%lL~c0(l8C+@uJ_mC;#&0+pX>G@v*U-t*tGC-iK8BDGq$8 z?YkFi$#yHS(iZgl61i-WNFM|N8?$t6&GfN==OKAKjZ_;?n4+QK(x(eBHzOhp(*T|~ ztJ!{h((og=1oXHdbd}^`RfVo(+JOd_+pA}ys7P%IuVRppMA4Am-q-N-@|wlCZ6DVX zmyd*mmL@6sO4-7;P7A)6genFLJAC4fcTiA@a&knesHmpu z9kRjEVa1uR26oIFV=pObX*@Er(ujx$zP$CerwJ7LVSo4c6{Vy?JiMS!@Ycr0P~%=p z@s}@*DEInekS^;0?jD<(Dk?2ymQ?ifYt{9;a)DyCv}>adRL0d@T#m}uU0ht~xVhCH z1c|^o4DlDwFD`-@l@t^*A?Eei)-ixJ7u<{E%~69l>{UbeS(=_mhJ=TYgAIq!(lHFl zsi(Vp2!dg3OiT`tbxn+o3knM*@$m4ZGBPA)RprSHfZewm^6Fa)8Y;FAo$lW#It?AU%CWF>S zdw#Z_zPh?f1wIy%BX9;$(a@mFA1!>bTQ35ng9$jg);O)pLFn^YJAmn`0WJWmG3JN6P&=6-p*fTH?*Sk7`7=3DL33zpiMma;t7|aVL zV6x;D6h0>?};!r@Fd2E}N-mlAh3uHOPB!Zcdj;qf!(q zUOj_@6L4-(k(bXH7?8swAUL@7R0^pyW_pL~CSZPYvaqO#{xQG1JeN_QLLrI6EW+bSI(+}y*jVFrVhgemDg4maTD8{0B3J@Bz!#B- z0vAOp$-Sn72zCw*yoV1n!IexZYPab??(Fnb+qn^(I*&R@?7A%l{FYXsa4`%!i!#i4 z<1DizJBEl{z7kY3gP_$+QC8N|v$M0!=99VTe%EVOP;%taq`3==N01KR#^TQy8BwgM zt}giUMFt2bjnC+qndP7$w03g6;Ey#nG?W3Onsu4bS;w;EN_KQ~L^M~W1DhR!Up(y) zxWdfM%|Ep-!k0W`EiiF8poW2UJCX8PVtw9<*tkNy8b}oo>I$2iXPa)m`#V5notl~& z`~ABBH~|~bPhI2}r6f2emY<)WD{E5c7&4ejS)-?xEP*G4IPO$yCz_JyA?mG=71Y#S)OiWCC9{V{!feI3E zW%7G~O|=ln?XV#sD zuWte4$Kc>#Q$j{=u1Pn$tgLLj_MkZ{h6u=k*0^-)F`>n{X$Fvbjv}}B4-dzn)P2;$ zP=?{f$jKQ)FwTS6Nf>t%REwdnb4gMX@j>-0eCiC6?WHd-HnJmOBNABgNrxi`mc|;; z#*+9wD#1gB6Ua-5`>CvS>}H2DSd;;wDIw~cpABW-Zeo%X5(Wu>p**0cvtn5wjN zDA+kXlY|Gk4)&$~#ONFYwe|iKUc`A{(cZos&cJerP0DdUbod7{Z{6 zvT{LQo)`(2_0ZMHywH*ih7o!G-dnaF!wOm&8gU3FIfBql8#-re0bA^R{^mL#R-*LI z&JG01c4pN09I$QJf)A&szdyF$RLRsdPxXts0la59ayu{Cb_5=w5^#E;Wo4BIF&N_Y z21L#e3o#!G_Z!g5Mh)zD3$Co8;x*OiR)&s_UJVCNc<{}kKT%I_FNc{qoDWApkaY+} zQ%k7rqobh>L$oe|`I^&?gnvCfJ=Fjblz_qZ)zy_F4=Kdtc(4@x9%|0tvI`tO#OD6L z-_ZXG#hT>cu_YK4UtdO)W8~vQ8%QwZ2tdav;HspeB0_$q}jXe z9UQ-WWW+h(zijqzLziKr)?D%zK!#`V|MpPOc8}3JgB~t<>+a0y#XW^vrS{^K5=b0W zZ&{I-KlH9Xm1;Y>H@pxJr!F-$g4?&luyY`C*#EwEqVs;jU{CZ4wnOA%e+7tu;o;$y zHa05oEDxld2nfnOWHu(B`pzB=>?P3o$l|Jr+IKOmWWH=?=B%#_OHTmEB-<_D^ aw{N)1+$Ie#lg5$YpX6&f(Nbak_x}fi3>b+3 literal 0 HcmV?d00001 diff --git a/binder/Readme/TFBroadcaster.png b/binder/Readme/TFBroadcaster.png new file mode 100644 index 0000000000000000000000000000000000000000..97056fcc2dad996654b29709c4aa6a1208b20965 GIT binary patch literal 28874 zcmeFZbzGL)7A^{+sH6!95`uJhmy{sgjdXW6iULZhfOJbqmozBdNQr=ebT`s*#^+jl z@3rsQXP>+8z2|rT*{mN+zL)vVcfK>mc*ZlH!7F)L2~0G6G$bS>Ov%ThibzPv+3<`X z8tH`}X9D5P0?b83zT_Sh-mtSN;WB zs;b%Wm$?B!vw=4sD!I@Ku3YuS$;D#mt>&pjd;SwUC^tAFEjaQ}N73x&>=%3N&54tp z3D>LF%5M$keXV~}E!Bx$k?v-hM~U-ga3jN=S*1lmKNx$2p1g2mddOMMveIdgpWG3wnF zMFWj_Pc532ns2HMQtLhT%yXEW$%~@NQ=n|nr^+p)b4*;gF{9pm>tT?*yzou(??D3} zBMcr$o-h+%q^w4_XS~V1CLVSrGF8~+?5FKkO@*qBL*o;)7QcPmwj(@L9+zhx!}j&z zgjqh9E+;>uty^Xs@r#uk$d#dYxV&eBf;%E3Gm66C>i3LNgu_@3ZQzar_s_GCBx;ns zsewTC-Q#cH+m=z@r0J5|`1y-GeJD4&DsZr2wLacpihp*3%z4`(T&$sU6Ske3IczU= z8EGCvTWbb=BU=Mw1~+Rv*mp=se1dLv`i7RqP9z4#rsg*Mq?{G@8^GE6dd zBF1Lsk3AfWl{{pX4LvLkxs6B#1bnWld8+elZeQ=tI=l(a^!%&dJ=?h6K^4 zzJaZ?6F(^_{GQ}*~d7^xOs}ob+rQoE-FACi-0TEL<#1EUd;R zENmuBf9Xon#?eXN#?Tni6?D#E4*hVmv9hu1vl`R08nLm{vzZvM&~tIVrHUeV`4UeuDH4AO}M$)IJu1U z^*R0=jgcXbxUGY=J}jrXwZ5q_qn(ZE?_nY)oJUw*lAn}?;g6^Oz9Mg>?_>fu@RLfL z+c>-Zqp7mFwXu?uK4LbRIhmN4xLMhmS(#b6xVgFh(MZ+U!4Y;MqEBWf23EG;zd~+4(>C_2*jrAAACI{ojZDNAvsN>H6<<{YNwKA2t5(?)vX^{YNwK zA2t5(?)v|1y3qa+P8r((3UY;D>B-)QJ_xi>4W3AdB3&TfGgMS9&0!vA)((! zd?O>pCE&rut4@+KVpkW@Zy=$ws}LNYA|a6=Ns0<9yN#_)xGLXKBW~T^EV+||c8TT& zI){+_4Fv^x5>>W+qGEAFbc3c_1Pc8((9^`zT5sJ&x44xT^ot$ekgnKrt1JY0@XG1YF506YK7~8v<8me@6yZetjS~|(_!2?d zl{Gc#Sy_Qn8JE7EozQp;I6bP>cxqm*X@2d&IqEI>N45I4Qr8|JlQ;7cC_f6SxWIqw zck9t3$!p8P*B`vN0S&G_c$o6y#-nT3ss8r)#pOu&4EMn0OK|gxH*m|JpC1dsZGU|J zm$wC7kes=u-dg>ZKl}5GKL#Ps9{u~cj<>esgQgvK*}|i<_x70C=z~N?Uk{mmeU5W( zTqJKgwa`b7a*ySL?LDRhQ-<7KI%VHMVN)Vw6M0($hFq#~YlbOjs%M(L5)WRuxq8S$ z--f4$+j&|QVJKIzPV-L`%VIz9SAL1DTa7&!UUb4Qc`-}fcWSIm{wl%~+wo-DyLW@T zojpH+W1m-yOYz3@QLzH>ZPvp~9=l!Q zOuqcK^R=e8_&~Y{E-HqNjQR3Fkgt59Zk?TzQ*(d++kuQHv#YCJ*$U~E_Oq>ms)0X$ zKE-FZ*i-Ea2@3i=IJirkbI}?~VDIEKw=>`6@JLdquFeh(1LIT+d+_tu8zN*%Xy3V& zN}JTA3Fm^NlHT+3rpGoMq}s^L-eNZ&$!EpX+3mvQ*$yu)Ej8>-;O}HB1w*Y|^w8)HgURJ_E1inK$*40X za(}%xPW`RwhkLZx1})9v>iqRrqkNokyA~K8oF7DJOAfs0TOre~CHPwJ$jXOi;#|(+ z8!r^`wVaQsP^O*a>Uq%U=SkKI$v(B9lHvG)_1y*KA`h_&Y4`Rj>nE>{+zC!(b?0s3 z;!gK_m91|yo6_?Ye+%rM?RQ!$j|tX9x9}}bc*`zBY@6`qoZ5P+VTIy5hw;w4b7i(} zt%;VJFGE9-ett+3oB5jMX&R*_827o}5c{4g;6Hwhz0yD^E64H?FKOdjwt}0}-i<6) zM?DosV@xs+EJK%5VFrGdO!?_cc8heLK1t#iNqVKTVehQHtp`jCVM3;AE*~sqDAki)mv#_eqzcP4(=vtt(r0FsI?bjtZSl$vYLthLn<* zue&X;cL(zp##3MO>%^<*Wew6Pe&dd=R>YP@-GceEKWE;nVjsV%r%ryu+Hkrgg0J~n zbQr7puU)D4g~zeP$7GI71m*2aEv%nj07O!DP$f{(GmkYxM=l<@ELE zHhAYz)xoZ^^PN%1hi3;%VpN%@8O6u+5F&w*X+%diO1t}+d@xOsPk}s&!8g( zM=?gwSD?SYABj${J^>a3Ni|RXt@U^WrCbRdj7K6O*D*1TVPRke7)FkJVp#+G(#y|+3N?!5YKd(<>Jb$G$sWB_)e z@Z-nVT7q#+XPRFP73jpn7VWrBCgNp_Ba1ZK7T&jilDqc3cs75e<7+z;EnXzX0P7v5 zUS^KR)fY(gDZRGgb?)EZ#Mr+I*t_>W+`pm>4~JFw%F;2Z1*HYM(-&<C&^?3yss85QA{Vg8z`nCmN~0*6)jNcY?eYTR5kG&K#Zth)2HDv;Ex9LTfe zl1Cr@T|VfE9~<_MyYg|N88`uM=CSxf9|qAhAdz0WZs)B*!QE#ak)SJD*2Q5 zALLUXAw|-tprNCqPn>u6^k@`4MSlPOJ(6~%-LuNd%7m$U;F!FRop_v*rEY&S4ur zsv_QzKT#|*Qy3U1>79Okmo|+GEfAad+m*;-`+ZmK^YioO=4QLuR?M}vHHV4l#Kc5~ z1SB+E25AEWgRs>kF8k*nK76n`=s}{8O^C5>-`1#cSx+4ngEjXLxvT2>eiGPraff041|At^PS zyqfA;o68#HJu**1L&+@}TDkEk*<@aK`kN$+`!N$C%?6XT(oaXE3QgquQ&hFBwGmSgY($ePT z<>{*HrT4#yjQp@#$KTc38c^f9S+832m_$o1nCYG`88 zn#k+wkf%5NQKfWJGe`HVprf@_JhT0x?QC`=^k#bv%I>JHf)aW`f4kT!SWMRCNQ)nL7g%XiEaOIIoR6@o=r z>4$pPgZS=jy0#|&*$j7q1(LHl-vqtWK|o}P(|}`)RhC*MD)Kyrym6Aj@W2G0@?LT7 zw8XtL&g>euEZAdA#+`Sxb#&|<9Z^1abp<;v_D=u&=@%FnxUrZXF3^c1fDL|2Rn^Oj z503C125qj@)BY}=n|J36`{wAhKG9`nW?D^DvybnPNTvHa5*Ob#n+=^ay&7m5<$6gRDVOqZ#m+v_rIu0EPHMJz? z308_ujSHOJul3%Z$9v2E<>l{0UwC+*-Z2F(85xXW{@2=Q1UNm|km3M( ztGtd_Zr;40PVSQp;mG~GuP^m`Cfvww^qn9<1 zv23trE#v04i&mk;q7WOECF6*V;b$r+-HdjY6eyNR#jpvI!*iGn1w9q-?h#tZmqs2l z4(rqsFzD4w%gf)eD35D=i9WlyC;@KQxh{#a$)YQok&=%uVY(?WA~yC_d_2MKVqc%j zRF*=z_FHHIXUBTyABzDy8G`qMS^iux zf2nd2BB5uRdd*_dSnVHDs@jX9nIF{@&%}SOK z6RT_4ob5Uq?+)#@rqcX|l6*{WMkJ3PY-Rp-oKuqOL&Bt}ba$WClxv)&r1_H8cZD%l zKNDf=ZN|6kDkmMBl0Vec=1SiRXzNwICTuI*ZO^_TE6{UPE8*CwB`~SaFlACu=lg;< z-L%-Cjk!RO?Q^yA-An!!Z|?I4%;TmmWlfc&1nv&H;*724U9;&L^8fkW9LKTdz0ZbL z|E{X*Th7;MDO6~h`8Z+s-tymOVVN11*5TIa@`$QS#dM)C1ySFGh1N z?yTGVxH=DS%P)@)7Ijg2Jv@3yG+t^N&h{L_#tSSIR`d{zkm4dnx%J*JPK8zs2k&0o zxS-x_=BIiviM!c__=nv07g40wGrt>;f?VJI4n}_mr+);a|2jDR9gO}CPX8aqw1%}-VxaEv~r zzT5*6p>T1oBZ7PX4bpRee?9e24)anx&MTr|6aZK<@}0L4``&<_!^5!w)XxFB5fu}Y z6bZg~icQ1+40*%Ye!V1QT#8}!gD%N~kBsz}Xl6HbU;5!ZkREq>HgsQAW#e4B@U^kM zIa6$U+*-Ktxd4vuA`4<*C9(y|ANzy)>NUG3?8)t2=8fRt{S%a zaV31ArsY@}d+G?45mR67IO#<>8J_s7Dj%$>NN{vKJ!UoC?GjWB1=CZ*uND++9I_pT zFz3p?$!ouUlqw}7L(a;2n}8rb%T&vRf|{DTI=QT@%xc_gr-L#CkNG+Hk2iw8=eV6A zVPUP4lS$l;3tx-$MXFsld%vcNWE8ht{q8@YJKu)9j`xZBN}$Cr^XWpnV_$-p^A=rM zS#`+w*O(5-PxpTMbsCrU#@&W&H5^r`;B;3-K`DDIt8BZ3_ym(d#qt& zpSb5gHlFFV_7_WFjJ#G(w?7f0+gLZ9=)383vWtu!y_ex7AirT{>=Y=_tV{d2rMhQ} zwW_n=m*aJ7-xywI$7SWQpRu(yjh&La<~sA}+8DYxyEtxTOQJG0S-%EKb3)3Av^{(# zx>@Pg2H$S+|J1G^pLp`Is>t|maG>)74Q*_Hw`{A9;8VE`N@PG7Apk6vd`5#vQ-F_49*((ta`=FOob;XVAl8P{z8~2JJak^t*yFq4$?1* zR+bF?2YY^j`I%eh@&K zKs4f$S69f?JL*wm=3o*2lCX3~=WYUL!=pUBFb<-icum=EY?*qmBPM3%>9KOlYGdb> zp;W8U5~R`RG=%`L>7PBEw6tCB@!+}2VLhGM8T+2FmO915Yl1;OabG4ue&R=CCdxfI z#=(k;;*A5R*BtkyM?RuzOMU-59TFW?Na`EKP-Z_eD}IXaBIsd{*)wl##h>$qCgn=G zl}fd4jL5p2xlR{BZW*r`JEi1z2cni#WWv?E1BA7&RLi7RVoFL%4iwFxU_<=To7@m+p!s?LtFQh{ZC7FW79Pz3m+yA( ztS2`bXGPxZfs^N{#nG)Td$B!6TZ6OI5VfJ9_bkSFKfjpE>UnPKM(*#36`1`hqE%(n zl9TQ$K-QB@mQ`n!7&6D@a@Fv!esMdjPgTkIrJdJ* zkj=!#MpE&l_Fa|#FA>S>{G^Q!Ls z=<`cG<4H@S7mqJ%`p5e3vgSExO9c9dhxx+C{-W;`%QdF+Sw0VyAW^V19|&6jEP$^U z0Rawc-wSDu=o!!=>>}X z6z{$3d;IcUoYaaVnetef^1z+D;zt+?$YTUr--`qjPle!hMCRyu*} z?f38M2?+^HW978q*rEe)h~?fWoEpmfwpWU=nb2e*(_jX5j10nHzs?q5;Ns z-g;p9J{~RZS+9Sa4j#EXahH$4t8cC0;S-obo>4C_ueO(ArCdZ(rKOelWQJJ=N32l9 zbFOvG3xqdL5SFStJodNF4^U=zx5sp5Cbr;OvG?o>x2j8Dy0jy8s=Yv`)s%z5x;G>{ zghusxWk(Z-{KvqrvVrpu^8Evh?%a_~i?D+jLvknc58=(WxiF376w@J|0%ak{*%~vkk-^eK)=7*tEygJb!uE5Q( z;uI(}e2GRiWlR#vdAZcWj=<(ZF?xq$!YT z5!DO(#~<#SJk7sgHd67`oHBdlEvHrK9b#>1lNM8>@LgKq3M5;6sZ&_`Y>gJ0L;Lo= zSeYpmu-ETnu_c#W8w6UnE#G+BrpRe8^CZ$|FMHDupC0%2H%G3)gz9tMQNgwk48k&k z5}7?eI*<9oi4NYdXwZZ*oU`mtnr&&Xg6im=%J)EK*t$z{u^u-lB<3YUa*s zlIR^FkV_a!+4A%pxVAIAK5S1#dECQmS@_AUIi{|ctTTw=ZIC|h?KvI&487t0feH;E z^{_?1MY)lY(VK*X5PyGvwy+yj+48BEEXwhtXjU-~BYgFae01YvuRUn4dHg%;^cS%G zFSAhp4(R_SUidf3tG{6OKcM|zZu`sA|CdnzG%)lYYXI6^n#Ur4q{n6iZ^}yz*!v`W z4K_iJ%8~DldR>pX#OLt9)7CPn;6q(=Eyuhax~_zUE_&~eCcFlRq4Q&;SX(=idlv-a zQ4YyBoFDCmbEY}C5~5frXFTa9FLRK+{-9Y9PagZ?sYkTj(M}sdq&0s`P&V}oZ`G)7 z>)GWW+mnz)tJ1-%VpjhK#4aN~tTd0FsauNzj z^|I{vn7}@`d3emMtVr3}F(E#9dYa}o0fNa4haa3%mkBM>g#EI^G z)H!w63RbyC9CsBv)wG9n)b;%5wctS6r{}GP4_C$&itVrIVdlvxG_`G_5#OI}%YKa0 zyg4tOhPrEz#J0wsfQ(7l5#8oL{NpgnT`9BJYL&SlD_$vWhjI_^^vbiaR=>vljKu3P zR#FGLN2BFb&&Wnti|Mq23&;Wnzf2?$1oLj&f45;lTBv9-eoKHdLYGz3qv@eaAl3P% zr~9JJPL;QIrjk9YK0|D9UK#Iz{0fI?@#%;o9~=Eky^4OX;eNv4Hl5MZ%X*{PJBjV*?~lT2(hV48b=Y~j@d{Aa>J>JGu)s*!!xqN}n|+}K zoK(u$i1}>-+6ppQNFSAR8p8;Azn2)J3kwSynV9TA5@+y(G$A-9#G7R`3@I#A3Fc$-S?`>r)Q^!QM&pT zF2tRmDU2OudDiJUyzYr^VMp67fk<%@eOat^z(~X zAy!I}=)qS999NKukj)BH$`H-=eB?9 zcQSfSSYOLk@?H`&#$gTMY}xtj-z?OMD4Pa~&@J>vZLs`RJ5>z^0+tE%p*3 zbw<&)t&dk+M?-6DYYPOcQ{=p=x-r#&{W*$Ot;3B*M}-!y|1f?TOOBUDT*UzR&y1 zbI5h1LzYV&m2Vr0H*H*{aNO?8yST)xs*pdCx(nz6PcJse%({MM?X&U|MP(3UdiRWOoe(it@D(A+-_uXnTz;w7 zmx*8B%QU}qeSkV_oAw~8VwM3brBkB#mYAC&SyT?WYO5VT^_44MX;)qa_T1+X_jzgP zaQo87_gU(p$lV1GC=1#r(!_$VVPJfaOBSd$2CG~Bw4}WJ%1>ZgtKREdSfCksb9A+| zkdGUpqM{D8&rIOWD9x9CZoKyH)}|m)oTC2GwjB)fLCvx3f6rk4XYrN$6&izfE-@EqK>ExZ3cUsCzJOLU{)V6m&+Ow5)7-Bz) zZ>&4P-$NUF8nqrYtgfjkG(fm9&v8@1IG`%_b@!Z+;x3!Uc25}ZIL-q5y<#&S!Y2vj zCZac-Ke{Vbtg5RLdis$r7PPlSq}Ean3=Sf4+#3gQXbi2b^W&Abo59aHUob*OV_{(d zxU}oo*w_2&OEC=4c)PG$Si#ET(VKBQn&3{aA>|+o+OxsZ# zV6MA(eJNI7MTmI)tmena^H(+%u@5OGuQ~>sdf4`<%`sGL(k$`DyknGek7=8g?bI3$ z6+lZF;Y8jW5SSaA&Zj#!!Dte!2|qf%X0aIkKwz5`sKbTc#3wNB;))8>{xmV54+9_> zVO&SAl)F4x$2&be9TOL)Smj_0+1r+C=T)aVS`iVEM~@y|!^W1#9i9P3-oStqGUJ)R zszV4UB@*o0aP_6`&6V=(u#RFe>2bT+D(o~1g|aGKo#w7!gXM-&`|(7p+bEx`zK4Hu zGNxHJ(V=>%QziAzCPNwP+?Mm8yK`DoJ9LLCHgb{Tijg*7TJ8~ytARIqV$>P3D)=VnaA4xKzH^TwYwa(kKY zNO3b-!@pREh98TV#87bX#OI}OpGTx};scv8<#Q(VpYh^ir5ksbHI%YRew?nG`uzCt zCEek!RF3XNWx0EHX?_;3>MRA5jl8fTuX1|P!ln57CqL_dwYlL$m@izglZl6Xm03m& zdi~l%Kaq&v<157IR$U)e^E*dNO`RJc<;?1`rrsJx7;jw%CSmnFIWA5L^bf$>4$)ge zS`g#_-JfJYQer+@lEKG4qk~B$q!YRDwyQY&mC1hRXh>L<*lS(n*E}kj^M}PwwrkH7 z!ba4!RstDCZO1OxClWOdoS=Sx|0{KHkE;3v*K0uwchCOJiVL%V@#)OZSwK-r)MmHz zuGE-%w@R*y9#HE!x*9#~YQ+>Qc23s~mpt4|?C3Lp^+T;a?&ns?Gfs5dfZlk?FF}tN zFqd1c>8MqzsHf=GWKcZovX(8>UoBuhIA5(_Yj_u6JgSKi%l#bnQ#fzD2Nv7LUD4Ab zyn1|>XXj69sf3wx)B4yRD=B>v;wt9^O*_0jufC@u;LFI%xbn z`Lj8%Q~HHq&?_z8kA9B>vOO1+6`986!pPKzgo|y3p8b3&Xd4AKZpR!cUF|Q|>hj%N z-pAfgoD88UZ`-l7*s#p7#TODA`R3)TK-O1(<56uN@-H>_s`1)$aR{WuNA|srW@S3d zu*gX*(9&x>BC4D(>G1gUY+UVpg5C1bO68-P;}=!EB=zm{d#olHcWIOl`v^z=p0L>$ zwC97Z-vkoC$jCd~=2LBcI}R18j`0IlT6YiewamG2S(7v<*Oqx4k!J;MWfT20y#~y= zO4B`my6ICZ&@x8sQWvC9dECh%?3^nyiH!8SMI3~V%kXn)sU2Y3R8Fv~qT)LnjU2@c zNF0gD$t@VY8rl8EI4{@Oks*!DVbkzj=fUlQNw=6lujmYHr9)O;T$VUW=0YRS~(lxEPq6Jms62ILQ$z4$;{A+uNHP!u-UtyU|IV zkS;Ro-C5LlNy@;W&VRwvPb=E9A%gey!y4KIywwcC?q5% zLa^~rKtMn%QBg?=v79O&mA~}#gzm48I|2)e#K+Hn59FXo8yg!S`@;5v;|-UPgTlkx zV1Z#-_`Jz2%OR5w0dH!}Q@KQ*yU?$;w)WE3RFuWOWM6Y$=e6%|v$LrtI0$)N<{-bH zr(1^)4jTZwL@*A$le70NF3?|OfMbSQG{|~mX38Ze(FZwLWGzlq+WSK$Z19t{77GiD z?&!H`Z^9RNZbt;=?Hf0QfJS#R?n&fTQ=00^ZdHYY>hMfS(10Ls3NqB^OuBZAw`t zqxKtM%0wSMy5xPl_ke)`%hc2qss3;V9o7K>#z9MxKE4>}+iwLrPe4XN ztD5(@ccUfz{o%<8$Zy0!u>uLyt3N?u_K-swo4_yX%pnq%sz;+LdqiKS&^ z{*d2kn4Y~v#|;V&MoD@6mh?lGX&n#D0jNKRbmRft_rSKH)~R;-hOVQRjEsV6H{W@8 zZG9d2a4td)kJ;dbjUMELTY7uLKtzEeUv8nITANvL>xAE}t5sVR}v9r;$fq_>5fgFgBxIOpjo5L|JBzt+{x*@p1oKtjq_yni9`9`T5K4GF>X=&DnEfS5F zQRPuyIstCBqobqCjn`A`rW;`=);q-m&QvThl6;LrFQuu852phZjyJ^=O6pE3%FBBM z&}QaaKYy`}!OvGQO@Juf}FkQti-jsS4QRuAWt z-QJSI9Wi}i;NV2+1|04foD^ypP9=^ZZu|3NcM+5SAT_ndZQ40aN`V`%UcE}-ahBqwJIF)m1*<23UVQxc z@zeG<4Lfr~0Xd zMJMd^SCDdVZ4CgzY5*Jxw#%&+%PId(YQ&jD+IuZu=y#a|$mDz3-UOw55{EfHRbTkO)M%2BA( zS(f@m^g>_Ayka0`uAD5RB+Vsj;SM)f#Mh2hZnp)xK+e90PCFNmqcpr`1ZO&iwoFZv z+}+*nH-2#6zkh#gYwPQo*IvKG9guvsIVdVBel=qo&5YBlw0kga7oC+w38(>xtJU}B zZ1_+g(R?uFoBWH$=RQqg+`9>oJh*I5_Q0q=5KMY1x`v830VkuI?OANlGHEf+FBln} zl++6vlbu>`PzK-$cyYm|fAQkQlF8Ot)c#d7$Z3KAyqalaAOjurDqS3ORQ%Z^Ym$jP z@q0LM60Bbj@Ht%BXJ(Bpb>Prvu6W#EI!8vys2LERs%3~9qMOb&NP}{;VTs4>{%{@F ztcY&?NiI$~x4>ex_Gq*3bI4sEA0Hz;Iz-c_XJ_Uk1%%AZ%m_av;C=km+FAx&T5)kP zr~>)hl7cca$Zc$FM8(BH7YqiVJB~fLyIXo<&kV%=US3|HUuQ~9P5nMPdh_<}rlZ|O z=Lm|V?jI-9fy4;;Z&MRln+NFM3~g+B0Rg-U2^pdXm;<2(4?>a-^(BC3xP4B!A}C}G zKuR=}r?Hz~o|v3WjKCL09q+!w9|JM#CxzM&5kQYS+Tx%xh~aUj0h??*@Ieye9?M+R zdNKiUAfPJ@C@y9OQujWWogc)110}{!t^@GSspw3(p~4%MY0=itnB#05V9VRMwTRVX z{TVe3!_6i3LCdAUViG&`PwXd`yI#tia^gX>2%Z-(O>eUA`KyKoK^z<$gdTru%MKxD zggp;a(w!`Lk6p(z*!RG2U{^g| z9>{h8x%fSjar3^iHR}0?--f%#I=9{rqZqD zN*53H$eq3nVxvb=QfMIY6v`bQC^J{G82%{c<#lR_X;@uZ$pmAD=lQ|p0lM)vKbeA& zv^fM|5(MPrP=kLW1&u2&FE3fdx3?F)-(p!I>qg5frLL+~KrvGXVyb`6 zZROPnp+C@7PJMJ`$fDfl8h7E8=1!-lJSwWKz{R?CB-B{VH0^ZGEuF;f5?twy5LBmv zDy!NsHLQ|vze*z-0%)PZ#Ognav;JLT>i=HA^*j9gt90!zxBag1IyD3|`!(7GioUjO zON)!Yw6>yZX=zzmSyei(zDFd&f_w|3FUuEbbA#rx1qih&_gxAon?U&;Gj8`mhFv^E zQ2~CB1SS<#2<{A9eS)YIJJeDs)J-H6dyQbQLD|yt$$GpJEH!OK1fr&FyQ13rgag#Y za69tSx%b`J7D{-3Tj!m*j)tP(;p?NNfe?cjSX-Zo zpMVkbeKK)T;P4XBkWjwf%N-nh+-$UIfqL;JNTNa6RVlsP{~T%P9vlK>0t99RZ*lqZ zWqCM>_YVl~-W7xWJX-CXYcu*!DKotT`avW_@ejcM&4vpiuoNB#8<;{44lD@hEfqxr z-Z2RbWF+|J_6S;d7q{e$j0_+F(Nzm|Wi&N4Ki$x5@ZqP|`t*>WpMRX=%a<>Je&0d~ z5)))rz;7-CJZ%dn?)x+eSk(-WJ2;Yd=2KEKvg_#RO;c0Eet%FiywhKCOxJkxIqxOwlMBmf*j9w!oJW`(4u+nRG-1~1*NqR@b< z_VCaRjQoey4oCtGKnQ{Bq4vLonBVd_otESQWb8HyxUPNw0*Dh)Y_dL9j#9GW8VW!f zyq|ao93N0eoDbTHx^6=m}*Wui07+1o*vqRLj|G<3qpU|{HKX2KPJ zRLlX)RWS*P!CW=Q_l$aBATj0ZAnh{(74Ieq$hhO!%n|2Hquk;ypcf&z&6a3OFv9qu z6ywBxHFndN4mPLy27SO6+BrKL0{}hU8)Z>aKSXy+#Kzy622S|+y-4dhfzYJ=!&$oG~n-c zXT)h^g-L8|YAP-(Lu6RiChOuMNUr;K4)l%$6!HO&YBb&W(rM$zJyup$lfI-Lh)Rk- zeaeKaHuq$-$0Iqpa9A5=pHnyBL&V^$!K|3TK82In5kaFHjG!6cn%p3@y(1>9aHmX@ z9w1go2nK}UdiW%dyq5kHePfCV@;*FcaX^Tdfgk*B_z_0+-xc@%|1Ycfr;6mii@r(w zJbtab1k+w>+SluxXg-)Z4dsrI&YyJiot&HmMDe5v9r#Sq$vpL9(zf~6X+rJk{&xX;co+5qghvdawvt zX8mb^;}^b{I@sF-E5kg#1B4%Bw72&6TSrG@!8k!+?;M`Y?T9KNApxgGT1W^fibkc= zeo8?>0m|#*pyF=jeZEf3dl)>T3KRU&=qKy=jbhlyv%vQO77ho54A!={_=nmsV}%2a zT7k5g8I|=|S*mm_3lvD4W*9>~H(2rOSXjNEE@0o!Lh8fBBs1YDSeKv%8hZLrkZ%+L zIRvTR5}mmbh_8X4l$4X}`y>NO4FXOZBZ#pOCj^))2qq8|S!sU7(=V6CK3R9YxPIFK zqoKY1G2+F5Ya?M`2m_?~QLRwc$%zdBqSNN&*-M9LdaYI{={{P!Sf6m$9vYsx*dAee zND-9gr>ngqOVOT2J`+_yVevW+eewruXvsijPSuPBR;S1IK_y9CN%!gb)|bVRYb$S_Jl$NJ{UUPIeU!kR+_cDQ+k2F74;6!IKjyx* zp8c;p?W%WB9(?Q8EeIN0omU+k9MZr%gJh+tAlzl`yD*&K-rioGFP(U2&7xBJLgWu0 z7P;@5fE>;$#As)C7kuxNxBbJceSH2PKnD|!oB~@2(JdlshlhC z2;Sexp2hr43t+_8K;|qaD$3-0?j>-xr-abU1Bu4vb6SbxPn9A%XEMLApa|uxah$fj zP$VAer&;gC4T-7@h}^}*<$*n-(h*bl*cQ;-Kc{OONv zHd;as;DGHDF~3J76c9!M%o+=w1CM?L16^C$+S#ezVCEjHpIND@?&18H3n{>%T($6U zf#V=xBucEuIe_y7;b)F4!fijA=8KsoF4=a-}@B8u0u zl6_`?NWtPq5LS>cH-bMr0FlUGwX-FW=NdBPo0ZH+6(V4lG=T*)1lQdh?V%Le?KKTIeuA5E3Y zI<2`5Fx9m?owOKuOrIIPiXxMfRtQ1pYzAx+q%u;#8;;O%T7IJgXVeC4D0thSQy1r) zQ1NjJh=Sas9zxH-RFSIyyuLuyNl-{gGw|gABzAjwH-ADAJMa(12N?y6s^x_bouQ86 za%Bmcd?$mFjZML168%g{qa0h2X1;p9>dwwidq+o=jbD2rr{}&EY&DaER)eEmHmmP9 zV4sAT5E2esTqY-V4F#>Bz{%QgR|q&W4~u&Cjy$QuhJ}^m61VLQO(~w{gHb>fJ7v4NizW_)bPx?Fhl`1 z5=BHu>JFmks{HzkbI)#*(xxxUkGs0XL_a7i{_B_cJ>q};5*6CIx(y3iBbZA5y4z)?c{Z@wyneTL~2{N6f7Q-|( z>re#90KT$yYAP9vkf+FekfH`om0&NhUFNWF;Va}m_d8$@Q0%sT3e(}BC;J@dObCE_ zu{)6$*AGavODHHBFteb8K+HgIBJb|65xw#CQp*trpnn5^mXL{K(+BP$f#36+n-@@p zd+X!Ta3hiX+)cO{$d);N!EtoPipqU6-gD4q+&JskX2%G$KqE`~rikOBVN{Ms3YiGuoM&Gr+ z>DDkh+APkR#7?gGBH^h%s>#qv=8_HABeXi23MhWAlI!t3y z7d-r&RLx??u>av_ZNcSb4Ty8<)O4cAva_2AirI*&Gi!C-faMKG0=n^4l-1OHA!20P z+$ctJe*XD2(6?xJU8J(|bwQ{J7-~sZGzoVBExsUV<;=$-jprdsSZE!#w!b zJ52jM`zxg9`56RxQRgw zgb@&(vZ|_QQIR?MaUn;3(xgd}mX;Q|Qj=ANrlu$EW)+~j2`>TpUoj?Z&_wdbxSv=1I33JL~japLyk9ZpV` z>_{rR6OoaTgC136H{cy^%-`4P4}m1uJ3l-ntlrVfarN439ltR#4h{~M9z(b$6*f@V zTfCp%8X7uE>7In+;9PuLbcq9uZn4m9*Q6Yz$GG$NvwHN zdg-2vuce6j8|WrR?vUj`uq8bIW;R3RQ^$O7om|@CtE=tKo{=8!mv)^9mf%pLt=(ES zIJsuMN9$P9Aelk(vZ~56I$D)Sdqs6RW*Dm`$PBA~@-sH*U%V68rVWd`=ffkj%*dC` zO4r$)D~*hd!q&0Br+0QyB08a;07ax`xYnBcg(mL`Eb*Sp!~efz*0tpxDZFzfuG zpLv7?BI+;wd^b8eh)~CvgJnxUE3U*7Z6N15DKE$h+*u?=rg$XwODMV6A z=R`#J9j#Hrlc7l2J6Ib(88<{D<5gv}~*bq}h zvG*s0_Qk#mdBj>G_9mVzbCC*G$-OKsy+b@}Xl%4>sV^lU3;CQY8n(({87HAP@J@pj z6%E;&)kCJXYtK+d>g7;H(S(4?uTg8oET!WNauQQtrr16lk65f{ZZ6+ntA6egZRyIz zSt}z6^=$K~?A;l$rgHaagWXtoW#gvJn}x0HP`CHZqNyK23$H!6&Kn{fcJNfj?P*0~}9#k9;hU3DN7_9(bt*EdBWM z+QD*idZwmB4)q)9dEI1AXJ2nwHZD1mIC3!KcHy_Uh9|{l&5f zV4I(DDO(QW?Ijpv)v6$YpqBa)OrXB7E{~cxvHDbqYovIkj=e_UxpN+Q6LbWwYu^gw z+WGqr0Y{JB+?8wS@KE;mH_TK?1Fv}ly26^gFHtbbf&h(YEm$hBVfb;3?oU{GVzl=`3gteQCFb=5aL6@-mK|D0AZ)__5e0)v9|;LzjOTy|}es5+^`N7B^uFw0E^253?@MhRkL`QW4d@obf1Mw`ztCc0^@t` ze`H(E#mLZCZSobg+v^vcIXg0W6Wd@JS2;R4wY&a$(qh*UFi8RgZt?{+NCI)r-bUxUN zC~F7T1??eZ(n?K=hv0LN>Rdby`H{) zx^==Z-z-FSd3n1%CA17+3Ah6(0ZbeSlkGKf_KB1fEjoj}SfRW9bp)VhMZuZ7@;;`t z)h5%aIDFr}eWE^x{f~X#>5$fO0ycCIYesp9=f|r!pd6+ze$_-${fOt(N{2Emh2zCV z=>p%Qy}i8>3vJ2X=Hi_p)5niLOj3AmpWM~imXn|VL?eWqvi%^1a5sXC)NPWX+|*6I z2u{|de9(~}M8Xt`(5lDkl=%jjF0hUW9vcKH8lB+;>hJ3+-iHI`u`2Fux<5_V7BO5H zMYt7pn_uJ+ned^E9y>O?uu;tS;&BA&kAqxte;aEm$9{NswBiY&uMoNyaR%BTXCQqy)rY8ov{7hCkUNXVYk`vp8=2Ni2g6wdPStMpE+vJzx;x3OnAve=kUA_J@^d z=@9dy2xNX|&X`vRSQ1Cr^P7<>GCLA@RK6g*cm}E{>}^_c=+oxEL#B%g;4%!SRXa*N zIzBuR%Z3GMrSd7(e(5`y89>2Pdp=MB{#F#zKqJ54;3ar*YI47>c@~Iq)&Il^YuEl& z&E(xF!TOoafI=lz)t^hR^ITmw+1Lyn76_X+{QRzKl#{=b){-+uGWXyv=@Y=X-}QzN6f2m^lChg@$4g7wpJr7!wOx3|s0k3@Ar zhw*TLX2Ft6`v>{yh*3Hk+lyLG`I^O=4-3uCR#sB#-qO_^wY{h4v^jJjgVg=zjrDi$ z9@T)aC+shdtX-3ml9K()FOwWk_mP$sA~TUYX3e#ua0yjoR2TfHH$Uvl2AmXk?;c>^ zKC>^mva!2$LhH>^m%Br|D@RoML;@`wA>>J2F3e4B>-vjET<*k*&>G6os| zK5;fB-!JLvDCv^zT{NFe{?gx2JO25b?9(R+SlOK&Z6J=DZ&GL8@5QOf=uuUD@5;uz za?HHLU?(<**uszxfEKrvO5<5VG>3Eqv8}*hXu0^^MHv|f!8^yjtJKO5s zKVIt~yS9SU@7~^!<^J)hjXN#9Ik~w4XM%j>ny=z^-{I)E5k3Uo?htBplHOhviwpRb z^n)gU!`uufXf(>W*xg#>d<65cDWBd&<4QToM44f}Uqu=B@XWX{SY(LA2kiE5JU#mm zO*Dl(N7Id&h5JDg(&<>&C$Z~9qZ)ufw)gn`U=l%s4NKW-AO%-ugt|_`2+tQl$ckGr(A+;y)om{xNy|1A+2K()&Bh^3MdyAJ=`(sNtRoH|LgV zP7bb(eI5U_NnKVX;m^tTkL&eMc7G|5iWX-(PX~-#;PS{=)QkM+3T1 z%4ktCC2bE@4%u_O_uz5$x4ZWTfE(EbLv0ttt=HKZ$<<|#sX~6T)9k*1rCD=Xl6gJ4 zYyA!1w?7!}-Qn~g>~PUYjtw^)euo0Xt1IHtr3Vp)iW1rd51c${7T+d3JeWRz@lRF> z;FZ04^?FHU|BVl7ZEFKzO6H>Gp(}mO^FxinK^PsD}>gtl~ zv^5=G#Q69b3+fdo>+71DJV=Bb(9PJf<)_MlCYwz>JZ=>?GX%yoLNBVUs%jZ6j3BK! z1ZYe4TfZ8x(u9k`Ft=!su{D;IXRCJFI@LS)Y+e4t;lo9yytYH}nc=^n8=t9A%+DV7 z9qkkU)GkwZ;OhUS<<3Lcn5|oV>6ObQr8w!$H)@PkrhVq+Vt6p4om`FnFErGInx+cP zg|#w0OXjGJ9zO41**CxE3jl)Kdv>@>5B&Uu#m#-*1AlCoe`f0b*l7QWsr%2@mASY9 zP&j;!C~RqYY;^=x9|;&k=?=G$eH~Tn1vZ3uXNNVRU51m`GMf<(#?7968icG)H|ow~ zTVON8bwM3?>b?{t%qSh55UTD6F{{-D%qU7yXS*!=D3nmt{ZX8B6uv1C*JuRKoLw4{{@N|0z-q?vH6sWZ#L)_jdSf&+WB@;+J_5u8_>^Ew zP)gvuGTC4?AK`5r-qPvD04K6a5J2UazrU54aCd5Tw!CHxkN_qGVUw`FP${CK(Lz%Y zf4zoJ%dJ%V9LW8_OVDihtkr4Xy<>Z=5piQGvN<-OZnu$DfC)W8jJ(X>&u<>J z8!)OowfV(e)NvxXsG#W=b^~8X1(B$Woh#nFd64YtfUa_n$wjR-i6z23%&)Y8j9R9A zOyIsAr}M1a--P)4-vwI=IvOM*4R;D<4;9K_RfwXi zu5}hKb7eLFE1}5HuT-Y)5`a8vU9u(-@(sX7!}ejX(|MUdg|Cgba_kZXF(r)9qu5xK zzCxgZS8sS_fjDnc+0^731SWL-*sI9-Y6w z@OwbHoPFx7W3eY#LAF*T>*|-ay}}W7p-e6OH;5*;pR*ee3-!Y7bzii1DIuls(8b6u zZg4~!#c8fv`xzN~V0rWe|kAUek`^Rlhd_is5! z?{kzxCIbw~N*S;q-UCfab5l{tVdrkG-DL;fFXxPEwN)p;M;{=P)bk1G!ImjQg`F7I zan)?>K6Fgn!YeTJuFQ|i3 z2(c3_Qslt07VhP;R8Zbip$D}-7Fr3$98&S%A%$I)Cq|w|grFvb)bYmASXx_a09kU_ z$47JV_U0G6)#_5-_lvvrNreW9^UNI5YA$lFE=eni6yu~}am6r0Ap&}MXw%-1f*41u z*dpZ>tF^nFot^F9{bgVl*#d&eG+GvE5PFzEhC_7aStX~wzcGGRQ-i(Mr^ug&F8cpa z&HjVhMh*`fgM2z`9=ZL(l|ikl7D{lfr*Bls7zm6oK5Sv`sOU#Oz>XK3H)$y^D@&(^ z;o+3g8Q&F92zZ+7_&AvkJsL3ajGgA`bw-2=gL7IrBvBDsP;-A`W=MJ28*llU#%GPb zj~yss5FI%I8o|b#o`o5jkrvr?jFx~`a8Z2u&?uCCyOMkE`4-;O2|xA>W}XOEco z)ePGQm2V$AIX$Rpyz1g@UbnkPK=#NlCvX=KJJsJV`RmR$i~6#-2IrM?4d$Q)@k>5jt9A6xl*>QCL+w&s{Y#(uTiDo` SJmkG4OBNX{jGe#X+y4Re-n_*C literal 0 HcmV?d00001 diff --git a/binder/Readme/VisualizationMarker.png b/binder/Readme/VisualizationMarker.png new file mode 100644 index 0000000000000000000000000000000000000000..f17feb1db344a97fef044d8f3d2e9d31c6cab65c GIT binary patch literal 33327 zcmeEubyQZ}_AZE^0s;z1r_$ZsCEe1^3)0=G(%s#SbR((KjdXXXbi-YI--+*x`@7@b zGw%J3`_Iv#viH08diR=ZuDRy(%x4)WCnNR}9vdDC3hJf!dtn7ADCk7+XZJZAxPvFV z^c4K_-Bn4|UO~@^(Aw6@$iy5%XzyYTA%r-a7(qcf&sfN5Ahi)9-fW_A32Nu|*lhLY z%Xf)^z%o=36C| zn1C6%_U2Vv?$n$Gfq?7K&x$uvg5s^8$$iAc+S0KMvD(pK`@P=`eKu|I;$7Y<7c__! z$TFMdyP3~-vh+kobr6L!HVTAurly^1@{TU@dcHk99jV6~;bqq#x8Mz{<|?jjE(`|t z#Y9L*PFzUn?_&WYNb!i|dEds5+o7W<@+;^wo-i(>5*dOgQJA_fvC{Jz!6GEmcu#?7 zzjqxS^42u$mldiG);1I4Ka^3P^6_hGrJ!l$v_FvezG1+}y;z-Z?waS~FNjSrstJWo zvP|xAmXb35&=IC$pN-7_e3h{(ghO27yOaC;+wYT&n%-t@vXnXAaY|>QZy<=!^4`@JqUb84WZ-IM zz+p(t#|zKx%n3TMfY|F1I$M}q+HpGb5dYCHC;0jCHXSkHA5HAdc!*V{j*P^-@Pyp9hDMwU!lHlc0$lMBf3&x^=A@%@a&n?|VxqOOHKt?W;NYO6 zXQX3fqya5x>|8AE^_*!e?cP3i@n;{x5IX}~6Ki`DD@(%1KK1mi9PD|BiNWWDe}6v< zYia3!bZ=?*H!A>p&^hZ_(=pJ}(^**1{q+eudl5&_$=_b+zkI?@39L{$1&E!MgRKEX z#1Ud?|Mst47#jTJd20t-^FM}TXg~)shgg87cHmnX{^cvh#HHo_@x-GEj7==8|9A=* z`(Ikxn;8AmSpV{FkDvT8oWH&Zc>Evz{!8n>kNuCvpp~>Vr?8cQ!{h6T3-b^^em|$7 zm4S&N=N~_EutN+O_1Gaa^el!9G|VjQOf-5dtZX#QdTbCweLaYwAuIb|x)Qgvv)8jU zfIM~uI;S-O{jjp>8yM*+I{GMi70rzjPsMYXZDd z&-|}%_1Kjm=*p0RL7$Dmkb{Pag@c8L*}#yQhJ&5OfJTp=L(dSx#;gx9fc(*wp#i6; zm92#ym`)Q5J!1%+wWaYNA3PeIQ$S9fhnSI;{-1Z`%=PSzzymzQQYMxT&j0*C$;1Mp zXs`EZO$Ii4dU_5fRt9D^c18vc=6^Q&0I{_Lp7_`&13fL%pPxKV3nv&1Fs$CApMnnl zcmj-tQ^*#gXK!VzWMyT}L;UzkgpW`D<6~*CoDB8s^@R28A)r%wMkY=M22KW6C3^5T z6DJcB75IVvFYT=iO^jUrcdZ{644t&4MAGiKoQHl_oKd=70G&lKUDG?I> zu_!q84E`K~ot`7a@Q?Qdef{~7!ACtyV+e>Ie{ zu3~aJm`hDHK5S+ZcGw;vfhB6Eq6msw7t8+j`|`+un};XY#;5z!C+1HmR`{HpsWRAt z&tG5>-KS}Xq6i9#2DGx6`=GpL6ntO)oQUYH&*Q!4L_QG_uLS?!T(5kATt1Y3_j`%M zZoBqe$PdxQKi8D~UQ5H3t|jce=XLBSqRtIiYig}9%Cn@=CUpwxakaWDyCW#LAufOA zJ3Xmwtyhxci}u4wsQrisBBw0qxsCnHH;x^0ec#A^BGURBkrR$qyQ=is;E)J-Z|e>u zf0?}Za85pX#>#lHYiWUXYQINyJeHwzl%U6%AQB-=BR@#S;`1{5Vy<%tgb*&5dhib?B9I zpUh^}+0zqfHd)&9;w;m@{{$Kp4ehiJKP$3=p_6oDt(M=wN8wdDa~#dBL(tr2h;f;1}|#tw-r)S zQr=5R#rR=(6?wVKY^1+T*ej?g`V}ZDc}{;Zr&Vh;B~}Ixoe(`}wTi>^QHaER}B#j}V;3OX;`?c^b zXZES2jg@fDivYM_W zkxpiXeD{XFy*(Kk;TLpee7N^^Nn#TDeO@gP`g0Xkj3d9tMS1_s0de<;gs&ZcdB;Ez z{!K6P1#P+20Q2?PrJvSC4E65r>$=wrw`86VeNP+1k277JQ{Up`FLeZ0z31w_@y`xAmS^cQ+T?lVt>HX=%=`u8hvVb)%xA&&pH^ zc{U8gzw;6b;nB?3|s|@X8L&&nNS^IUlH86bXK_e0Uh1oQ#9V z<+wIcqCr=(`O_DnP`jD4w6ydoENq3%YG-_@*X^avOsz#QXt&-MZ@e{}`HqBSTPK~# z7)eG(<|FeEZ-PHE0q{DCzPbGdhu!DTpMRg8PJBb7Zhd`f!ePR@7I8KCv_HD7wxUV^ zcI#k%qwF+gV$|ApT=v#eHn`!VA}NhVM^p!u8p|dErRvw=xex=(ev&&pbEpC-n?v?5 z>r`*(oqoW_`LJacyyE6<3^|-!e3yUoBIX&FYWXQ*IQ@^BJH!tqYCV<8W|xIJB*%r! zbE>W019c7=v;sAzBJ{#yKks>PW!+x;#d{hb($Ey_|1R4IJ4znYy4_VOkc0LHmNY*7 zIy!QBIx5TIen}531_9$VpRV*3_yX5#z5K8iEvs5-_yR0O!-XanVG$ANa`S0MK_MY% z)e3!)IE$eaj<%6p$rlI+Z>gz6V4fk-JMK;4?y|X^n~R3wiqAJVBy!l1wzRaI?u-Wm za~n3^Pgfb60Nl7P^x*nE~o*NN{76jC#Y9ylL%gaVh5jB)Lty?>~qQ zoO`NOJzTvK{oi_R)6?qv!4F@&7#kcbI1KU?=p0UQ@ExpvFl5p>e816N=Jsu}`UUIs zo;c)H_iyyrU%K8E-(d4hp$u?uDHZj1w2@59Y?p(O;IR~n)mc*Bq-+k|+)UX?e34Z{ zXFK0t4}u#bxO%l@^fYI);b3L4ueTRoQBm>!dY2CBL#bxZH@nTLdYiW-l5zc)C^*<7 ztzKTGI;~+}zQ8~YB(vp%H3$_$trjI2Ps?CDh}+8)^?gDKLlgTT~%VPU_VJ~CoNV>^kwF$-HBMr6y`vsv>UtQ@|%lj#a~-#?eUbU_R^iLS-{&bZ;Fwxc*=A$T&DSo;Uk-n*RMDa1JlI+&PNBjh@b zGL|`iR20D<3bUvFlc|D{KlQ7r-2 zKxg+SZu-P7pKC|DX>Bn;%GcDKR-ekbIy1U9(GDXZGN>Ki`PK|4&9#)iv&QZPEIlnLJC8SmhO>>P-bhFpWUzI3UcO!Sk7u_Ex=zRC0 zozK#<69=|7|GFj_1I7> z`L;<8#11tySDjxJSYMJ z0$S~+fb8tIAoICS59hmQm-OZa!BtYNqM|}oO-;T)E;Hn$>pMRm+C`p3JZ|9_$j);5hrJhlcO>p(mG~%i6E);Z#+&MZ4gQ=q%DMg^E;d)Wz8!pIIhl1x zaY=>J51k|fb8Rm_328}v=S{*sGEqAPn1ZxMOw6feo%z&6F{G%ZI3z!jLiG}*Jhs!9 zJGA#@_>-F(^{ zo-d@-7e`|-S8s!e$B7my`lYdv>tth~j}dvKTu(?Qm9yhw(JMSM@)a<19@s#yCp|no z3RTMR<>lq)Kmrr`P^<`gqGw@Q&rkPUX*_Ic11WW(V!lG7rx6LC2?6g@q?>jmW>pJ5XjA@Iw~%RW9na#_MJT+eno5*Q3l*XtV_QD43K(H@AZ z*5b}FI5=p3Fn3jRppO24IG!sRe{Utb25G6`U}QYTyT7a4dw{PB^ri8YbX!)b;~01% zsh_wWls=030N=A&i-Onem-=kThKT`PNYYKh_1OsXrQ%ogzWSG!+o%sOc5K~w=fX9p zR4R7IXz-KK+NaB~<{Q}B+ID)7>@KPL8+=x8aan@V8)a;FBVVzSP`*af^vx;wMcw$s zm+vO*YF;bNgK2nPU!*%1TkJPtoapg2b} zBzn7$6vtG>HEghq&g|Vg{OLLs`*($5h_n7;i^s@w04tj~vYX-(FcbB+mjnjFi0n&r ziR`EZ1H5t{Zc;)}4udZsGNJ)qs4i0)0D$_0p!|VT{|-q1JFWweeKVVzo2x&ge9It* z56a3I-5%by&&kh^j){5q@~zLQA^7(9-T#2Y@Ba7K&SgCAml0r}UID3lRTUF7G;|0) zPtwiBVXN&dNGTPIKG4{6YK85ZFEn8R&gKl<*%!ou}> zER{;0e70z@dQA|k#Y|IqY8E-v)2B~SP*4b8QrtVNnT4Y~JlUNn$#%awR(k^XeSSW5 zcvudkS7&{cN(KC?s+c7jb$LpK3MrfpLBD_h#;Db*v%~{qVdvr+%@RS7N#~_`Ns~kN zw%vcLKapwrTnP$*U2WA`+jR*}`z?O3>XDF;=$h`k2)t0Rv4hgn31Hw5mpVgnghfRq zgo3?HWJzhl?$dH@cB^9=C6IP=G)ZYIkq2O?mbTR*zi(tp&Dti$n14_{D9bedHc~&4 z-2cL2Vv_l$OKu<+EmtBotGWtjy@+}3qzuDmDeN3QcFfl85ZAA|B(y9a2SPQGGmyct z*O=_UH83#Wk3Z*^6w6Ja(Lx#O=7VZS`r=NH!bxqWCscv6w#=^qV$NCbRSr_b?V?`?Az~0SrMoLO( zz&!nFJjvH*yQ4K`Dt?Gq#Gy0`qiG=raC{e5ZSfjWHpQCp8{=q$ca?$LI=D;yJ`iEn z%Apt|_zOq#wK_xCfsO%l?pK0X;hRO7dAjREANLK!M{2&bm*7g@=!BuZ;)zRgoLP?2`e%{lBdEKE- z4xbvH&gLx+dvcQ)imK8o+YxSc<=ZDJ+3_9KB-#U9a^v@E&4}hyx&}}x={hQQX|T<+ zOqK-oW0nGwE2gwo8XZ}5T()0g`#+k}t;Q3S=bunP0oVWmHn?6aQY!q}egN+O!oA&~tw`Q?*-g$`tr-+M&zqDORw|yT$N_3SRgbe4OV-%Qky{F98c7NdEg#`{*c0*MtjsIx6mg(VvZreRG z{3LJ3RI?OzjqpJ}au>=ML~Y$aDSsOzN?0?~W!_&yB9raleKHukOYCv|`GyJp0jz z*(b3Xp6d3Vo?QBi5&qC;Mk|t}nxbGY8h{=F~j%gaAL!8|){#?sKx=#8h7y*gg+ zNoG4Vi#IkilhoJGVlKW!_6a$_kEi9~XP^@h7juXsDhro<)28b3J(ubtt>1!tZo2l< zoe9#@vEO9nt{jME7J93{PF2Q6!W43gmzOyP=iO~AMViW-@JzGy9;KszUIcGUjWhZHkM!g&q(x~UKZ@xXX1o$2Ihe*H2{2jk z=7l7Fxx3oOyX)ODwYZ)KO7&a5raSAzsNPjHSY>?0V{WHVrR23A!nqMiQGQPf?CYj$ zkDyF^)#cj;FlPl>elz2?#f5s&f1iD}8h>hZyw>w22ra5=yNBGwB!_}BBs8>po3SJ( zHzG?}E^))9G>uY9`XqxmHYTRHkLK3xNMu~KCFDMigl2Oo&7yNoUwM(Uc!W%Yh&Q<| z_EoI5dHxt0ETS~M=j(kFJ$BE`yDTTvgX7 zNg6#QgkFgvCqFlPO;s9I3NdZ`L~WQH0L6@mbPW6gR&wFC`}C^%X~Qg1D??#NyArqw zr8|AhfgnEdXUh2S@r+MLbUu=yqN3;IM`XdiHyEmKu-CXE%pUYRKvb;@DV2$0B=~AF zn#bUE?;b~^(J9M!=MxzCf|iz6DwQ)9?j?592epHP$HW`pYT-CKoiMN=gQU{v_VQ?C zc!dW6>&p`~TJyl2C5}PuNrjRGb-ob${huNuN>>!>?bzs?mX_1qnM!ztyU$RodF|qj z5t5O7KOC6}EXo?if|{j7M=l*#)B9wtFgZOK&HE_>qhZcC7hKT~Vi zK;)c-`s#-L=>X0q87aHsMb2W(d*ZiDo_S$+XvX7swU(R-ZB70^@3g8^-Iap1La&t= z-E3YuyyE-Hj%DpMJ7nIPza@0wx`%5-r`0um+Jsq`4;8|?#$*8;WGw4?A|&%~0X)dF0Up7OO98~@NQ zw>{3?jcKtj+YP|RQ(0lPl`;_6H|14Jx0A=nHuXjwHL^5bZRwJArBt`P;|!;0P1H5n z^f5kJb{}nK;dSKD@=-=BU(t%ZmSFD76P)m@^AQ_R5^FV~l>9bKTk4_c7#XS2W0Ut3Ly|K;M;XO>*uJgt6 zi_GKY>bMP*)vxhH)^h?Lo)lIRo7Er){plXt@@O0Vi9!QOEH;jgc@nXdQt7;SA};3~ioQt$OS(XpLILP=F>nybZT~1^b;%wnZ=cU%yv1QZGx&J;N z76Ee!a&G7%Z5lfyRusoa?*O4k=XAea4r@$w9rpYw%n{wrRp)kL+27xf$zl6WrBqX| zH-@6xavr-zT{@lD1E4Jc2uAW{3078Cpb~i8Sffd$^+Blz;BmY2J+;m-JjoXKtLI2a za7#Cbtz?vxK}$=zlq#kDR;_oP$b7fnfR*uFWME)8-Jgv|!sDa|WtNFzHKEB;Eww76 zmtZS6-Ux6)W1M-+5|Mb@UYs-c9Y+O9N?xCf8+qM}ZQ1U;&ehiID;5_nnQ2RRa!`#w z&Q|Nzbyd0}-wh+cH~tmzqJP#s%2~**mj!-(7utcs{B~`2x-I$^7wgCE6iiC^q`rK6 z@->hDNNWqKi>*t>%xo)zQ!jIzC0|boGeVH^NB#=|9h5agc=FqtoVTB%2exOJ2;AOu z+T6y$6^*cLahsFxbJNr}7r=~*?UUf?F67tK+8cjwfY{e)$%gj|y~l5gbxB9>{phcP zTX(+a#B5a=Qfbgi{E+uP?#?k%Y=h+a7GqS|tegH-j^ycois~JNP6cWhw6zwqk4z4Bs2_pXZ6ttkOr~SxP^Ocm1E4fBU1ycv!p7`*>-_oi zXG~UeOenyEE^qzH?oZ{4|NYzA#jc$Tn|3s9a|l8Aa3^Ts#6SSfw_wKMISh9EAa9|) zSH*UbuApZ_klCgUsA>8+cF@u1t8j@Px__@4Yz#9iGAbV|puHoLGIZYksj1EEjjxD& zg30d`t$fGD=-!x=1Vfy_WQDD#tf~|kI73M+iz7J^M84SmRivb! z-w+fn-qt%fsj?Ws8*9xlt<2h-lE+JFUZQxi-y0IrUa7QfGbYqfc%CLR24e{&>pD1d zHoFdN6n~JJL;h4#Q^Tv9<`<@3GVu(NKU2^bs-86dclh7608WSaP>|l3Wsv_refDg1 zb5m@(5;EQ5!3DB3D9u*SRKOZ20#1wirgttF(9XD^f{+JTznr|hsH7wbS65B|_HlV! zl@>6MklYw4#JQ#Xo34(H;M0`wbB!8$3#I9qT#odMcxt>&aPU#-X@lfL_vN6|m1u*f z=dVK&8)6(i=gE=0;ro)>5?H?Cf1u1TLJ#6LeSd@gYwuuP#aWV`m><2lcr)rOo4pk2A4Jg!e&mTNx4B1jknJ7F*e zWqAwci3|C*#yMrr{N~BwQPbCS;BGWxY1{dRa1-irQ*Wr0X8Fl+h_wABZX(Z~1@4FFh>E%{!PY2>H0Typ5rUOV5*ilG67p?jpMAToVUtm4fLp#BNOMy3z=u(M z`xd@WRl#+iEFia9y1jv;Ir37M66Yt2$0~VUycHFZV0G{lpF@~^xxu)!Er?5^1RT6VqUzU|MDf6VzkQ7i4I>@S9o5Oeu{=aXV} z$x>e3{`nm~DMdzmmCKf~d&MPPuOt3IF-ehXl_~X^h2533c6|Srr!;V|<`sjs)uzS8 z)I>-4$hHjvGO-xJO_a>y;yG(Oqz!dk2hN|33a+tqZApSJXVjD6jc+#fVhbvPyp zN~t4$ChOmk1`>Zimf5yt`IFD1`d@!m5;Mcl7m1J}5Rh+kjn- zB$Rq#**Yb(2jv-a7p$ zUc$Ch5fLvhG&METSyozEx5vSP3cWounQSQ|O?+2sLgUwDcii_wRxsOzZtVjGvudaN zAN@SjygNFrO*f*K8IQ8Oy`dgAWI*xRfb!<@Pu~1<> zDe&l&<;Fw!AW~->u4CfhfO$f(E^4WV4C?;L;A}A&H=t3 zduxJu77cfEZGN0+T7w;)YpX($)pzC#HgtW47q!y~1U>-T0+tmCu#Mj@k5+*NENf4g1)E%C;b7odv3ny*EU;MDnDFs; z`3(r3Nhw&`?ZiW%#K-%DL=|cldV#(WP|kqgPT}I))Gtr6?7?#e^LaUo$b(yvQ91tK8}8 zz?G0McZ*30PGR_7A^w~u-X5Y*RyKTQ=~H#&P&!pJ2WE5zEsQW;9uH6>_eoY+(!p;vdUL&v;E2_3~J8>e~~V&hSjLw<=PV%`!9cPIFHX^Q4y=w==25>3^11 z6X4~Ejnt@rl9KJhSvkLw+nG-qY8S{4V6)F~|NX87>8RfsPIO;tl48-?%lWBf7m`4Q zUB1kPxDpqAG)v*pJ90y*nO1X@zL9t$J7Wbx?$6)8G+JX&Nhp2%S%=^%KlEcsO%OXi zU(F-nE)UtiG+$r20q%=2Qg+&WG*bGfx1p|Zs5cO19WR$e&tMO7y^FlAyC5UFV=P54 zxdhCLgbE(xsEl6O3fnVGrXm96DJg zcCP$KSmUxrhHUTw$Dn<(bui1sGw~2*I)x?wAT};ZP#Oz4At!2sOQP7747b2faFaQ4JM-k+z|x&1hpHz8GPMwC3f5L_fS|AQdWet6qU~U*~BwuBSLdt1TWX9eQQ&Kw@Nt zBTn+xo0--kp}RYP1-B))t+N>^m6As=@fEXOFX3`&+3x6Y0uax!m`$_;og4_F^dNDh){D~O;yDDuPWR&;GWYB4d{8EA zt-Kpb=L-jJ1zwGmo<8Duy>GWKiOD#urNv=)0s?S2fwnAZwHek14M*RX_G%{#dMFBH zaS0VYy+jO;&W{Q%F<*aOa4Y$dCM0qfl`0QEZ@KwO`UZ>2j=FC$%$apa<3~*vp4yvV z$&8&)fkckk! zd*=i6T1)^(KSDuGOe_y!o=z8<0dIDO!z|hcKP{fDA<#kWEyaW)D(QnfKC5|Xa*MSVLePJOD zFu1R9ar;3HlYxb0pf=U{0fc6G#Hof^2{ap*E(?JMOod9ttY=%OvM6u?#C_rh0 zh4b@Qw%Bxo0~M3;V20vC;Hl~5o_DU`87ZKB_!Q!TDJj{95!N*|m5{_@R_StL z!qsVZM)#$AVd`v{@BRVzo%J;NsxqWHjhRylWZ) zqL;w1FrzlVmw+FF$pDiBl&+8PRQJbcrBY2Spe_Q!bLaxFc)_~UpRKh}6Wq9R9MREd z#s*p%X#mGS;zz90;{MI_As>`K1wl3Xto3lF1_8vA2K((N-atwnPQbSTRGWt$-D|G( z<_A%H-|SfeI~{_CGabZ_HLzQwy`kmSd;EO^1%EdCknv!ke;9Ao_q1pJ6`c2LVVxyE zEXEL@w6MIkB9705a6#kz{QTM*np~*>1<)IG^F|j3^JsM1DPZu?08X2lQvRXbi=kfp zxxcqp876vpS#B}Q3WhG>3y)5&QA>?Xz&j?payVOu94jHBtDE7O4C?VHsHj5OqM^1P zQfIr9o4=Raz$`xVuCHg`883SFJ&nf=szAHBq2+*;m6e^7)An@h7j9p5ZSA0~!6zWT zGObZ3pqHIRS^}UA3dpnk8l4Vb&n7>qg+r+5ZBIdZ(W>B&T%WBt=JkZBpIvwd?7@VngUYlW-?oSzYCDJ1_POpsIRA zkoEHcuigd(2OIoe`r+*CtZQnTM8b{F?d%Oen5d|zT5X^Er-7GX_oJqv2@DQyo1BaX za8$0<)5BvP8ZdUZ>JDD}@~DKQq<;5zHz33i0GAfNzrDiZu+8E1(S`sGE_u*TP*1dW za`M_eKO8GW1sZT__3D6v0&*aydyLjV8R~Iph3H&DE9fY2G64;v`}>tclE=@}OoW6t zvk8F$j)|WIy37{!tyHmP*-$+fZn)}PIafbMFg(2=r@%_p^l$e{_=}=%GA-yqBDkMY^SXl9kuYkJwQ^5x4ah^27Je$|;bYzS(t7F-&W zbb2!pC|URPSvhXv{kF52@@k4zLQK4zjM3#iI2^Y3Pr7Oc-HA%N{qan(G9rgmr2mF~BB)jMnjBu23g$ z+|*>MoQUuK(x5Z{Qk=eN$8iy86{?&LwLg?;mk?08sXLW?=mXiVPJvq_vB-kSEDs-b zTwGiyh|+e=9;uuTn4I?HVPRoDettWL)Naw|&pyu8Gk_p`&A$((7Vus@jP2(Fr-o^V zzfzhbE|H#Wm`KBqQtQJa{bEXNK7J-D@*q|mjV*|5o#~MozQyIJWVe6;m zX#Y{imN!LF_toaw(TY`8J>%lHWK%OU`X4`bgDB3x%9;lztlDJM53rm-9WMz2KFBJF zXlcX1R9D$;4w}0?{qW(#pSrJ4SwKsi$7nV|&5Rv-KcQh|Wp#Udi^=@)Q8zXTaSjJ1u; z@>rpwR1$L_7L$=&jp?}4gd-5q0L6?yn2^<_rSBm2aCqHw0|j-r0~XNs=z)CYu^tN~ zehkjPmsD!KWSW|q5?C#;^YZdQsI|NNttXShE&z}kZ+}D&F7siGyZ~hlfq3ruTOEZ} zc*J>|l*}PKKeq>I+{1L2L2-hgn60&q zj6{J@!(chb?uUdIB%1vLsDWHgHk$3bO~6KrNWhx{u(loqA_8nU4Wx@8Do>O#*=}iS#$(fQz&&a`K?hGWkOJqmgN8G71V&_rz2_&c7r#4MRc}?punT0H?X=$D>jIL`r`imHI!w{tL4DLtFNLaebSQ z)w0(yg~yh_d4smS-M~gU*WK;So8BnL^<7(C{W(z%S@ihqQ$&8(hOojaS#c@^Agq%* zCpxNK5Wxb2xc@?QlIPBCp<@?}#_H!RH#40&!KW>nyw9mV=rI|?I5_BxJSRFct0ZR^ za5O$&faQr9ngRpPP2Ky1gy+-XX~Y|Lea)C$R25(SD22FL*?4RwQ)#qs!W`6O0$K?? zp02W?iA^8iDl^a--aDf-P=@NWGgGspzVn?_KrS_!kG-9Gy$FZ7e<5=dmy42ip)H{F(#iTy}eYC;ilsY1*5q17#?k2PY;tEy zE>;!J0Bt#j#T;6(4|8;0AloiJ(AOuy^}T+lRB5j+(f_(Rzsk#;5OUjMxcQc2`eDHJ zd@m3H1istfLSeg7$*eCys&{?9e=~7&a&`s*BG{4ND~srinOc1jizAm-FA_quMa6em zsXLnM$Mv;e8u5RH`Hu12Y{gF3l|RUMji#-eQlu z`lIq72D@a^O<>koX?8&($Ro+C_A5pfuHR5fvN6Pg+5fan?ue^v#9$2Hoa^p;`-BW8 zOwPe-mr1McFk#f8pAuO*{O_90`<^${+NU_FUCJ&auBG6Ca-KPEDql2y*mU5f@@)lXr>9@*m@K}O^jE#iE6!?K zaZkxrCv18wqUfNB7Fua4lj&y8FfLAhr!S#JUS0L3sHSMc5ou|KWZ9KjIV!JSvxa2a ztzuuQeDw~uqWdsE9vKyNYwCnAAT_WCC1}g}27uOt9%ca3W^HS`0+gcdAfW|&2XsVCOnbRr z+aq|u$H#X+pEkzj^VD3>e37U!do^2v@p(fF4iRd5JEzFJV4<3l^hTxXC<$r5!=ac% zUwokRUNwt^=VTuu!EGbN_tx-83sfiCioyA{W?Skrb6Y!APRsqd??2u-TW`=C6Yx^0 zh}VmKrv2nVgbtLh&c}*jw33Gzl2Y#&>Y{&JDYvqbOYRHHMIZ#Wny(LMbM0NP%fgQp zgvJM^Y#n|X8&i5Lv4fODTv~eI^*g}(%I1QUQ>Nq0Yf0a7Kf;RAK(Bu1}RgFVF; zxR)y@LwwJcippAuK^{ZbdK(oG@LWMr(PXj|5A1%&aDCQl2cO|G40aWmOBJ6k&BOLb zFH^yyU)?6lwN+viO{R5H(fIN0f4=-0H61<4RN?{Z9BgDuT*N66a35s-ep*Jc#Wy=D zP7b=WWf4|2NamGIbp*gGu+Z4qY->#@&;HIu8 zGCt=&6Y<;2yc(7dDP8%o=IV&~hR#2KT~lVh_lsm7<8^R#lzaL!(GLklF>}8C8smop zy^PicLLNhf{R!;BVz4{I^P{SR#}@$XV*?=hb8#^pGraN|mj{(O?4g z07fs?s0#yhNhDae0BV5aQEC%aRaI_!UKn)Rh9JXID*6x#Fw#zZI+s%zh&w<}UP8@7 z2{P6&AT!TJ)R-+s){duA2}7s)plf9%tE)>0q{h^m^>UBvhYcaA3gh*n2f%_MVymKP z8uY1crgU(u)Ug&KFX2D5*X4vIzJf`JnMsH;=~6vg)kn(pwy?FOy~yp%Jeov&sKL7H z3e&BbL`<5wIdM_3nvvQOv66mnamOoqH>vkQY+ys_J96>PVPs=Px06EaBz0c~Ak*WnRKK=IRfX=|=cBTib z9~`RPaeGx(>9G4@%#;O`gorsf5}RBeCKpn>y6jmzaUY~eUsb+(8amY(C7>_qQymvT zGvPlmF(Fi_t}!+-QF=Zlh)yz|HRG>v^FgvGMv0>2%wHjQhB!DtI4<$(E;A8ZJfO6C z@nSa?!!F+LkjHM*b2G)xc;h^jCs9iS6iB)&WdPH8sP?GZ2FFwkKr93*3b?B2es5@) zk2BSUX}Z4sRtQOa7G0FL{OY4ZK5++RKgTj^3O z0U1HpiBap<`i=9|ly6h5b1L0;eUye!^l}BR4icMJX=F)o_vd7)_qK@y?G|GNufRzr zV^DekXJ!z9J}Aw3<%K_lQE0mjna>d99o%PQimfdcz3W=qMpcO*N^?5wv;)HR@gOYJ z!9m?@AIR(T0mX#0TVFqSqZJG|Hc%s}af+l-E%$EmxTyqUf1vm{eMe<@PwQgBx`~s- z!AvhPa_1$seNbKpjX2}}S-`2*MWRl3E$U53lifGtq~Dqw4}BMqfr=I1C`=QSO>iu>m5Faih?dSIvk#f?-Lh=C1if!g+DLz?;x0$f|!g|v3P^(UZb z+BD^I*cl@tB=r6twS9Rwm3zOpVMl|gB!omoW)_=7R3sIt43T7}Bx6X%k}2~{GL$GO zW0cIvxXcZvM43wFG4uJ{`+44dJ@2{Bd9U}J>zw`9-fJ)Go_@pk`xH6=cf#2+zDO@iAZ2k;^5JUB@3$&6KQkY z=vl|7y{kg?!oo{>ugZL)Iv9&O+42$&1eB(9kaFv}hKrSz^^2?Lcn5I1sh>}iNKh`|&K}fy!2*obr0vNm?U!2b-o5h+ z3Ni(0EOGsFAQ(SW-Ls&YY+!f#J^78$JfN9`lWcdO(mv?8ZeL&`>1_RReu`nSm9%*M z_|VE*|3Dqn)YC=jD&yM6!~bf<+Kwn39q2u4 z?RY{_k!v4P|5&kqcnA9V9W;T0m-ysy=)Zollk_j2_#IbLRQ&ss^R<3{e}D4V5B>eg z-#`7=CoAV4YHr~6*yeT2VN%T`FP;8l_}_G8)1;%Z$j!Yz9(rooXF+MJ zdE4`dCuWSh@=gX01nFJOUhB4KjBfB2k?((>-)lSYIjLiANaAxsV~fr~?se@#mfupL zt|OxBF_vlfb%)B+yaRkgY?!F4_Wby6*}p*lsME5{(Djp9rJ1Nf?awLejd2t7O6t1HT_jcgtYwTG4s`ETE;Vs)O{YH`AMqet6Co8s zWBQb<*|Wf3pJpzr=6++G zia$}Z1aEm+}T)JuBv*WtUUD? zrw<}8V(sZN9Nn77n)VC$NAGyWA^LFr^W>ZUcgqIdB{Q~R;_*6Ds_vJHCBn~B$A6n^ z-0hf{e<9oGz-Bj(yLo()+0}MSDx|dgrdG6co;mD7wDXUT**Z~mGoe!1(PtCe`1$&pqMDzl+c5EHIw($Mjm7l$vCyX;X9Y>;#nRK&qCMxGvv@`d4 zoeW8KiWS#?(NW<%_r$+eUf$%zo5+`Uq}Mk3W@%SAMyTs2^ylo>oO)#v{FQBT)0j%g zXUYMo-8KSxcfy6+{flgujjSgH)imw7rVq1O)7}#bGrsR+cJ$MBk0*raotAjAY_EFo*SC8S=Fa@T z(;`Ac?>@3Q(XgR(c%V?@g;bLbPpL$diu3q+c~)1a-z-fPL7S!;eOvQ49t*MvUwGf{ z8e>~@KOk0RKwpvHl_>mNnDulu~c zq&SfDRZod#7cb+VR2OvY2S{_rMeKhY@!d_FeeWpOA0xJl_i|8sXPFf>ulw0*rQPl7 z)62dGLw2Y$5mQP-MM2 zvp==dCXknUe2>)=J=F@I<*YedaetGGYG1^4oqbj!8PXr;sVlB+;4-FWYl?h!enY>D z@1cjoyqOx$Ldw`4=5?xjRbIbnU#jAC<%f1)@n><@orOX*+*=n{u6^jYb-y*C@R@_3 z?BO*N(SAfEb5K|O&6#ahG&KRgTiF-JDhgc8e~s1;bLR3D@QBR1`y6*}`+d7}C;i%v z%O?ah_xFZZx`x}ueUC~kzV0zTbl2B+i&SQBxsMD@d35a2#{n|q&U8%d&R&X83l!knZ^w|8(zHZ*uFC8%##>S86J5u{o1BTo~~!v6SC_ z@u|E@J?5ot@4Jvp<^F?{-Y z)JFl|-?Ozs^-IjdO)m9xi;WtBx1!y|VhT;keM{*#iWk0dW&T`QX+H?73{S+Sh`RTv zwR0PKp>TC`$42I{Fi&8lbtXoLA9?P&7_Up37ce~b{PV$z%;wdN{DX8~#Q4WF{QA;D z>p_6L4XvCC}=QW}lbljoo!@nlM8W&Tl3817*jTuyLBao$ zT3eUA2>pVc4AYSRyij5365_4W`bLe@jy+vBxF9g34?b2E{^&z0-Nnv%{7QRH`Mi21 z5hQGGIQTSSMrXLqpLv97i9oMDd*D5e|Tu` zB_;KWWbr6C3JktIV7xe}gpdGEsB1zZK8%Ss8|9pX3l62eRoMyBZfX0W25XtTms)f* z)SwlOQOyw*DiE`=5a&-T7Ye>H{C?qIWmIuhV(9h~r_+g*vF1kuExXP!eOWzSxA(w2 zi%V&f!l38f=X)2=L?NgIy0ODISXkIyfoQjEG zquhjqL((kE5n6Z*v)ZtI4&i(zYgeMTbl9)*>4u1pY~aZ7?!2Vvp9#w_u{BXD>I(>Cjb*2|Wf#f3VwP z=&UUz*$@{ciz;^rtP?>dfHefdUx|PLJ3YyAh%DnIuI)f_OEp?lBIo5smjqb(;p{I2 z%D=w0AdhmDVC4V!l+1FWGK{aVuP?g~u-Z8B=f!*x4J9wNqZyXaWO12Y{~ zYiEki*mF&GipgeWlIl|7xBmvF8vIv|wxG7)F6hdAP`yJd;h;Sa8J{b{4_JbfB(1*G z;(rmh+bk~!1h%hfPfrign8Zuo_?}at2I1|}FyBrn6 zx*sfTwOL;0x)AsY2thucnrHqH674UmNUAh}w}AbS4MoPM)6gIUu}M{Tc1{iM-nPwv zGagq(3^o`q2n`uBHGX7ULK8ti7`Y`-$aLv$1S$HSP}Tzr>Z0DCS4DWeDd4A0$jBAv zkhXijwtny4ANQF>=tE68@u-^6Wahr`SiotuBjgJLlar9T)C6JXEhb z6RN(h{BEh1^~p*GXbIX36B?Wg9S{tarV{rKO`h_ZGcJ8@t}WAFdU`f7FqmU)812d@ z?};7ZUv@e8`NW>w&}(Ql!55igIuWrwAQM{w`B?SXtuz%u7t@B}2{FnEh(?@|V&m`U zcPo2~XGBB^n-%61WS!It(<_oh zCpNDeI5Dd9HU?UOzLAl7XJKZ1aElWbg&o*%Vjb{C+F;^agIK;9Ge2eCBN{YQ3 zySuwP+A!*t7dqmYuQgbIMqh^0Zms$f9mA`(=Yhnv@EdOR3hX2)dFP2 zf}7pKF9q>tuYXR_Iw1L7tK_JGftuXu7T@fFiB{-m@ffFOXZOP^*lh}JM>Qrr;;rZ) zi;HbE10!$ZQL~=hO)gHk{@!mpW@xma&hh5NBU5v82c)GtzZ&fpGg8bXH^zt%gELJj zXg9^1!op5@Ut{PPo@ve|4}MBlr}aeilA&b0!-ZAVJ$;Pp{;smm_|%J2I!Mo>`<-G; z4F_w+KExHgW?xl0a;o#>$UGIBZN}{j9uM!>x_td!NA-45+g)0G?Y-IxnNt8Bvf)IR zV2GR$)pm6GM$9^ zG;0wly1%jkgmztkNU1Ue9@xTDfMGn3EITh;M7F%#Q+P+j^}z@3mJQueQM1pkBrwYr z->zAZ<;gWQP^FR)8gjW#bJARK+c_sev7bk~9BDMA`X?ql+Vv^)V%7ua+`HHGrKr4U zCdbo$&RS0W@rf!!{ps8pL0OiQqmQcSu5l`zi#lrIBVYOBPxHlmUtup!bVonLgVObc zJj?q;yBIFLztf>#5NqqX$&ga9c$$W>$cIrQ^}u=F+%@*p!KXrWH&~92Wd_u(oIgX3 z64726`5^IJGw6B#?pEiIn}c~f_dL72eX*Z4NC}wyLA|#U;I&gh!90)jEj?ho>OaOt ze<62Kw4uph^4d|wNfVy&FAA57c==2yto9gORN<#A+5K(!kM@bny$5351ESknr^zQe z93w=Si>r%M1~+9ykwub=3lp5JUk`aF8visnRO2JnyMH8g{)LUu(J^6#*e>xP#*CqC zgNBW#HQbVzRg|na9-LZm&zQU_<2kh|(C6IGB4DmK)mHn?@>ZVE2`f(a-W%F?n)5_N zhklZNGfTazli?m;qBNW1XqtCbn=#XnYH+?2@9Q_x8jzZ9ILq;Y&Axhjw5m(O6)9P5 z@r(^}(oq839&fX=MVH%aYxnISeLkbxVe^Vg=!%H_veP*_?{v=d5&jX5)6U0rFS)QO zOTP(ltBZ1e6vlbh>9s1|*T}8(k48m=BJMR;lfIwX$RX{&9!)k4Nw8%^ z&Ic3g9lajB2b4t2S3XqPP`%4|V)N{qMyYJLGDCz^fsrb!SQ*pWBc>@^s*R6l)rzjl z&WHy;$xp2liJ!NU^Kss{yMK|qR%L1>J|{R4#8NJEG0EWFa@OR%*Ob}Q{Yz5X^LiVW z+$0hb2Or+Ktzj#7^1T4L!zPEd$1P9bqT)a=FLThwEyI#G25ufb^B^jFT~5@ylKYvd zOnI=Ie~0qmWM;|!4U(znr(Bq?1@zPnv}P!0E^O|XiEda;4vmoVF7XiR&Of)k_~GUY zrI!ttj~#MmPV(W9JUWkD08;16cLLtO~1M&gy5Brzjgv zn|8MTF|XnrmM(VU)>=^dE1|H$r+lt+i|tQh7*a~Jyg_$dQ2$WNb}nIhh4Z9Z>er&n z+qdVNjECCZSB)>_eRiF3PtiVkx($_Acay^SWQ>$8F8ir1?BCInzrA#!p5<4wrMnwD zn~-X(WM*SYOk)r`ZJV_dIW_6Ba@O#!uw7!IkIv`w=^o;2m!j|g>0EeFX7zf3rTBLf z`~F{99y}=zema`!SZ_;;JzJgA`6^RxIWubd94{AZPXIS}I63r`{9FIVi^qR-x718M zu$ts~p(Dg|_G`tk{?g>N%M=N0i(gZ&nSAs8(>OM}GEU20sqIB=(yDX|U2vvumH%-L zo%tn?^l?`i*UViujXhG_YymAcE3#c291UmASL$4L;XATA+C_IYG$v1JAPSTbh0kmtxKT6x0^tWbpmTVZke|ckd+$g_1>Ubql4`uPogS7WWm;Xz~qwrk8Y{ z{PoGzfy>c>KdL^_Io+qdH?zX#bxrU6rr9u-?P1*)zq`1-Y)D(nkJGtHud8%#g|ci% zoH|ui-rI{ud?uR4x2#^?xTiG8R4?FHyzHR$LVT%~(%L4q;*q}Q&2eQ)G*irLA)Hnw zz2UYVFQ`m67ygLb;T?F;WY4iChDzaEG0y{ECvN!*xctG9rEGQWnZmyVCTo)>5~HZ0?wh{4K_xgTVtbh2M?Ic@K%sx(m48E_ z|5b2w;Cv(w0c9d;xTi){_laf&I>LzP=(PI9ErggD6ec>bIQAGqABMIEQD~=_qR%uv zrwS`e`ecy`zK!@A2(@#Wm!(Tr=XFuN5bd!xxJjjy^GtKR{1={VL}8r@4d`<^@4#Al zGW5GR3d5Ob!AIbG=YIlye}p~ig?7$e^F(JQ{7rVJ)%qbD5LYope9KXp zfGqS;D5sD`qlKu`sn(O6(kdPkB@0N@<$?m}F)B`Q?^T9tu&(^I#euIwDAM_GGV@zWHMt1l%n?#&!VS4Q zTmYRhWv+`PTtpgvwR3zy*Se$%4$G@ZP6btxjG+Jp=RvX^ann&1LKk+v_|}x*ObEO5 zJLu5(P_#e``VaVW0S`IS{Xa&yB-XyLM^8Q$m6rjTm zYeTsxK4$4BK`)l)x@d>H_Z#gUAy9>o^!M-I9YuGc`y=}^^4i$duey*4Gsv@ZToec> zRV%qYr(I}w0AD1G0vJHJ;~Xw=c&>~%>2izwuBU}XMR_K5I}p)J`34bOAdhJG?%RjB z1vEfxXcknAjJOe;IQpfK5t0amt35RJ5GRptp~J!0+6wa?bu#`1?Tvk3Ii;_uZoWko zhP0jRJo=e)Fe{?QhZDbmlU(u{y+f@6uf57%DWXrp4i3~Y@gD&9L{K;e5h>dSfJ88wi}Tafc9*uOK*eQnYFVL}2Li&r5|CI!MI zCPD2`c%LXj@z3C63sDxRr!5PZhiJp(J=}3LnsOi|glqwH5iug6oc@rdUq;I>B2}aQ z#>SA~Dhbay(r4i9$Jz3CPm^jAa<@d$Iw11U`~GpIfg~=BKupxZ-@$loPRkx;3Q*_^ zbT1nMZaC7>R8qfACg~O0Rk>5@BM1N?%*f{rKzIPOD5szZ*mKBW!bz5b;0@8$X5vM<@|WhFVWSOM+%60Y{5vN0AOV6 zmLiPuSS<6MPF0NAh9Xw2bZJCjxoAd4_bfyX+Je!7%MSh3TbI|H z6J%;ID$_O6cThm)-@HT1sn^X>zEFCPCy(j_15uXP!w&qw7aV_77pdnMRUL$3fe7H- z5zO!$&KaG=5SSYhUN9&dleig9)gn+X4kB_QP7EhS*u{ws4Rc-=S(FrS-o9-sa*f8{tM4r(XR6t((Y&4p zTaV-g#{#Yo$gf^nm{7w9#5_NGhYBm#9#2%}L=q2fP`ZAZoQ%`B31&k1n9K)Kjmh`{ zsT%6Op&=!x<+Y&;57slKP)Z4dLY@Q{2Z1ka+GL2s<3biojYXY)!S6x%j4-ST!zUnt z?X0Zn5t>4*VJ9cOe+(!hQ5@ zB--M{}1>%qk<&fW-*AhrYFiba`9 zYZyf6*bi-kF=3a;6-&Y{-=~ZEXpG|seJ>U#+NG|jWe&Bp(9mtuu$c_z zDLRqq+9BZ~U2WNmIe87ZVCM0Ovv=;?!5yB0J);Fj*(Io5UY9?*oq}R}A@Pm?Y+6|n zbCj%YZEcp%X~LHCIxRsJzt9rU%80^32;4p0~1-Qd(@iPTcc!@npooV6YiW?W3U+Nb~Til6^4R`$PL<@`qn`@aca{PZ4v_`j-5NS*6M zWEsq#$nW0I$M^G2{r%uz0^iYo`MGSCg>WIEfB-(?u~Y!K*BE7?}) zUo6WbpI?%3lTV#J`?+qO*>2&cI?mw|Bi~Ix~l2~ z?-zYVJRyc0=m7B7rv|$Aa$X= zIm#y_xtPJmLf_+o#R-3pTFEfU5eqBsE>h|puf_qw19U`~Js|dZJM2hJO^yF3seA>@ zJ3K7xk+3+BHj}p~Iw;^*pdcbH0p9{fYxrl`fzfY>LUuvW9I_ptv0_l06E1N~79DK* zz~#(s}N~A38-1}poDPA6n7ZWKq@as8i(wyZF!w4DAXK`R=rWm zPlslAT7D^ZW~2zHdiT25oeU>G0-005J^*Xu-nS161XEVo+F{QUT}yzIH-CK&!eyE1 zI>HqR#Rv->4eUtuSTgsxZS;MRgR2Cjno= za@JhnVufU!o%|YpPG6mCQ``q)`h%lgQuhu#EaR z4@w{0(iBEju6@%JHxbN3MNQ3-rinrpzvat);=axFz$yHY67DQV^tJ8+AuP)MSYYXm z4?DqvxP!*4V(ksQ<9N$Dzpn{{DzxZe@0Zn_JB4W8RG;I)b|(ZOI$GKD1U{Q!{+K8<@UJ z^0`8F7!ZhrWt=Hkf)l)P#1RCL?~Qzx;X`HE3wyLQ7L6Ak&M54hT2AUpwmAfqmR@B3kC=KzRwB z7c3i(u}iW`+ub8Z3>c5zPvO9MQO66t&@W3wD|GJd&1=4kc-h44cuzcBShBLR&vf#5 zP?EW#b|_vPitmh;1}d9)dxY=Gt#2FFmV4KU^$OcWx=vo2o8?m!8mK%7JyW9d5Ucy| zZ@z+qb3Z@$qPQc$a6)LKFd>m!P&_;(c%?WN2N#3>FY`)C{ilqJV>9re`qi1VZAuN@ z9#(W@c{C5dHVuPL4qkIYEVOd2hfu{Y_YAs2C0sn;b)9(e!kJnMVgiGRAijpB%@@lP zULYU=KC7D~fK&vm1%yi8z&FGp23vl;eW%c+NNoM6Gfts*BVNvd+inb+V%`oT z-v9o6Bk*OexC(&fi5_dtXapYiPoeVI<%veaEUq2YV2|lMGwDfcYNy6l?gjI_PRw|y zx3GKvGbaF6u=?$FcdGx7s_DPl%Kt~39HD&rf9ah5lO6SM!4x60`g?2sOJ-H)llT1S zz{K20Miz8_^)AABXi-t)gTASCbVq6lD%TKxb^OBjAE+5puy4-SfYVAtCr9wM^Vjeq zi2>Z_`9;K<)0@JUtH#8KYptudl*Cpu7LowSTJ!l%^g5lwoGdJ{{jy=cL4V(skUb7D z{<20O91ERi(kdlTe9_T(@t?#2r<;e6nURu5Mt#R|Rfsjx=W%mkc9f z&o9$Qm{Q)CcY@Q|ZRKVEq9QXg2d9;nzFTp;8EiG4&!v}mK5ZX9oH~6PzAm+>eUGF6 zcU5P9KaKykpe^j=X(9nVPG!CfPzjL^4KtJyFyL9wtW)@bDOs;Z`DizBj&u;3>j^U}^XsOZg=C(PT}lo5Z=d(vIpT=PzC zCE*5xm42D%C5crGy6qo5MX&jlA(ac0*Fv*{wu{)(JOcyiz{9FS-%sEeRy_}h9h7_< z7=sC#b-c{yLWJUyfB_*Fq5}TxDGB6xWBtqC291OaZavSvB*Rx7!j)K>_1@I!T zrwnT+(a~V{Q9xb^0sLTzyM)aMzx1Vv@Vwc=S(OjA-O;Q^3tDI+~zc0-25+*xa}Bv-4-~o`C;v) zo+Ji8Jko?w70bo%A1NVNH))Bs3e5NX99{r$3`GiD^oI!vGbRN#1Tlkh3JQdDRe{L+ z@ug54#SpO(5~MRg1i}nJ$Vbs#quVe-I{=&Z(3_AXk2PuHH50JsPn4}E672`n2-sL4 zKn5N`!W&mWN0y_Fp*&+OlA$S6_}3B>#Ga4c6Nk78e8#qg!6(j zq=*GcTv_m;t?d^0R1m+WP;w%IRn)Y8CmIQ$DVb;Y5*1Z$r{%m;A8r`o2S>-!mU5DT z;H4X}ZM{b>zBB%uawE_~ltU0@G;*1s60s-~mAcUtIWS;C@PuXVtEiKRKtDvuUh!CU zpunT0Ac{|{(JA;{EU!BWZt&aSU{t^R^5WtYy3g+eH;ar1pj|CqUt1o`) zTHKihwOjUx#yv8Y*gZx`eGZ@v1(Yrn9dHUkVLIRsO`4k$-_#l*=BTp`zQBou!W#leOdkP!8Uxg?cTOV&wN@;b! z<7jW6=akUn_Dxk;d9TOXN@uiQ@=;0(qAUZB;#ra!t|#qbcD>Ok2R&P?>2lmM;-jp4 z+lv$itx!ljl(zT5S(wEwnD6l=`Xp&g&jW`Jv3Nokk&QkYW40Rik#cf=o(E$LiA!O4 zpT+WR^dR}o&8N(^JjNSs<}2oqpyO*w%+X%EwT((C+Zh-bmgRa%7%->`Xqy21Oz1=- zYm!LDXOj{p7bEUq z`H|g#OFDQinF7FFO>ZwJyblOr8O?6M2}0g6pG+R5A{Y0MhG;rtndWJis|^#um^9A5=Gz!4p@zra1mf6ffeIb5>VQRqx~n= z1k5ACL5sGF@UEb$>i!yDSDa$`vn>_*7{3{g6cG5`;(>$#krwKg`X|(WojRrE_#9 z$!%T-`J&FhUcM&ae!M4(umuCs?~FlUMk)$&L3jd?G2#!U!n$FN7K}Xr#+wjm@B=6g z&Y4hhpv&phJqHfHAEI$n=nG_L8pI^#ute|3ltM#C>cp4(ne(I5DIhP z$cO#+_{^k)@h)k!3(OcIG& zgLWPMCAM5^7XL@>EPYm!7XR^}y&Q(COcFq=` z#u4wv5yyqpf&vEo;?Uv4Hq*HjzYIN@>HP2)+0&;f=r(TDQ(B|7aAVJ4+-zT%|LnR`BDbEzBCi})1~OuYaLN8=}uDTBzH4D)K|=YEGy2GxK&z#HzT)% zCIyeO@@*V>{o&Wi?(kDux1=6=MMd=8>$>p%54Vo(MdIZmv~O2VZf!5;8T{4MnJH>K z#u358amViAhHS}6%7HmmhjX-?_JWgSMTL2_t_KAfm6^F`s8+pX6-G1`Y(%8;$jW{` z8q&1x&4;WlDY9ImBF42#R_wF0iaewy|hEK@IwbG~`=hU8UA652|qvVn7ye(#hkwdTN3Q|0HT>YZk_ zJl~(kuq=Pt_h{+$q`C6K_N=U@#1nU5p%*{sRoFFkzrM+uF*C6I_uWX*_Ez41XdZOA ztc=WF8(<-SRlHX%u)$KdiLyO@GSB7)`RVQB$z%%dl#gz9W}0r+kJWrM8V-HLk}O~O z%)K{Cd`jLh?)LF8e~+8Rl@pp9IO%gz$2Z^Hc7~$+?b|EUhe=nwhN39dq-nFCHyOC_ zhQEEUM|R|oN+%mxOk57B z?tgT>#Zx9Hm^`8B9rJ-lMnQx8ZGKQ$?&2zqu6aQp(`j;FEjLa2Z3cBw?4HWXO48`_ zO?QHWbq82f%!-bjqoSg+GqAI>yVH7%GxW4}K+al9R6;`k8hlXeJd&2UrO~nJJ26QN_65>y0?Tj-wH$Qpq0L}-4H2$a9hAWa* zN-m_Am4a;U64Yse7yjorkH`&y%v$R*nc}t*kHdr2(o;?4)A7kN{yvpK+NwRGFiqOw zoHzHsug2hVLUR*0%irt!`!c0$Trs(>Qv3dW5za^44z=7R@&CPOcFuA`)QMK-|K9d? z;7b#dl${+v4j}vQU$&$LE`6(uIC8}EBf5DH9$Zh_!$50fWffdkCtV?#!e!U__H9z-JmDcs~|6Wp|N^7(B!jB&$FYAkZJUr5;PkZaL43Ww7 zD%oBC^BAoY;(EHOsw8@PdVZZTyf>ZS+m4QrN|J?z1=TM@H)AW2e?JOCdlo)nWPChb z3YRJkDOL4V37N8sI!X}y3IL=`}6Ssx<9&nnM}F=^VB!p8YNE`{`)Iu=s%U??;5m(5mn^hKdW#G z=k;;KB?mx{u&3tZfQR_TY@O> zLiatGRBnrRpR6Hea`dF6YAIhL!{&y!F4o zZMP~}9y-p;yK!sKqlzb||NUTjx;a}^6crUyv)@l1q5Au-w~zCdq#boRpzPT(@YHR~ zkxS3K{QTscE&Tr5O~nmi8}w}N4R>a1yvx=&cv!!j;lP0dEf046xANUCLB@yB)X>;AHa6Dsfc}5pPuJ7I3P*rl$nLn?$$vlEBQ5KNT1y25 z+MCN?4qnCk|L>aTX(x=gN;%KZ&U%N3pLe$K{qK{NXb(F5x8WWwsS%y#pLc%rUd^FT zRwYSnLy#<`L~{7h(2(voQQN-bxfh>goNc>kxUx8NX0X~b;YVWVSlQrB-@H6N@mQsQ zo~!9gI5Lvr(xBS%Vp&i?%AugUW=id%zC$hky#;@-jYZyy^< ze!nIrEFv=e`1u;SYqr1G(zm$yc)I0>N|$;TLl3nnu^ughkK0`G{`V%c|0w^vJ`sOX zhl-gK#N3aba+$ns(Uvqk_-9S%_wU~kv9UdS8cPccYd^nBV;|LN;rqWg!YjQ{pN@5< zrj46*bam_AyxFvoh5z=02M=^t#NFqpsn&14Ew#t%$&+KPN#eY*YoFiky*fRx1C?@q zqV0^ky9jBIpdcghDAhx^D=I`NDJfNTbaY0R)Ya7)wr%qr8Zu&KWBYXPyo5LIGx70L zxEyv#-V|G2oC)VQs02WYu=YvDW$)X%p{c29XmXM+NY)1n5HDIP%jF#u6x424b?|(W zY)`%cCj;%!w{M}NqnG(xT3a`Ba&kJjxdo)B?V5Ctwxh?6S(k8-qGDpCHSUq={@&Tppy~1{qs}a~?+XiZc=ZFnrJX5v8Vl}gOvLr+8yL*~UUJUWDWpt06CPvzQtaCIJz+aVd_>)*hlXl> z1A~JpRT+z05=FMXe*IcOK|#vHLrnYeC4-Tr>A~k)#Kpz0etzq%*HdVEX5jg)WW8$F zZ){<^#e=PT@`qmpZ3_$wTSt<`%`y8YzI zlL9AB5WCvp^IJ}m7gqj&Qk>V%Z~gT(HKdWo@WxPfAuF+osh-EFc;zw`Akw9!rGdFu zk$c}&d*1jwIcf4HPEgok$V>O}nP?QvZFtFRGgXTzX=%PM@34%tN&blvoxplgkPIrX zdi(pYQ`gX-AjQYWzk2<;)_47uw;9Upo7j#kO!tyMZo9wZn7NnWI$*q#c~O^1&8w50 z8;I>46m-_$($T-WKvtP4@np)6A6F}e&U}zMw0AF6UtgcV@#9hbWphR{CWSiFe|GHH zLE_P+mi+x)rnkRehAYx&X>RNgH+S}IqHTYv9QxltrH>C~vHf6@-gY{_fj?+^kx5DU z-BW7&_wJRMj*p9rlfp$zyRfmcI{fMB?jD~Lwrt-QvRj-D3*?oWnyRm8Yr3@1W5~$P ze#d31`$X@Pf6q0;*dbwCDO?8sTlMX4zI^_ilAEh!_aG=}!?|mC$)^kdqM8#Q_xUccUO>(6SLe!&$J6CVlBWuq>#7S`7w{;>X^fj)V>1; zKD|wq!CTgnwQ|0fWdS)kIdz8~6J;hppMTS)O+&-OwRx!iq9&%M zAX^MfOt-~v{FK_m;P9oox|&tcgu3$T7oW(zXNY}`O{B7A*D31r=g)`iI3~}ZlJ_Ms zGBUE$+_&qki_2;tKmBodNCw_k3TxkmXm_S~Mgm zeZimz3<F0L9YI@Ybzcarf`1V!M6+{$0w(=5VZb zk29s_&%d{}eq?^Bps46m%%7zRj?wY)?xkx`0@P9d?P^}Wq#-e|umoJHx=ulQ_UxI% z=qpAs&t)dPGP{=+$)5gbs3g)U*RO$jdS#!IZ>`n7e_}D)V|a`6@Zn9Ql*f<5qj@iI zadJ{@*suYNCQj6i->n+wV7NV9Q9(te0o`Y4YO1-VP`AhVFS>76{pBHnpTm576q?7Y ziObZ$DCiY+?|uFaZUyK$qwu8tCIOF!ku2e-jm z+%c0vRtgFVkS=Of!HB!z;al87loL)G|Nb>g@`{RL0_e-VRKwU?d;zhC{s{SFtnDOm>7aPv`$=tCQ~^JeO{;BfwQ=zgmL%o{D|Ga zcR*%FfKI=Djf6)=MNyLu9XZn25XwIL>E*_q;@6o_vTG`wCrBh*G111~f-~&fzkhi8 z!&7h=E#aT&=fqkNd_v&pQA*QI1W3SNh!+rOP}S6YR4|AI_OXAyx}BSwTiAVWA6Toy zrxzP?4W4e#RC!Q`p3lI+5q`qDJIjSWI5^nI#wG;#!t~=acXYr{mqvcgjtF`#U%hN@ z&Lt^n$SLXV?d@>&>h0uY4i8UH=CIYT?~jSO&&lR_yt-m(={Q4Rt|6={N!V!=HIQPw zEjfH)s;9oaeJd^i8?M}OWF2XbnAlG2i-N*J@4`aImx-l+4oXPu&dA6B&n4V=*IN{Th8d}vh@|K?eusL$V|0vla!_=69GukEJ-!kbMJC49Knfrh`Rs; z;H7g|-pT3c;+_F>IP4=C653{3cG$~)y~zS zkVtO(mJk`~oq0a_Q>@|5(^66-@SYdxW22*cjvdKu+)xg{^Zjx>aqCmObmtu1Gyg2UHd!KkPx5{cy* z_eLc%e*JP1R&3{~tATp4kW(TRUVO7KF`-mee)%aSm-!@MBX0gcQFb;t2S%{|Zx#Fty;1n|s%226ge<>eIkpOn9 ze&y8-&;P86#&!eGqR!U#_p^6*ck2`wc@NAgD=EFLy5XjjEMdSuM8h-ggSK2>WY#QT z-F^7?e48Y_lgeLutb3GBMK7X>;u4mUC07M|uHK)%9yeuA^ts`0-&#tnnky4xVq(Z* z)5M_#UpIO8P;Owf3^n5Z{rdwq+maO0+J|yHg`>|;#pSz=#lMr z#&$n!ZE4YpPtLe||9;Syj!aX~ZDE&5CjU)4e4rd1HmuhF@)JO_++|ApLHlkAk5@Eb zqAjmnNhvPY9D9=HB7X31XXIm~$>e(l=t|%|;^W8i8`KpT*ON4_&R=zO^v=jQuv`54 zZH-J7$CV#n-*3Yj)}Z36sj5QE-nmoQL2A0(wy)SbA%WezCEhPvBlF?2XFF9?RM3X% z@Um*!+Wy#Lm%e!{FE5**W?lRBozuzLxzKS${@LQk8zd6y{y?=S`{PSh(rRjq57W}R zPGzK}?L~h8PopFCR(n3}TZ+6`U_{}+d6(|gs%FLY1s>2s$FU}6yQoX|BO(}HG&b%< zeFp2S1?C%?p59CX8m{--$O5SD*W0V(@n>~WzYkrOVb`wEkdRHNJk&%%!Us%B+Pz!y zW(brU8J=h^Y$#|3FHys=_4Nc6^*_jX>8p3wn z`TpHu`eHL)Vq_#-vcZdjs=#B(X%nk}SN|E1%Jo}z%SuaAq74pz{u~&vg@Z?Y?Si4F z-2gmtPD>6encAd)?-pw4$P-XfH%QR;D^3xJpa zM>nE{6J)dE2h@c*-Jv{fCzCAMbz)!kZupGa$I)tMLjuK=a+1ozT!=}Ts^5$cM!loxLQ>vY`8E%<|N zvGe>ju}6;{9q*gfOITf5OtT-XrgwcdTpv*1)O7CK`WAK>)2K*1vbMD~|8)4@CjLu zpVjoAy5_a6Y}qZw3K(Zo@LO~2%a@>CqOQ2`u6L|v|AJup>*K{V?rXnAAo&=Xnx-AE z%J!9kGOS;FWUc}NCo@=Uan7h*q@@52L55aB-F`r~OQ z0@k#9_ipraXh>&pDq?|oPn4IJd$mpQ+M2b$eM<^&99g@1^=f&s;msu)bkfGmc@$0v5jJtLjfZQ2Fp7mr{}#A+h0SuY5>E z{~4~x8Ze3B^?vdB-jL?>-Rwa0ZY)lB#WhamuVg4E;3GTCev*6hK$Hbk5X^I+dVzcI zQB;q{L=orF46fzrr!z*jw)BNMhhsTN1lC8RA*=&@uI61+ukRfsJ`3PZ;)4f{Kfhii zNu4`Kr=+AbG(Nr#_vP@#B5J@LoTZ%E<-esTCfujvKxc)s1)%{$GNIkFC00??d3=+J zi3vfivo-0mHG>I^pY_>}C;Hs%a6s_A$#v`20flksmD<#HH7WUN)*a1W&sN8O|~ zQRLd}CmKkI0Xxj~uQ5`V({I z%(--Rs04CfL~@?4bJ65i6Z^%CvH!DR~Iw7abqwuufX*mS4PLi zC`fa2a}IN(XTc_;qN9hu57#@nWM>@xxApVWsU)ZdY~Cec@`4th!?+=22fY&zhqBFJ z^)9G8aRSDagl@{p&Q6uZ8qo;7=H3BipO~2K87dEgzkan5yZ(a~7^)r;qo76W&d;Ae z8`b*I&^1;&Pi*cvdI)02jvd^wc4lUN;S$TVgcY?1i!(ZUd&9N^DV{4o1q1|YfV~|@ z8tCmf^z`(4`}*p7ds!*HN!X%azI?ehH@blzVhr|y%!Laqt*x!!fBtNMhFRe`=(%V> zfF68ily%it_Lna|(#;DYV1vVqAJh?evrMHM=;>cRbDtmWwzRV1LP0{&kxDpeD{$rQ zo|3lgNw&^2$~^|r%Q1{856xT$${j&4K6URBb|8WM`hjUdz7cSn*8e*AoP$Kby=&L6 zKRll-0fmb=H07(%SP2OmvZD;RRhoRLkIvzSf7lF;!VvgvNr|7YuWwyRPIkz@XW~wh zi04KfJ-zylj%}#1{@{9L5>R4iXJ;LpoIZ6&M@Ms_vqQ3W%S!$)3y=<~27vvL7KMdJ zOaqiIaN9u@hh`8nr!S?YrF8BPlxtxCc%wU|J$gh9$rMFvqP?WJxLoqRlcgp1-Fx>a zND!VzOFb7RnQ?}#J;mA7LCWvmy*o5BbENEM`=hf8N=h$qb0Xs7gU?GWQ5)V`Ezxb% zbfKS2%b3bP=h>_Pv%jvso>^D&*wLe-J~F_ogbQdHeT(|@+f?6yn>gi8W_fef(U0$c zeO%r17lRaUVoI#03EL&=4{o0V4v+5N&=k!}K?1O36)^H@w-AE(b7x>c-%dnGhz0hI zQ$KnxShDn(yP3DN8TzV>qoW`smmsKsCV;4*d6!F;EJA8Qx`5WoZ!Fq9QHfTMF0$aJ zkoqf5(r(yLi}O45<;w<1Ny&<#%9E_7B%TbbNE*Em!Rd>gO%pUcl&_k43?EG8XJ@~D za3-VL>@rkEm>}yh_JEQA?UJx}9aooK`1wRd_3WPCy}R|YnVBPn z)tF~=_Hz6`$l+B&P~}4PaFXP$u=~d>{$U-mveZCJ!H_;lB%-Ulc=2MW#+&L8FE0$Q z-S{y6b8}9@r%p*9-adjiCV749FB4L@>Ez@zgmZ%5f5PUcGw{|bgrNs8!wC5hgyklZJn4Wik^#ewAw^v!u|Wh-FbRWQsxpWpw%S zZL}ZLmiQAm0nn>z0NwyWC{UzeziU;94fJ#gijO9{kn&@bAgq$Jj3=1O@! z!C6^{;K6vY54(V1mz;9b)z!@#=gfPJekfpEN9{NLrpP%I#1cJ+z-j^CavNUSr>1h#_`>5MaZLv-Am0A;(ZGd5@FQZAG>r@{f zb%OkW_Qbn-x~8#l{rq@KJ#MZ-s$i^h_hS%!i6%m@W;lNFTYp_%IOo&2lrRXUokMHrT-A@KF@UKk>}Lw z%0lhxwdkj%r9T&1-rCMXoFFI;8XO$i%mb2t5{RpUGyt~XWn$8`m{-^w6fY(&E{MW- z`}Xb5>xTclSxhds2{*17Kw3&hhRWUDo$i=O*2=Xc^0&|TJ7T;FgA?rD(|e8?MRyC` zflP&`sv40AY6M3}z^sX>i~WR|h}vFN&(-A8iD%PSuXg8W|apz|(2S z;QCI^eLc(|cyeRxcJGho*~e&Wqrld@RfZ2L7>d{<6R4x+Bw6*VmuykHPnDx~|K5M%UT%w86Mm^Qja zv~6S-{U{|fGXPa)baa&D)t5&mqDcR8fHJ(MpA_@2!DAUnJ$0=kAJ?5>=ij%F8m;Nn zsZ+wv<4VpJ6QLzw9b;50&(P5m>2 zXSv@w`?6CRWa(T7{A^#PAVTFPG3TXQT3RY7D$2mRprfPP!$fCnYDxtyAz#tK?El8+ z^se>WnV6`vHOX^JuNs68k`5bGGS$}B3g7%K3>A*;YdQU}ovukE5L2h`@5{3S5i-(h*rE0Yw5I%jBi51 zqOG<;h0W%Y*WrMq=%$3jckS9WI5?$|&ON6fd){SNkp4LVsdP`{+He2|5N6HD?Ax?6 zTb|uqtvnsp&yZ|@qu2{O(|0tpP%H1Cv9U3Z)0Lk5T_4fDD<*mg)8X*Gg zX35vDs7n`z&I?RSN^T2?j%L2Ox^SUl{U$x zpAyimIy*HlTUhW?lf`yF9=EH)14(R`H!DfA=@}byqGLHO|FBH|0vGMq*C%aE)k8NH zCcBv4TWjM^{sIm|h9D6yfs#@Z91|bkWTug0dy~)zpc%pw;&|%%%?FqQuy38R^0Ma> z2?BV5DA~Dx?JfM=UuItw{`A(Lo7C&qj}TH5^Z^KthEp8rY>N8&JK@fPdG`-o%vS5V z?gX$y@T-Z|2fi>rQHlKB=f^pZ9^Fb3xbf2lNbONZ#-{*|n>BHQrr&?fnnGn;2lIkE zBs3IGkT=X=W3XWdFnTBtL`OtX+6j*)prqskw!qsG>kEX1B4Q|kFc;hVa9bF8B%bT( z8~mgpxxI|(Xp*7Q)75oq$-{Y8PMFeefa(V&|*H;8N0;G}5tgsC>*8qOgp4^P1O z$`x8d)^b+6?(U9)tz)*k)P8U?3k%EDFYR)i-vDaMuYTEzb!f;Fz51B}CjV{eROu-r zmzme2ukQ)o{C(}m%peD>T!Lx#u!-9A3fO#ncE5iHs0(=^83=PHZTpChf@?OJ9;m<; zgCsCks{H@3DZbdu${1guM}iNh>e++7Toc<3|2-6+y8h$G-GF23R2{c*M=BJ!e$&OB zrNUX?8g$#*8>%bu?gSw+H}@ZFj^!;@xL~pNdkIKJ`+CRD?c3KKJb3W?k_Qfm!-p$| zRoDHtNd6`qHe5_^xno*i&&1Q2YG2$UXhoneoi_#kz%78NL$J?7HzqInlE>6tKbYbA zsjysj6_u558O$D4UZ*5UuKn5zyhiBVq?!m$8G@t{g1(;KUU6{)yN^?-rS&Z>^k`y4 zheU;E3cGmeQW#pL$=v8`{hQi(x-`zt&e&RnbFZGQX?c@eR8UX@D{**wIt(5n7Y`4e z)Jtc6=~M>b(1FtRn|Bg{j; z#@5ywp_D*;b1+EJfWixTLP$tRSX9*X_1*pOA>oyhlK0~NM3A` zPtjDu;T#iZ6#fY$qOqTOHml1E5YsoqgrFdSKN1NL9A15WeF3LY1-tJd@gL#NCK&;T z5!~L@wE^xCh31=PiL0Mgb9GCC^>%~kc0V@UlCs?Pxry9;53WY)tv^V%q^<8OwY>wa z&ICIfM#dT7;msTpA@Cozg0*biez*pk@cZK6Eh-WOpgVYB#93?W>!~2C0|Bgugb3je zH}UQBTeolrO+iVOKR)qikdD_tr2haoLZ%tb^{{F(n=gM)4Jd zF+{KdGTuu_YRsh%KnU*y1{#G3nj0I}Zr&+e!)kh1MC3leOG3XL_L>cjMDDX^i9qm$ z*p<9Hn+FCGJ%7(O^2~RoE3&x4#!I&(h^t zpdg~6yu1L&{b&O#;5hqKf7y|;!5BWhxU#acfx`9lY>$4#-*9&?#Ogjl^LCvdS3a;c zs25p~`t%;n&E$Iz9<-1O0MP9Wz`m(!0Kl7AO>H_dl#W6 z-OviRGc)fm3ne?bqfv~HjMTH5zNx8^ny&f?=of-@JVrF*ZJqjfrEtW9n@x)l-+L?HlRo&4^356mTl}T?lvgJs|re zdiIkcdet6F*nbd`nuwPr#Uv-U#T>p^hhu&p<+Z=aY@=z2AhHaEqx+5MY$pLL8(2-( z*4AuL@4rIU`uhCO>JcCe4!oQ1fJ@HwjYJ0N%Y;)!OYJ0xI7I3|GH`+JEv`s~FC5o@ zetk`oskKF=*0MwGpzwne)-g@1S~L{O*}1tPvr8T^hy$S=yle>PXu}q-t@Zv;;T(XQ z4ydJ9b^Sy$U~})SrYLUEJja31Tec5`9eqSjo#LVIE-EUD!yO+`_AqnVpu)SplJ`RX zWsM9aV-%ISF-3?}qSG#$b{xIEy7>H0v}kD&`!k${V{o^KkDZqw?8t>=%1Deg&-$)x zeqp{thfqfdMfE_W!st&8=0uRQA{1t)W=Ma-li*{6D>E>`4n z3u|eyussaPA|Hg#eEFF98zX22`Y9JK0&(Af$+L0u=5fjc4Xk=4R?IixzeFb~YF7h8 zzrMaW&3EA^OqVx5e*Eag5ztXni){MMV~Wr<%kfRS#o|`H#{j@Cqk7@AAf=4`G;wpF z95)^k$=&8NW<^6v@24K0+qbnaLCC%cr<|yrtU0tpd%3ufr(`QrF+f7X41Q#UUgqR{ zQHImoQd_<5r*8IeRgcBQ#l1r9FK?&NUyY@KQP;CYA_X;nWPj!U%^7E4L`?N@NBd zrU+|v^R81b_+UsM1D5Gdm04d=`KZ;RxahhQR1f0zy28aGZuLnZzYHiQgj0u5(|rhn z&8@BG)&x?T3y^qe`V>Jz-=a5MBTzEO;1nk>TDxNNZZ6Q3@7B3aSC@uolAe!(jtf4|2CnayM09^CAQOtH5FkVRb5}G zgCycO{$>Ya0-UhYkiGldnZ1p)2Ox$()!52}m3P1qQ56VAQu>jy%_kkpA z@jq*e&!ac9BBT%oUAeBQiG1@&(N>(q)j=F__LEPcPF`F5;8qAfn}`J<& zBFPIppbk(N&Y`f|bfW&^*_7dCZ>TIiFEt?pV%bkj*Rv9;=(bFTEb8u1oDt==Zu?MHo&y-BQh2ZryNP>WY{%8`ZaEOpu7@o7j zHmyo-0%w5E%AFe?7UmD*w5LiOOAanTs&P^7X>b3u#^aXEfwbO{dYriCh<6Km;99eN{&dAiTSN+RmC1{`gjknC?OBxPU&4JxfISSND003``p}JUYSV` zdET6Za2$1>nA87WT{X6~4F!Jj7F-8_ifWUJI>_GA4@7pvuzEBpd$8PbFQM0A?-SZJ ztN8WfZlUNy0k9INX=sK4+MHGxr4_7Y<`YX9#CC^2y>A>c44gvOuPKz`2TNd}hOOl# z;5UvDHR;Dx&lafvpSyBc++=3pg~6XBL^0@pFTf06f1riNW(?9q;#o(x^f@gY((B`H z5P;@%POko?3MU#EuTE_qD56^kP5~N% zC`R_&dzo$9wpApwAxMsSk_y`>0}hv;8uEv?H`6FVml>G9JE>2lHFmdg1dF#RL=bAw zA+e6fWd6>w5X}qcy@J_46Y*UrN>H1)eBxDgYs zv9&;U1VR&1+T=~D(FRYEGb5ZZ_>kT>;$Fdf$d$jfRQhqgO4=B3-Ix9fTpKoQ#WdO<WL;Q4UB^ zO!Nyohm?+<5?)@5h2D)fUJeg-L9 zk`WNdA>;tN)`|>Ut$De*H$Yo*GK^m!OxJ<}0b=ug{P>ZUo<2H(jZhSDD)gs(fVyH` zzYm?BJ|KsyKpVMGK0Dd-n8U}%hpCmFjV%~>?IDUJoh7kf;0Ga;a4Dxpz2im^RCR=8 zQJ4OU&^D$6*K9hUBzF4Bm8^l5!jSv-cVLG7?IRr_g3$=VE=1ub!eD3?Oid|8PVh}s1RBaEkz-7hyp{BH7>9rj za&!P3gH-r@IAFQgq;`9O%b^1Wf~|i-Uaj|uMfiZrg_k`&ENCxvP>UmxS%oso^R*0@ zkM!be`pqLqYZdCep=T{cUDq|hZf<||iWVvn1m1xY*-BalS@t`!^OHz~I|M`1A7Me` z$H2Tt>ehp$KOGG%k(B@lfO9v4GA#x)yUvbfwhRcEL*M~RO z!-OMgZn`>;P$F^uQRLpDT&;*@y++U^GC7%0;q|MoYvm7|k3YTvM)(UtwwL$&_WsGi zQ&&HGr7OlhOi3Xj;yRFWyz6yaTL8lJJye%r0np`jxo9EN0xn>JYoxOzOB?~Hg8NiQ z=+o%^P>_iD3Sq7Ex$A!Ig=~HE}m5XiPVuLDis% z}iF&G&0%g^C1U(igjl6HOTAo1Cod?e+@Q;ac6Q(e6w6UFH*BB5@icky>4kogR|UrNNrOL>P_f~KV674b9a9$rSE|sViLy=%!a#6C3T7C9$Z4fJ zT_5CsJ23k9#YH03xt(ACRf!WH6k?(jmz2DO?mz@kOUBG6h)9 z-Tnh`-=N#YOod@#g5aJ&(X9XQVHbSUhy?ANN^4bv3QQ2zpg|7L%!DHzdZ_r5_63$n zU3n|=!Ds@}y?XQJMWxFWF^xeiJmf-v9AUWFI4Bi%F}M<8sC?B+Z!ItcPauR+H(`usR)XL9qz93NT z+?UBK&vNs3dd$9L`P^4RKt&=wM}Qd1?>S1SDwdxny}3;7f{Scsd}0X)KZh(M9z z*2o}2q7dBx!Qfbh40IkQOQczo58|STWG)0)!wh#sxYPE4&lDPg6 zZy>E}?(T#K`qXWPIIiW>ZwTyzBaguwKV-j+Uj#Ci#BWKzBj@loX$8g1f83+C z>^`kbxJS9QH@UU^q9s(bq>P4b9%`@T4Ab#sW3|QP}Iu1BC8{3TpD{-OLmncmQoiPssB8nMXxq~R{Arz2Zt!dm>G%xTc$S5|SH?2fw zn{Xmr685!ZVqy##ptz%ENZQMVk=s5C6(%K$-`Gz05SZ{J)fX4KTCKR)%O zI=VPTdz!2jT~_8+vVs&6Bh(tgAn^Sl<`)oPidY=0kX_;cY3C!C?0o%`0WmSj4M#C| zl!)DfEDnzCX=jVfu8yuQTgTcWvdGEHpKQ8u!n7ge`mOwX{$?N^ zC`H_0Dd^L=7du{va3K=61vzl=F%95xX=CHmKIM-mHqg=eXz~zA2b1^KIEy2AD|q)SmC5Gu)4Z9_<5k> z7=#1?C_O~c$SXzQ{9zYZP%(veG+@QjDGg%QgN zcgaEXuIT1*RRe=8G9KAm>B5UJ83(bMZ^2~qT_>7%5g}j#y#ZX{tV{3PY7E0*;nV@s zO{mKfa4w)?Vf<|4g$q6FnjBY4iYrwgkQYWV(prxPgq4>I6O{bK31%4NBp!K>-N(!~ zVIs*J9TY)P7J_tJD^c-`Pr=RMh6FYEO>{|(*Mq#GhC zjK})}U1N#Eam!6>yeI~$0sb(U;)UT=L{ZT-M(6fLDqy)KYu>-#fe?BeBr7ZjF;9X* zYxfiqA}UmXUKo;Hu`e1A05Wz584_1gEd4jSb;5F<742;&m-}YTcuU>xS2nGod zG}nK2jZw%LGttXMnE-CiOcm( zt;SMjPr5PNN=yTTC1x2um*C;y(M&ooAGR|HVnpAW@96o?H8`k z!Pdg{ZpG$8$Cm}ozPO5UUM9qS1sp%g5~UmwB_hTIDx{e~AqB%5(o5To>GAR{L4cC4 zC7_>w2Sqg{hA@^h`3%>ZC9A{SzJQitYFC1Xmp2V6#pyms9cQ^B;j;H+K}y1OiwdOI zgIo_mqSbK<4+#myZr!%+bzPkgz7T*rZV(#R+VA=Eep9QHIghWv-gO$mhp{-Pr1S_2 z6C4_f`QN=wZEbi7RF6bN=oKJ76hn8UltK+T!1WO5p#!{%`^b@SgiNx~bbg>AZ)JRk z8BO9+5Qh1TsS2M3@mp(&$PNQgt6jXf!xlj;=%CrKU1*A$48_0&H zZ{C)q3|8dhj(v3=(dqQMu_Q6~yD+)O8qUbdMnF*h@XY;QU?7;E4EVRj7i{5Ti?-b{ z0k>~cS1eJyMRj1x7dmw+9*GC03?x7U5s&x+%Zjc8kw@xgWkp4pQg=z)l{ zf6Ng>6@=$(Ja9JGSP;x-a~xC@DW9bk4=~5HAv0SSSdO zPfbpa#-QqYG``ZH>r!Ts=bp4Iej+k~=647lzsV=#{_4NFW@M@Iox45Q7&K!x)c+|A4O_UAE8Wo`+enu*MXDx}%ysHnH-Nmk1u zfuH|`xk1@9T`7ZlA}jj?NAjqEK+3acVkh%(Va(gNZ;hOEW@UT_HSl$N`(2n`O0u$N z&z{v(Q%jxm*viIs?umKJL#!+&<97pHYJlWI?^4P87Ww7F)3Ow$ES~k`FlKax{b=@V zU|BoZ*)>oAA<8J)RM4{>PeBJ%2Y4kMabjT!+iu0y#^y7Gq93ELw^{WTaN2&T)QV`E zY&`d{sS;^n1svLkNK{Tjc)1U=#Ww9>Wy+)uPxHNpgQG}fBjhQEYy2v7U-Fhjf<169 zv5%TsTGAm~Y|Ix&`KxKt!-^v%_6|jWdP!aLJi@lwNc9jxdsAy`2I}ow2pSmqK#;MM zti^l%`w&IT{bK=8o>fS=yJyXGwG2HMqU+|ZkQWla`8y8NWHmpj8a-cqls{~S8X3r# z(-^L0s;I?LsFVA>-nV0sC~`El7qlRCWk6ItDQ5nLHU6ksuu;6w29=y`cV04aaNtx! zGVr;x3jzJ@iP{8wB9uQy#^~7C4!|)7gUoUO)0kXAvUUFZw{Cze5ruO0@z5X&lh4KxG9d}Dov?~( zcOTp*{Ned6Np=*=W8fU9bST2vs6Vo@nwpxjaN2z~8kwz3B=hfW^3edLKlvM=O;tf5 z(1=a0))JmSc65Pca3GJb!^Ik@M`FUE!NDdhXpityuY63I^3(S=}A?cLoO zXx>>p4$-L~K}c+78-#P} z>3lWhTuyftYQ`LtdwzC7QV73%4Sk(HHY!RLi|`7m3JeGE#JOQq<2d3rTwJF-mx~9M zLKPgvx%v4sfK?btlu~f<9zsm#A`i@d=6@yM8%bqGBY^j-1o*LQt=mD<-OKcJmItE#%V?G+S8EIeYMl)%8gp`r8%(3xU9 z+YpL}?DjTGZ7<|oV)O;o5#I%+tW3xV#MBndCPdtN6<#)J^^()o zt5MC?h&2(@!|p4Ips5y)pCzWwkMt(FoyDj;&X3t3S1`!_XpI zqKBYo`9Xjr^5Tdf%Ry+g*8ljFXRlVmU2O2I1-<6@j_cR27yV8Wc6`{ds5CJ#u@?jI ziZO@PD)pfr!Xs-=*OF|2%Pb90GcBB!Wmo-WmK$sMMNs~MsUO)XI|Ly@LSrY4Qh;-W zsB&MA4~j@okf#Wn70IqUpmp6!hVoD{am0y1KHMqXV>%KsiUWQWmBd0C!hXN<@mYm_ zrY=mN(@<^%Q6&Rqxe!HEjKCM!=ysodi^tGdV(JwLjhckeX)W^gUC%*IyN_Q5O7Jmn zA-5VI4gUFnJRfv;OHsH@IW}iH1i&Y@6>c+019L*QeYfG^VSr5~VvE+8)cZohtAUsY z%R>&SfbVFTBPjJgXH+gv?3Y^mh0&A!zb;kTaNmuN-Y;b6LZ0*?&->UI9@5PupUQ(o z$+%a32zdPKZ~kpNcZLvb9OfGUS0gGv&6lRh*KUKJ0noX*#Km_(s=kdrHdWRC_ALXf z6@tto$?@LtDI5@<4&ksBf!U!S;>Py&N3M;h^T2tp4Zurww-6m>D1sFP zvWSq_D+$;qSNcoyj3nO6DQFd4`h}Gt=0|JK_9DwjWE`5GVGaj7IR!7|bbp2yZ{xS} zB%>HIJ8d;0phdV;`xh@?4g)t4JMZ8Q3jX$`umCeqJ!}fja61+z$-YIu3{wQq30u%Rz`fMN_r!!OBi!gQ#vYy5qnPT z<2H$vO~4-wgvWznFBGzzDiyO8lBxkqAHE0+XsQOTJd#lwmFJJ2I6(|+kfIyUqxPmx z(2xi=kF)|IHDU;(U=|yZa4g_HIbfQNm~O@AGyj76xsK60aP$(RHjFxWPNXak*At?m z30=<-2-_*@x(WaG0{D~o28nSEm(BOoif1~-lQr>mc6;~w+A6{U7|ZxjU`&Nd$}e(7%UJdjms5qeTgKoA~A@WU>h!iS>qOvk4f6QgzA372iyyN93SD z;)aKYQjUg>lyBL#MP+as1ess(WgM_1XrV(O?3fgxAi-WCzIp)PC{T~RUw{^0(WCup zI{y&HD19)-Ny~3OKR=&}gM#62s;u8E&n91{;;nD4d=nzo;0C;>*`~U5z6=A57?t{t zvFzHH${70pIWriJj2EzzF|@th`aonfhhT2QtlNV0_AEjqHhsls9ZWR#<6H#6n5(d#nx&OAlB?OgduZbO#a9u|#RB#lHW(GV{E7 zA&_kI=l6%BbLXR}*xA`nf1u=V!T_nLFg97{dl=lMMMa$VPb-4_=rp{v8^DE?i| zN9+7&=&QFIWO*}t5ON%uz`YPcgpuP)%KIw?<;d2$nQ_tf>wM3v-+p62p^zi69kVty zj$f)J6TrD3HZsy9_rJWnTyd_E6DN2Non>e2;HaeS9E3kca{&7igQ`D$#d^e&S&?g+ zYt^RLYWBeD$)qpvfHU!8Aa&eGPj?U1fyR)4rHlg)ug@6MQ$_91?(}_s=cxk%p3^=) z31tuceA}NJW&juiGToCn$rd^RQfNjcXqmW z6MDgc%Q6nS8tPAH{zw@I6++C(u&~x-fhB3(B;SMBUZ8SjpfXp)cwaugZa8=D+(QwU#x^T6mg4*-IlCWPzS?!`3K%GA%~k`+BZ5Ivbv-}~OK&~y z%@cQy3orH-7@wRb4QHe`KThuh@ctK8MT$c~eUIQPXL8wECfJypZVbL*eGJrGoG1X; zuLDih9{Ee6`v4`tOo`!j8?|;pO?~hTsYcvz7!E{aJ_bHbCOH*{T4|7J#R=laBqsWl z^WS{k(S+vkioY!_RUYU?ao?Oy9qzO?@dfl_USL7eV12?Nr#aMVo4*=m0%vMGRUGQ0 zZcFPLMQ>P7KV1`tsS6lQP_7%B@YH1_pW;JuD$;0E3-l*ooXvLKk}=kk<9F3Arj%lG z=2F(&P)MZ=J&lURw*HRu<6y@Qn{5k+NrFl4wrP;Ao=20{qXi0)~%`J>Nq+&;=80oJX~bK+jL~8 zeOEp`HVgHT+c7zHE>uVVQ9wf;n25E+FAdWQ&YT=xei2T00!o-VWvkLJnTZ($U?L#d z!H*ePOx%2U^F+o^Yt9Idt|%)Oc#+4}5e@5>;9z^#%o=(cC%ULojxph~fQEU~`eu|n z1kpQXbpw9Bk)aE2aC-WVexq;Tdv~MnqAgI!FjyNA#^O%*+puA6K{zb0T$L-K%+4(; z+KIY(AyE3J4-kK*&u{PN;V;S;Mu#U|{%lttIUVP^xfEShoYOqqGdW=P;Hjt`sMN-i zC1ntp=u+!kf49r)bK)DU>T8mq^?4Kg)_WakaddYbGklFs?4~Q`ghauGu32lP60J=xZK&6fxR|Lr$VPwHIxz#-CYakom}is+&`$|~QJT)$8BpC8>(7*;;7 zxnKNt9P2*IhS9nX;0nqAk)Y`!&AxlrJYztx` za?z0oZhl+)NKgG~9fzXp+j5X#Fv&A+!-i`QEx-$RPz*y_?~A_ir316Le?XSeBU}16 zENVaHdwpV!pr&GsK}VxeInKYE*qP9HtS#snA5|hy0gc9x%3e-cV>;YD>-TxZv^U-p z^xBNDSo-y;qh_VIO49j*$BymciEe2%l0&%k$<;v+xM%I!P!s-P)Z1WqU;PQ|){Q{5 z(S3Ea>Zg(uzH_cMEK1$7ccZ`Y3#?XFn||rI`f1T7fScMN8eQv69d*-b7PlVQ`B9Pg zwf6BTyOn%OcKL2RV0~oo_a*V~75cw(zOgLrF*TWK9V4S757#(<&Tlmps~H(zPMY|w z0|j0DiE-Ox{IYUZnR5^Q{C9KDomXGi8|K`V7%sIa>i+i;iA}bB3Q|`bO1f9fthpTI zQk8`x`_Zx&Z`+s`=G<{bYJzS1_^N+CZLDa0wCr7z{X_QTRsR#_xJSuHW#6O&T^GP~ z^z<=~T-~pv%L_FstuELIeGLpQP3>)TA!l>Z&1chuSp;U!T|3$;Gxx?eCiR7Srw{&? zSG?8(g@b`#P^~rdp)D?@I{U%QRla($wkr};Oy+ctFhusnBsN3;HGB&uj#odb0`XkRTM|{2% ztcG?BVsBVu{rdHcFh8T64c(WQF?3bb z3WqU=iprkD0?Y6XafH;GUg2LOhs^L2pbfAVT>mX@LYG2-0d}LMq8NtJA>Ccd>2L!W zaWjN5Bo(pr_th;wl+2rL+y2vr+}J{;(*WR0Q+!iq8>d0<9w(o}9*JXEaFXWQUXBOD zoU_FN0fE7mZnkC?Y9=A)LXUr6PY<>W@F8k&tHIe zXv9+-Uj9`B*O_>F0UQi=;8q~XaYZLLl`Ck6PBEdfUR)D#UMyMhG-}<4m&#~MT!HV~ zQ?)@dxLyCG7TvI9(cBqlECuz@W_C=xcPNP)sc5zrr?)oo{0^X1 zX>@+YM5v7&Al;O~(){D3Ra+t1AGLjK;++L+4S#9@yoQ%@f^hv?*SBI@URYW@rH712 z|8-%(xY#i1tgS!rJ^kyOmYGK(PALar7Jmwyw&t}|w`cSsWcib}lyoHiSUMr23~Fql z^6(irNd+uprBisd+gIDTHo~(+nlNVK&P*6TK9)f&FaubtvD8{qGLh0ceR#Q%yBtdg z3IZd8eNsrYZF~1@XH|qoxm=9G1%8sch>7=8V0w0aJP~WfiYW@3DNqXtrulD^e0w5@ zciFXTO2EfR+_d(9QQ&um*~!wqUJ6Qwsc#-AgGhdNt0iTW}RWTr!Hx3{nBm z+yt+A{pyuig;3BQ=e>t`G?(NnO?bsL2(=z=KKuoqbH~Z=W!Q}u>SC+Jw1X{ihrynN z8Qk!Q8YvzcOfIHWL($ZH^QQ=$5#GO#=;v8wplv}+X+TQHe= zvDD{0Y@X^S$7ZQ|+Ip{Rwb3uDtq|L@zuC%!1^~^J8L+-6)-LQ?e*E2`$y99&^@+za z<+|#Xd-VAzIu>CV;eU@wI|TstR!q?V(p`X>wtPOnoZmtzH5T0!8aI)rURp1DEbQyH zPOHFSnYf~4Y;3F$KOK?(GNuX8Ca8pmL8^b5jNo!85rN$~917}5Y!aLW9gqK+NpyeW zZiPuS^SvUPmy}94x6DGOq=r;CIEhiSzUYn)SDwu`g#i+r2eCp^y1aoavfE>XX`M|x zmcARLZ#*L5{KR(lFYaOU*AFh$hLIM_YRQ~ce9)PRrZ&(|+yt5yne1cR0epIYMGj(_*27oz1_gLP8zK4t+R6pezHWr>0XNu2 zjr{TI1#sTuG`1pwAV#AW*jgnbuPhkyrWO+}I+ynHAlEVb{WzZat4fOmx9{)v2IbA= zEm!6>44bVyAr5$D4lPM*B* z{k*FycL;R_vM$7M_8CP^{=x2n-!dA(X!3{$a&bY z{Uy4W#iphhIIq#tT1ijSUqj<8FVG<{kfS)Hel9PcVPGIq%H6b8J%$ZC3i;o8(4EA@ zt_uHkcOi^jC>7yg7=`?ezObjdx_KdGqh44NibX9g_^TH8y@neu&qnhw6T8VCP~nj7 z<3MMYSkO&(+o3fUX~`+xonhn^C?4aL5|NLJby?fbSFFe7%D5Zi5Sv)a{vzD zCpc(%))6Z3?dL8{6%5oM&cz7ep0HAw~uwq(vgIC?O;`_!PJBf<^OR zemPj#M87cuaj;ri+;!ou=wW_s*KUfI7GTCnl754CuL}y|x6&(5K@)X?%-FMc@6+fy zE`sB;KIzAx^4EKpEsS??M_ULOJhSly?s=Cy~c5w zD=WXQIZSip$i4ejS(${lR|Y2^@?T>yY~k`juJ+4d^ut8&QPUNSW>3&M{WW7}UZv~* zD`R>S9qUqFO)V|#b0%OMW0wrQ1w3ql%+I{EQDz#L#e6?`-`?_21({NSFXLcX=#`jjOn zxsn-tQY!cD%aZWgJ%{SQLE7&PbtbsB9nZUQu-95D(8KC;@7A2_zze3;Y#?o$%eUA+ z-P|V7Q(8ZDV7MIx_Gqm`v44=+Do%wAGqy1(+dIq*8O5#mcwOje_P zc!-1O*L&~Vzb4sETugr1p|ujnJP`@Y0C9)S8Y{A=a#5!5xrW_i$BwO?`5h^Tswx?( z6XnuX*cOj@=@xnec-^tBiNnsNY4^U~$ZX8|xI$cY5>bU?uUnsIm!iF%?Cuxur^Zm2*`qXBI; z(@c>;+2Dj?a3tt~sD414i1L{7%b&rMKvWS3B(}qgd1lA_2(>VR-i;%P(y#1zNGQ&{os<0xsQ@Bxq9I%o_} z7<{MQ_8y+|)Q9o553;H}wigN(Bo3%A;O zwt=#&s0s8?s1YA9}>@7=vKJ7``-K*5?shYl;#5+BT5hE+FpeVgLe>(JyDXE7eF ze>B=4AQ=L3df8`c#1qhFA>;bEQ?FvlH#NWCxwGpp&;f&7l!hKFn+tj%_Wt?#TgcXn zfK?TisE2$TLdJ}xY;3X0+#GBYg{L%zeDWJ`tZ^SVUV1v^1#jO(tk$TZ>g2(o+u{~Q zrG-lF&Y*&j%a_eN)S(cYzVEDmB^j`ljJ$$9mNE`3YF%11B}L@w(wbC1J>UBQ|CC3W zLH^Z&%}e!!s%j@Jcg(OhJidkAzV{1Ax(S!1-nL6%I3P}r-ZZC;gZn6f4!leaXa_)5 zgM_}D;Stf<%?|Wk6u~rW<`sgJ%$Zuf@ttU3a5yL2V0=R*9j`n3 z+SIg_dz54>R-7A2=Pq7e9ohx??!MjKw;PFAHjhwZi}5q}J(ebkIHPdEFf5nEC6g&s z^bdH-hcz%Rlz|TNq}T+l)l(=asV`vcB}h7BDr7As<%=u#8qV+xH>D zHPv!lA`HRSyQ7(aQ=9+;Cxj$X4a30HBW}C`%sQF8ZR9u1!j~4Kp?Y8ZYtP#a=ai+} z@CJ&XB5%<%ib$+$THNzn`W>9*I4?2Wz<3VRp%=x=+?36t&v14P4c#1Cs!H>Ym+-jR z72lgAQQpUroh~q;!upZUg9hp6zTY304MDCFcf-SyY}{d-e?JbFB7H&qRAsb0s; zdapOr+UI=z{GPgZn`tDqGR(^uEfKo+nhn?QAAAt@<&UjfRr~gRyTWb%(W2|zp?*v& zgk8O=+O?~8q4##mfUphUhHcus88UgVIKSR+sCbom1^b(~wTJ;*nS2#LzR~%?{!kR% z@pM7;`S$+cr}d5v*DovB==-G=P&D{)4DCG~>MPaxKw;4OynR5Ux?yw1SE$4O(DUD- z?vPyumwTJV4^eCi;Vt)jmAi`L4RQqe;cEKT<1jh7?S+Dn8Y%I4Mbzv2yu2FI#nX4= zia&eC^n+>%Jke%14VtPSN~x1R%&edYEi!_CIeEqZZ;B=LuUY}79e-9HUZ%MI5n8}hMw}qF$b?v&ex7N zGEnO*$SQbUmSzq?H>Sk%S~p^_9ClIgl4AllcQIp789jFsq$HhCc{<<~2(>0l4K5;j z#78cV^7L_tMRTf6d5M5T7XUfP%|tpRCQ<9Y6#6J!Kqn=r3H`_s#AQ{$x#O3T-NjOm zi8w{i;gS2EG!B?Vb-sYnQ>=mnzVF@4VdY9KJXo5wY`K+=0Qo@0ZV6BQTRp(|N zWUA%1iGxTIvD9MohcAO-y`7X4&n3#-a!XGCKFm7|=P{waU5Fu@!6nE z@~oJaw;Vy~*a7^0#_*)OACsO62@GnJOV4Y!CgA)rggZIVE1O;;E*Q9dJGZZJGrt!c z;qdR&_lz|o07hGgKPpB6@Cf4q(xy99^RB&{nb2^fmJ~UI#(mJ~2ZE>FI%Dm1DdGTIrQTtS<;$BesE|5yX4&vVC^5}q-KedhloIy*j;8dHUMt*)7zf^o zhL|{exXw00g)E1lFO?_%>S?sM+M>UXj~U|hp}Pn<&;~<$<}g=fm*CaktO32eIA32X zg<0XoFL7+=SJ`n8b>A2Ud8l44m?g9vGxTM4)Nrvx!YtktKFT^0*7u(zu4UA_p2TP( z`_inielB-Yo2AT-`q}{p5j)3ek`o|Is)jja=$7Fpkl1l_Cn^W>K!-86f8)a4vHLIvMMw=;3Lun_NC?uum6+S8@;U6L1#k{4RnRLMjzuDIX z;^@XN(<**;U#=)r_#2qm<;o?Q!|UXm>LS&dT}Lj*z_ogaNcz5!By+IOLG z0?V8yJ19z}#Iw92dJIlHlwL`zY-_!G}!TfE(rm;0; zT`?O<37guXHi>gaOUIqH9Syqt*Lh zlVg}scFlL7zQkO5G)b~xQe(i-Y8P_xH@VyCqsmi0jltd;%IeJ9Z|DEP;>J5gQe0>p z9lS!;&xwIGyd%~4tl>!%L|7&xzlZUud;F5pJd}7JRXP(0;!)Sh7%H%>?DBANDqBpM z!NC1yPz)NvfYdJt+P8z?kwRn*;1Nc}A`*rXU*)ba0#DZ~*zY5!I{W^OVQn@QJ29c1 zAwuiN$)E*u$y>2ql4+L8o4yt*QV4NYZ_(R5e|PGilyO#vEVAl#oOb!qNU3fB6c}eb z?a>)V3BDuGvX57Oj~p*$0(2%0)ms1I2?p@^Z{AY&P^UPasw$?$ZI32M5ycC?KhV*sP*_?MN<{cgTpI( z&%WG99Pt6&(9&N&JUC_0(!UhQ6SO&jvO9;$7W{nP>qy@}k#Zo17G~qXl(lpvNQY$} zQxHjJR7Yzu@$7E$dHI)FmvUbN)ZSC4 zFwm}GHmvrv@m7=lELq+ z2LfeUz;OE&o3A?Lj_ZrnTUdCw%=l0C5oI@8S)A{>Zr|Y&^5wUyKOB$ZMd))8GcTXV)l(;^0x%Pe5t#=9@QuUWY_B-M7c|D98b-YZI}4-`{Zd( zmHS08CQ25*?5YRIeOt_n-S(E870< zPp&&Y%6`O<{J(!j_Rx-=*Ua#app+kNZ0vrwkn(|{ig|hO#5seuBE{gNW^0Jzar6ZL zb^k;E;1bk=a`z$!lBC?;b%;gTj=kD2DCL zl&AEe2(IS1cGDN;A#U5`fV)F1;uJpj4T`!t35O@2DS!ICavQLnNC}x}ukzoP`8Ar- z@zg#KfJ?12FE>_*;0O{ih8aeFG85f>fc75uKXvjX%g}1_4s(&6a8FR|WAzVUkofX~ zFfM&`P8onQ=|uvS4vil06Nsj4;JX;Y@Kf-z4~S`I&U|3?O}(1$Y)BJ*HuVE4L?)(h zNzDb=G@6Z{JrA8ce%xgmu=1w=8S86?)RCNiu~5uRSt=2GiHz8o4wWm;q1_J(Rr@K5 z==Y4X{*oCGS`JB3Q!x_T_wiP%`NCn!f=meRnW(uA(^qTY+A(+e8VDWnEg%!@p&{x- z^+?F?y&lX|Y#pFN;IWsR(gV@vFDRr~yus6c3olKlo9D6O+5!u1glvjLnebDMbc!ohf!E@exQLASy3*J%LO+dRMxy-2VNE~N4v8o6eu@;WuGp1BdbGf@@ zeMwfhZeH-U{=j;&!9@&;0MveCgqije*N zz7+Lhj=MdlJ`SFq()@(MwI6Tcn?<)aCl40$d15h{>;(62(?BHHLfnydkxGrD<+7YJ zk5-Lho+eij$pKhp76Z>8IG_e;2V>d4Z{g^;H7uRaY!+LKl@6BBE zQwxxqc%+{gTQEzmjYAWSVb?2_d{Wspr^tErYB!x-Gi9R4jkEN9O@uzUfQGEfkwt7} zFVJc#V#I`_&$aTJ9C8$X(yP~AQ^y7BsFncyQqC%30HCD$mLm?hvozJe4NHVYs#0Yu zFY}f>d09V$B&B6<-INtI706#|E3@d%BzMKzvm&76rYJ@e8Z8^?P=z%{7>jjaZ5%vW zYpxqYQ)EkPVRFCKkLbF7Y54%3(B4SU#7GO92^n*S-+R>hxVf3xnBFbN&5n3iz>d1D zXU+4!*VX!iqqP8*tasGu(^?m%A|{Xhgsk(@n&^r*!>zG}A~K9+Di5GCKegoL%kHfM zxg|VX>~3zyF{yTv*U9?vy?eXYx7wjamr`57o`YPPV(=KVHMsXLa;(dKbA~>eD*k%# zU_mj&daW647T=9@Dr-P*JPsO=H@Pl6z+r4${Z=|(o0jrv?lcA|e~y{hqQ{UVb>M*R zvL$ZMx}-B>v-^t_tSOFPZ9~lp{TkV}An`d!S7v zoxsPDz$6?1MU^uU!Ap8c$}-WxBl9p>URg9!iDfybK#^q)3gu=E1-;g$h(qX2l-Ich zB>x8o(_e1yAj7o%`(Fp8Y>~Y_1YCba+EFjBZzc)Oy1+i03fB7RJ}SP16!-Y&w`8(( zN61vj=9zCtsQt`}k;W?m=<>&I*q|8_5_0^^nL3?2pK4oRyK2=|m}rqlD(Z z9~orTl4*q*GiPpOz%UP}sW|c4{_Y|BF1%L6?em?ER^0WyX|4_v$^y=Cp2H+Icnvov6uX=|Jm=OzsTtRqZ(S}gN@OGLd{A0bI^{P3b0grEY~N9!_iThJG%O zK@Ua84K8;f5DF5{o4TjOx9N|B^km)PQ}NVfpCk zbG5qN^qXzJCg*DNbQgBAvTrC`1EQwRogVQn`>+ydnm z?>IQu3X?TIYMij9?pqn-vkEqf`n)h@f$Eodk6D36$~z_<(EfU=xIA8e*`Fp3&KtDy z(k5t`(n36@Ym7+RyR+*R6<@6H#EqG7@0*kUv*Oi#vFzq7c*jj1JyTTT{m$F}b@Xf= zWr%K>%Os7j`(0IrT0UBP$b0X70%|{`WgU;$RcF-iJtN1R&gk0k2*ZZwiZ(u)(0{|z z%5NnTHfWB$)b-)dth?g+=Hv{$k*2d+jxH??9e(VmAhGFx3l^)2xNl03tW7v;zwXA1 zmF?AWR-fAXO$A+`|6b|fFlwjaUNMj&@FMYfjo9YoIc+%kT|gCun8=|DMJF~6sTk=qC{zU&noWC7 zk*Onoe(rB;ONaZcIF7>w#jXotMnYy>oX_dgro?~Q1t|$GJco*5ne2opue{6sIf3j( zv~46oWfhe^6Qk|&8({fU6KV^v{}jLb@@cfQ>lz0~$9RAf);7z=MGBW3pmM~AEkO2m zF}Bi>;P;!VsF2Y&C@D}^i~9-qCP`Rk{T^i~^{0`DBV$_KQ~4Pb+Y1V;j6!_%>eVsK zve`^1rFszczO-&&j_cqdE&EWvHK*!Wjo4=Q?%iSvJI0CjcIK7kb6J?MfJR-s?@SWB z`Yoy}bQMZSWIeRGu4n3?ui^tMT+oq@WoQHVwf89c0er|d;UfohmBN(~cwnLQ)&iSV zKl%#CyjTl0fAZlsa;XaHtXwiHOZTbjz0eRZTRSyC!r|mEgj&N$q*AjGUrPM(oHu|wuBdqwYRflNkT1BYcpl4?QU1HsUb~4prt;IyqZsR6{vT6 zJzm=1R38P*Hhlfs9ar|Nt6uwl{P6QKzD1PggtQ#WtQXU;S~LK%ryip9@Zo*?6hN3X zDK!*~FxBJV0mKwBJQ*Ma(tXZ?)CN^!@P^ttm ztHFd-ap?XkNIO|O2{r?C6+S|#PMuC%=l8u)Yxny3-mCcjJ>&R=k+EI19;=28Ql9R( zbn^bO=grRca6IE~?6`Sb|7i1ZzmI?3-QB&z)RL7)cdvY*e(9d|g-aiQ*c@?afKi%%*<>W&DTDCMO$xBOlTKREs$JIGCIQzx` z|7dhpI!*%jQdKpK+FFqk*7y7lW{!`kHrv9+VjvUI^%C(3o>>f~7-tTuX-8#-% z!?39j!6GiY$+lYCZpb_iP3xe;Unk!%or2^&8I3%A$V ze)Vg}yz?qZ_Xp6$>h*0=bwjkzvvQotyw2xLdbh;ouZNo2nF|;GGWuwB(ddFvZ!`c5 z6qw%obKX0@#iuvOxMFUuZEh``OZW=3;l2R|*I07wDt~^rSp+vU;>nwLMh$!#_eSAI z2y}GoRP}^r1^Lda&u7_wBR6K@MbqGP2(vTCkLN^AaUPQ!GA7+xLo|dYCP#lfD&_O7 zctl3MTk=tc*yOle97RJPoZiTDP5&TnRIW|y+_Edb>a^SUWV!7AfNt7Gl!=IFU;Ws2 zJ%ibup>{BJRUZredU%qYQ`QR#f6?~Tw^wcSpL~5B14O3{j~d|{1<=W)f43UzZ#~$O}M&B=G=dFbg?pcg`|L)yMfB$<=%&H&Xqe=SRG5mT#byTpf zD6p6B*q)x@hABx&({n>ktXaK!hOu$soBmZdORK1Nw{AY!@%{~bJ8F2`H|o>dZ9e7$ z+`(7bQJH_A2mi3J@=JS4W|q}H!;D^DUH$NN6a+VbR%9}Q4tu7-CI z9WyaCMghI|>#XWW`~1@Ig0(ukcI_HU*5*ucL?ff3+FepVe<~zoAoh{P%OcTm;{+Y) z)DCA0zMij3Y@?HVuk(7QRMFX|HuCjAfOg>6F&&y}>XAVin5?gUcc)wNz!#``0Vqx& zI-qJDu;FXDlkdl8oUYa-lX>0@ct>T&U3+~wvmCWe@v;%sk7#~DV;_B9FD~hEe&BfZ zF*sO+6&zbTNAnu?H%yPqrbQgT;t+D8>bq&?Kco7>vgS1Ku`>%!x2E_BOf`$b<>q(r z>G*{gZC;0_y<_=y4bv-`@=2Kul!AlCX+Lm{<$AIS#m6Z0oeQr2Q9mVP-ug0qTTM8v$-c2Fdac_Y5Qy}_)CsfNdz{6mJqTu}CZ%~Sb)E;*D99T!sF^Xz5N zMZ?1tg+PCR5NnNg03#`TE~Z;YetzLG$MK1SQGfvh4oc#RRL-~Fod?Z51u>|CE(Zf( ztXX!ZSeij>5AjMIHW#~QzP?V*4cSlq&;?g{bo?px3|B>XaT_91H|!npt{y-_e~yRs z;|m+Hp{&7aRU##UZuBG*pP|pweu^iKjQsHLI1W6WmE11>S^VYr| zM0CYy!`{_a6j&@Lw=r+2NpyGqRy?0rHh`JDydjiRVjD+=qdH36s$XAMoh1u$m`4xH1!O>657+V zW?UukSi40viT0pewMUcE4g5mm%6Rl|Q)jOTU-vEWDBpu1tq9%v>?tFoZIB&};QuqL zFo2R8Z9!U+j8Baxy4^yojnE2)U;W~!HKMR6Y;#D;5}o!@3ZWa+613c zU_}?Vggl3sLILa0t$X*|OB*(5ph|26#Gyft=gnesZ2@tNJ?0qQPp9K@wY_IPKmlGg zIBw+?q>B;j{F4ixL&!{Z?=M)Tl>YOa3V&zgxNVzWNIaF5Ei!)9@d$&S(yVwj0AnqA zV5>i-FR^OBsK0w_^wFRJel6!EodG>fIh=}&8=7~i=L*CO3MTs5w>DPx+P}3a@jkk3 zTl|`m`XDs^7n7_tWG>IM{%IUt8rr<5Xn^FBp?8MU_p=Ry+iEpey?0e?3Yf7 z7@=-g;LVgTL36_Y#O ztkeH)P$xPrBzlKM`la8|CObN|sX76!Td!LzGR)ka7jE9EUBU*r>&oFpFE`?2BVW%} z5!Ln4*W6s(zfFnSNUDRW3^ml!|GnzB^(hW^ynMM7t^XtfxJ;}+hy5cI@`)24N?cAtO z*?ETy=jCE|bQ)3YIyO`|I6XZNAHH|w$HzaDkNOsKop#}z2&7Oq(L5BQ3Slc}%CTQ~ zQbtr5!_=MmpN zBs0JknH^{kS;b850pNW?SB5O{TOR#w)v0fNoIf{&TPe60-w|Z&54wM1w)HwC<`Y8I zi^1!9QKM5@7wkN;zh%|kHR<80@e4v0P^JOMX%M6Og^G6_qrcKdrdU$>-db8rVw0r> z=;#r%Z$^fF>b|u`FqZLf9{1TegLR1qY0T^P74^c$69j>lt z&_;mRJv#S^rV`anv`!k$w8f)iI9LI)DEMIn2B5a}*_Fu61_9^^4kf?#%P%!!FeIJG z+v}PK7~6&s8-jHKcbFiyi2&O$m2!ixvgrv0c=80JA*YIms~?2FnP5o)kGK2RZY#6-mP_k|3l!Awu2ZF zN&Vb*TG!^#2Q|;NjG;bMFq5rh`n9}NOf8VgKCYLn;Ev0Ttzy?LyV&=H7~Ar<3(y&g z$J!Ci^~0FTh&CNrb-A;?6L=Nq*YfO%D2y=Hh$&pzA6ABOqeL{=VBR0|RX^^|o()H?(Noy549ErZ_heanSHre!LQ`KRghC z(V^|&QKP&`u5Hs=Gu^#yTg&G1R&Nj6Oh)>Md!*C@!m7|dfV!V{{$5$|I&bB$e(qB# z+JY@pdUC;S&t=$KJvdp1JC;v?JwwoASbnde?NyBR+{%)g-7`91{8>kBW+;={U4 zJHC2jS5;p3Ol@Y2H)YcUcNSZF|Ll#A4s8)WQP?R;nNyq2%k!H!a>fvT@ye4`?VhfC z@A{*|vH0azovQnxb@TOq|66_}BOmVl7Hy44IM?cb8`Rq?2HHE;cy^RPDk>k^)P5fK zyL9W8mJo)bsT1zESF)Y_Qa>X9Or}S18k)9+GX5_LL{FV=U|RP)2JZzqNKJT5Cq-u2 zM=Q*|EHax~70%C(B8JZ+9==gOF;7Gi_=e7k)vNlv4bGTFO^d<5d@>ELJmCiuRBq+k zC@wgb%mbUd#oEHe#)GqBl|eJhJgMjX59rPeX82;zlMEkE;oAr z))O`vqWG&x#ltuUn=qm-I{#bMoASk=&O=&=i81583|Cf=LM8Zd@N9F3C-i;Jz+u}yU-2_Wtx($3w+_bBrh zxtHcIzLL47@QfQPB@@j?xmA7BIr2?mSXZTNLer#7XU$Yz=__)rYv{zaGK}I$aU~UJJ>1X%+wq?9L zYE+>R;;;d$Ln}rE81y2aisB1(UcTiwZE>)kO7`yRygqI7FI8)!ij7$Kfjz-*X+mGs48%@s23;_TiL1DTPkK!NIIB z36kp=H;2jHzprDebQebxpQ@LPSese665z+ic$aaQO`FovLEcSzwOT^ajkk#hld546 zzh0@}g`t{deenVA{?%&aWxrEORg?+K5a{DHBoqp^` zOw)Qk_-J^9V*l1Zv4&+G&5u~M-(=~Fkov{=%pCquoiI)vw~=ha*K!}5o(>vl7U`Uc zuecUPWWDf3RT2!7I;Brl=+J80cuR8E<+Lb`+7D^A?MCjq@o|aG5LrlN;Md~79T^?m z{HUtFczC3T=j6>KtHlUaq=lC#=6`%x>)JoH0JIHOf#GN4Y$*_B9>Zqbma-+Ni?MyU z8quig?bIHZ`=RHR#dm&TFoQVNl=1|p2PGGd7z(fYjT_&x4DAnZ+O{M%z|Wbrik!1; zh+GikG4iCk`faR|>qmNPc6^uD11d>n=wFOli^ z5@`~!gd!4Y2VlGipE+!CXj9=W^M6mVgJOLzlZ+^A@gbXkY9wYoL_3VaEJIMP>_2c| z97Fp=XmtcdSx&_P3IQp)9b3JLp@n@6qSBAAq3@jgrHKMAMB)yA&Ee`XDpK4G+Axs_ zexm*9bnvBDoIC%oX;DT*XYf6@MikI;rSZ#wcrGhRdOW$+;R^n52!OT@T;a?iF)P?JX= z^EtZKkoR}JcDc9c2soht6wvvmuD4gh)a{gsJmXa_|LSC|G28Xqzn5(4pFLq`7Tn&~ z2_)|wP=amJ$WJy595WSU8+#3j>WK23%_H93?##iykl`TE3>aFQGR8H58h22`DOJV9 zfpr`B7+&1Bui2|rYhAw)opW+b8B}n{uIL&S894<0%qvp>J%KtT4?#!K0?)mW&7-wL zPQs#qnR&zBTrF1Lz#RO1o2p}~9Nyo;q_8J;4DpzS=+GB)LF@w957K=~?f(>Rr%b-f ztMu6M+GR8oTV-v^hnF+4)wzRWgt?kCaNDi?%jj8hr#pXX4oJVjHT^GIiOP!T?;bKE z;ezGTqLwKwm_R(u4aaaGE?=|NEO1P~8P}vhta@`P38G$px>?0#|K72Y9*hzQ zVzE3t|FDTl*h+QEex&Vt0Uz_9UAt{U4c#v22H#e_&fA{S9a93+Tl-`eRaHje58Y9P zxps^F`td~HB`bz|>F~O#TlGV8(^+%Fb+eJ%zJ8y2cK#^uZ);chRMUv52H`}>Fc}L z4@>$Z>}lPIvzMZkj}BO}Ct^w!RBmBI$@V5cXqrQG)lr*c8{%&$1)G*umQJo-ku{1% zier=qAFfu_9w7M*e5PdqPPJi`bCYd1@_m-fz0KXfnE4t(a_GD`zgaV9E_l?sMGO5E zv7g31#gm}EyuCS;aRm$l*Us_&{QfPa(apY}7+u`GP1bs3t1dT4IUVRmb!8>=jYt86`#dkaJ>N$NrY#kL{~ZFo=d> zIIqfI#A*PmxLLJomfnzkiv_6 zFvfk~Q0gIpLa4rX?B2bY|IyB*)*dZWx+b9u86ei4P3)F`Cty(q+3;OjFLSfgsmf__ zV6;1m+0xBBh*bxME(a}_f#EI&tw5MgQ&|(}PRvYgUO03G+me@q>o2|Dkfq&t`)w)! zobDio1tfAf5)U5p`wXif{o$}bZ}&QX-OL;vSngdQff{c=d>Cjs^#|TuUX3?jnRjh7 z{hH}Tqt!*{eT;Z)kZ%IdUo;Z`&GK(0&PfOgu;9%Da+CM>Ls3dY7pYmJd7T7AM2077 zrmc6_K*bsV$TbW;d~4AzXY@!D~yH2lEYQVkcLOsa3gA!&}k z0IfKJ%X7(&T_meMTSb+X=<6*dLB?KhZ|~AY7mYmKGB?$k(x+nRb3-~sdv&7=$5Ss; zo(wk(Ffp^9?%w~_=SRBJ^@pEDc#(*C$JLB$IJ6D%ndV_`9b|OzdOFJ3Ma+F<)*rIB z{m@xW4Q&cJs9xxK6LEAZDB197_!6kK2OqhwPtvgz>Xw7>F4Uf;MV{dvd&&`=7>oYy zo)iNo9~hXJ6s>!8G2YXqxy_!|{jM7u7?_8!O&~K7ba_~fCHRKDMxiYl>X0Fyw6Kdf46QFw=$q?!T`cChigG_y5%xfO$%84xJiQsb{26D4{b0HZsV8Y zWII0X6a~Y>YwOq2Y=Cz?6I9JHx}t*s=45&hE>9?)Jtz&>dYb@C%}{jBoQ+BykCUAR z>LK}Pmgm%xBwtI^s~})n983N#3{GFBAQT{gYd8SF;yyefN@LsNfGf;kZuURFQwR+QA1PE(hp4cWL6~=xRv;GTf+r*{2STr$Y2;(;yZ~q$CRNo4P zoeC%fC4K4b&U>Z5<&-)8Jx3i3m@4ydX1yc7n4UNOJB&EbiVLmh~%NGH8 z8wWTeOGP_z?s6ag06f)p2=*CzdN-kzEk8v3igO@vVQ_Yw?7ZgZu4Bn^oUT(1SvA0n z_Ue+TPd3B6zT$slj&23t{0=Ty#=a#Q>#{bTw8l!aWuceFV}T@&GVSgJmGyc7%V=S_ zzGo|k(RQ5SO-7xKH(h=L%r?D%=GwNn^t5}93M zf{@=;EM$W&Y=5tpJV%m+wFu%_tFJ>SqG>wc}KXv{- zl7Zqu8AMbWGo-qc%|Q`wuI?fz+b5`9Q3%KfKQ|g$k6U$`b~ny}DW!+(ea4q+5~?b~ zaOC^M;fh9#?IZXA7-eD30zz?|SPHIcuf|RHfmFr7x;`pQ8_H1(~Ybz=4nQJ^ZUdcw3=a zgh%0pCW|y~`3iH1`-D^hO`Xec)T!WIf+AhR!Yiv~-(@6;PGx+GefYJ_|KD9w z=mr6&D5;KfP;qIJ6VqlHDt2vG&>_0FwAoSB%|`z%y5|k)C0Ijv@O$~*?_#zlClmkO zJ5S68g;9m?KYG+;kuxs5XpGD$?b{Evs|^_@C2GWpu~k{8*Dem0KjorSU>?h_?w|(F zb}CjowTwRx7?t!GZ4rGnREx}FLZmXegmn-zt3wn(tb6V(ewJc5|92QonB@Kot_PLO z&Hz}VBNMtfdD>vk{~o9C!}wacQ&dxHh4Efe%BX)Di8z*sD&`^Q+)SX{uyKKlIH{dU zHR0I4i4sYzr1bs!Jc`B_LC)WLQ4yBeEw9d&lY{=Wc!rnL7XqLQNUD`44oX-4F3C`QuM(b)0XJbt5y#yyodTpuLMPKUplm9fNRTA1#}3EP>!pWH&O%6SzN8ABNQ=`#ITAb z%=Y0*q8?9y_F-*ZB9BRwjudNwsT)p|9Ou~!G4Ab1v{k^RyH!Z}L?jkmPBxt$b1Leg z05MrGXNtZn&7(u$j|+ZyDcjEzSEJH!fC|c$ut!O_WR{=L2*i|%j)1+D;i;M+E(`fc z)S>swhpzuJ5c7Grm5l-E%qieUV2nA({{A4gRqli+pVIcdodv<4QR$q^nagi1zXG9H ze>5z^lR55HukBjUg8+^SZ$#YXUQ_0I>9C4MS>_5u6ScPf@kd|A!vLjrd(#S|x^P`Y zT`lcfK%Sx6;J|=y(Urx~kMa7WN$SG1IweWLrn0ND^)x+d?G@$8xG(hexUYWSph_n& z(5!*aEI(N8Ye?^N?(Hr>B2YXlnnJk>YWU?B$!>hWXTX&M6yHC4f4_r*(ufM)t;f!>&J$Z9#*X9T(Y(JZ@k!K>P z79_rF!g}@7Bw_fOw%&^tF2tnQoEgur?-Ke%ekt4Fq+@L+UHCypMnPn-vD|%SwdxDY@kdQfa}Y}secOJ z$J@@n5d|gq0CR1|fMT^@CYZ-KhCa>;3Ix;|`%w7f)#v4AY^43if?#P!>P4Y=v%SpXxw4VoS2L zXBEr#Sy@(82l1IUg(H2kv$LH{r|7N<{4MRrcfH-BATsw6i*V_DJar0MRAf(-U<14V z)v|YSSy>r|@B0Xl3Z%CPbZiSpy4kH^(!CiTkzS737Lk8e=aJJrN?qpHvPdabr>Y#v z&K02F2ICA}fR>I>eo?u7#>?_ab3MrVYEZ0vmLu6Y z_Ne+8s%3%hPnJ76Hh!jxa)A=-_1`)vuX(>GZ^!B49S=L_k?zv!&$xp`r6mNA%vI6a z1Gn1zltPth=Y}YYum*waSthfH@nJueU{0rOGPXi14>=nhFrrkDNCMggfNnUq_1 zfqUD9;kd`w{x5*-^|+5VPaM+v!N&69T2(Ot1g=tmsIU{ms{i1Ww0lqL+}<*hvnl7Z zzX$xkV zGT>hr@V@R-MJ+89c%QuM?iF^e)J#?;8kP=R`Gb=5>bSj&p_qMiT>GluPgPmLarb2H zH|Pm&ng`1S63Pd_4B6}ABDryGNz|2$QekWlOxLU-cDrArzkm831~n#t3A2iQ_w>T5 z5P}1hpua&csL<<$E3eK;qZhl6Hl;YXK@x{ZoUEmgrx^uFX^9}j^<(tc{65kcpe5SP z@ujR1?ngml2JH?(;3cXiusQzTqhX!Zs-E`}=D%}Zzh0jnmv+yhGdnvb!Z6dj`d%Iw z+VePV;%*?QWAGBEUQ_5U0mP8zLehqm<3N{c0~u_)M3XOtBD5h;;s9vX|LBxtqaYvi z3_Tjjwyq1Ruy#PjoHCvUV$w4JAiCVK{gZ8X4N27Dwf~l3Etb>RI}dbAH6y&cRDDrA44=vn+B|GC2!(TZ*CSr5Nex|0~&GxC^0D7cEk2T@OgeZ z?D&L$Pk&@{s;7EuddX3t2DPJ)G_V?l>M%5kCx2^ke<+!Iz=EXquvek;w{s#8eK92V zke*wCzezPKUK9VMS^q_gTimM38gs_;r0=l)!&-w&fLZ|ro`u1ELAu_w=7W?uY|Od0 zt@!rsTN~U}=?Js9oIy3SRKAx_pq_~(RX?Vq<4WrMhUACwKt2){iCwUbB8IsYyKAn$ z+RtEp7y@cRL%312qkAY_=Dj;YisY)^F?_0c%g3Di?nrgE>Ada67<8jxNXHpE+jVO! z%}~o-XEK&;DIlT=3ELU~buxja$iS*Xr2z2yC&yn?j>ZHV1x`R>!F!Ks@nR~f(j z*^xP^M_k>~&`nuoRPLo?d6pkYI(?~BW#IbG;{G2Up*T6#pqB-4Md~_W$RegB&#d~9 z$d*^PY(XZ+hE&)u%Um*mi+jJkeUoja_8Rv+HEikoz=$?)qmqeq?rnIL2J>x+^Y?Zx za)@5NdSyAiQI+;)e=oNixj7WZLRiwNn=H{S8-2Q~H8(J8b)M@Srqv>WVBV+~{3&|f zr|Un>#KV$~m1)2Dw6wG*W;>*!oY+Bci{3d+50hE5$O8u*O0vC>HrQV-c>a8#=^(eW z%;r%2C;bpGPaJu^fvlU?S0bdmh&eEZug6!~<#FFCz!U;kL zs|yJzw_16BubuprVtg=wL=XH_R9F4+zW*n;2X;pp?#~IOb<>)DtV)BfJaiX-T__vW zx9rT?&8*H3Hj!_=Dce3HW&=w);acxSSC&Z;^aI`Ae!In(0SL|62ZTJij&AkE1ap-a zex~(a)f~a^2#Oc%`lad**bdl|T-N}y#K&hzz_R}W-Z%RF_yc|T1D7%H@HZ$Pnh9tC z?YFX)VYRC4**vG;W>wuDrj&E&6azxn1KEvW9eVla&x33*rj@TZXKXTD5CLq+{y5bB z#lRWWe_7SArCM?IXI8$VJLEtA=CHY&_c}PxW>wVatm+aZu-?^zkc};V{q=%P?pR_6 zuf*R4k6~?&)&&|8cM!RrN2HiAx?Z!VC>C^Z& zAs=3eXq{Cp=Hq6L=Vsnse&szhaX*Fze-=u13?y;%Ha$D9pMPs!MJbdVZ*Lw$9dq~1H$chrL_7ECQd*mjLmr0kt4m} z3jzDBLP(QupC6c>YH^P#h-S^3k7Fc{z+{eIt4#0pE#y@(i~HALh<`i-LQ$^kGnZW{ zr9V#1tmZ^#MI+DJj)+Oal(hRsdkq$%F4|FnxEzB=dh% zFbHg~umAMK@YGhiA1^7yVao_~L6PqoP;{|vX16oKbBC*`qP`hszfN6@ALsS$# zR@E=t{D0^L&$Z3H%lSdHnwC)lKbi|DaTbGqCMab+wnBEb(kuasn9&0385pF#j6f17 zt69;vbDD=Dm8fa@uTmOqq~_2mf&CIWFgtectSM+auYDzy8)Jh>BqG;5+6)Mp8o$9s zk{sGDdi^BAjmFvVT7QLm@vKg_>cb)rrWLu#@RV1b60dN&;8XYQKZBCOb5-xPCUj=flh(u=fBJ8q zDjv1n>1+jFE#QPy!K_-w%52hBiAZ*)e>M+cWS|tez@IQ} z5S~f)Nh6os+fx$_dpmFXU(qK1R;}eZrPjUsc5XE9zSvo?sJ0WY97z%l$!IDr#s>z+ zAskac1ZA~OelpDQ&8v48$&5c_i-0`ZG*PQj_F!Z2b8zFdg)R^hEl&BX;3PpNgfL@R zBfxg|oy7}bSs~_vOjeI{cJ9tDqDl_Lh^ z^vq@m>y}1xFsWxXTeTnXKY+VT?bvknR5!l#2mXzs%VmViXxXHaGdp+eIKRr<*N@%@ z+aQOc<}F*A-|ONGe~AG{n`IP7EYjGIf}g#K`~l<@dd1AfPUa`g`&+>+8YMm_uknPA zYyJQ@MEAyuih&sntkQ8;k}@m}k-qxs#D7&E z4dk+Eqz{U29*~!@|KdTO=GFLm!3N-O@i`Re6f`jTj3zL#iqX}TJzy6o08eG~FZfs5 z-I*5yYIKa3RaN>6Z(Bukhwh1<`*F355}sxz>{83%AG3tzqtD-2{H5%DdUSl;rRe&y zW*EI;FD7Y!B$9_WA)hF7Z>&spPNK?ZV(|RyA(W}XQ+iDgtoQ#zhW>n~nT7{v6UX+k zxgigR4}YuwZFY;VZIdgzo}~d2ZQzfjH|HWXE3=6dXrg5x6a-yv6K{Witj6JQRayVx zVy_O9kyp8XYv5D$3#xYM`dc3IMq8c;*?GN6owa!)pyQvN`Wy9a z+_in4p7#Jiq03F9b{oTuj|fMozLUK+3WDFZJBxkGmXPPzjCCdTGLE>4|KRuPqsFif zh%a@oTMK2AT#S3#SQ^)3?~S(ThClngOP3k5W{rhlM`w~NocU#tGpqJ)9v)V&`e5#F zJV32c70qv}wCfha)>`WAC;L%R*#RL7_rb`0G9pP34Zo4UGlzANrr{X@rGsNuEF%oA z8(>=aA%8%Z+rsOh?!8G5Eh|?3(dqk^cFcOehV#=#bKUBwIj6vnOSfB4EW)0fTYHae zUiA9)vR8vW?*G8Ym2JHMW|b$uUKKIr|6%RT<8t1&H|`tTEc2KlL)$#7l%dRIC^Kb> zGK3 zZHDfVw5n7Y;pJK7EBy?2Mk9byvhfa`)%?u+`$wfxz#n0UC#Iq!nT&I_qqTaQ36&fh zS9*b?K9gxE3zN^5hlmKCc{|irb3fmxNQ^}?l*b*wP0WBdoHY3FDm-aP4kdJhjH1F^ z!$pfuKPjNY)!YY$nDMP$fv-cX7vt?R0oFi7fb?#}UT6J(SK?3%(b|jm;|cZjOczbf z;P~Vv6`5d&tK!Q}1OQ0~_35SB3q$$G5N@(L0DFC(aAjP3>UM6TF%3bmK~Fp6lN}=| zAb!3=<0XSdH2S+`4*c&6f!q>Xj_;OnXuW4GAuT^BY|QzeZ3c zOk{z^cydl`I2UF^r9sQ(`tOEUM_wqV#tE3mECdX)$cDJm!)fi|O#KC<>GZMb}I@J~- z)HWoSYt47J#RrJM!fX(U-6q7@((=on{{2^s`Bw=M^LvVOcHp_An%1O#I~Ct)N>yd? zP^aQ^d#+rA-bV-hV{YUNvcM>ZlFbk7>Y8spmlWVrTDY#jZuN`;pP2H})bc*S1JDY= z#&hBs-v~;(Mis1TQ zh&$I!iR(HpFVk8-cS%HTsnH)*unlA8z^|uU1uP7;ef^tRZuRfg$^LIU-P{&4NA#uV z$+?4mWq8oem4&gUsZgD0I?Vefvu^~Rex|w6iVh5E#NjtiXSfG!79tC~7P58v_e9*Y zm%4l)c|Lk&h3+9@@qc$GW~&p_L=#HsZ`a}mye$$&9@oP1z%{v6lb-!5kDS-9Lx*9n zMwo2PX)tu6QQoNICN5Lo{24cH>-5uW%^Njqv~T?0U6XHqnml>loL!$MvBr4qEZZ5i z`!ws}uhDCJXVbMCCWUlvTllN=mfMwG>+24PSA-vRV<5)iP1ZM^T;HCp^egUivc&XL=<#R;^Y|bzs#nD9QC?g|D@Ho{OGiD6$YEhQebN|>$Q>G-QSyj*jdNaMQvcvs}EUaW$ zhC!P4S94P%)cDaT!U3N0TTm&RfO{9*yl|lo%^lIW$sieu6NQ2)Fvb3{TNoxWLGL>8 z>{R~Z|5rt}*ADlcJiq9Bbgz8J$9;&E8vzYo_@|8ZZAhqGu$+liR!w5C)_|b38N|F3 zx~=1v8`wdDOf(1JzN$r;YwS>pV1un#FPFc1_N<98jd|CV*Y=cJcY~DeOd1S7JC$`` z^#FH`Qr55(5d!KKzM^QV#qb+1ndzxT8*QlQw4KWa!Hl=*;#s}*73cD@1@m?2r!haY zqYuUnNQ+M5SH^k-S+!}(;v$AF73(R(JMX_gDkeO&G%&8gAC*>w{b))=d-h2e%p=n} zpj=}OEoGd~uI`ekW#B)3`0kds(Y+ARcK>jMXS21QGj2ymD3ua?Uck;=H9|sH5b93EjGQ8t(Ko>*`GCN_acY*0A zmbPAbu@-!bkNW&QvnvjEpQe5mv+1CTZwJD{V_XdivpcME3o4KyxpU{vA*QSW^Y33g zX#dzhS}mb?T44hwAVbfH6R=nF96tF1AxP{ZZ-TqCE^{9bu8{ zw4psc`!9`PKP<6l6TVYT)jX8H+$JV1$h9Q~W5f_KL?Zc%)P%RuI34xP<0Tp&WT*G! z$(P{VF~{hm%O<+e2{Q`N)f*BDyAew#J{iG6bEoL9w?M9NrM z;)wfl&<6+RxQ|UgKkI4rGe_D5`1@OE&7C!?_M!1fXTmt+vgMMT&fEMskfhj*kQwsWv&SSc!mGW@@%{k@NS&H0jp!n)O?Zr8uTe3VI2r zaHY5)B(;%K#nbMrZT)gLgV8JXdnwOraLw)p%758@@54;5$v4P$Dg+a8kEDB|xq5)| zL3>(R9yELcs6gA{^G0pynuef!$lSR{Z{>^51^tT%4_K9!z3}13k4y7n=OAlyebb`| z#C01Nix*`~uK~3)OHCwXs9bIN9Fa6Rm zqLUS@L^m zO`FyPY)bT~@a~###(wZ8#D^ zrBW>t0;cWWF(xZkq<;9(T_H<6W{29G9hueHBX$oCUkVxT;CR_->ph8z3-tB<`gBthlYAm$WT9upmc8F|q6Z0fkn!wj+^xLeaY z_HNnwM)(rTn(Ws=T%e#SKgOlFe+&r{cXCDB-4zBA{_^3vp+R_oIdEcd{n?8P}Jh2~QZ>0r!<83tIO``$W8nRP3 z4I9j8Ca&_BjyI2DoI2pgI%KIBxRH^?Hh{J8#m}vir&(uJv~Dfb)V4o0=)8X{n%#4g zZmi|f%DVu?l3MqUpW#Ub|aEWitV=?6R~4fm_Vb*b$_~4bLp~WR&4V@wv^*# zXl8aw`#?A^HapC&3E4Lxry@<6Iq>xCKu;t$#CGFAdYoRY3t@uP^64XdOL5^` zi)KgYI09OwGxlz0>Dr+tGQs(pH*`EGXlj-N>5#LNIeOq(dz8{mXi&?lK!GT5D<5qg zln+hcHaqzuRXr z9*(b3>nl~+b80`( zo|*7A(Jm!W+?^0O#ziwxzaVn?_hTU&ulRnhIHDg{zGo4g{MofT>TD${wc5~ucldT! z?^?eZ%w4_%1G zwyy;%lGc;_nrkc7FYVi>FR)r_A}$I0#xA_l2NP9N$gM~t<-2LnqM6!uvmxk?hf#g7 z5B+1ubb!)rCNMF-GJX5-_a$`U5_;2s2+!jNn~u%q_0iRiRh3{=TS{bNOs^(FB=bHw#LOHrS?o{WH^u?1xncZtFCb>q2jG=D~^% zie}qsof~rwLUUzZU-#4BPlbl6PVO>eit>Op&{U6m@L&^LCR?>?6;v5v>}HS>6_`RH zDyVxGU+WthZaaVed|+bRimWhg02A;cDgxoHWJ5Dib^L@0?K~e$qS+1Ys8~PhWS>>% zEPUG5xW4+cs%QlMJ}m94eq5xVV>D}46$M>Jeqg!Rg_m7`umA(Pr15{>`>vC>46DRn zg{*DFm8_295}OGY&HbE&ul}Axhs-~*%0m7aH!(-FF1}@&;|}}yxY27uFSjJ_T*66@ z2buIfG*+wrK9DC1OPUrZ6`nW zU8{gR>4t3GctyJM`0jNA)^=jLu?zI%Wf|1x~80lPIJdbp#8(pUYsvHI> zwx%!w>Q2D600AI6$x1*jGN?(R)dXgWg!cd#C($Sl`L-q^s{yN>gGB zn1qh6I3EZlq=+P^@D#2^eDIZy(lPeYPfDe$ETbyS>EA_nfvCHZ0aNG{;Fb?AWj7e3JHu4>*Am&kq6?u!!&IZ1UMl2=PZ1`?4T~Q5V@i1dmn_X{CoKpF}Cvu?QA55Y%j95NuS|P34gv z(~{4;0OAZJ^7Y%d;qcHlUpnm{D?6iD?SS)O3oxBR0gcUz;5j8YX%qWEMC9%t4kBLP zwuWT+evbyp9Ec*4=SDCTGq<=0{5L0uqrC9tnZrXGKE;DN}Wl}tSonk!Ct8)F6 z>ME-0yK5@`qwLGF&b;3QW&hl)Z^_e;2+^Te9E&~ib1nioQO27rUR<5cAjpeb^32#h zQp)!}=nFOxIekUxS_|OhrR!+CYaJ87$br`z`$yAt`${uqCoVoF%a(O>`tm%m13s#? z6%)@to7lPWg7L>Ew(Zrc9+81IhwP2s!@>#iN2UDWTM!0p)80+cR7BE@YnAw%E#9_o zW}JNT7Pet6x@`R4RM16AHA!LO)@Qf`jS~f~QRV}){<|t%q6Sub`_`mR^WH!)k43H`^VyX6}cQAO_}PWywz~W|Imx zm?C>Mp$xsg@?B-|8phh6L|kpi9IH^4ILhuh+H5eg8~qxJy)s0KXigyg?$RPtDBygkS-L0M@)8D#Vz^3e);`37j<{Kw zwjTY*Ay_YAia1PR8#*5-skG7qOMYA zAO0@u^wlGYubf)9(bZh4`7vU)>*+67M&w64vhWS_ZgLKWN|+S}1uQ;IRX)xy|KJMF zxwG+NS#Htoi#>v`^~0D2pUu<1bNJGJ6n3@~;Ip=>vwlbWu2!uV$9kU`0khY=b)u{y&hB}TNtfTgWQX$mvs*~O#1I}u8twg2V!)7i zi{+H!KR^SbUFXhYdYMk2F~i013xc2Iu9q9vs)|c4{pa<_e{tBH)GNke510skE~aga zos7f~)7aQ#?~y0*5^)%`-2lCjN}BlI9%|(y%JpBY3?~qYQ3H(fF7JwLnq8Ck(-Yo- zrphfw$v1#-Wp!3gmp}mj)=itLEVr=enS$M)6)V6BRTVo=$nPSNQ zYw4O3LQX(3-$3S~(4>4NrMd*tGM3fnY{AA5p)LR-xQO*=jR9TaJ%X_PK5NK|3Ma4?zC z7_g&=49*^4DxOD07$QihtOT~X#O;el14i%<`?VW7%5kg~finT@v0rpaeV zOrGrCobE?2@fydQkN4gW#P+e~W2#QbZK^DMZQ&dNRxmtjtO3Arn@TBkrECB$kkt?oh~x8t$F1=UlN~?_&}v zSVNX;AUE7F)^{U+iFpQDeVxl3L>oa)xXz{oF-wwte)PV`=!4j@TPfJsRj<_L+|d<( zX#uhgh0eWeeFSOco3-gGv|kz#xj~HeV;ml@S*1r#9|5s5e*E|#CpBfD@~`?|Su zTvM~!A&keg>(*`DE@VkHWYHoPcnonL*If4D%a`4LN9}6K7xA9@W2iLb6>W8NT9D1! zklx5fG6*G$3Udy^scyP*r5~Z_S?5%7*j=>f>W5Z;Hmpe#Q=#CNlCO>P;1h>*^mxaN z{2c};qteM`RWLx>=;zmo70*J%?eC_Ls|5KV&gN6QHj&lzTmp26;-!?i(4%DY-KMGCKx%1~IO`G=T zmu?=hcO!Djr^1^5E2koBd~JA&p9YIm8+1OJwO}qJOp1H};k>C2jYs{%gXZPGj3|$|ZLlstqk4p}M5S3BIxB|zSDi_U5SKHcZ!Xz}VwdFb@iosN-6!~zI zvc4?uaJR;_#`xNnm!AoC>ZH8mMYqAeDeO|^k&vQ)*zt+tjNF{vy^h68G*rRa@CWme zsvsKCoOm^K?}N;>3^s_RpRjiXGH$$a)rDv{x!QL>^Nv76x7n~laf*4`W}*}KY~r+O zTbRfV91?cz;?%CsQXIWiT~AL6sK}e#4v9`A6J}~jrY17`(qLrpiZ%{y> z57Zjx_{a3GIBs{qK7-O=7;hVYqr5D=@)nTPG(DJisv?@9N{aB3{Bi!_p$?rGoTwMv z{TG@TiJ~+n3chwys;R%%AZwWtr#V2wm;{jw&bG~uuhuZ?!}XTgb6K?o$Uv(5@s%F< z&9m1$r-MPZeeuC8q057!CK53_X=?)qhau@>A^^L-^7!?Oc;+i2S*0SQ#N6HP;W^)c z^LH6;-%Jp1%a#Kfo#XYR!U62tI9kA8SPNS_k||5u5Ql%5 zk;OOB2E%*d-(^8jE!&Tx4YnvD#+O_66{PgtsHpkejNY1>;=D9B8rQHpWGt2f6?IIP z!T^QK+}%IgK6~~I&+iSRPHw>10o%D9i2K8K&0%hWUOn084sP$gOqGXsZ`mbn-{M+z z>S(O4WjAT!L0iF1K^D!_f-C%7 z6$NswxQz#^pEfcOSwzlKIxRObrb|o=~49 ziA1EGr4nL*50NnPLVR%=E2__WxKPcRqjGki-kOSRyR$s_%_zn^?mT!*OyjQ-M~=|FX&NZJv|7-~CgTzJ;CnFXSZ?;1_Sy`Iaq(|4Jf&pyC{y}32DKuE8aw9HPC#ms z&V&F)^y^N|Ze#Nh*yOS$^VrZ$^eF#~CUCOL$&E5Xd*Hx3F)^ce>8m${ajhgS#>b|1 zZP~imsW3*1+Wh8^q*=`UPID=$co*+@7wNx4u>Zu)L5rGZuF`?QsPr^$JWHwAsZ<`= zCXqN+o`&ax)^g)&Dq)c)63x6ENPYLF^2ZMo3<{V z?}|ScXrh{qQV>4Lo<71h%39s4c}BEFWI&w>PZFsVPbl~6LjF8?xtL)MVHYr2rZW)q z<=fP*`?c*0xC8|pv z1-5kn_DbuTO%v(=2vbphKV%8g#= zAdZSArrSQYb{gS7y`m%cn{u9XL&kC#4Ktnie-MWx?Q%++H9p&q%D%{NK zFlN~t*-x7LJjH-!Xa9Jy)Ha038UfI*3H+HG< zf$l~d5ll(T2)@j&rScPDXx4uJ1G^m`_EP-n95FbAZHy}Z4f^Q)e7A&Vp0V}2pID(i|&!385p1k(SZMxD=W;et=# zRVjxE{H$0`WLM~yBD`c8Z)_WxkZ}3Qt$!0bU;(d z+4oCcrg++9HKWdVp;LrJRYZb?Wlby1=C`Qb?u_ddwwcGw#Zd|{>L+F47-H==^VNTA zT(%eb5x<(j$~)7jgntkKC(NjghmT1Cr6<8Gf1Y%QJFWv zyIroa2z42P6K&SjmiUeS5^q`&2@qtsicq%&lFO3?%ow+ZJvv0<`zyrOGa&j z09~PA`Oh8p?E;IX82*a$%q_weOh(ejtco&?4A1^JRbo3aP(jD~ZmZ!HSvS-EH+_0B zS)t$&m=9g55ZG<(&&sN57$p6{jue&@@-)^pu3B_T-$S-t8I`3Whx8F$z)yXWYsQ}-qH@%;}}P+f8C$&#;JbyMhH za_~05g?2x?h@6uyz{MR^-|y=(;|>t-v-Ihi(eX-j`rVHqiKuLkfU>}N#bX}pz=c6A5}6Mm@Cgu z3rewQO}9+<{IjKj7l$2Ray9jiJa`DcgKMp3aax`=)|X|!9yuevXvv+Ea6@Suc-XwW0OD*q59R+y<=T(VZEP(5O{eswLxoJI&ZemBMgdMO zR+KKbx3^aeAub{y+JFKE9z+Ns0L}RojvHP)CRk$eyMtpg%y%+=>!&A0*bnY(S)=f% z3w16^qKOkHw!KQ`GjDQA#pMJ8uYDGQn3~+UrZ%y^#|!swEC6K>W24-ZKR&)`H0=@b zf{K3_E^~eR^^>;1nP*F-Hr~!&9aEyCZ1G_-_3ob$P|&gioU+x?E%oV|(zbD>S5=Qr z85dzcC!mMqncxZC4SZIL_7qUCXYbw(P)a70r;3k@h7^C#u7Vbf59FQN-)QPoF%&s? z=#cc^b93Ld8npJ(+T65svlT1c79U+#4Fwoj>ox*G*$h1&hCEFdlU)^_S-ke$a8DX` zb4EXwb^o)N)wFxIlj>9|;C)j#Q{t+uh~z(miVTlvsffd3fk zL3S^T?27lAy>O7!4NF@z^)u84esV0+8PADEH%;sAk7EH#you-{hoE>92f_ia*C5pd zr4k+w_MX3SdLO@f*x;n)zliz#e-x@~`D_wh@PwU@Hk_ZTtT6fc^&QD&2;yE~j#yA5 z$CW54GN+}C=$UUac4bwq4tiK+~ z|CgFq7F_T0H@Z@d6E6=XAnYq{liB+o{jCj)>hyK%wrwtXQfr}2YP$G%dRm%IXf=B0 z$SnmZh#>w zLPPC6pKHEKTB2e6poZEur9SNIk9yVG?Jdc*zLWcU=I5sYxFa?o>#E7IoHWa1yYYRP824)BgHyl$T|?{M@+vRyes*T>r1ClQG*m;q@5$<4_3)0$ zwtJn6n*tlP?eJuYV)5cu<-Zo!`TA|yZ0)5Qwia8Lb^^<2wWKu+hj-4h~Yb&J%5S7 zd5Gjce6H!Isi`TG%Or`dKoK;j%c44sKlnJU&{+3_>YxjMOV&c8#;uBb_)ykD-!tnQ zmVs!a3Pmk=N^fd8z;W)1-2N8#<#rtEw^%n{oBHGfPzMdeVA`_THcKYh4S6Y)- zFZ|4mh6|3<(g4FZKMH7p=&`rsfO&JI2z_e2^8NRkw#wGkdML34u=kW)8`~a3;i#Z> zuQIg0zzTV5VJ5 zPNN8>heuTa2Mr5Do1lFG)^nm96vz&}oW@OWWQtttHXYUZ=H_A$B{k2wPt0{U1WOF1 zXRJ_AL<(1ipysP+wT0m!VFwo>4*X}8us$?bOIy1+Xol@ATUeO1*6~Z$kK}nVl(wRY zfOAo0NaZ#%0-I2!M%=79b#=(U)Oqw+8>UqMzjW0i@&FxDaEt#u?e@do*~OSYnk-sW z&9A8NbY-zJe2o7eE(7iR^=rh&J+WR9CrA8a-;ouB)P!N#%)(#A5MyIi1c{H)rS|cu zRHd3ifk)YKUeqglCyg}pi)DFk&LVviQz7<~|BPHV@gf8``>{pPI?Kj_Wutj|WC#dwwpq4-1xsHzE^M0e8fZnF689nr1!|6N)tC zTcc@3h$9q&w@Qll@!qw0Mrln7x4~y7n>8+;aCA@$7;M=nji7HUkbB1#3yN!k!tv?n z`(TCCYJkm|SW{igkb0yQY;x)#jNkX4Rz@oZW_|cj16ZYaoO6CKOyBW|odq$`1QXpe9f}2_P5%om zS5csjr2pQdX?s*I17uA$<<_?F84VTCRKhb;;zUBOF|WAI+uOUj^J7i=!;eGDC(a;x zR8vs$_^&2{LUoHuP+B#Kes1xmp(JTKq8kBFkQckDZ2BLb=Fl8m)KE`^!88P%Onh*> zl5NN&nf`Dj+i7B&(*9x1s+y=r(96);X>$7XX`H~8dyHF#Zph)cIZiGl#OrB^k5+oQGLU;YuBDnpE8A3Na>iUE{f|RA?;W*%f#~?NO3ju z3!^jXPBFCdckwp=&enGDMF_p>eVSFiULCb<*}A8lik51qI&jj(=Y<$MY0ey15M}j( z2XS##72k1ZS>CNjkCCthlV;6wfk$21}l0D?Y|QBjVxN zWgKNbCE~apN*QdPC|+(?d35qPC6)u{h>!ENL#mq654I>O?R!mxDQZiTCU*1~dVJ!m z{!YCrHe`>;2_NbB0y&a2S`jQUh}IObr=8xYabjk*_Q$gsaLF=HATR*i!L?@sKSrp* z;P?*w4u;T_Z`wDk@ufDwyxD&W}v0a=RTprzQuE&M;zbIcU_?B zGyze{jxf=#;=PfMs`P0{IShX#B>ZU6vi9bm@tb^Bl+`ECovX#CY`Ei8?2F6;`A9QT ziw~2=q^ay$kXKM(`Q6xukHq=slhe+^SVMKIqP*9SHv;eGsgCMlu8|3>B0> zWnp-~GPGSu!5sdxGtM~XEsFO#Ya3xPoU=HRmJjJ(nCMT94!0~Kd=qsR$@)_!6{M?Q zy4nr=0Q#2YI-)0phcmbmBM-lswp0rL$z$r)1@Fn@#R$tLXiMqgpstEA$ldS7zE@hR z*z5k>{DSPPuq_mHe_j$LG2p9nd7-l$1Y4)bNqmH!b8l`ZtPM)|_3ZqaGehX!pbU7& zGXOGisn@oMYX)gVqh96M7pLSRzxI0f80FiFI}Os9W<2OoNJCPV_%KQ=avM%`n&avJ zYEWr?Y(~F{^B`S(l25~wYs+73L?y-Z2RU5{yuF}148C;bX<@P6W~Wrcc=A?W{^n-L zi)~8|9XUc9RQi@<^!3G9#-^yXIJ?~eE(vSxO}eokU9J_WjV?|7?C)Ji_Spc?`cx<{ zpKkrSVT|FqqRIv*&vr}u(&N+1aRXaKL6O$6yNP}R`Odl6=b}jjFK&9TWORGPr0qLA zuk7XAl-M(rDc{3ST`M~}S3btl8`m#XP_rUQHg739d?Z0Q{MCZb`b!HtCYM%WC5e_; zHxNmA@bsDwY%MR)zI~Xf)yq-fPykLE3Hf(NtNp7xNB+_RY*+q#I~oK;gui5=6<=eP zMZ&9wLoH=3+aS0f@L>=Bb@O>VMQlya^Dp`5-Z!wx!#Vx<5bc5)XN6tjUn1pf6|@8D z2m#?Sw~X)D?=OL`T~u0-%Gq=0=oGH#TY&owbB+m-Eu?O4&_Frgbc)me!YC0^Pge9* zi&rw}+s7y;$zT^n3IvVpkq5I|m6X_f<#c(JMvN#z6sH2Z8AezA>P6H(rVeiU%xvr8!88t|J-1&lhwb8!j*$BaK}iO?M?_A zN>|wRCFidm1O?PpI=F7sJw#92w||I@X2u9z>j+>EO)Pd0r*wXURS~XHExP+KGKzz4 zQ)Xj_Pn@`CZuEtKfUP6iSCUb-4n2BI=#{REgiu8~WCCy4T+fKhs5oU2_Cfz{+P0Tj)y zvFXHmS1X-{JOcpG+B74i2dQ8sLofO)Or>oA11xiG`8Q;zC0S!*+ky&(@11w&&0cP2 zR*xY(VLkgE8o%5S6OD=2E)-G>Y#nyIzNvUmh&d{g5rcj_opO(g7@1no&gcq0_-%gX z1KQydn`$E;s;B!?fnz964u1fDD4n+oAAtX=LR{2`w%;51=1m*iUtROVP-_!UpPsPZ z7i-2zsjLvO9@S2dkL6r5S)v7@K7x{vDdas+`!X9Me!hUl7iUZi#*LHC@7s6pD(xTZ zo9v)Gm}Ay>=~PU){Hx38rz;a-xT!O-jxd%knrzr45nK6itNzK3%AgC99~pGv+zZW( zo;=D4mCa~Gsxo`Qb{v{fQ1}p2vut+%Q$X7E#~NGPDCh@;f_h1oUxUY_j1>9^34+LW z>l~=3JlWZ_!avW3Qez{uK z{NHi2R>j-?`I+^_@KLZ=83Uns|TPv1?c3n1t%| ze)CFCA}#xgG1mDh5!7#Kpo+%xu1s-uQ+A3P1oz~*`u}^VrkdX8 zt~Nk@#Lq{Q_D_Fv^L=)9uY>)nO$RnZgOmUWMAr0sEOCT? z<;4anY*DU`{Js15is1lN6UJm<)?rj8M5Cv6LE7K8M~}Em`W4BeMGJn{d4GRW-m<kR7VQj7~_=G<)sxyRgCuGGSCQ61J`aN#Zb9NGIh~>{H(1r5GD5shl$nXR$ z%ZkB`zowcZ?U@H+pqHA3&8|`=1}0Xl&R*I?+j^-9bLI>;n9f(KeMdZ1$j2gKO}+o1 zVgT!D{qyQoDg+n*HaWBQ(b-CLHo?X1G&P_7YuJT>rMCZT2!^4g<@g&R;{MkZi;PwM z=VXiWYh!)sL1_Lx?IK@;cN|U;B9_H}AD3Gk7pj;`0`v3=z6^eNKlDv``LabL8tiQ` zqHc%Ybvtj|rq-6t_APDCXKv^l+4#ol_cb3Z@t8MNE9L2~{5@Yj`#ujC(<`Fb<;zoz zI^!&I_NNsrYtt=%v-_@{8@Bh|leW?;Rn5UjXO*hW+xK7B&Ti&;B`NGnvC~D(l3R(z zSCR(cx!RA1;Y3U&h2nYFpIr}Cp1tx`)sVLvYwv7RMWHY`|L%Slg+j5Vkstrt*ucxO z6P)m2T4dLr=fw}mxiA~Y$sVf*DHQ8f8u+Db=O3~lUE&#_uzs=7(?2*2Q#~EbmHKBN zd^G6Wct~{j*Q--{Fo+$O99|II^l(AC5h@2{w(jbbcK1nbuNK6V#Wyk`-5Py*$6WH_pxJ`$_7U z{wT9p+%(nQ44<($LVj^VdI2MxVp62<4yC%7ybo)xZ)9S}@C->&J zd`zTd)$p><#ZUqRSdTc1oyWf7p}7uz(nFnHd_(YMdnqfH)-e_IjjWk4~sc3is_R23nF=vYoLEqi}OGqb1U{}eF<+uW4 zIzo2Ev2NoamJep2&=87SYqn{0G%9_Qq-k~dluh~kZLOydSmch%E%U;a__6K`)OY6= zFB|MbEY4sDjnx$&XKPnpi%T}%-F8&o=-2pq{`#^e;s{LsX$q1SSS<3)y-efNMeZKv zWtoLjRsmM4gQKA{C zx0JgXYs<4~NSe>0QPh_m^)S3yT;MpQqaN^;+R$`%IItX~tG^gVq*rU%oTKlK&BOlP zMnQ11TE&5`uCD8t6ZyuK9}F)n7UZjs6lLYuVt_6x$ebnbjTq{c*>zde|q)oRF<}?pPzRTG2nZaj^0P*u#d^PE*D`M26)yc zgvE6*xMqzcJ(kn#$;dstycv2;Lw9;uok?i2pd{h(<2^jIz2UEI>SAc^+Qyn5Xh{0* zfwH2}3|G96cUxPoVs&pvqtBKkO62BCx~VvrA7A*%C4w&&BcBdGmBH zPtc`})^(0PcJeo_P`)HwMFu%oejnu>8)DBP;_blkTXDG@Kk-ALe~bJJ3dN-k4gFHC zv&`0y1DNGyZEzH}_GwbmBD5^NpZORp5Sbtmp(NYT`F@ibv-hgMKq5C~#tcu|c&A`V zag&`}hEL95u~i-Q=vT-i$DTarahMJs!WOYV0dro@n_q9MpHBzBh3LFLXxew}*SAy` z*GHz?P&^#cb1v(c+n;)%(zxj*w)6i z7+A2&Rc}x5{{5w;S@p`>T-#rKZMgJ&b`SV?W;T+jk#3x*)t2LerUJgF6dZScFZ-1JmuxoSpG7Ch7Qlvl9GEc@Jjs%Lj2cS7=e%9S2=jd=$hw-nMB) zoOAN#)T=h-s|ovB?5i63#8jb()Ee$(nUiE2W#u@d9lyVlVtwn~^+r@yD2}a6+t>P~ z(PHoY4|?9X@SzVWaU1!i0rYY_xylQ!e?^l%wvd2Xmml0@d=lO6p4=?KmKGmvx;KnnWZq2nk{7|up_d(zFzs}{0YqzkWaIKcMfKIVO_ z{H?_xiPhfr*gu?AkHvs-KSj(UJVM6<9`hf}E4v(<&V%=Tw#}1~avBquQ3sxPKmhgf zgSAm=u9+)Yv*g2Qy|HMUr|^7HWm*4IK(wd_aAlKt(Ks<+z1QyLcJPsm%x zJ;m0sFk@H0_F_d(K2cDY}*+3ZV6H=Rp!=6$0hMUK9} zX4N>|`L{Q-CiF&Z0VyVSTFcnLbAL zFNP4rC|0~m*l%r-boseTsX@}gz6-|^ACBW@b}e?*`ybxc!!O>VpK>_0PLibb_R5q)rO2{4jfMC3O>o-HV4Y6Rg)8o6{t83)Muvm>C_z@ir$cmV_kGDFk}@DQ zCDieL7rzWP$1S~_%lOT=*SSvpak3xl{s}0MfGdw9`5z!T z^uO`x@;Fp^M@)C?bfg349M2_82%lGy)~ugNt( z+VX=Yoq*VO+gd3hf}i(l<1g3KcYE0+=$j)`cQ>Pfqzt0!zR7BwO%1Ei)=a{8FMUPf z=)ihXefQ|-=#sb9_3l|*dwoEBOxXZ%58h~;8|kid>6$nn2J%l4GZ_+I6i%Obv7h(! z@+L-CmmAd`@ZngGpBIvn2qvwZOY(j_T&$azQN}JQFXysfvi=U|r2Lzh-H~`X)H!vE z)z`5iEdQ*bV^_WMUysI3D#3JB-CXq@f;uNYeTrEsIi3Ui{CVyvotQbvS6#!ZN$>zJ z&)u2mHrJ?{V*QC7iJzaNNbpXvywQWzpA*@SXZy zUtLFX4pl$zc{(7^JJ+ET%GC#`P5oGX+Yy&uN2lVHRIL{)CTzd>KtRl5M%Hz{Mpm&V znJr?=frO9MAY$32+H&@}8^_ZF##uXeYRMYTs}`R$q5sTatvrz4z0u)cK_ zMdbVUgZ)whxf+~NKUxIl%a=bibjtTwlxxpa`eLvs$<9fj4R79z0~GhhnP0su?4q?b zrX#rHIZAnOljXukZk}4py&X$EjT5!k3WxNThcIn}Z9BB7?tspMa%B@n_gPoFL-LuF z<$Fdrq#5ab$u%>LdHr}90e)L6tGf+!u-5Izx~~a4Kk{vD+23ZFeI5^76YKiCQv#bW z0||1pcM}Q;z8dzas2Q{om^>h7NDU(}LhjX-LLYuV**Vy)UqQ#>_%-1kfUQi}^+!a7 zq+e~~-)nOa1+++5F>rrHFHXSw6;6X6mnr1qx%0Yt7ko0-Ty7V)P6ct&ehE8%UaRhR zY;Di92{6aW9seHRk&CJ-*4uWGLMFR-sBY1;c530TpFcmyNRnmJeD3V~U9Ih-7Y(ld z=}a5P?@!?Wy9$cDqC0J^Yk662c|31uG6;p!wIaGEEb{fMBgO^8EX782&?{PT|9x3Y zYezTh%*Lw~AWN|h{$^PI-S9}`)B5alb<3EQT6CayRfWlw{0(C+dD|11zkz-R0PXJ? zIu|8Qc;gItd}MxCg<{EAuiL9Ffvu02xNwmQR_os7xfF%9IvKn;hS1CC<5rw5=9=i6}3V^1yS>Y9p6cYj|}j@0@UrzGz*{he_bk zZK{(TjmWCKgcpvyfZc8vZ}tVTTkJLMHT!z+Q)x5k z`iBO_cZo;L2E42>g=E(tkh#vvDUIKs{ zjBd5}qT}afQVsVL$j2_lAfBq%p1>A84mKIZu`hdxCfEh=F-m97a0SKe&0ppGx)Ou= zne%c|#N^bEo}+k^LKjUBEvNpu7o0rzh`?v4qE$zUJF@1<_cOEEu|uo3-bc~Ym)6$< zb3g9`>N?*a4;Qdn{v)DnhQYwkK~&tA53j3p zs__9y9qgLVOt{K`B2s{Us1C-$5w3bXwEF(5xX}Hx*z>j@j`f@mH^+-5R8l4OH`n8l ze*j~0oia-zlW)qLP#g1A3$2KF@s>9}A29o|ABXY#GNE(ihZnEu>oW`fo1k&brWg@p zuQ^eSE|{1f%6reJ@$43Gy*<*+SD&%~t-5W%KRM{XJ$ic)Be0a79U4Xra+6v_-yNK> zh-wvjWQw^xqnWBLTh0Pa^gyvA z4e8wa0~jNBp!qRYYU-Aj*V`${ju<(OM&S*p^%pFBCxCOP&<&lp+0oaLvl6_*GV4>XBCKGWNcJ&bh+$UnV4U zcZ*a~W&)82Y}Y|v7!-FHf-RvyP#>4l05xnPcrwB7htLJWw9v-$!WGe%`idbT^CX@A zvYwnX63b(Ch;rXBByDFmt?Xa4{0E}{N=)#i9s7%HJ&5ScNe_jGsc9V=Ll?RdI37zW<79g9-rILy&Iik$ACthJ- z&(@4_EF>8(Yki&+=3BVr(UJbWU`du34F2(SQQS*LbtKaW4ds;QGA~0|F@fZW0nPaM zLII7E1$RHOAydc$mlwo*$wk(3RnMc&DF9tg&h8-D%*r647-Bo z4H9KpCBDC`v^Xn*&Cm3)i!az}+71`ce9rw9kQ+9!|n?SrH77kLR!%2(;eyiE^>#nIu{#=UqO-pRAFhef1r_EO5*lN zG#J=JKmXZ9C(YkPoxJY;g4VF-$oUScPbl-dC0wsM=)m%g3r9ESoxOpP-@hl-ScIx$ zuOTX!SF{dpQ8tVRKQR?r4!2HyNcdScNroS}9S@N^9_5kK3UQ|72x0Gs`-Sk!MNdAr z{Dv%0Pe1=+dC|qVH;dz*#c)d!q$pF@S8@k*H4RY$3IgM0d*REn;<7VeNVfkZiz0=r zr;3;!n#)A z{yr%+W!IGut?(OxM)Uk8PoI9^B5yI|>+RY?T1($RzOBFc8;Kt7<9fb0<)|eY3l_}D zgLir{*kXdhDQ8ydSUAutp5NI8-ge%v`!iTcURZ9~@Vn1cM@L6_HU*V|0KrOcJARJf z5G`bhH?YxKd6eLl?l%knx@8cmZjzS$$cRMz}wl7c-ed zLI1_?`;JK5bGm#3UyDshrq-RM;4`1| zcC=>=r=P2-acB!%H`)f}eWc&&Pc4r8Xyvd|szRS=rR|%rnz(0?u;%n-WAb@VXqyu;AS8eHg<-#&lvSie zCqoM*Vg#-hyrl@zwhC3zhMVli<;J9JU_|lj+?{QzgOj3Y8Zp^8lELtN#upn8t|j=a zkzdLlj*3Ly&an84*w){Q}(dDV~)CtOxRF5!pLx7W?D!zzB?cKQ@9 zi59USf>jxNM+@lIdAq)f@>jlXbpG7Au_#KkUmuYEk`SMh5&nGd%rEkpNuFNKhD_e& zEHBG(=!=d*z^?O7`NC;rOu@3Y;U8SGY-u=B|ETLr&b@1IaIFi6+c_s3(hEX~lI*KY_?)R!i;4S1uE2l07W zvfyamVug{>iven#3_z#PyYr*&X5J6h>fKk?=*GaqX`FJ8Q?c9HSZvo`xJ_;@s8Z)G9{-s{2PgBU>5(j|{P=~Qa}Gd{>s3_b z0W$+n1eG}u2-YE%o|SQZWQ)FLV|cJVsWqAm9@_>gj-fpb6&017IZS&fe5MLwrW0xD zaa*H--z6idp4P#pNRGA8z04D0iVd%@DV@yA`o3|K#*Jh|c{t%7`_U4iar3^q-p`@# z8RyOi2>pI!P#Lf&UZ^wmY>o$jXhlXppI_sJ$dml%8`EQ6_#i%yAu$e=WX;~6)0j-Z zu%1H=r30a3{I*3$Zk#?jLP|Di8j~Eypm_Y|;Zvd>`?3EFHR>d}+=%ZE!?O10Gx?V0 zeEgUIOZdtrae~zOtX=ez{YuNcv&enp3Gd&SX8luN7z-%%zJQ9w(&`j|JE4s;bXnF3 zm!9|g#I*8|&M_@yBa9>5Gf1T4_*LJw^m0%J6OU3YEkhnl`q^r}P&`t%13t#aFtqC| zms=W@h*x@j{>DgVcx)eWc=!~W6CiD;7(2%EkA-kq$30lfs@3m-Zt013*BZ$6Kq+|z zCd8MSYnyVq!UVshV%{g>M<#Q^TkZ*6_ zEA0DZ{0owcf-Z4aw3s}&2h(~K*T0VX26S{qLIZb${P6x+|P)l5JAoKdd)qKngU@( zjiMgQaL;6_lb1z4qWM(Nb)Yowbzk!}JY3sz3d)y^H9yHzEB}{jj18ApvsjfUW zkPw3JL^!dVU9!Sl$j146gcJSkkE(WFxzyoxE)(BcRX| z{G;zq3D-|fc=lSZ^o-s72wm)bb4?XcsXQ#K9V*n&&~P|$-dC+7-EQdmu04{&xYlFG zjYwX?;z)V_1M`h;2uZz+Q`M_mo#U%uuy5NGrnwl&3-&f z?H8}zfwwhQGA)9W?(@QL#+JdTST?+&RsdKyg}~<*Px4$Px*c)?y)^- zFZzlMd4vU`{%AuJMK?gIV2BN&?_IW-FEGkojR~@YcW%wr|J@6CW>!o|ccetq1zIEZ!n&kuj_fQJJjSO!K(ukl z9yf1k{y;UPK2kah;}g@$dOY#*+AV8nuhSnn{tO=+#y9w6R7BO=`x8Hp0BPe}7noEk z9bO@Gr4@jS;OuU8mN)aFCG?40=Nki|8Jy4wmy7N=bsT?ik0?2)U!^3#?Dx&5b@WPR z3`lxE9eRb^e~L!9@FC-J?^px~*dhyy_Cj)#naDCI>?J)(AS7b-~5y|BHQkgS!k?pEB`y0!KuU9a zmo2rn;q{txdUwdHU)f^rzE7!&==t^JgJDWlgq43`N^lUBr;cgN(Lkd|fgS8<;R$^t z&HM>H!`7e*5blm}Zv56J?$V<7^~y_2zBa5}==r7mO<}kveTqf*{jUWS=P4A+J%6`Z z^bH+sj8<5C{tC#odSe~xy^J=Plq$|ee$GqtG~dk{Z<_wGMz?Oo#gD$s%PQ@koU~~5 zoH>cGohB_!c(gvD01*BV>#@(E&wvkBx`#AplRvAH}8WfyMAmrP&^~Tu%J9_MpM3FWPlfS`b5BZ)z)j@ZV)UYgikZU+>z5q zdRY#Y#T=k@J3q|ot)HM+=-z6ACp{8mC@{9 zC9|l0SH*9%+)n#QdRx3`XD@BQJ9-tlV7GVtpZ}2PHXr4K5+Tq!KZRq9@XLy;>(aiP zDyt(P0?55BC}*Tw6{?K5zqFqf?@mgicdMUk4<^n?2%L?aLKHfROLtP{r++_v#PUAv z`Mqj%v?W?7s~wYVSMNldyMKcF6}8ega79z){jO`VZFi!&&<}s#N4_=29PrzQlv(j9 zkAMDZW%q2_j7(8t5O8NHi==@UTI(9namp96>JVZ=WjXfg((0eujv`SMbg4WltCtLP z@WPXR5Lwh(d0##~=9}gKUm2aKkhyNVIy@#@ay@yQEYYUo0}W4sbKkk@{h`J0`Pu`` zVQZA99wGy$wRWTx+%KeDDv=5n0nc znY>bQh_pc9sRODVBJm}J1*RS)y5^EyhX>n`I2a@!5!DBYgJrem(gKj|;Ar=@?h$a= zki;mG@KRMJ2_M!(gn8}}ppQ|6L4yDy$nu`hf?%lhDMN8&NM5KTp&dxa=>Swjhyu`t zao!Q~qz&1#md^-@Lh{P{JhiuhAf^}kN!pA*pkH1)@o*}wT%p+_Jr zneGHD*lr7Y1U$`Y2$raKfHio{T~JFTDy|1MT=21YIFQ9j_XS9*^3Im02%Qxnw*a3# zGIa~w=Qp5|{lMFf3k%yEf~b}~{iFHUH;O>B>Si>oUjIf{2sT6{u07jnaTE8GG2ALI z@CKER1WrL`?9PEJZa%bM$)mGqgCT&ind9&kc3TJyGP79>Ol5;$_Dr- zlvKE5lgnSO`s4T!A^ffCAFyWs#0#Lp=$1eaC~U+>NWud2LHQUQtn(U#ONeI*6u1%I zd8FSPEN0`$l2@voyV3z$o`4jMrPpcX@gp~yTmW`~hi3#(9dQL7K8Ncc8{)nYz>7lo zYJj@GLoo{npmeLZgR*_iopHgOKMRSsIXk}t4gX+G2^!x8|1EYD>~AYvi%5awaWH?k z9sm{f4ruW;H|C}7aWM9%q@+KFBL0cT{Xcs958=Rn)fxP_8NAA2K$*Ug0xz2ol@jd! zA?{Q~7ELVRZR=w5pSmb^B_SYI84GRW!8u2-t)@55a7|#aq}Wa;BZ60m%{*6c(oq7!SoY5Cr8GDzyhm_0NY~0wHu$ z1W4;krP(Vk3y|ThNVpg{qUoCMXXSS*zym1V?GUQwmz$1(NYZ#xrvBIp_@K|B#V1Jq zJBf1PObxx>E1IYHiUFt(4g8Zqf?O6x7GFf8QVZ+jSVcT3^TJiK-^f%WzoZ&Ew6S zOH%KJ&u&)X+8Q#K&yyz6ib8SS(Neo;yncPTr_qJ%^vp8eExUJE^6$ppBA3#8M`Ze_ z#Wgk^N^;U8goT+}5qEtt1zGKU(+w}z9eDVn?hr8JE;IQ8=1XLEvTgjA5;wYYJu8fkxw?1&h!&Oj3|Mi z>*d6`s@%^D?#1}71bX%;=3DN&_{<@XQ@z9aE%7+lOR=UsoQnYgX*p*v)MCPBYVuX0 zm4;vVDplrGQwk0h+o~J7`P)};^V2)WCrsbP-SVv$!$P@8mWX3yu-@;<>tbWW<__gp# z0HwfJCw7EGmSr+DwrFbkxzM(jB`^MZr_B~4TjUhT3i;)nVHqpxm)%vb805X&)T+Ha z>I~6S?S1zbP1P@qx3|4wtX>F_1-8NUZZB(Ugv@(7i#tb6*ORlhAY6qEE5hXqA&MXi@F?o8N(Hs!;$* z);h?#9QVmak~oxgd|P^ceuy1DaG~+40`tdmV*m8qMn+_trpY-{F5W-rQMY1ITp*3j zW_&L@cawHxD~%jgBkiufdg#M~+DyM;T@6Y)jl~jf zk}f+qWi}OVG>scDK~oBNxXYS9)h{Y1t#42)toGKHN!0F6sfc%>rmK{t&I&|ZvLg-9 zv!>n-MKhHS5#0PW8RL6qbDBTNR4BQnx>O&kh!#~cGSV)PJC||nKnX z(0I0oGTB`eApY}4Rv6y!V4radE+xweuasl(_<4QX1Z#tZ)=eKZc6Vqft6|r+^L3wg zVzzB$-7f0g8<<=#bN3!?V7yh%r~9QtWF)~&D<k#!On-Qu~J-YQ| z^VR)Kf0`-!;?{@BC#wqkY-;i~e5uX_q`)-1E#Ze>Akn7r;z+sLJ zeWX8KpJJTBAn=J>8W!-^d~%iP%!Bs`vgB_4LclO@uS_?o`h6`Fc5u)j7A$%%YEKn+ zMvdQBrB_dM@qebf7`d^E@nZUnh08GXVpIKMhwn9MSax4JP!*f+>-@%CoM zysbb&#=}#+u{}N|mb#c?MD1|eN~=3(`X>}E<)&m3#7-JJRH+u%`dRSeCF>0TI=~=f zz4Td=lRfnk`WLVVERi2f#v#e7I-H@siFQO)%NdU?cSaEHx@muJpxIadDc%&ESWt$_l**7Vx}6U}TBQ`g9)#l}hDj#b#F zjI!euIsKsRhbVVf?@f(hOzC+pB6!zlLSv(5jOR`2 zU;R3Eef~iOLdekS-OjWIqbd9#dknjIublQ-u7HVy_*kI;;jImuBuf>KdqCBk~@dS>nyi z3Vn{&EvGT+es5l(6&P1E2QLz4F0`$$N-K zItQ(iA_rfs#6_hr)Wnw0+i-rEKIQm(&b6V?7ZWhn0&I`_B}doHwpN_|K33P$NXEQw zc-gHES;=XSUP7+V%G}U4u&bO+cc-R?VYbBgmn-W>kCR7G$` zn)LbFvmXEUgI62`Jm=Goxeo+tdo$a#wq~!g2cJKr5A^CaQf1D<5$Pn4k_TahstUK| z`F_r=Q&?C$xdu9lFnZZWZ=dk=93UxL$@|Nv-dXvP`ZxF_c8BFJh29txGtG$WFV2r|B0E7(9+f>i9Ok$0cDV@ ztWGl-j2)L@BX))twfp#{`xnQ?$6M@6E=AxwzKoTrt#>&ld!|b)(O~R$M&tvPw7I6u zBAKL$X1SB7`~He}F47Y+)mT$Ae1KHt2q##yx|Zd=e5u-C_hbS_M}o@5Cs$ya56AG0 zG5rJ=n)8$24odHQ47GnNZ+U3qvJTEpm<>Ie*{}oO>l)u=e+7%J8Bnd7l10NB+xdsV7m>v=R8GCb?VZ}m;E~L>b`i&`ODi(3O!!`H9Qz+Wtwjym4xtk zH^Qp%>@68^dr9ouud^?u(^KTQ^b=mIkdo2?w^$a1+4uu)zA_Vo{q%-Mc1U1l;2n6g z0z2mtv+ET@V~cE3@rkdS-aRV7X`^@Og;)H#M`G)X*FOYbMB&Z!JK&!h*?ftqOe!yWU#HNRNCg5kM7L!5#(}o?(nM_T*FCFa~|`V#xXsR0ALj ztN1TtB_RX$r=RI?hYRM-c7DB4p)_ST|L5PxqPKf~LpNf3N06DNjVZCShrKDWsk@~a1cdv%t-useqjY zS&E7(NsEg9eKWuoz&_FZQXNA0UHU3Hnep#1Q5<@eQt6~H#^j5X0^xJiEvDKw#*s3l zMPt_1sOm8BA3hfI)N$?a{icEaL_}Q5pb*NSy!IR;5{8Wwd4GDeynaMLJUJl8&f5*4 zRvGS0!eHh^YxEm~A2x$%B3OEG(p;s0jIU>g-`l%6?2PW%$uClm9K`aA5_N=WsXTZl zgp!j!^<2OqDV{9o2JAlh0|8agQP=f0!fDJf!2C;uoM$AL93AGuM>}J67S%Plwct#v zI7Sm)buN&D`hePW6Q!RaQyD#@L+TbX>c?Ls%E<4tLf^(2zLzPI2n}I7?BRd-94RQy zkgS7eu#qGQLqpbs^z^2+ksV>3nUfm(4UfLfy)icI0c1pqtsl{X>pJv_Ae4sIfPMj# zN_zH;mevL=tSuDQ488m^6oZ?80HrPqndI37Iy}tp$M6>FHy2BgOGS2|As?^+1kN6f z2NXU&B&m46-nqM*h8O5L&GPCR>SD!l;X%~D0`NL_OTfE6%FFQ>gKQZLO+ZGb4DPn} zfZIVp@Cmxx8yZ`iIuje2np@iOlN>j;k`P;(@RMk;%QMN_i<(+kN_je(s(31>8hctB zbDNL|3c&NZ^8f;DO`Q#i-ED2`oOs;%N&d*?0qB=uMiSybEY8;aBp>CKh($q;ro?Ov zYz$2F;_jBNEF=Q(#C(n>W<1Jb5`Pl`eBvjuaCWxmVPtf3b7OF0WdJ#vGct2?b2Bor zFtV`F103{D9(K-#?(}v}q%R`=k|Ad5Wb9~Z?`#ROBYu%-XasU`<|iQmt`q-VKU;fw z`G1JFbNZVV0DCaH8`?86GcYmQ+A{w03@2xCS3t<$6#ADloK%5B%BXDW1afgSHWha@ zwR0x@XAvgG|Cn#@;%M_{J0`}ArZ%Rw0IL(QD)WC@Qc_x8=^ry*Oki$lYyW2!VC?_I z>1=8CAIADmy1iWavz>od1epF0x&Mj#?|c8l3~soHp7m*$7OloIGGqa8;Th^n*u_aSXg(gH!Z7lyBC1T<~hl0n@_^&NE z8M>O9{8<-}_17h13qw0|Qy_Z$&0YUKZuu`}j#6re@1jE1C4AA%g z<-fn(i~pBP5EK8;BL9|s|HoYaW3GS80{<5C|9IE`nCsuNz`w=(Ki>6!&0O&RkxrS~ z0Vv1~NR|W%rrm)=>$Q=rq!`5W%h!+QyjWla&R$B>2?7EE?dAIwL<$%i7<}U_Eie9N z8vzLm0v;vhfdc}97(!Z1Sk-<0Fx5>*Z4>WTt6Rm4_-cdws*pG|j0QCqu?9Cy^=@x+ zLIOweX&AnHlcWA08@< zy|dBaq3@hdC%=WeBk;^SnsIN<+bY9#doPR*>m+Y+aI5!h`I1%Ll zEf4DZJ*wp%n=<3|$%U+&Two?N3&uTxO1CVuN*O~c$j(6*?@Mzj9juOp8B#W(Q3BsE z82yxiGgz#1fQEsIkMN-t=&p*-f>p+mYIRNcywJK4%joK0H$vIOodYQ=5d2FUj*4%W z%Mp@#L2-4u5X*%;5RgG@)X$j1pxY2<$;s~OIy=X^{vqd8#z^bP!OZ;c0yebg1xmUo zg%Qn(3Uw+)BtjuhKR4=MaGSVcU5?s}AxZr~aqyx+Zao3c`jy{JDNE1Jx0=H(2*0qt z_I)mY1F}(&SbAV@dAecdtF)H8Luk~zpR@8^yk^{vmFIH58!cDUNFx{x`vI?+5q}z0 zaN+*=Mp>r==TVFOUGcokMPJblf%BwaKIP}H0t#p&M(s?pJkN(Z9fc9Rx92MeWG037 zW%K?Cy6MKFXhZq=uh+*EcdplDhEtYc{hnzl0(s0qHU`gwElmwiEbiAEent8@1-gCn z42!%hG<`qYm8j5RrfV6zev{@lGLjd4w;H7@C!wL!5q#jJ3>Po6;(6v@|JvFWLxhCt zwS=Nejub4|wH)E(;c_E+5IW*zloab{G#$uzvmVO79KZA-8@&B{%cJRPKJUTl(JZ22 zSTH@pXtvYTX36i1Nj$F}p-jy1Lmv`CH;dyH5t+7-ZW)2$)TDs|`CaYjje~LbaKS6R zj=<1Rq_3+Ww|!fzem9f2XSd2Zoi!=y=Z2ue`v7#6`e8Cp*bu~$j!>vcv{R{W%r z(|&D4rxdE}Ud-!7m&KZoZ}$bgLbmMS!?8#;Yj&N7Q(KD#MI+e=nbKYK%M9j1%QRU_ zDB0QVA8$11?p8^}rzYt`cr`1o^v5gm3|nuDS8m?wm#p++mDP0W8g8^B(avI;zg8od zuPzF}WtF~nJ&zL5{*m`=FhY)&-()#a%IsP@;hM1sM}0k_UY|6y1({jFFz`%cllqX^ z|Llt-N0X>613~0_W0%K?f_ZPvYdV@Tc{M zCG6V-s5fOv6-BFokiEB3YQD|~)5sd8>hn8u4={K9RT0;2xehlo{GHc((p~K$wli09 zHx29(akJcwYx$7nS$iEN1*~33ekn%WF4Ktdlap36k@K_)j&z2MjZwI8mYKiXm-)f$ zp9;@90&lG$L_-!B;zpe5Te<9Nny3msPEvSit&Mr`Kk_V7@zji*Nn_YAAbD#7c_iF1|r`VwrV zy~`_#1|s6|9ETR!E!8y$oBC3>Dy)s>$7!)*&$cA%PmL_2*G4q<_Rd1Dl1laSdRbz*({v}kuo@1) z$l)^LRvk!vRC7CEiK;YSUv642RGosg)lbiPCfpi7TH(GmA;0RxuE;MOtLN!y0N&rigq)7Q#eF=i`Y(C@Fv zc%6q)qLmBi*yexs@3llEIS%yE_iN`;JF-t5dl(uicR#G2FJ!#HNGSl%`KX(Qzn)lcJhIQmNk5nKLtw*H^%Gcbt5C z3~fL7m^Uf}L0iCdLX$L~X1r8Z796H?Nv4f8Y&yIcWW!yMDUyoZo{rzo>x9M1(}@zq z9sk&f6cfE|!)nZ;eI_R2_w4c-4L(kQ{e*fge}Cku2L|m&p=_m4EqFev>xU%ZB0`!4 z^oMwsO4w1AzC(oL^j3vcZ?n=G(19Bu6BqYv%96~4H*qSHDw|q_Vxf{aD<%U|_-0G2 zsz5g1i5;?RvOXzdH%Ts+q(^Y6VC_ctR@8%Y!-OS;35Qjx#XT@x0Iz2!*-MIr_SD;g z3Mz$ni7mgW#*bg$ulh?+80VS3>xE6dZ?dfPYoUPHMqUpV;fePxdR6hU1r$u==f}0I zx88oQF@yM@Y_--jJ3q|0dz$5_b&J~Euj(tynU(4<_9POOtpzjFJ`UdRdQ9Ys8Xurz zB6>n$y0D8ZObuYXUXfS`Y9z^7bnBO+Kr5Z$T*q4>u-%LKl0cJH;`+m&yOX=>|Jj4UVUum=j zdxv6oo98<6teN(3KaSUhE&LZnGZ+q&`uz_l#`5W~5h>`X?2A_tGjwUOZfArDMnCu9 z*&2^!h+Pfh$koEoFyT~C#hHkYN|fqzibTr9x$`duP@G>^a&~-b(9#y!&$lZ&Y+s6s zD^@N{5rCi=wfWkoT|PC**cGOW z^cz%ND4NxL)gKN;GD3-oH|}>3xZH~e#V4BuNajq1+Q?Ijhe|Z~Cs+Hw{H4)6+9ls& zl0Fj%rb_z5k05JJX}q#3{2KH@QmwxR!A)L<<`Kt={Ib8MaseX1%lTk{7MB4n3lOsE9k zej$C2&JDe|nC2&BwbFIPXFE=fJ~vD{0b!>^j@9$x^K~Sfi!wj9Mfr zwvxs&D>)HMrqko`C&cG7ItihSQkmL-s5MeOn(HxTJ8sR1TB|R!D&Pp=`fn*&*G{u^2D1ASgTZ29*_Rw_WWI z(JE7uZjMLOo5xWl`|_Ka-DI#xT6bn_xCJpBIM)|t#|159-281Y+qEBxro^YgWJaig zUQ9u($#Qk(cFo(_(7)53*pHI6&k@_{ipxkSgzF?pD6HYlIda!iIquUAqul0g2D>jr zRCrKgi5E%7l%HP3HH0f3hcqaE$d^wXHT6z0cdje3mVcQlS^%E2k+2NU61g+K_HL!g z_WLr9oruORO+yKLZC|Cz>_p(UHCM}W{2qgKCSG&$MHyan`s5)qK9-hx(A{?Qsk}m~ z4FP*d5_AS)P@Gqi|8#kY4pMfLnko<~zSsu&W(ZrtkiSg(Hk>R+v3Mc4;^yN#@eF2l z7JAX3XPhgxFEH$B=DswY;ZFZN{B>Uv?MwA=~6}$%bRyM!<39YHrS(Yq56>+yg9ZR);qfe|@4HFeB_4W=dg#cEVhSf$F+ zxed!c3$1c4&5-(m)CIs!Iwt9Bfe-ClebA@LcAKUK#sntY8>riss2rJ1y1mrg0aFO8B;VFGBHcp6IE zYH4DMyeQ&0+l_2h8bJHbqK=Au{^RcgT9au2?R3;RN1_ZY(oXO#_A*Dk2w=(Px^4m8 zC9W;v0gGsrFkGJaKcL@Bg`%qs5IM$XJ|Ohn1xp+`54W`i$j*4Jb(0)D9w(^SOHZMh zzxgUMQ8x}R^P<(dGlSbJ{KkH=`nUDl_X!&u&<8YFRNk@?(#S_B)S6iofb^^^Qgip$ zm0Qa`Ywg7a?Ko*|V`CM+q(Itz(m-P9CZsg&JiNS2_=XaRfhWAl{N8!YknEiT;q1b~ zcD6%Jcmm+0_HVK%;$?zTQwfHLhjmn3$htO{X#?}>F1At%Nr9o+xw*}32f+2(`KhR^ zdGgeYDr#$c=H`;ICuFhlzb~^sGI4Q`cVD2s@GdN5sTUz+JG>Z#ADvy(Pn{;7`$O#a z?|70!Wh-cx6qUK~0JXlgm4HS+cc-v;7$Qy7m-OrI21#dND)Y$M4E)}4m@3U;1^nw5 zW|f~2n^SFiMmbIZJsh4#g{2R!>m$)ud5`CjIuPn1?qrr;v*+aXIc43UF`}m*`BI_s6*P-E)p8i>y4+_GK!^*9+<9AQUZ#qP=^9;ZFM zh9>W5y64+@*3+3d9ZuJX2kspHx42g(Z4PJ#Yn|HQ-dORny1=k~FQ?eA=`qwK%qt zgGQgJFv2Ns?TJ?k%(~ygtmBO-F3bif6kd1Vd6v5_fV zOX|*r0bE2JPci~Si?Dc$ZX&^JYJjJj?i~RcJa*fw-71qdpZ_jiM)K zEsVuR<4p{F7ruC4cxYKlO?G4Yyd{#P3P%pzW(@z3Wta4(XFGj6Y=6&N{ zlHYbcJ8z}nTM!hM1c@t5s?k5-+&S9>nVa#MO|*&~aYf{4Y23MtZ#pmcJ>%R#7fC-| zN?v7ed1~`-vsG3D+14m1ut))456$sM1(;W6c1tkl&u z;dJn>pNYb@T1E03MM{_NKg!&0nl#I9udRK`%cIoO)5Dj-8Vbn-H9SG>QSAKSRN@NYRoR{oJ|Sp@%;>U_*Dwr@KRBk;6ofe0Muv z@M~=B6-=^;$%gLHycslOP=meIl=C#019LS;w%9KRjeys6&@)J|YZ2;;NR*1%7nsSb zSyLhppMLgIz54ceT8%nK_Gsr=onJ_qV0?Uhdso-)i3zk+g&x!S3R2T|8u+gv+}5Jv zKheH}nvG`pI#4B=H?g|A8&X-x`tIF3H&vOMB4+9X`*IC~zFuNdeF~%DLE?$bU(0Rp zU<@J`+NK{p7kSx!t*>bgCtIWaE;3kA)V|%nMAkyT^)3wBpD8nL!=UUDN%=AML;WMu z&RcN-!h-V39zBn&R3PhmPf7}fK*+_lq2WeOh{qZ{74;mY_*5Gd667-%G#)#e*nM6H zaz)R!|KZ8cZa`%ZJ~+fM=q2umi-$Z;8&A$yAv3GiTuQ1~@$33FuWaIpyeD7JXtSTn zv%e@Yy>_$ODUdIBc;fV!9NHa06@JQL8zz3(r{>~jq&#oP;-xaS0ELBxr4vf!yaGo( zry$o4uUdBWWo-lvUl5e3ORuI7>U1>ew}U}AS-cto$%<7AGW5$$9wb`M9zd!WEjqMW zdgh_mn#V#h)+5TL`4iBBa zaBL)g(3I_SEx>nWLqN*PyoFuyu8)d4_|_G3M`_LZ6gEd2{w@HQNuStpUmu&cW_v2x zDT$SGpWW+B<%XK!d}3NKEPwr@)NFOql;8K0quGcA1(+G7DfgtB>Uf={Q+mN3ZO2ac zr=F3I4Od=~csfdj4?D9hJfTj4C#DZS)S=b*57wZT=cr|UVfA*NJQd+9Fe4w z>&z=x4&%tP0_cqA(j29;(oNz4=FRF=mJ46}3$LVHq{kZ;$6|_#Xthc(K_C!~MyXtm zOnjZmJ5#qcsTSEAaO>a%w>jr0lODSrf=@rKlx6Y`CKX@FP!6Wh00UC42i@F_C=aG- z!)|ctmAnpQiGvxcg{mR_@wDrQhY{*UT~kx+l*%;4qdt_`&e|xkw~GwwbkgnIGvW(B z_9v<=SwCsCXS#cBhFx%9V;}C*a9y5LxISzPH&S=F_reWUEX+BM220io@U2uYMKmhs z@__ZKBj*Hd-`_<{R}ChNRr}~yi0vx$CkxJ=Jrd~@K47y-RA(r;<>Q_$?i|^8-fAy< zQ$z@o;I28_3TktR8y5&BWuT-{`TGYL@3vf;PPdLF7PSh9_)m!Y-ako3T71GjcQmJ= zqH-?87Y|ZsVzFW8r994Io9N@M#%Y_4Y(3e!)7V9u`8+(-w7Q4l>g$ISW^GJU-%FMI z=7U0zxZ?C(tX4@k;2ppjSzKJ~?FG(1>E|j$`jDANX50vD#Mg2ZD#O=vZ4n@g3Wa*3 z)Z$V{(>M6|KlLIbBLM`N0iedp$^jf`PtMG2<&ZviPdo&{| z$T?-@$Dg}z)DK?S9;zcI-@LFSV0nKI zB|1d5mBD=L_^QrhhTe@x4OVib+UfBbk4pCi zX>T7*Qe;!>8k*IRR&T>$(apebnFzBHCXWj#&#BfqXd4=<3y+BH7SEKfJQ=hs^^E&) zwK`v(?_DcTy;xooN**`AXI!aRzaV9V)pp9q%tw=ALU?(39UL5#1IT!64CQm1|CohX z*^Dt0wxga|CAXx)w2zjgg*96WI8jYZT~m{k)D&gK*)cB%`p4-0CHJYYAuDM=V!|fU zE%*pjY*g`N^T_YUW&%{NlI1*1fS+eJAdFBoK6U8=RT@ zL;4vN=}Ur58Ph;eAE$xyGD9GC@=>C~DCU?64SH39H0u^x_|L1MU?4;ML&PQUb%8vJ zf%i}^Nh30lK@k7B_OA(8Ad~sS^WPEBfFgf*{x>2QpRP~x)^#uJ!fFLf5%FL-pGylx zQA~VSxZ5qW^)cbnR%|_yGxozc0p9hQ@JG^i!8-(FY96DTO?oXh&p2-8TwY&fdbsa6 z6E);e8eK*SPBO?x-;&0Wm_WZ-n;vcPFYlY$s<>G_KuWUVyn-e|tx>bFMjrN&Ne+T4 zJZzbdae_`_h4%RpLi=AW)h955z$%}VtR}n4jMiG!R6gRXLPGja4%dwFo7v>jdS zHV4kF@JXIO2_V_&?O+SF77z{00jU_B5lbq$UcUt7tCD``M9IlIo2Nn?S`ty|H&+nNZhh0S(Q!Xw1vi5SW&)m{mpwZ5CEyM^6i z@C(c1`7$~y7+e$8+P(cIrrcm_ynowrvYc_i_$^rb3H>de!0?(1h16WS^|t zIZ$vr1-;RgqvUplFJ!Zk>U!`9{fU|(+Ra=e`PeSXc#cui@`%sqha%g7m0NDVN|tub z-(^mkw*5I@%udJ8Y`7$S=pr2T=BcOpI@V1BN{Ge^j{=%MJeXK&C_h>4EK3*X=!v9ElS8HD4r|G zTIng8E8i1s;5}N)G6YppziVpn?d^`3*wvJl&mo+ct+T{byvw(1UD+BaPG^fdD#WTMaC#S6p*gO+xaL8cc5IF73JA?Oyy%A0Uvb?LJLR*~z6eCu|cDhJw`N zU)P?T()pIrYQZ2cC*bZzjUDf+J#df&M@GJbMg+HEseOViJOZorz^OW&G`2n5Em-Qo z6>G~;4uZ7>zfNsGcw9DGBIZX=O;5LBNF80lJ0%eOn9vrUlOzko%4-qJlacxHu53_h zYlrmsbThZo8BZschryxF8aF<9J{+QT z5XU9eGngYlM0V*1E}3mw=P$z5DoYd*`vI)myTYLG@E9^D>VuVYq%DakLo-x%R?8p})zVuPG?)P5i zucQ+SCiSh3}BROf}|id z(CG4uxYw0PkP^yQ`pB&tniakDz{_b^L%TYB7p$~-e!qA>$Jj5iMA*B9qy)ZUGZN8E zR#4;%oQP&jZe(XzS>j~HbQ)_c#YYu+`zTOz7(SwMvQ*(BxYaNOH(ZdbEhXUher72j z@!iwUuVRT3H#4e+^=UF%EkP_Ls}2mMD2O$eV- zJZKr$c(&E3+{6Ne3AE9hfizc!bB!*pQ2oPRxrcpO-^M)rMcc*|ebD_2mRzX&tCIJgv2 z=gF9K#f}qYvI)ioy>=Po1UG-MM29@mr;_}j1;dgCk|&?QsbLHyD=>PKGNsfvN6Xi1 z1gSdZ;XSRPs(T41+oIXtSXBBg_u@x`zEj$RJ*sE}XJ^Z(^}zRG74;ur-guaEiAoCT z&u))jcLhQ3MCa9d*=4jMo`1OQc;5D=DvTf4^7}1@?!Dnf^AS&TP`ou zWr}k9OeBcg^>m(WvG2Aq6tup(mr9^RQ#AJ2wS9A1qSo|0jiaYaAVP4waOlSTwYi&h zP|s*}U9%|pVNE0kop91>K3+OZKc^%N+|>RUCQ>#dOTf;X+Vs;5;*i49{duPA;_Ta9 z1aaI7E&x9M^wUUhlEtGz3%{V2{|$)zmytjGFR10eBmNIPI;(b>2|z24$OkZ=M@(HE z7b+^Ml#~>NP|;N8lvROh0cy4N3`6X7JYy3&bOuC4MTMB8WNbo$>%=8cONV>+uDhp4 z5-9YF%%Knv$jiwM(%Y_YZ%f+Smk-SovjZB-kdyl-C1Gb~W!X+g8d=K;9yR?s$dP2m z9<055jT;g3;WO@u)JKflNtg_99;lWyXVGzd*O^0lKQtmqhLjxQbK4-mzNvy0=s4Ws zbAR@5w7M$n?#_i9k^9YGR1}~H2?=3HN_k`Y<0WKjE0JW+KD0dUh!cWVJ_$W{vsq8X z2cW4V`%I}0CP=&+*%uExk$y<~aG`Z~Xl${!@>OvpWkU`<&_*GRPukPdGtKn<`}aG} zJR~F}XT8!{W5_5d0SbAfWMpI`9Kid8&hGAn<|MnsZ$f3-D^!mV=lbpmwXMx^%>ret zw!?DEJ{cI@>3J;WE0PD&6^m80X_wk(O8Z~j2Z&*X>&Sr`6g*v6Xei11_peISzmrlH z#Z_t1!@Tpe7`+)CY<}He-+0GE7hgB2Qa8!PT;yt`s6^;;Y1CwcLQ2g@@+` zcu`T-fIckQr1K#sw&P=!V0rqFbTTwwTZf<9H_6ZfwaEnpS`1t>X3%hOq}|=!Bf<)ncP-$P5x(FjdR7B03dv?tqT)2R2`qmG{E=y#G;Kct0V3DR&z z8nSkKZ(xOcWsQuCR&%0kxHU=h*0N1#nF|J#Wd>&Ow?%Y3;kukdjq~VKeGA{Gg+AO( zqVR0Ui=5N3Io&l@yYsUqg(yyC`l?~vBB|`9?IQa4(C5~OCf#WHOy<>|&t;}&YeT-= zFjS+8k1{}}y7)6m0?D%TjJ-!%ZhApM1_FmV8yCHH_NCs zRqBI-VQXv`zO)%oIqSQz#cK;R()067{qS39aIc%2Q;<=I(sukl+a6!`bu80TCB>{& ztEnm)dLSaV(OsjnBA)>FdGog+znbWR%F0nUhZduvsv{x12q7Ooe^|V-iHS*C6~psV z!}r4?xvnakA!dc1+^y(X`fO;Rbk{SrETZhK>>8LYw6JO`pkE!TM!P*;)<*x@4S3Kf zW4Nnd#H}8FQbOcOE&cVgyu2KeJ?DWv?}b>HGxFc0*FF5ust;)(wBmWOqYCBkS-m7n zpF_t#)6?1#GjyL7!p@$P06(ecVzCF4#OOFH?huyi)HVd8key>Fk=Be7__5>#5&TdvpbBF zUz6PO`((4hTApDQ-E<*8ui=B+&$8SLT2hMg9dz3n#OTD&27TX`dL%&`TJER~Ti^Sq?g@Jo9fHWFQm`F>;^oiuR8v)L=Vqb@%? z2;fwGn|ab-2MX1mwRGiP#b9jiT7MZm!R`pfJ}`w>_>+;mKmY1I$S{mKb# zzQK0qQH)D6Q7@)a2^qeP$E9y6?J9frHmUtyYx1*gd(tq>sI3RF}hz_&Ldn zXu;;FD2IF`?(O3BiF1$!=$o1VedcosI|)`BNgghXGy@LPAX;!y9sPfEiRwF}We@4&7z&-ZMXE(y7u zXjK0;12cgAtN=lT+Z-^shwt^t2{9iZeuRXI)US;90EL7U1&K04AiW7ZNVJbckpq9O zZ}i1x=jCl{Vxppc0^&Ll=A*!DxNlKVP=KH>A|i5T13cU$Y;0`i@*HbrrG8-Dztf>E zXqdfJ(Ed^!mM0Zdu*YPxB%!BFpKV^|fzOKZQzk;Vc>V!5fCW|r*)9Zl4FNfjnVAWT zgao{FKt(}m17Zh6aBwj2K#lqKO-NN$HG|sFa-#mfg!+(_v7P!T%~|0nm|yO}n`M6O zeztn%MkBbIhNvFFi>}NzZ%X zdZU4mLgv}r^2>GlRAEy_PMw;)c)P78|6Fy9+u=P!b5aSq`?Ozh`Q0=rq_!%uMix%S zA?~(iHZw2O47IfQdG71XJ2EJBs@fx*^Obu$R{8xmH#Bm_X$`X?U&c})w zmLoP`(?=g>dGSpGh=U<ajbH98K1GT1wa&k{3KsM`oR^imlF# zQG=vyuiXLTIIufgKt}D1(C*_O6@}#M>s$NS1Wr#+AIcT1KXi~&=Oz%0r&C4^yocVO zBzN^y3bAN^5?#m#kpr8;K7`S*FviA4D@@0UM0rnbuy1)fE zQ%(|Jz1-b@1207s@;YW_YUP$|XM?4)J|uX$LPSU$CBU^e2bYzBlKZyJ(5=G(coio@ zHyyGD6v}K8fRjob*Z5Ce+wTJYWy$OR64Gpc4AOd8LEP{$^dvA48o-tiqgK@x)mk)a zg<^;E)dL$on+S|B!c;;wHgrHB$j-@Ga^^QTH~;kcGvL=KKu5TeD*!mr(9oP@7jABE zQSk9?DmkQp282LmX*gmEiZ44m7T>G0W^pH?co~_zc0VA#KDTWSkjOHb{PCI(Rb5=b zMVM-Pci~Wqx)$urlPW*nU__cbE(Q0?fQc1g|ARX#K`SkMt$^kG@b} zze)xK??+}k=0uN|9Fj&HOF}EP`aTvXrW3t|60unDVLC1m5Na=B>!?eVHhcQDDito`aD^0p&a`_3GfM(sd`ibS=)UDPJCv6a4 z=tJ71&>!(F&@~aNQ zW!s5w>Y(ROdaYq@TAV-Tta+(!n0G?F*@L^GuueK25_jh)g1ZCgclmDo#Jb2GOqRsb z4rhTf?f3DmQ)X`mCT@*8)Ay^tt(FN!gT8)(gtb~qesx^3ZXZgnIGNyTLJzvOm8|rq zs5-cSB(mcdHEV$wcD_Xt@H(gFse#Rw4vXaD^`-x+Lf(%iBLRTgjDhok0xs%!S?0|@ z;jkV#QLn#wkDJH~E-V&PQ4%Jp>|}jmCyJEh>`@NpT4pl~bwEQm! zenv{2^_9)&Hf5cRVt+tP2D37Hf7ddbx-G^df>e9^MR&rd%4 zYpZ4&6wxueD?u0U>}3A*v(tdLDG$4|uGugnEF)RX7!Dpkv!<9iTcwld6zi#OMVAgK z;V%rN!zF-A>(xuZP4>hTHe+e6SnPrW4;kGeF)T@-e> ziT%xQW{c6tt0_m<$o>hu5wPMB&%GaSaE2XrhMJs-nORJ7K~I}taKpnuMv`3pUZBzG z-yh{LRtiCH$*FAgO=)sXts@00Yf&YO(@7v}LN$}+p|+HWn-8@JyUQM=CL_aRdSd zUQd`We!T+C(HouP*P?aLW4q2U2|+@X%29f&$U?Cud20*IGcl6klg zlSPMi6Dcw61uSpBb7ZB#!(tCru3WF4d#s!dj_2hUs;(WazT1T(+gp`r>k-lN=EH&4 zSkwt~Eg`3lMh82%yb96`!|Nj>+itcQg3}18waDK(^3S9jf#%iV1Fy;%p_&ygev942 z)mW#mV{;WQux}p{k07UxaArlHXU`#JP>^90?$Eq3!!EsjI;y*?%Och-f@+GgJMi);T8~rCE{-3Faxas1NQ+G-UGz z-mG5eWhD(_hs%oR-&lXoh6*#*kk~Hag{M?U>)v0LA5P5R)H8j-9SQ%{_fO<~=nEGIp`mfcrb9aC+f1^5mFUpC zC_tDnFaEu>dd^g*PD!;!kPx*e?-MblPvGHp3Z2_j>(AW0oppAVx6Z0~HX1$R6rUr4 z(`qEpV0nJ?aG0UP%%d{Z%Fj4R&|$nRgUks>-uYjX=Pv_!0LFy{3XBH}wPnA~oo*c* z9RZx(xrNpx{YnHmP-KFKh$tQW7Y6R;_V{NEY=fG!rao#Bmy>2Flofru1HG!(2|(k) z4JX!6_HH1Nlp)957jyVT3`;J)^?(VTvG|@l;r}J_{Zo+5u!#n(VL)d{6|Z!D2Xa3V z5l9H2AEZQG7U%`Z*KKr7ZYuLG0~5o-05t=09-fq{s;cj$+Xn}7_V!GGJG_*D`y&B> z3*ZhrOFThAK>!xpPQNaAfyFe`uR1$BkqHQFD_zmGjqe<`Vayo$L)#2mN;m;a02Kp& z$@aotz^I#iK8*y_n+dTBd6m*y8aAD(xYVz(5rMw|!%vgm0Ca9&9WEqpyCESVwRdy? z&BH;^__zRddU8UA?64HATFR#Ub5j85&gT91Yov=LpXnLjD6Nz+`v~%XE*N!@1AiP1 zlkoLr^Rj(&H_kR%myX1HgC=mu81ASCkHqER-~f{#E-oJZ?VG=P(NJ`(nv7OS0+2cY zDK)%2+(1r}$Y1qQ-Wj+0%LsbUr{$^;w4k|m_rQpiE`zxH;7G9ARC`U+yam zP~Ib$iv4Tw=PP@!#2HH5G!NrDTOJkOG)LRW`OrJ%i4r)YzS(S|5?SusuhdX$DPjC9 zq~+!jK)sUQKez1c{fhrloAu1E5_`S?=9Mkwnf9yWoYU)1d9d%?1KnJ8-WSm%42KZq zGGB~+wZugh``#nLM7gKzx@W%HpYn>$j?cd!Oyd0GJ_U5dLqPkNtfeL&@q?Z}X^69@ zF+=Qqb)KdWrx^kBvbX-7MXs}jRG3C>bjnnLX#jLL@Bs97VLTwy=RP?3~8fOVz zY@Sl2e2WMDVltXza=JW%>QOhnZyyp;_JznKDhwrQgqL_f48`sLNMiiydmuz{q=fo3 zFDIbO@pY!1<<@Qyc8jRjlxTq6SF18CRI#aT^4e2{F=`oJ$-fAFa-E%~oZ&b4z3q!hZefm&WPixv4WNCXYP`Ckmi zvdg!cUK_lwW=ELy8=@WxLZCVhi}FM{O=htfUp5{O@PP-6e_&KrTBXFS)` zNkl8c;8Beg2M34KN*bP*#@)k2cd*`R2Th;l>av$AgvUYq+F(o@}m-1$`- z*A8pn;2_zAYAS_%6&V4ySn*{|#!r%E&LWTaDxaVu$&fI&E<6$Hww6g>-5q7hWZi|V z`p6KcM%PpQph)L;uHT9jsZdiDGz>I9e*74aqWqMi@-Ykq zn5Z_AZZO;WUkkdD_RpvFNd5mu6{mXtMooI;X{7$~@9DFgz=mO+Y3hetr)Nx_?5UU8 z6}#%&-DCSgw!XZyl=0;LKS%z3IsN9>QwdQkJEsYIV``i(0$W~>o=h>n-VYq%1opfg zKqE(>5kTNSWUAmadBE7F$(PMvS z^1axK-AjYN{eK>1ov8kLo9e}^M<#J~A+zT$i#_5Rx~aT4=LZwF+N%hg3N2x~oWth9 z)LhqH-=8K(wuIsUI!{NLjv+zFq&X!|?_LHQ&ph@tHGuk%)FEBY7v*=y*)>j^%52VkqS*JVm{@&y4 zv-OkNuI%&WEb)HuM3r5Ng-vM2->jhRY*$~09E}WgnmJ`v?e^{ZsaO3yK-xiT>Z+Xinkl9TFt^% zW;?Fll_qvh>U7T;xhq%Ylm0GWeRDoz+|e_tldVs!xb?VJ?awcZWHtX3=LzB9760sJdu>4M&u-rNI!`lh2wm&v)R_4*_tL)TJJW;QkLMlqk^e6(%3ijp z(@oE6VM@euy`9UK+jjo?8zkwed3)B^U6+jy@ExBZSMpg?>3iUB!<1(s^H!C%Z4JKn zsQLW=g|{|H?zy;APSohJr&gw}$4lSkAKzcT{88L))`n@D-Aqe=olX9^Th`#eN%KYK z_=GQ8fSbI2H~dtdHO0nsQ|Rx!%y=#>7S_Pa=i1%nGIcIb;o7bP9*Hzv?j$U&t`3}Y z$<`gOFKqi3OZhRLa*^Lz^~o~S7)XEVOu=koFOJP*70qFD#R(=G-qQJKON zAAjFyvj57Uo$#^47Hj2Y|IPf;9{sW1Ve?N={@cfinqIBdLNh-{3$zrq|8W#0@q`B) j6BVG7BEV92=KN>=*ig!S_WNScxt9!{u6{1-oD!M<2hA72 literal 0 HcmV?d00001 diff --git a/binder/docker-compose.yml b/binder/docker-compose.yml new file mode 100644 index 000000000..2889040d4 --- /dev/null +++ b/binder/docker-compose.yml @@ -0,0 +1,30 @@ +version: '3' +services: + pycram: + image: pycram:binder-xpra + build: + context: ../ + dockerfile: ./binder/Dockerfile + stdin_open: true + tty: true + ports: + - 8888:8888 + privileged: true + # user: root + working_dir: /home/jovyan/ + command: jupyter lab --allow-root --NotebookApp.token='' --no-browser --ip=0.0.0.0 + entrypoint: ["/home/jovyan/work/binder/entrypoint.sh"] + volumes: + - ../:/home/jovyan/work + - /tmp/.X11-unix:/tmp/.X11-unix:rw + environment: + - DISPLAY + - QT_X11_NO_MITSHM=1 + - NVIDIA_DRIVER_CAPABILITIES=all + deploy: + resources: + reservations: + devices: + - driver: nvidia + count: all + capabilities: [gpu] diff --git a/binder/entrypoint.sh b/binder/entrypoint.sh new file mode 100755 index 000000000..ead7b837f --- /dev/null +++ b/binder/entrypoint.sh @@ -0,0 +1,8 @@ +#!/bin/bash + +source ${PYCRAM_WS}/devel/setup.bash +roscore & +roslaunch --wait rvizweb rvizweb.launch config_file:=${PYCRAM_WS}/src/pycram/binder/rviz_configs/pr2_config.json & +cp ${PYCRAM_WS}/src/pycram/binder/webapps.json ${PYCRAM_WS}/src/rvizweb/webapps/app.json + +xvfb-run exec "$@" diff --git a/binder/jupyter-config.json b/binder/jupyter-config.json new file mode 100644 index 000000000..3ef7c4419 --- /dev/null +++ b/binder/jupyter-config.json @@ -0,0 +1,6 @@ +{ + "@jupyterlab/apputils-extension:themes": { + "theme": "JupyterLab Light", + "theme-scrollbars": true + } +} diff --git a/binder/me/CMakeLists.txt b/binder/me/CMakeLists.txt new file mode 100644 index 000000000..1418db54a --- /dev/null +++ b/binder/me/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.0.2) +project(me) + +include_directories( + ${catkin_INCLUDE_DIRS} +) + +execute_process( + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMAND rm -rf jovyan +) + +execute_process( + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMAND mkdir -p jovyan/workspace/ros/ +) + +execute_process( + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMAND ln -s /home/jovyan/workspace/ros/src jovyan/workspace/ros/src +) + diff --git a/binder/me/package.xml b/binder/me/package.xml new file mode 100644 index 000000000..2dea2c92d --- /dev/null +++ b/binder/me/package.xml @@ -0,0 +1,9 @@ + + + me + 100.1.0 + tmp + Apache 2 + me + + diff --git a/binder/pycram-http.rosinstall b/binder/pycram-http.rosinstall new file mode 100644 index 000000000..4ad9ec467 --- /dev/null +++ b/binder/pycram-http.rosinstall @@ -0,0 +1,25 @@ +repositories: + iai_maps: + type: git + url: https://github.com/code-iai/iai_maps.git + version: master + iai_robots: + type: git + url: http://github.com/code-iai/iai_robots.git + version: master + pr2_common: + type: git + url: https://github.com/PR2/pr2_common.git + version: b34703bcca2b07cadbc3777d3c504c232a0c0c28 + kdl_ik_services: + type: git + url: https://github.com/cram2/kdl_ik_service.git + verison: master + pr2_kinematics: + type: git + url: https://github.com/PR2/pr2_kinematics.git + version: kinetic-devel + orocos_kinematics_dynamics: + type: git + url: https://github.com/orocos/orocos_kinematics_dynamics.git + version: v1.5.1 diff --git a/binder/rviz_configs/pr2_config.json b/binder/rviz_configs/pr2_config.json new file mode 100644 index 000000000..27a8a3f2d --- /dev/null +++ b/binder/rviz_configs/pr2_config.json @@ -0,0 +1,72 @@ +{ + "globalOptions": { + "background": "#111111", + "colladaLoader": "collada2", + "fixedFrame": "simulated/map" + }, + "viewerOptions": { + "camera": { + "position": { + "x": 8.8, + "y": 4.5, + "z": 2.7 + } + }, + "cameraControls": { + "center": { + "x": 1, + "y": 2.5, + "z": 0 + } + }, + "directionalLight": { + "position": { + "x": -3, + "y": -3, + "z": 5 + } + } + }, + "sidebarOpened": false, + "displays": [ + { + "isShown": true, + "name": "Grid", + "options": { + "cellSize": "1", + "color": "#eeeeee", + "numCells": "20" + }, + "type": "grid" + }, + { + "isShown": false, + "name": "Robot model", + "options": { + "param": "robot_description", + "tfPrefix": "simulated/pr2" + }, + "type": "urdf" + }, + { + "isShown": false, + "name": "Kitchen model", + "options": { + "param": "kitchen_description", + "tfPrefix": "simulated/environment" + }, + "type": "urdf" + }, + + { + "isShown": true, + "name": "Marker array", + "options": { + "topic": "/pycram/viz_marker" + }, + "type": "markerArray" + } + + + ] +} diff --git a/binder/webapps.json b/binder/webapps.json new file mode 100644 index 000000000..5c96ac83e --- /dev/null +++ b/binder/webapps.json @@ -0,0 +1,37 @@ +[ + { + "name": "rvizweb", + "title": "Rvizweb", + "icon": "proxy/8001/rvizweb/webapps/r.svg", + "url": "proxy/8001/rvizweb/webapps/rvizweb/build/www/index.html", + "start": true, + "mode": "split-right" + }, + { + "name": "XPRA", + "title": "Xpra Desktop", + "icon": "proxy/8001/rvizweb/webapps/xpra-logo.svg", + "url": "xprahtml5/index.html", + "start": true, + "mode": "split-left" + }, + + { + "name": "rosgraph", + "title": "Ros Graph", + "icon": "proxy/8001/rvizweb/webapps/o.svg", + "url": "proxy/8001/rvizweb/webapps/ros-node-graph/build/index.html" + }, + { + "name": "rosboard", + "title": "ROSBoard", + "icon": "proxy/8001/rvizweb/webapps/s.svg", + "url": "proxy/18888/index.html" + }, + { + "name": "webviz", + "title": "Webviz", + "icon": "proxy/8001/rvizweb/webapps/webviz/icon.svg", + "url": "proxy/8001/rvizweb/webapps/webviz/index.html" + } +] From 0df49c23415c672c4e6c9fff19eaeb685f37f813 Mon Sep 17 00:00:00 2001 From: kecks Date: Mon, 22 Apr 2024 11:31:44 +0200 Subject: [PATCH 180/195] binder: removed neem interface as module --- binder/Dockerfile | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/binder/Dockerfile b/binder/Dockerfile index c36eb0594..4b04a8afc 100644 --- a/binder/Dockerfile +++ b/binder/Dockerfile @@ -7,21 +7,7 @@ WORKDIR ${PYCRAM_WS}/src/ COPY --chown=${NB_USER}:users . pycram/ RUN vcs import --input pycram/binder/pycram-http.rosinstall --recursive -# === Following step should be replace to === -USER ${NB_USER} -RUN cd pycram \ - && git submodule update --init \ - && git clone https://github.com/Tigul/neem_interface_python.git src/neem_interface_python \ - && cd src/neem_interface_python \ - && git clone https://github.com/benjaminalt/neem-interface.git src/neem-interface -# === To === -# RUN cd pycram - # && git submodule update --init --recursive -# === When all .gitmodules use https urls === - RUN pip install --requirement ${PYCRAM_WS}/src/pycram/requirements.txt --user -RUN pip install --requirement ${PYCRAM_WS}/src/pycram/src/neem_interface_python/requirements.txt --user \ - && pip cache purge # Remove double numpy version RUN pip uninstall numpy -y From bd718a29807002f9bee76561586a907aaa5fa2ba Mon Sep 17 00:00:00 2001 From: Vanessa Hassouna <33067562+sunava@users.noreply.github.com> Date: Mon, 22 Apr 2024 11:34:48 +0200 Subject: [PATCH 181/195] [virtual building] Create README.md --- demos/pycram_virtual_building_demos/README.md | 1 + 1 file changed, 1 insertion(+) create mode 100644 demos/pycram_virtual_building_demos/README.md diff --git a/demos/pycram_virtual_building_demos/README.md b/demos/pycram_virtual_building_demos/README.md new file mode 100644 index 000000000..8b1378917 --- /dev/null +++ b/demos/pycram_virtual_building_demos/README.md @@ -0,0 +1 @@ + From 109edf590b3c4c177fcf2598c9764706f64b2e66 Mon Sep 17 00:00:00 2001 From: kecks Date: Mon, 22 Apr 2024 11:59:23 +0200 Subject: [PATCH 182/195] virtual building: added method to launch PR2 by script --- .../setup/launch_robot.py | 51 +++++++++++++++++++ launch/pr2_standalone.launch | 26 ++++++++++ 2 files changed, 77 insertions(+) create mode 100644 demos/pycram_virtual_building_demos/setup/launch_robot.py create mode 100644 launch/pr2_standalone.launch diff --git a/demos/pycram_virtual_building_demos/setup/launch_robot.py b/demos/pycram_virtual_building_demos/setup/launch_robot.py new file mode 100644 index 000000000..5a5581fb3 --- /dev/null +++ b/demos/pycram_virtual_building_demos/setup/launch_robot.py @@ -0,0 +1,51 @@ +import time +import roslaunch +import rospy +import rospkg + + +def launch_pr2(): + """ + Method to launch PR2 + """ + # name = 'pr2' + # urdf = 'pr2.urdf' + executable = 'pr2_standalone.launch' + launch_robot(executable) + + +# For future work / robots +# def launch_hsrb(): +# # name = 'hsrb' +# # urdf = 'hsrb.urdf' +# executable = 'hsrb_standalone.launch' +# launch_robot(executable) + + +# def launch_armar6(): +# # name = 'armar6' +# # urdf = 'armar6.urdf' +# executable = 'armar6_standalone.launch' +# launch_robot(executable) + + +def launch_robot(launch_file, package='pycram', launch_folder='/launch/'): + """ + General method to launch a specified file in given parameters + + :param launch_file: File name of the launch file + :param package: Name of the package + :param launch_folder: Location of the launch file inside the package + """ + + rospath = rospkg.RosPack() + + uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) + roslaunch.configure_logging(uuid) + launch = roslaunch.parent.ROSLaunchParent(uuid, [rospath.get_path(package) + launch_folder + launch_file]) + launch.start() + + rospy.loginfo(f'{launch_file} started') + + # Wait for ik server to launch + time.sleep(2) diff --git a/launch/pr2_standalone.launch b/launch/pr2_standalone.launch new file mode 100644 index 000000000..b2a605ad4 --- /dev/null +++ b/launch/pr2_standalone.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + From 65fc59938cc9521e878cfa82dd900da33b0d3247 Mon Sep 17 00:00:00 2001 From: kecks Date: Mon, 22 Apr 2024 12:10:55 +0200 Subject: [PATCH 183/195] Added more info to docstring --- demos/pycram_virtual_building_demos/setup/launch_robot.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/demos/pycram_virtual_building_demos/setup/launch_robot.py b/demos/pycram_virtual_building_demos/setup/launch_robot.py index 5a5581fb3..eaa9a08a8 100644 --- a/demos/pycram_virtual_building_demos/setup/launch_robot.py +++ b/demos/pycram_virtual_building_demos/setup/launch_robot.py @@ -6,7 +6,7 @@ def launch_pr2(): """ - Method to launch PR2 + Method to launch PR2 on the parameter server and start the ik service """ # name = 'pr2' # urdf = 'pr2.urdf' @@ -31,7 +31,8 @@ def launch_pr2(): def launch_robot(launch_file, package='pycram', launch_folder='/launch/'): """ - General method to launch a specified file in given parameters + General method to start a specified launch file with given parameters. + Default location for launch files here is in the folder 'launch' inside the pycram package :param launch_file: File name of the launch file :param package: Name of the package From 953c53114d0cd391ed2010753a38aef88530b2b3 Mon Sep 17 00:00:00 2001 From: kecks Date: Mon, 22 Apr 2024 14:51:03 +0200 Subject: [PATCH 184/195] [enums]: added additional ObjectTypes --- src/pycram/datastructures/enums.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/pycram/datastructures/enums.py b/src/pycram/datastructures/enums.py index a6867246f..b353b5319 100644 --- a/src/pycram/datastructures/enums.py +++ b/src/pycram/datastructures/enums.py @@ -48,6 +48,8 @@ class ObjectType(Enum): """ Enum for Object types to easier identify different objects """ + METALMUG = auto() + PRINGLES = auto() MILK = auto() SPOON = auto() BOWL = auto() @@ -56,6 +58,7 @@ class ObjectType(Enum): ROBOT = auto() ENVIRONMENT = auto() GENERIC_OBJECT = auto() + HUMAN = auto() class State(Enum): From e7df23f11b0ef8299dc99bd9ecb4ed6ad1983627 Mon Sep 17 00:00:00 2001 From: "OEM Configuration (temporary user)" Date: Mon, 22 Apr 2024 15:57:26 +0200 Subject: [PATCH 185/195] [hsrb] changed naming and some description parts --- src/pycram/process_modules/__init__.py | 2 +- ...ess_modules.py => hsrb_process_modules.py} | 0 src/pycram/robot_descriptions/__init__.py | 6 +++--- ...hsr_description.py => hsrb_description.py} | 21 +++++++++++-------- 4 files changed, 16 insertions(+), 13 deletions(-) rename src/pycram/process_modules/{hsr_process_modules.py => hsrb_process_modules.py} (100%) rename src/pycram/robot_descriptions/{hsr_description.py => hsrb_description.py} (82%) diff --git a/src/pycram/process_modules/__init__.py b/src/pycram/process_modules/__init__.py index 30f5906a3..31d37839a 100644 --- a/src/pycram/process_modules/__init__.py +++ b/src/pycram/process_modules/__init__.py @@ -1,7 +1,7 @@ from .pr2_process_modules import Pr2Manager from .boxy_process_modules import BoxyManager from .donbot_process_modules import DonbotManager -from .hsr_process_modules import HSRBManager +from .hsrb_process_modules import HSRBManager from .default_process_modules import DefaultManager from .stretch_process_modules import StretchManager diff --git a/src/pycram/process_modules/hsr_process_modules.py b/src/pycram/process_modules/hsrb_process_modules.py similarity index 100% rename from src/pycram/process_modules/hsr_process_modules.py rename to src/pycram/process_modules/hsrb_process_modules.py diff --git a/src/pycram/robot_descriptions/__init__.py b/src/pycram/robot_descriptions/__init__.py index 3385fab74..7a40acb8b 100644 --- a/src/pycram/robot_descriptions/__init__.py +++ b/src/pycram/robot_descriptions/__init__.py @@ -5,7 +5,7 @@ from .boxy_description import BoxyDescription from .donbot_description import DonbotDescription -from .hsr_description import HSRDescription +from .hsrb_description import HSRBDescription from .pr2_description import PR2Description from .ur5_description import UR5Description from .tiago_description import TiagoDescription @@ -56,8 +56,8 @@ def update_robot_description(robot_name=None, from_ros=None): description = PR2Description elif 'boxy' in robot: description = BoxyDescription - elif 'hsr' in robot: - description = HSRDescription + elif 'hsrb' in robot: + description = HSRBDescription elif "ur5_robotiq" in robot: description = UR5Description elif "tiago_dual" in robot: diff --git a/src/pycram/robot_descriptions/hsr_description.py b/src/pycram/robot_descriptions/hsrb_description.py similarity index 82% rename from src/pycram/robot_descriptions/hsr_description.py rename to src/pycram/robot_descriptions/hsrb_description.py index 053a58b13..d26bb4fc8 100644 --- a/src/pycram/robot_descriptions/hsr_description.py +++ b/src/pycram/robot_descriptions/hsrb_description.py @@ -1,10 +1,9 @@ from ..robot_description import * -class HSRDescription(RobotDescription): +class HSRBDescription(RobotDescription): def __init__(self): - super().__init__("hsrb", "base_footprint", "base_link", "arm_lift_link", "arm_lift_joint") # Camera head_center_camera = CameraDescription("head_center_camera_frame", @@ -25,7 +24,7 @@ def __init__(self): # Neck neck_links = ["head_pan_link", "head_tilt_link"] neck_joints = ["head_pan_joint", "head_tilt_joint"] - neck_forward = {"forward": [0.0, 0.0], "down": [0.0, -0.7]} + neck_forward = {"forward": [0.0, 0.0], "down": [0.0, 0, 0]} neck_chain = ChainDescription("neck", neck_joints, neck_links, static_joint_states=neck_forward) self.add_chain("neck", neck_chain) # Arm @@ -33,17 +32,21 @@ def __init__(self): arm_links = ["arm_flex_link", "arm_roll_link", "wrist_flex_link", "wrist_roll_link"] arm_carry = {"park": [0, 1.5, -1.85, 0]} gripper_links = ["hand_l_distal_link", "hand_l_spring_proximal_link", "hand_palm_link", - "hand_r_distal_link", "hand_r_spring_proximal_link"] - gripper_joints = ["hand_motor_joint"] + "hand_r_distal_link", "hand_r_spring_proximal_link", "hand_gripper_tool_frame"] + gripper_joints = ["hand_l_proximal_joint", "hand_r_proximal_joint", "hand_motor_joint"] gripper = GripperDescription("gripper", gripper_links=gripper_links, gripper_joints=gripper_joints, gripper_meter_to_jnt_multiplier=1.0, gripper_minimal_position=0.0, gripper_convergence_delta=0.001) arm_chain = ChainDescription("left", arm_joints, arm_links, static_joint_states=arm_carry) arm_inter = InteractionDescription(arm_chain, "wrist_roll_link") - arm_manip = ManipulatorDescription(arm_inter, tool_frame="gripper_tool_frame", gripper_description=gripper) - self.add_chain("left", arm_manip) + arm_manip = ManipulatorDescription(arm_inter, tool_frame="hand_gripper_tool_frame", gripper_description=gripper) + self.add_static_gripper_chains("left", {"open": [0.3], "close": [0.0]}) + self.grasps = GraspingDescription( + {"front": [-1, 0, -1, 0], + "left": [0, -1, 1, 0], + "right": [0, -1, -1, 0.0], + "top": [-1, 0, 0, 0]}) - def get_camera_frame(self, name="head_center_camera"): - # TODO: Hacky since only one optical camera frame from pr2 is used + def get_camera_frame(self, name="head_center_camera_frame"): return super().get_camera_frame(name) \ No newline at end of file From c195c559a18b801c879eb4710f57cbcef3d4428b Mon Sep 17 00:00:00 2001 From: "OEM Configuration (temporary user)" Date: Mon, 22 Apr 2024 16:02:01 +0200 Subject: [PATCH 186/195] [hsrb] added left mani again --- src/pycram/robot_descriptions/hsrb_description.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/robot_descriptions/hsrb_description.py b/src/pycram/robot_descriptions/hsrb_description.py index d26bb4fc8..7b87fc934 100644 --- a/src/pycram/robot_descriptions/hsrb_description.py +++ b/src/pycram/robot_descriptions/hsrb_description.py @@ -40,7 +40,7 @@ def __init__(self): arm_chain = ChainDescription("left", arm_joints, arm_links, static_joint_states=arm_carry) arm_inter = InteractionDescription(arm_chain, "wrist_roll_link") arm_manip = ManipulatorDescription(arm_inter, tool_frame="hand_gripper_tool_frame", gripper_description=gripper) - + self.add_chain("left", arm_manip) self.add_static_gripper_chains("left", {"open": [0.3], "close": [0.0]}) self.grasps = GraspingDescription( {"front": [-1, 0, -1, 0], From 9049d50d24f92d0300c62ba7887395fa57560aaf Mon Sep 17 00:00:00 2001 From: "OEM Configuration (temporary user)" Date: Mon, 22 Apr 2024 16:03:51 +0200 Subject: [PATCH 187/195] [hsrb] neck forward --- src/pycram/robot_descriptions/hsrb_description.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pycram/robot_descriptions/hsrb_description.py b/src/pycram/robot_descriptions/hsrb_description.py index 7b87fc934..197d64e4c 100644 --- a/src/pycram/robot_descriptions/hsrb_description.py +++ b/src/pycram/robot_descriptions/hsrb_description.py @@ -24,7 +24,7 @@ def __init__(self): # Neck neck_links = ["head_pan_link", "head_tilt_link"] neck_joints = ["head_pan_joint", "head_tilt_joint"] - neck_forward = {"forward": [0.0, 0.0], "down": [0.0, 0, 0]} + neck_forward = {"forward": [0.0, 0.0], "down": [0.0, 0, -0.7]} neck_chain = ChainDescription("neck", neck_joints, neck_links, static_joint_states=neck_forward) self.add_chain("neck", neck_chain) # Arm From 21f4ea0c97d46ecf1b1ae793d48ecda238844f39 Mon Sep 17 00:00:00 2001 From: "OEM Configuration (temporary user)" Date: Mon, 22 Apr 2024 17:09:58 +0200 Subject: [PATCH 188/195] [move_base] added move_base interface to external interface hsrb for example is moved in real with move_base --- src/pycram/external_interfaces/move_base.py | 81 +++++++++++++++++++++ 1 file changed, 81 insertions(+) create mode 100644 src/pycram/external_interfaces/move_base.py diff --git a/src/pycram/external_interfaces/move_base.py b/src/pycram/external_interfaces/move_base.py new file mode 100644 index 000000000..d443ef739 --- /dev/null +++ b/src/pycram/external_interfaces/move_base.py @@ -0,0 +1,81 @@ +import sys + +import rospy +import actionlib +import rosnode +from geometry_msgs.msg import PoseStamped +from typing import Callable + +try: + from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal +except ModuleNotFoundError as e: + rospy.logwarn(f"Could not import MoveBase messages, Navigation interface could not be initialized") + + +# Global variables for shared resources +nav_action_client = None +is_init = False + + +def create_nav_action_client() -> actionlib.SimpleActionClient: + """Creates a new action client for the move_base interface.""" + client = actionlib.SimpleActionClient("move_base", MoveBaseAction) + rospy.loginfo("Waiting for move_base action server") + client.wait_for_server() + return client + + +def init_nav_interface(func: Callable) -> Callable: + """Ensures initialization of the navigation interface before function execution.""" + + def wrapper(*args, **kwargs): + global is_init + global nav_action_client + + if is_init: + return func(*args, **kwargs) + + if "move_base_msgs" not in sys.modules: + rospy.logwarn("Could not initialize the navigation interface: move_base_msgs not imported") + return + + if "/move_base" in rosnode.get_node_names(): + nav_action_client = create_nav_action_client() + rospy.loginfo("Successfully initialized navigation interface") + is_init = True + else: + rospy.logwarn("Move_base is not running, could not initialize navigation interface") + return + + return func(*args, **kwargs) + + return wrapper + + +@init_nav_interface +def query_pose_nav(navpose: PoseStamped): + """Sends a goal to the move_base service, initiating robot navigation to a given pose.""" + global nav_action_client + global query_result + + def active_callback(): + rospy.loginfo("Sent query to move_base") + + def done_callback(state, result): + rospy.loginfo("Finished moving") + global query_result + query_result = result + + goal_msg = MoveBaseGoal() + goal_msg.target_pose = navpose + nav_action_client.send_goal(goal_msg, active_cb=active_callback, done_cb=done_callback) + + nav_action_client.wait_for_result() + + return query_result + + +def cancel_nav(): + """Cancels the current navigation goal.""" + global nav_action_client + nav_action_client.cancel_all_goals() From a16f3d522acb2fcf0c674c68f8bdd292dbbd90f2 Mon Sep 17 00:00:00 2001 From: kecks Date: Mon, 22 Apr 2024 18:27:10 +0200 Subject: [PATCH 189/195] [binder]: added specific requirements for launch --- binder/Dockerfile | 2 +- binder/requirements.txt | 18 ++++++++++++++++++ 2 files changed, 19 insertions(+), 1 deletion(-) create mode 100644 binder/requirements.txt diff --git a/binder/Dockerfile b/binder/Dockerfile index 4b04a8afc..67f506fcc 100644 --- a/binder/Dockerfile +++ b/binder/Dockerfile @@ -7,7 +7,7 @@ WORKDIR ${PYCRAM_WS}/src/ COPY --chown=${NB_USER}:users . pycram/ RUN vcs import --input pycram/binder/pycram-http.rosinstall --recursive -RUN pip install --requirement ${PYCRAM_WS}/src/pycram/requirements.txt --user +RUN pip install --requirement ${PYCRAM_WS}/src/pycram/binder/requirements.txt --user # Remove double numpy version RUN pip uninstall numpy -y diff --git a/binder/requirements.txt b/binder/requirements.txt new file mode 100644 index 000000000..39567930a --- /dev/null +++ b/binder/requirements.txt @@ -0,0 +1,18 @@ +gitpython>=3.1.37 +pybullet~=3.2.5 +rospkg~=1.4.0 +roslibpy~=1.2.1 +# rospy~=1.14.11 +pathlib~=1.0.1 +numpy>=1.21.1 +pytransform3d~=1.9.1 +# tf~=1.12.1 +# actionlib~=1.12.1 +urdf-parser-py~=0.0.3 +graphviz +anytree>=2.8.0 +SQLAlchemy>=2.0.9 +tqdm==4.66.1 +psutil==5.9.7 +lxml==4.9.1 +rdflib==7.0.0 From d7b5b7f57f1db1bc530c0991659e1b428c6ca12e Mon Sep 17 00:00:00 2001 From: kecks Date: Wed, 24 Apr 2024 16:52:38 +0200 Subject: [PATCH 190/195] [binder]: removed uninstallation of numpy --- binder/Dockerfile | 4 ---- 1 file changed, 4 deletions(-) diff --git a/binder/Dockerfile b/binder/Dockerfile index 67f506fcc..61e70c19e 100644 --- a/binder/Dockerfile +++ b/binder/Dockerfile @@ -9,10 +9,6 @@ RUN vcs import --input pycram/binder/pycram-http.rosinstall --recursive RUN pip install --requirement ${PYCRAM_WS}/src/pycram/binder/requirements.txt --user -# Remove double numpy version -RUN pip uninstall numpy -y -RUN pip install --upgrade pip - COPY --chown=${NB_USER}:users binder/me ${PYCRAM_WS}/src/me USER root From b1c3791149f173e45b75b13def0570df1096fdc5 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Apr 2024 15:36:52 +0200 Subject: [PATCH 191/195] [AbstractWorld] Attachments are recreated in the prospection world instead of being copied. Added a test to check real and prospection object attachments independence. --- src/pycram/world_concepts/constraints.py | 13 +++-- src/pycram/world_concepts/world_object.py | 30 ++++++++++- test/test_bullet_world.py | 65 +++++++++++++++++++++++ 3 files changed, 103 insertions(+), 5 deletions(-) diff --git a/src/pycram/world_concepts/constraints.py b/src/pycram/world_concepts/constraints.py index b05c34469..aa41e3bdf 100644 --- a/src/pycram/world_concepts/constraints.py +++ b/src/pycram/world_concepts/constraints.py @@ -1,5 +1,6 @@ from __future__ import annotations +import numpy as np from geometry_msgs.msg import Point from typing_extensions import Union, List, Optional, TYPE_CHECKING @@ -268,9 +269,13 @@ def __copy__(self): self.id) def __eq__(self, other): - return (self.parent_link == other.parent_link and self.child_link == other.child_link and - self.bidirectional == other.bidirectional and - self.parent_to_child_transform == other.parent_to_child_transform) + return (self.parent_link.name == other.parent_link.name + and self.child_link.name == other.child_link.name + and self.bidirectional == other.bidirectional + and np.allclose(self.parent_to_child_transform.translation_as_list(), + other.parent_to_child_transform.translation_as_list(), rtol=0, atol=1e-4) + and np.allclose(self.parent_to_child_transform.rotation_as_list(), + other.parent_to_child_transform.rotation_as_list(), rtol=0, atol=1e-4)) def __hash__(self): - return hash((self.parent_link, self.child_link, self.bidirectional, self.parent_to_child_transform)) + return hash((self.parent_link.name, self.child_link.name, self.bidirectional, self.parent_to_child_transform)) diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index a7b43a28f..ea41ff339 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -558,10 +558,27 @@ def current_state(self) -> ObjectState: def current_state(self, state: ObjectState) -> None: if self.get_pose().dist(state.pose) != 0.0: self.set_pose(state.pose, base=False, set_attachments=False) - self.attachments = state.attachments + + self.set_attachments(state.attachments) self.link_states = state.link_states self.joint_states = state.joint_states + def set_attachments(self, attachments: Dict[Object, Attachment]) -> None: + """ + Sets the attachments of this object to the given attachments. + :param attachments: A dictionary with the object as key and the attachment as value. + """ + for obj, attachment in attachments.items(): + if self.world.is_prospection_world and not obj.world.is_prospection_world: + obj = self.world.get_prospection_object_for_object(obj) + if obj in self.attachments: + if self.attachments[obj] != attachment: + self.detach(obj) + else: + continue + self.attach(obj, attachment.parent_link.name, attachment.child_link.name, + attachment.bidirectional) + @property def link_states(self) -> Dict[int, LinkState]: """ @@ -969,6 +986,17 @@ def get_base_origin(self) -> Pose: return Pose([aabb.min_x + base_width / 2, aabb.min_y + base_length / 2, aabb.min_z], self.get_orientation_as_list()) + def copy_to_prospection(self) -> Object: + """ + Copies this object to the prospection world. + + :return: The copied object in the prospection world. + """ + obj = Object(self.name, self.obj_type, self.path, type(self.description), self.get_pose(), + self.world.prospection_world, self.color) + obj.current_state = self.current_state + return obj + def __copy__(self) -> Object: """ Returns a copy of this object. The copy will have the same name, type, path, description, pose, world and color. diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index d9b927525..abdd8a20b 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -169,6 +169,71 @@ def test_no_object_found_for_given_prospection_object(self): self.assertTrue(True) time.sleep(0.05) + def test_real_object_position_does_not_change_with_prospection_object(self): + milk_2_pos = [1.3, 1, 0.9] + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) + time.sleep(0.05) + milk_2_pos = milk_2.get_position() + prospection_milk = self.world.get_prospection_object_for_object(milk_2) + prospection_milk_pos = prospection_milk.get_position() + self.assertTrue(prospection_milk_pos == milk_2_pos) + + # Assert that when prospection object is moved, the real object is not moved + prospection_milk_pos.x += 1 + prospection_milk.set_position(prospection_milk_pos) + self.assertTrue(prospection_milk.get_position() != milk_2.get_position()) + self.world.remove_object(milk_2) + + def test_prospection_object_position_does_not_change_with_real_object(self): + milk_2_pos = [1.3, 1, 0.9] + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) + time.sleep(0.05) + milk_2_pos = milk_2.get_position() + prospection_milk = self.world.get_prospection_object_for_object(milk_2) + prospection_milk_pos = prospection_milk.get_position() + self.assertTrue(prospection_milk_pos == milk_2_pos) + + # Assert that when real object is moved, the prospection object is not moved + milk_2_pos.x += 1 + milk_2.set_position(milk_2_pos) + self.assertTrue(prospection_milk.get_position() != milk_2.get_position()) + self.world.remove_object(milk_2) + + def test_prospection_object_attachments_not_changed_with_real_object(self): + milk_2_pos = [1.3, 1, 0.9] + milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) + cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95])) + time.sleep(0.05) + milk_2.attach(cereal) + time.sleep(0.05) + prospection_milk = self.world.get_prospection_object_for_object(milk_2) + self.assertTrue(cereal not in prospection_milk.attachments) + prospection_cereal = self.world.get_prospection_object_for_object(cereal) + self.assertTrue(prospection_cereal in prospection_milk.attachments) + + # Assert that when prospection object is moved, the real object is not moved + prospection_milk_pos = prospection_milk.get_position() + cereal_pos = cereal.get_position() + prospection_cereal_pos = prospection_cereal.get_position() + + # Move prospection milk object + prospection_milk_pos.x += 1 + prospection_milk.set_position(prospection_milk_pos) + + # Prospection Cereal object should move with prospection milk object + assumed_prospection_cereal_pos = prospection_cereal_pos + assumed_prospection_cereal_pos.x += 1 + new_prospection_cereal_pos = prospection_cereal.get_position() + self.assertTrue(new_prospection_cereal_pos == assumed_prospection_cereal_pos) + + # Real cereal object should not move + new_cereal_pos = cereal.get_position() + assumed_cereal_pos = cereal_pos + self.assertTrue(new_cereal_pos == assumed_cereal_pos) + + self.world.remove_object(milk_2) + self.world.remove_object(cereal) + def test_add_vis_axis(self): self.world.add_vis_axis(self.robot.get_link_pose(robot_description.get_camera_frame())) self.assertTrue(len(self.world.vis_axis) == 1) From 8c1adb7372a1782b25872a4baf9b7aa79bd8c714 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Thu, 25 Apr 2024 16:53:21 +0200 Subject: [PATCH 192/195] [AbstractWorld] change name of milk_2 and cereal_2 --- test/test_attachment.py | 51 +++++++++++++++++++++++++++++++++++++++ test/test_bullet_world.py | 45 ++++------------------------------ 2 files changed, 56 insertions(+), 40 deletions(-) diff --git a/test/test_attachment.py b/test/test_attachment.py index dc1ba8869..30b29790c 100644 --- a/test/test_attachment.py +++ b/test/test_attachment.py @@ -1,4 +1,9 @@ +import time + from bullet_world_testcase import BulletWorldTestCase +from pycram.datastructures.enums import ObjectType +from pycram.datastructures.pose import Pose +from pycram.world_concepts.world_object import Object class TestAttachment(BulletWorldTestCase): @@ -39,4 +44,50 @@ def test_detachment_behavior(self): new_milk_pos = self.milk.get_position() self.assertEqual(new_milk_pos.x, milk_pos.x) + def test_prospection_object_attachments_not_changed_with_real_object(self): + milk_2 = Object("milk_2", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + cereal_2 = Object("cereal_2", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", + pose=Pose([1.3, 0.7, 0.95])) + time.sleep(0.05) + milk_2.attach(cereal_2) + time.sleep(0.05) + prospection_milk = self.world.get_prospection_object_for_object(milk_2) + self.assertTrue(cereal_2 not in prospection_milk.attachments) + prospection_cereal = self.world.get_prospection_object_for_object(cereal_2) + self.assertTrue(prospection_cereal in prospection_milk.attachments) + + # Assert that when prospection object is moved, the real object is not moved + prospection_milk_pos = prospection_milk.get_position() + cereal_pos = cereal_2.get_position() + prospection_cereal_pos = prospection_cereal.get_position() + + # Move prospection milk object + prospection_milk_pos.x += 1 + prospection_milk.set_position(prospection_milk_pos) + + # Prospection Cereal object should move with prospection milk object + assumed_prospection_cereal_pos = prospection_cereal_pos + assumed_prospection_cereal_pos.x += 1 + new_prospection_cereal_pos = prospection_cereal.get_position() + self.assertTrue(new_prospection_cereal_pos == assumed_prospection_cereal_pos) + + # Real cereal object should not move + new_cereal_pos = cereal_2.get_position() + assumed_cereal_pos = cereal_pos + self.assertTrue(new_cereal_pos == assumed_cereal_pos) + + self.world.remove_object(milk_2) + self.world.remove_object(cereal_2) + + def test_attaching_to_robot_and_moving(self): + self.robot.attach(self.milk) + milk_pos = self.milk.get_position() + rob_pos = self.robot.get_position() + + rob_pos.x += 1 + self.robot.set_position(rob_pos) + + new_milk_pos = self.milk.get_position() + self.assertEqual(new_milk_pos.x, milk_pos.x + 1) + diff --git a/test/test_bullet_world.py b/test/test_bullet_world.py index abdd8a20b..0c9cad689 100644 --- a/test/test_bullet_world.py +++ b/test/test_bullet_world.py @@ -132,7 +132,7 @@ def no_collision_callback(): self.assertTrue(self.collision_called) def test_equal_world_states(self): - time.sleep(2) + time.sleep(2.5) self.robot.set_pose(Pose([1, 0, 0], [0, 0, 0, 1])) self.assertFalse(self.world.world_sync.check_for_equal()) self.world.prospection_world.object_states = self.world.current_state.object_states @@ -144,7 +144,7 @@ def test_add_resource_path(self): self.assertTrue("test" in self.world.data_directory) def test_no_prospection_object_found_for_given_object(self): - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + milk_2 = Object("milk_2", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) time.sleep(0.05) try: prospection_milk_2 = self.world.get_prospection_object_for_object(milk_2) @@ -156,7 +156,7 @@ def test_no_prospection_object_found_for_given_object(self): self.assertTrue(True) def test_no_object_found_for_given_prospection_object(self): - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) + milk_2 = Object("milk_2", ObjectType.MILK, "milk.stl", pose=Pose([1.3, 1, 0.9])) time.sleep(0.05) prospection_milk = self.world.get_prospection_object_for_object(milk_2) self.assertTrue(self.world.get_object_for_prospection_object(prospection_milk) == milk_2) @@ -171,7 +171,7 @@ def test_no_object_found_for_given_prospection_object(self): def test_real_object_position_does_not_change_with_prospection_object(self): milk_2_pos = [1.3, 1, 0.9] - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) + milk_2 = Object("milk_2", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) time.sleep(0.05) milk_2_pos = milk_2.get_position() prospection_milk = self.world.get_prospection_object_for_object(milk_2) @@ -186,7 +186,7 @@ def test_real_object_position_does_not_change_with_prospection_object(self): def test_prospection_object_position_does_not_change_with_real_object(self): milk_2_pos = [1.3, 1, 0.9] - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) + milk_2 = Object("milk_2", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) time.sleep(0.05) milk_2_pos = milk_2.get_position() prospection_milk = self.world.get_prospection_object_for_object(milk_2) @@ -199,41 +199,6 @@ def test_prospection_object_position_does_not_change_with_real_object(self): self.assertTrue(prospection_milk.get_position() != milk_2.get_position()) self.world.remove_object(milk_2) - def test_prospection_object_attachments_not_changed_with_real_object(self): - milk_2_pos = [1.3, 1, 0.9] - milk_2 = Object("milk", ObjectType.MILK, "milk.stl", pose=Pose(milk_2_pos)) - cereal = Object("cereal", ObjectType.BREAKFAST_CEREAL, "breakfast_cereal.stl", pose=Pose([1.3, 0.7, 0.95])) - time.sleep(0.05) - milk_2.attach(cereal) - time.sleep(0.05) - prospection_milk = self.world.get_prospection_object_for_object(milk_2) - self.assertTrue(cereal not in prospection_milk.attachments) - prospection_cereal = self.world.get_prospection_object_for_object(cereal) - self.assertTrue(prospection_cereal in prospection_milk.attachments) - - # Assert that when prospection object is moved, the real object is not moved - prospection_milk_pos = prospection_milk.get_position() - cereal_pos = cereal.get_position() - prospection_cereal_pos = prospection_cereal.get_position() - - # Move prospection milk object - prospection_milk_pos.x += 1 - prospection_milk.set_position(prospection_milk_pos) - - # Prospection Cereal object should move with prospection milk object - assumed_prospection_cereal_pos = prospection_cereal_pos - assumed_prospection_cereal_pos.x += 1 - new_prospection_cereal_pos = prospection_cereal.get_position() - self.assertTrue(new_prospection_cereal_pos == assumed_prospection_cereal_pos) - - # Real cereal object should not move - new_cereal_pos = cereal.get_position() - assumed_cereal_pos = cereal_pos - self.assertTrue(new_cereal_pos == assumed_cereal_pos) - - self.world.remove_object(milk_2) - self.world.remove_object(cereal) - def test_add_vis_axis(self): self.world.add_vis_axis(self.robot.get_link_pose(robot_description.get_camera_frame())) self.assertTrue(len(self.world.vis_axis) == 1) From 09e0ff192011945092d8c20f13784650869f06c0 Mon Sep 17 00:00:00 2001 From: Abdelrhman Bassiouny Date: Fri, 3 May 2024 19:16:15 +0200 Subject: [PATCH 193/195] [AbstractWorld] added list hinting for set_position --- src/pycram/world.py | 3 ++- src/pycram/world_concepts/world_object.py | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/pycram/world.py b/src/pycram/world.py index 3034d05d1..a1d64e65a 100644 --- a/src/pycram/world.py +++ b/src/pycram/world.py @@ -1109,7 +1109,8 @@ def run(self, wait_time_as_n_simulation_steps: Optional[int] = 1): prospection world. When there are entries in the adding or removing queue the corresponding objects will be added or removed in the same iteration. - :param wait_time_as_n_simulation_steps: The time in simulation steps to wait between each iteration of the syncing loop. + :param wait_time_as_n_simulation_steps: The time in simulation steps to wait between each iteration of + the syncing loop. """ while not self.terminate: self.check_for_pause() diff --git a/src/pycram/world_concepts/world_object.py b/src/pycram/world_concepts/world_object.py index ea41ff339..5ac03a825 100644 --- a/src/pycram/world_concepts/world_object.py +++ b/src/pycram/world_concepts/world_object.py @@ -668,7 +668,7 @@ def _set_attached_objects_poses(self, already_moved_objects: Optional[List[Objec child.set_pose(link_to_object.to_pose(), set_attachments=False) child._set_attached_objects_poses(already_moved_objects + [self]) - def set_position(self, position: Union[Pose, Point], base=False) -> None: + def set_position(self, position: Union[Pose, Point, List], base=False) -> None: """ Sets this Object to the given position, if base is true the bottom of the Object will be placed at the position instead of the origin in the center of the Object. The given position can either be a Pose, From 48267728d727bde2b370a9da761bc20f653aaa94 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 3 May 2024 21:49:43 +0000 Subject: [PATCH 194/195] Bump tqdm from 4.66.1 to 4.66.3 Bumps [tqdm](https://github.com/tqdm/tqdm) from 4.66.1 to 4.66.3. - [Release notes](https://github.com/tqdm/tqdm/releases) - [Commits](https://github.com/tqdm/tqdm/compare/v4.66.1...v4.66.3) --- updated-dependencies: - dependency-name: tqdm dependency-type: direct:production ... Signed-off-by: dependabot[bot] --- binder/requirements.txt | 2 +- requirements.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/binder/requirements.txt b/binder/requirements.txt index 39567930a..81ce6a51d 100644 --- a/binder/requirements.txt +++ b/binder/requirements.txt @@ -12,7 +12,7 @@ urdf-parser-py~=0.0.3 graphviz anytree>=2.8.0 SQLAlchemy>=2.0.9 -tqdm==4.66.1 +tqdm==4.66.3 psutil==5.9.7 lxml==4.9.1 rdflib==7.0.0 diff --git a/requirements.txt b/requirements.txt index d40530f22..5ff4c4861 100644 --- a/requirements.txt +++ b/requirements.txt @@ -12,7 +12,7 @@ urdf-parser-py~=0.0.3 graphviz anytree>=2.8.0 SQLAlchemy>=2.0.9 -tqdm==4.66.1 +tqdm==4.66.3 psutil==5.9.7 lxml==4.9.1 typing_extensions==4.9.0 From 1e4ee08d5311807e1efbfe6030e555b0dfaa86b6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 3 May 2024 21:59:26 +0000 Subject: [PATCH 195/195] Bump tqdm from 4.66.1 to 4.66.3 in /binder Bumps [tqdm](https://github.com/tqdm/tqdm) from 4.66.1 to 4.66.3. - [Release notes](https://github.com/tqdm/tqdm/releases) - [Commits](https://github.com/tqdm/tqdm/compare/v4.66.1...v4.66.3) --- updated-dependencies: - dependency-name: tqdm dependency-type: direct:production ... Signed-off-by: dependabot[bot] --- binder/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/binder/requirements.txt b/binder/requirements.txt index 39567930a..81ce6a51d 100644 --- a/binder/requirements.txt +++ b/binder/requirements.txt @@ -12,7 +12,7 @@ urdf-parser-py~=0.0.3 graphviz anytree>=2.8.0 SQLAlchemy>=2.0.9 -tqdm==4.66.1 +tqdm==4.66.3 psutil==5.9.7 lxml==4.9.1 rdflib==7.0.0